From 487f56a5494de652a34363502afd41a2ef939159 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Thu, 28 Sep 2023 09:00:43 +0300 Subject: [PATCH 001/273] Update NuttX and Apps Signed-off-by: Jukka Laitinen --- .gitmodules | 4 ++-- platforms/nuttx/NuttX/apps | 2 +- platforms/nuttx/NuttX/nuttx | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.gitmodules b/.gitmodules index 6ecc529b165e..e353c5fd8c17 100644 --- a/.gitmodules +++ b/.gitmodules @@ -20,8 +20,8 @@ branch = main [submodule "platforms/nuttx/NuttX/nuttx"] path = platforms/nuttx/NuttX/nuttx - url = https://github.com/PX4/NuttX.git - branch = px4_firmware_nuttx-10.3.0+-v1.14 + url = https://github.com/tiiuae/nuttx.git + branch = master [submodule "platforms/nuttx/NuttX/apps"] path = platforms/nuttx/NuttX/apps url = https://github.com/PX4/NuttX-apps.git diff --git a/platforms/nuttx/NuttX/apps b/platforms/nuttx/NuttX/apps index a489381b4983..77e6c39cbd47 160000 --- a/platforms/nuttx/NuttX/apps +++ b/platforms/nuttx/NuttX/apps @@ -1 +1 @@ -Subproject commit a489381b49835ecba6f3b873b5071d882a18152f +Subproject commit 77e6c39cbd4758e2b6c7994cf266a9326cbfecb7 diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index de41e7feaeff..62897c422bf3 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit de41e7feaeffaec3ce65327e9569e8fdb553ca3d +Subproject commit 62897c422bf3e9fdd1fef02ed2e6b454e26c649c From db543dbca8188f67f6410c193b57b8502472ccd8 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Tue, 22 Aug 2023 16:32:06 +0300 Subject: [PATCH 002/273] systemlib/hardfault_log.h: Change stack_t -> fault_stack_t The name stack_t conflicts with signal stack, defined by POSIX: https://pubs.opengroup.org/onlinepubs/7908799/xsh/sigaltstack.html Let them have the type... --- src/lib/systemlib/hardfault_log.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/systemlib/hardfault_log.h b/src/lib/systemlib/hardfault_log.h index 574a2628cafe..7540776e49f9 100644 --- a/src/lib/systemlib/hardfault_log.h +++ b/src/lib/systemlib/hardfault_log.h @@ -208,7 +208,7 @@ typedef struct { _stack_s interrupt; #endif -} stack_t; +} fault_stack_t; /* Not Used for reference only */ @@ -321,7 +321,7 @@ typedef struct { int pid; /* Process ID */ uint32_t regs[XCPTCONTEXT_REGS]; /* Interrupt register save area */ fault_regs_s fault_regs; /* NVIC status */ - stack_t stacks; /* Stack info */ + fault_stack_t stacks; /* Stack info */ #if CONFIG_TASK_NAME_SIZE > 0 char name[CONFIG_TASK_NAME_SIZE + 1]; /* Task name (with NULL * terminator) */ From ebe9661bdf7b9fb86e42eba9b60a91d69b59f954 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Tue, 3 Jan 2023 17:28:18 +0400 Subject: [PATCH 003/273] Fix print_load to be compatible with upstream NuttX Signed-off-by: Jukka Laitinen --- platforms/nuttx/src/px4/common/print_load.cpp | 6 +++--- src/modules/load_mon/LoadMon.cpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/platforms/nuttx/src/px4/common/print_load.cpp b/platforms/nuttx/src/px4/common/print_load.cpp index 8c6486453ade..230b23acd59c 100644 --- a/platforms/nuttx/src/px4/common/print_load.cpp +++ b/platforms/nuttx/src/px4/common/print_load.cpp @@ -202,14 +202,14 @@ void print_load_buffer(char *buffer, int buffer_length, print_load_callback_f cb if (system_load.tasks[i].tcb->pid == 0) { stack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3); - stack_free = up_check_intstack_remain(); + stack_free = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - up_check_intstack(); } else { - stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb); + stack_free = system_load.tasks[i].tcb->adj_stack_size - up_check_tcbstack(system_load.tasks[i].tcb); } #else - stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb); + stack_free = system_load.tasks[i].tcb->adj_stack_size - up_check_tcbstack(system_load.tasks[i].tcb); #endif #if CONFIG_ARCH_BOARD_SIM || !defined(CONFIG_PRIORITY_INHERITANCE) diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index 80c54f482694..b9ae25f1f19b 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -259,7 +259,8 @@ void LoadMon::stack_usage() if (system_load.tasks[_stack_task_index].valid && (system_load.tasks[_stack_task_index].tcb->pid > 0)) { - stack_free = up_check_tcbstack_remain(system_load.tasks[_stack_task_index].tcb); + stack_free = system_load.tasks[_stack_task_index].tcb->adj_stack_size - up_check_tcbstack( + system_load.tasks[_stack_task_index].tcb); strncpy((char *)task_stack_info.task_name, system_load.tasks[_stack_task_index].tcb->name, CONFIG_TASK_NAME_SIZE - 1); task_stack_info.task_name[CONFIG_TASK_NAME_SIZE - 1] = '\0'; From 813849bc987d9cec4d74a7f29f0b48de1c97bee2 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 23 Nov 2022 12:54:47 +0200 Subject: [PATCH 004/273] platforms/nuttx/src/px4/common/board_crashdump.c: Fix prototype according to new nuttx --- platforms/nuttx/src/px4/common/board_crashdump.c | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/platforms/nuttx/src/px4/common/board_crashdump.c b/platforms/nuttx/src/px4/common/board_crashdump.c index 4a5f50f7cef7..7a232557ce69 100644 --- a/platforms/nuttx/src/px4/common/board_crashdump.c +++ b/platforms/nuttx/src/px4/common/board_crashdump.c @@ -250,13 +250,14 @@ static uint32_t *__attribute__((noinline)) __ebss_addr(void) static uint32_t *__attribute__((noinline)) __sdata_addr(void) { - return &_sdata; + return (uint32_t *)(uint32_t)_sdata; } #endif - -__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char *filename, int lineno) +__EXPORT void board_crashdump(uintptr_t currentsp, FAR struct tcb_s *rtcb, + FAR const char *filename, int lineno, + FAR const char *msg, FAR void *regs) { #ifndef BOARD_CRASHDUMP_RESET_ONLY /* We need a chunk of ram to save the complete context in. @@ -274,8 +275,6 @@ __EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char (void)enter_critical_section(); - struct tcb_s *rtcb = (struct tcb_s *)tcb; - /* Zero out everything */ memset(pdump, 0, sizeof(fullcontext_s)); From 8faf525905ef6add0c5f91e3c1dfb1a761cf43d4 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Tue, 14 Dec 2021 13:45:28 +0200 Subject: [PATCH 005/273] Add initial ssrc target for Pixhawk 5 and Pixhawk 5x - Add TOC to fmu-v5x (to the beginning) - Enable crypto - Enable uxrce_dds_client - Remove some useless modules to make up flash space Signed-off-by: Jukka Laitinen --- .../px4/fmu-v5/nuttx-config/scripts/script.ld | 32 +- boards/px4/fmu-v5/nuttx-config/scripts/toc.ld | 61 ++++ boards/px4/fmu-v5/nuttx-config/ssrc/defconfig | 265 +++++++++++++++ boards/px4/fmu-v5/src/toc.c | 41 ++- boards/px4/fmu-v5/ssrc.px4board | 21 ++ boards/px4/fmu-v5x/init/rc.board_mavlink | 9 + .../fmu-v5x/nuttx-config/scripts/script.ld | 34 +- .../px4/fmu-v5x/nuttx-config/scripts/toc.ld | 61 ++++ .../px4/fmu-v5x/nuttx-config/ssrc/defconfig | 314 ++++++++++++++++++ boards/px4/fmu-v5x/src/CMakeLists.txt | 1 + boards/px4/fmu-v5x/src/toc.c | 99 ++++++ boards/px4/fmu-v5x/ssrc.px4board | 27 ++ 12 files changed, 934 insertions(+), 31 deletions(-) create mode 100644 boards/px4/fmu-v5/nuttx-config/scripts/toc.ld create mode 100644 boards/px4/fmu-v5/nuttx-config/ssrc/defconfig create mode 100644 boards/px4/fmu-v5/ssrc.px4board create mode 100644 boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld create mode 100644 boards/px4/fmu-v5x/nuttx-config/ssrc/defconfig create mode 100644 boards/px4/fmu-v5x/src/toc.c create mode 100644 boards/px4/fmu-v5x/ssrc.px4board diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld index d73a97deb9ce..0d7c9d34199b 100644 --- a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld @@ -82,7 +82,7 @@ MEMORY OUTPUT_ARCH(arm) EXTERN(_vectors) -ENTRY(_stext) +ENTRY(_vectors) /* * Ensure that abort() is present in the final object. The exception handling @@ -91,12 +91,32 @@ ENTRY(_stext) EXTERN(abort) EXTERN(_bootdelay_signature) EXTERN(_main_toc) +EXTERN(_main_toc_sig) SECTIONS { - .text : { + /* Provide dummy relocation symbols for the dummy ToC */ + PROVIDE(_toc_start = 0); + PROVIDE(_toc_end = 0); + PROVIDE(_toc_signature = 0); + PROVIDE(_app_start = 0); + PROVIDE(_app_end = 0); + PROVIDE(_boot_signature = 0); + + /* Make a hole for the ToC and signature */ + toc (NOLOAD) : { + *(.main_toc) + *(.main_toc_sig) + FILL(0xff); + . = ALIGN(8); + } > FLASH_AXIM + + .vectors : { _stext = ABSOLUTE(.); *(.vectors) + } > FLASH_AXIM + + .text : { . = ALIGN(32); /* This signature provides the bootloader with a way to delay booting @@ -104,7 +124,6 @@ SECTIONS _bootdelay_signature = ABSOLUTE(.); FILL(0xffecc2925d7d05c5) . += 8; - *(.main_toc) *(.text .text.*) *(.fixup) *(.gnu.warning) @@ -180,11 +199,4 @@ SECTIONS } > ITCM_RAM AT > FLASH_AXIM _framfuncs = LOADADDR(.ramfunc); - - /* Start of the image signature. This - * has to be in the end of the image - */ - .signature : { - _boot_signature = ALIGN(4); - } > FLASH_AXIM } diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld new file mode 100644 index 000000000000..0653e72606b4 --- /dev/null +++ b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld @@ -0,0 +1,61 @@ +/**************************************************************************** + * boards/risc-v/icicle/mpfs/scripts/ld.script + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you 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. + * + ****************************************************************************/ + +MEMORY +{ + progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K +} + +OUTPUT_ARCH("arm") + +EXTERN(_main_toc) + +SECTIONS +{ + .toc : { + /* The ToC */ + _toc_start = ABSOLUTE(.); + KEEP(*(.main_toc)); + /* Padd the rest */ + FILL(0xff); + . = ALIGN(8); + _toc_end = ABSOLUTE(.); + } > progmem + + /* Start of the ToC signature, appended directly after ToC */ + PROVIDE(_toc_signature = ALIGN(4)); + + .toc_sig (NOLOAD) : { + /* Make a hole for the singature */ + KEEP(*(.main_toc_sig)); + } > progmem + + .app (NOLOAD) : { + /* The application firmware payload */ + _app_start = ABSOLUTE(.); + *(.firmware) + _app_end = ABSOLUTE(.); + } > progmem + + /* Start of the payload signature. This has to be in the end of the + * payload and aligned to a 4 byte boundary + */ + PROVIDE(_boot_signature = ALIGN(4)); +} diff --git a/boards/px4/fmu-v5/nuttx-config/ssrc/defconfig b/boards/px4/fmu-v5/nuttx-config/ssrc/defconfig new file mode 100644 index 000000000000..91633794bf38 --- /dev/null +++ b/boards/px4/fmu-v5/nuttx-config/ssrc/defconfig @@ -0,0 +1,265 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_FS_PROCFS_EXCLUDE_MEMINFO is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_UPTIME is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/px4/fmu-v5/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32f7" +CONFIG_ARCH_CHIP_STM32F765II=y +CONFIG_ARCH_CHIP_STM32F7=y +CONFIG_ARCH_INTERRUPTSTACK=1024 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0032 +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CRYPTO=y +CONFIG_CRYPTO_RANDOM_POOL=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FILE_STREAM=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_FS_SHMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2944 +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIBM_TOOLCHAIN=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=3 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=48 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_MODE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32F7_ADC1=y +CONFIG_STM32F7_BBSRAM=y +CONFIG_STM32F7_BBSRAM_FILES=5 +CONFIG_STM32F7_BKPSRAM=y +CONFIG_STM32F7_DMA1=y +CONFIG_STM32F7_DMA2=y +CONFIG_STM32F7_DMACAPABLE=y +CONFIG_STM32F7_FLOWCONTROL_BROKEN=y +CONFIG_STM32F7_I2C1=y +CONFIG_STM32F7_I2C2=y +CONFIG_STM32F7_I2C3=y +CONFIG_STM32F7_I2C4=y +CONFIG_STM32F7_I2C_DYNTIMEO=y +CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32F7_OTGFS=y +CONFIG_STM32F7_PROGMEM=y +CONFIG_STM32F7_PWR=y +CONFIG_STM32F7_RTC=y +CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32F7_RTC_MAGIC_REG=1 +CONFIG_STM32F7_SAVE_CRASHDUMP=y +CONFIG_STM32F7_SDMMC1=y +CONFIG_STM32F7_SDMMC_DMA=y +CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32F7_SPI1=y +CONFIG_STM32F7_SPI1_DMA=y +CONFIG_STM32F7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI2=y +CONFIG_STM32F7_SPI4=y +CONFIG_STM32F7_SPI5=y +CONFIG_STM32F7_SPI6=y +CONFIG_STM32F7_SPI_DMATHRESHOLD=8 +CONFIG_STM32F7_TIM10=y +CONFIG_STM32F7_TIM11=y +CONFIG_STM32F7_UART4=y +CONFIG_STM32F7_UART7=y +CONFIG_STM32F7_UART8=y +CONFIG_STM32F7_USART1=y +CONFIG_STM32F7_USART2=y +CONFIG_STM32F7_USART3=y +CONFIG_STM32F7_USART6=y +CONFIG_STM32F7_USART_BREAKS=y +CONFIG_STM32F7_USART_INVERT=y +CONFIG_STM32F7_USART_SINGLEWIRE=y +CONFIG_STM32F7_USART_SWAP=y +CONFIG_STM32F7_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_RXDMA=y +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_RXDMA=y +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_TXBUFSIZE=3000 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_RXDMA=y +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/px4/fmu-v5/src/toc.c b/boards/px4/fmu-v5/src/toc.c index 5f3fec31f412..7a1bf1ee53e7 100644 --- a/boards/px4/fmu-v5/src/toc.c +++ b/boards/px4/fmu-v5/src/toc.c @@ -33,21 +33,36 @@ #include /* (Maximum) size of the signature */ + #define SIGNATURE_SIZE 64 -/* Boot image starts at _vectors and ends at - * the beginning of signature -*/ +/* ToC area boundaries */ +extern const uintptr_t _toc_start; +extern const uintptr_t _toc_end; + +#define TOC_ADDR &_toc_start +#define TOC_END ((const void *)&_toc_end) + +/* ToC signature */ +extern const uintptr_t _toc_signature; -extern uint32_t _vectors[]; -extern const int *_boot_signature; +#define TOCSIG_ADDR ((const void *)&_toc_signature) +#define TOCSIG_END ((const void *)((const uint8_t *)TOCSIG_ADDR+SIGNATURE_SIZE)) -#define BOOT_ADDR _vectors -#define BOOT_END ((const void *)&_boot_signature) +/* Boot image starts at __start and ends at + * the beginning of signature, but for protected/kernel mode we don't know + * their locations. Assume binary file start and binary file end ? +*/ +extern const uintptr_t _app_start; +extern const uintptr_t _app_end; + +#define BOOT_ADDR &_app_start +#define BOOT_END ((const void *)&_app_end) /* Boot signature start and end are defined by the * signature definition below */ +extern const uintptr_t _boot_signature; #define BOOTSIG_ADDR ((const void *)&_boot_signature) #define BOOTSIG_END ((const void *)((const uint8_t *)BOOTSIG_ADDR+SIGNATURE_SIZE)) @@ -64,13 +79,19 @@ extern const int *_boot_signature; /* The table of contents */ -IMAGE_MAIN_TOC(4) = { +IMAGE_MAIN_TOC(6) = { {TOC_START_MAGIC, TOC_VERSION}, { - {"BOOT", BOOT_ADDR, BOOT_END, 0, 1, 0, 0, TOC_FLAG1_BOOT | TOC_FLAG1_CHECK_SIGNATURE}, + {"TOC", TOC_ADDR, TOC_END, 0, 1, 0, 0, TOC_FLAG1_CHECK_SIGNATURE}, + {"SIG0", TOCSIG_ADDR, TOCSIG_END, 0, 0, 0, 0, 0}, + {"BOOT", BOOT_ADDR, BOOT_END, 0, 3, 0, 0, TOC_FLAG1_BOOT | TOC_FLAG1_CHECK_SIGNATURE}, {"SIG1", BOOTSIG_ADDR, BOOTSIG_END, 0, 0, 0, 0, 0}, - {"RDCT", RDCT_ADDR, RDCT_END, 0, 3, 0, 0, TOC_FLAG1_RDCT | TOC_FLAG1_CHECK_SIGNATURE}, + {"RDCT", RDCT_ADDR, RDCT_END, 0, 5, 0, 0, TOC_FLAG1_RDCT | TOC_FLAG1_CHECK_SIGNATURE}, {"RDSG", RDCTSIG_ADDR, RDCTSIG_END, 0, 0, 0, 0, 0}, }, TOC_END_MAGIC }; + +/* Define a signature area, just for sizing the ToC area */ + +const char _main_toc_sig[SIGNATURE_SIZE] __attribute__((section(".main_toc_sig"))); diff --git a/boards/px4/fmu-v5/ssrc.px4board b/boards/px4/fmu-v5/ssrc.px4board new file mode 100644 index 000000000000..ac15a9d41529 --- /dev/null +++ b/boards/px4/fmu-v5/ssrc.px4board @@ -0,0 +1,21 @@ +CONFIG_BOARD_CRYPTO=y +CONFIG_COMMON_OPTICAL_FLOW=n +CONFIG_COMMON_OSD=n +CONFIG_DRIVERS_CAMERA_CAPTURE=n +CONFIG_DRIVERS_CAMERA_TRIGGER=n +CONFIG_DRIVERS_CAMERA_FEEDBACK=n +CONFIG_DRIVERS_STUB_KEYSTORE=y +CONFIG_DRIVERS_SW_CRYPTO=y +CONFIG_EXAMPLES_FAKE_GPS=n +CONFIG_MODULES_ROVER_POS_CONTROL=n +CONFIG_SYSTEMCMDS_REFLECT=n +CONFIG_SYSTEMCMDS_SD_BENCH=n +CONFIG_SYSTEMCMDS_SD_STRESS=n +CONFIG_SYSTEMCMDS_SERIAL_TEST=n +CONFIG_SYSTEMCMDS_I2CDETECT=n + +# Test keys to help local building +# These can be overridden in CI with environment variables pointing to real keys +CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY2="../../../Tools/test_keys/rsa2048.pub" diff --git a/boards/px4/fmu-v5x/init/rc.board_mavlink b/boards/px4/fmu-v5x/init/rc.board_mavlink index dad84376ce73..0d69e36794f6 100644 --- a/boards/px4/fmu-v5x/init/rc.board_mavlink +++ b/boards/px4/fmu-v5x/init/rc.board_mavlink @@ -8,3 +8,12 @@ then # Start MAVLink on the UART connected to the mission computer mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z fi + +# Start MC flight control mavlink to ethernet interface +mavlink start -c 192.168.200.100 -u 14541 -o 14540 -r 2000000 -x + +# Start uXRCE-DDS client on UDP +microdds_client start -t udp -h 192.168.200.100 -r 2019 -p 2020 + +# Start MC maintenance mavlink to ethernet interface +#mavlink start -c 192.168.200.100 -u 14543 -o 14542 -r 2000000 -m magic -x diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld index 8d5a78da6bfc..0d7c9d34199b 100644 --- a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld @@ -82,7 +82,7 @@ MEMORY OUTPUT_ARCH(arm) EXTERN(_vectors) -ENTRY(_stext) +ENTRY(_vectors) /* * Ensure that abort() is present in the final object. The exception handling @@ -90,13 +90,33 @@ ENTRY(_stext) */ EXTERN(abort) EXTERN(_bootdelay_signature) -EXTERN(board_get_manifest) +EXTERN(_main_toc) +EXTERN(_main_toc_sig) SECTIONS { - .text : { + /* Provide dummy relocation symbols for the dummy ToC */ + PROVIDE(_toc_start = 0); + PROVIDE(_toc_end = 0); + PROVIDE(_toc_signature = 0); + PROVIDE(_app_start = 0); + PROVIDE(_app_end = 0); + PROVIDE(_boot_signature = 0); + + /* Make a hole for the ToC and signature */ + toc (NOLOAD) : { + *(.main_toc) + *(.main_toc_sig) + FILL(0xff); + . = ALIGN(8); + } > FLASH_AXIM + + .vectors : { _stext = ABSOLUTE(.); *(.vectors) + } > FLASH_AXIM + + .text : { . = ALIGN(32); /* This signature provides the bootloader with a way to delay booting @@ -127,14 +147,6 @@ SECTIONS _einit = ABSOLUTE(.); } > FLASH_AXIM - /* - * Construction data for parameters. - */ - __param ALIGN(4): { - __param_start = ABSOLUTE(.); - KEEP(*(__param*)) - __param_end = ABSOLUTE(.); - } > FLASH_AXIM .ARM.extab : { *(.ARM.extab*) diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld new file mode 100644 index 000000000000..0653e72606b4 --- /dev/null +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld @@ -0,0 +1,61 @@ +/**************************************************************************** + * boards/risc-v/icicle/mpfs/scripts/ld.script + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you 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. + * + ****************************************************************************/ + +MEMORY +{ + progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K +} + +OUTPUT_ARCH("arm") + +EXTERN(_main_toc) + +SECTIONS +{ + .toc : { + /* The ToC */ + _toc_start = ABSOLUTE(.); + KEEP(*(.main_toc)); + /* Padd the rest */ + FILL(0xff); + . = ALIGN(8); + _toc_end = ABSOLUTE(.); + } > progmem + + /* Start of the ToC signature, appended directly after ToC */ + PROVIDE(_toc_signature = ALIGN(4)); + + .toc_sig (NOLOAD) : { + /* Make a hole for the singature */ + KEEP(*(.main_toc_sig)); + } > progmem + + .app (NOLOAD) : { + /* The application firmware payload */ + _app_start = ABSOLUTE(.); + *(.firmware) + _app_end = ABSOLUTE(.); + } > progmem + + /* Start of the payload signature. This has to be in the end of the + * payload and aligned to a 4 byte boundary + */ + PROVIDE(_boot_signature = ALIGN(4)); +} diff --git a/boards/px4/fmu-v5x/nuttx-config/ssrc/defconfig b/boards/px4/fmu-v5x/nuttx-config/ssrc/defconfig new file mode 100644 index 000000000000..5ad4e11f54df --- /dev/null +++ b/boards/px4/fmu-v5x/nuttx-config/ssrc/defconfig @@ -0,0 +1,314 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_FS_PROCFS_EXCLUDE_MEMINFO is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DMESG is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_UPTIME is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/px4/fmu-v5x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32f7" +CONFIG_ARCH_CHIP_STM32F765II=y +CONFIG_ARCH_CHIP_STM32F7=y +CONFIG_ARCH_INTERRUPTSTACK=1024 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0033 +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Auterion" +CONFIG_CRYPTO=y +CONFIG_CRYPTO_RANDOM_POOL=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FILE_STREAM=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_FS_SHMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2944 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_NETDB=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIBM_TOOLCHAIN=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=3 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=48 +CONFIG_NET=y +CONFIG_NETDEV_IFINDEX=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DRIPADDR=0xc0a8c864 +CONFIG_NETINIT_IPADDR=0xc0a8c865 +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_NOTIFIER=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_NOTIFIER=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32F7_ADC1=y +CONFIG_STM32F7_ADC3=y +CONFIG_STM32F7_BBSRAM=y +CONFIG_STM32F7_BBSRAM_FILES=5 +CONFIG_STM32F7_BKPSRAM=y +CONFIG_STM32F7_DMA1=y +CONFIG_STM32F7_DMA2=y +CONFIG_STM32F7_DMACAPABLE=y +CONFIG_STM32F7_ETHMAC=y +CONFIG_STM32F7_FLOWCONTROL_BROKEN=y +CONFIG_STM32F7_I2C1=y +CONFIG_STM32F7_I2C2=y +CONFIG_STM32F7_I2C3=y +CONFIG_STM32F7_I2C4=y +CONFIG_STM32F7_I2C_DYNTIMEO=y +CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32F7_OTGFS=y +CONFIG_STM32F7_PHYADDR=0 +CONFIG_STM32F7_PHYSR=31 +CONFIG_STM32F7_PHYSR_100MBPS=0x8 +CONFIG_STM32F7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32F7_PHYSR_MODE=0x10 +CONFIG_STM32F7_PHYSR_SPEED=0x8 +CONFIG_STM32F7_PHY_POLLING=y +CONFIG_STM32F7_PROGMEM=y +CONFIG_STM32F7_PWR=y +CONFIG_STM32F7_RTC=y +CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32F7_RTC_MAGIC_REG=1 +CONFIG_STM32F7_SAVE_CRASHDUMP=y +CONFIG_STM32F7_SDMMC2=y +CONFIG_STM32F7_SDMMC_DMA=y +CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32F7_SPI1=y +CONFIG_STM32F7_SPI1_DMA=y +CONFIG_STM32F7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI2=y +CONFIG_STM32F7_SPI2_DMA=y +CONFIG_STM32F7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32F7_SPI3=y +CONFIG_STM32F7_SPI3_DMA=y +CONFIG_STM32F7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI5=y +CONFIG_STM32F7_SPI6=y +CONFIG_STM32F7_SPI_DMATHRESHOLD=8 +CONFIG_STM32F7_TIM10=y +CONFIG_STM32F7_TIM11=y +CONFIG_STM32F7_TIM3=y +CONFIG_STM32F7_TIM9=y +CONFIG_STM32F7_UART4=y +CONFIG_STM32F7_UART5=y +CONFIG_STM32F7_UART7=y +CONFIG_STM32F7_UART8=y +CONFIG_STM32F7_USART1=y +CONFIG_STM32F7_USART2=y +CONFIG_STM32F7_USART3=y +CONFIG_STM32F7_USART6=y +CONFIG_STM32F7_USART_BREAKS=y +CONFIG_STM32F7_USART_INVERT=y +CONFIG_STM32F7_USART_SINGLEWIRE=y +CONFIG_STM32F7_USART_SWAP=y +CONFIG_STM32F7_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=3000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_RXDMA=y +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/px4/fmu-v5x/src/CMakeLists.txt b/boards/px4/fmu-v5x/src/CMakeLists.txt index 684b11736eda..e07012a91592 100644 --- a/boards/px4/fmu-v5x/src/CMakeLists.txt +++ b/boards/px4/fmu-v5x/src/CMakeLists.txt @@ -42,6 +42,7 @@ add_library(drivers_board spi.cpp timer_config.cpp usb.c + toc.c ) add_dependencies(drivers_board platform_gpio_mcp23009) diff --git a/boards/px4/fmu-v5x/src/toc.c b/boards/px4/fmu-v5x/src/toc.c new file mode 100644 index 000000000000..ba9ff4d033bb --- /dev/null +++ b/boards/px4/fmu-v5x/src/toc.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * Copyright (C) 2020 Technology Innovation Institute. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#include + +/* (Maximum) size of the signature */ + +#define SIGNATURE_SIZE 64 + +/* ToC area boundaries */ +extern const uintptr_t _toc_start; +extern const uintptr_t _toc_end; + +#define TOC_ADDR &_toc_start +#define TOC_END ((const void *)&_toc_end) + +/* ToC signature */ +extern const uintptr_t _toc_signature; + +#define TOCSIG_ADDR ((const void *)&_toc_signature) +#define TOCSIG_END ((const void *)((const uint8_t *)TOCSIG_ADDR+SIGNATURE_SIZE)) + +/* Boot image starts at __start and ends at + * the beginning of signature, but for protected/kernel mode we don't know + * their locations. Assume binary file start and binary file end ? +*/ +extern const uintptr_t _app_start; +extern const uintptr_t _app_end; + +#define BOOT_ADDR &_app_start +#define BOOT_END ((const void *)&_app_end) + +/* Boot signature start and end are defined by the + * signature definition below +*/ +extern const uintptr_t _boot_signature; + +#define BOOTSIG_ADDR ((const void *)&_boot_signature) +#define BOOTSIG_END ((const void *)((const uint8_t *)BOOTSIG_ADDR+SIGNATURE_SIZE)) + +/* RD certifcate may follow boot signature */ + +#define RDCT_ADDR BOOTSIG_END +#define RDCT_END ((const void *)((const uint8_t*)BOOTSIG_END+sizeof(image_cert_t))) + +/* RD certificate signature follows the certificate */ + +#define RDCTSIG_ADDR RDCT_END +#define RDCTSIG_END ((const void *)((const uint8_t*)RDCTSIG_ADDR+SIGNATURE_SIZE)) + +/* The table of contents */ + +IMAGE_MAIN_TOC(6) = { + {TOC_START_MAGIC, TOC_VERSION}, + { + {"TOC", TOC_ADDR, TOC_END, 0, 1, 0, 0, TOC_FLAG1_CHECK_SIGNATURE}, + {"SIG0", TOCSIG_ADDR, TOCSIG_END, 0, 0, 0, 0, 0}, + {"BOOT", BOOT_ADDR, BOOT_END, 0, 3, 0, 0, TOC_FLAG1_BOOT | TOC_FLAG1_CHECK_SIGNATURE}, + {"SIG1", BOOTSIG_ADDR, BOOTSIG_END, 0, 0, 0, 0, 0}, + /* + {"RDCT", RDCT_ADDR, RDCT_END, 0, 5, 0, 0, TOC_FLAG1_RDCT | TOC_FLAG1_CHECK_SIGNATURE}, + {"RDSG", RDCTSIG_ADDR, RDCTSIG_END, 0, 0, 0, 0, 0}, + */ + }, + TOC_END_MAGIC +}; + +/* Define a signature area, just for sizing the ToC area */ + +const char _main_toc_sig[SIGNATURE_SIZE] __attribute__((section(".main_toc_sig"))); diff --git a/boards/px4/fmu-v5x/ssrc.px4board b/boards/px4/fmu-v5x/ssrc.px4board new file mode 100644 index 000000000000..fbeef20f68b2 --- /dev/null +++ b/boards/px4/fmu-v5x/ssrc.px4board @@ -0,0 +1,27 @@ + +# In addition to default.px4foard + +CONFIG_BOARD_CRYPTO=y +CONFIG_DRIVERS_SW_CRYPTO=y +CONFIG_DRIVERS_STUB_KEYSTORE=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y + +# Removed to save space + +CONFIG_COMMON_OPTICAL_FLOW=n +CONFIG_COMMON_OSD=n +CONFIG_DRIVERS_CAMERA_CAPTURE=n +CONFIG_DRIVERS_CAMERA_TRIGGER=n +CONFIG_DRIVERS_CAMERA_FEEDBACK=n +CONFIG_MODULES_PAYLOAD_DELIVERER=n +CONFIG_MODULES_ROVER_POS_CONTROL=n +CONFIG_SYSTEMCMDS_NETMAN=n +CONFIG_SYSTEMCMDS_REFLECT=n +CONFIG_SYSTEMCMDS_SD_BENCH=n +CONFIG_SYSTEMCMDS_SD_STRESS=n + +# Test keys to help local building +# These can be overridden in CI with environment variables pointing to real keys +CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY2="../../../Tools/test_keys/rsa2048.pub" From fa8dd09be511fe6fd1c95c818532333c1616af5c Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 25 Mar 2022 10:18:05 +0200 Subject: [PATCH 006/273] boards/fmu-v5(x): Update the defconfigs for new NuttX Signed-off-by: Jukka Laitinen --- .../fmu-v5/nuttx-config/cryptotest/defconfig | 28 +++++++++++++++ .../px4/fmu-v5/nuttx-config/debug/defconfig | 28 +++++++++++++++ boards/px4/fmu-v5/nuttx-config/nsh/defconfig | 30 ++++++++++++++++ .../fmu-v5/nuttx-config/protected/defconfig | 28 +++++++++++++++ .../fmu-v5/nuttx-config/stackcheck/defconfig | 28 +++++++++++++++ boards/px4/fmu-v5x/nuttx-config/nsh/defconfig | 34 +++++++++++++++++++ 6 files changed, 176 insertions(+) diff --git a/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig b/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig index ff995b6cf5bb..8b9bceb4cbb4 100644 --- a/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig @@ -134,6 +134,34 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 diff --git a/boards/px4/fmu-v5/nuttx-config/debug/defconfig b/boards/px4/fmu-v5/nuttx-config/debug/defconfig index 74f4ecac3c7c..a7ea4e784241 100644 --- a/boards/px4/fmu-v5/nuttx-config/debug/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/debug/defconfig @@ -178,6 +178,34 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 diff --git a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig index b0453967b2a9..4f92a79ff28f 100644 --- a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig @@ -90,6 +90,7 @@ CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 CONFIG_EXAMPLES_CALIB_UDELAY=y +CONFIG_DISABLE_PTHREAD=n CONFIG_FAT_DMAMEMORY=y CONFIG_FAT_LCNAMES=y CONFIG_FAT_LFN=y @@ -104,6 +105,7 @@ CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_FS_PROCFS_REGISTER=y CONFIG_FS_ROMFS=y +CONFIG_FS_SHMSF=y CONFIG_GRAN=y CONFIG_GRAN_INTR=y CONFIG_HAVE_CXX=y @@ -132,6 +134,34 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 diff --git a/boards/px4/fmu-v5/nuttx-config/protected/defconfig b/boards/px4/fmu-v5/nuttx-config/protected/defconfig index 1902014e3b08..24bbc8cf4c77 100644 --- a/boards/px4/fmu-v5/nuttx-config/protected/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/protected/defconfig @@ -137,6 +137,34 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index c5450ab1f4f9..8ef7d34d1f13 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -133,6 +133,34 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 diff --git a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig index 5de6af261f5f..996e9b9ae38c 100644 --- a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig @@ -93,6 +93,7 @@ CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_GPIO=y CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DISABLE_PTHREAD=n CONFIG_ETH0_PHY_LAN8742A=y CONFIG_FAT_DMAMEMORY=y CONFIG_FAT_LCNAMES=y @@ -109,6 +110,7 @@ CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_FS_PROCFS_REGISTER=y CONFIG_FS_ROMFS=y +CONFIG_FS_SHMFS=y CONFIG_GRAN=y CONFIG_GRAN_INTR=y CONFIG_HAVE_CXX=y @@ -136,6 +138,7 @@ CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 CONFIG_NET=y CONFIG_NETDB_DNSCLIENT=y CONFIG_NETDB_DNSCLIENT_ENTRIES=8 @@ -169,6 +172,37 @@ CONFIG_NSH_ARGCAT=y CONFIG_NSH_BUILTIN_APPS=y CONFIG_NSH_CMDPARMS=y CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_CUSTOMROMFS=y +CONFIG_NSH_CUSTOMROMFS_HEADER="../../include/nsh_romfsimg.h" +CONFIG_NSH_DISABLE_CAT=n +CONFIG_NSH_DISABLE_CD=n +CONFIG_NSH_DISABLE_CP=n +CONFIG_NSH_DISABLE_DATE=n +CONFIG_NSH_DISABLE_ECHO=n +CONFIG_NSH_DISABLE_ENV=n +CONFIG_NSH_DISABLE_EXPORT=n +CONFIG_NSH_DISABLE_FREE=n +CONFIG_NSH_DISABLE_HELP=n +CONFIG_NSH_DISABLE_IFCONFIG=n +CONFIG_NSH_DISABLE_IFUPDOWN=n +CONFIG_NSH_DISABLE_KILL=n +CONFIG_NSH_DISABLE_LS=n +CONFIG_NSH_DISABLE_MKDIR=n +CONFIG_NSH_DISABLE_MOUNT=n +CONFIG_NSH_DISABLE_MV=n +CONFIG_NSH_DISABLE_PS=n +CONFIG_NSH_DISABLE_PSSTACKUSAGE=n +CONFIG_NSH_DISABLE_PWD=n +CONFIG_NSH_DISABLE_RM=n +CONFIG_NSH_DISABLE_RMDIR=n +CONFIG_NSH_DISABLE_SET=n +CONFIG_NSH_DISABLE_SOURCE=n +CONFIG_NSH_DISABLE_SLEEP=n +CONFIG_NSH_DISABLE_TEST=n +CONFIG_NSH_DISABLE_TELNETD=n +CONFIG_NSH_DISABLE_UMOUNT=n +CONFIG_NSH_DISABLE_UNSET=n +CONFIG_NSH_DISABLE_USLEEP=n CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_NESTDEPTH=8 From 8098aee03ab8fbb42471493bbe157be059a98434 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Fri, 21 Oct 2022 13:05:49 +0300 Subject: [PATCH 007/273] boards/xx/toc: Make sure there is room for the firmware signature --- boards/px4/fmu-v5/nuttx-config/scripts/toc.ld | 3 ++- boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld index 0653e72606b4..540b219ff408 100644 --- a/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld +++ b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld @@ -20,7 +20,8 @@ MEMORY { - progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K + /* -64 <- Leave room for the signature */ + progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K - 64 } OUTPUT_ARCH("arm") diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld index 0653e72606b4..540b219ff408 100644 --- a/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld @@ -20,7 +20,8 @@ MEMORY { - progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K + /* -64 <- Leave room for the signature */ + progmem (r) : ORIGIN = 0x08008000, LENGTH = 2016K - 64 } OUTPUT_ARCH("arm") From e1bbedd5444219507282487f37925c9d86a13ef9 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Mon, 19 Sep 2022 14:23:41 +0300 Subject: [PATCH 008/273] boards/fmuv5/x: Fix multiple alignment issues - The vector table needs to be aligned correctly, depends on the amount of interrupts. 4K should be enough for this target. - Padd the firmware to the correct size, the signature must start at a 4B alignment. - The firmware end address needs to be aligned as well, because the calculated signature size is the firmware size + the additional padding --- boards/px4/fmu-v5/nuttx-config/scripts/script.ld | 6 +++--- boards/px4/fmu-v5/nuttx-config/scripts/toc.ld | 3 ++- boards/px4/fmu-v5x/nuttx-config/scripts/script.ld | 6 +++--- boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld | 3 ++- 4 files changed, 10 insertions(+), 8 deletions(-) diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld index 0d7c9d34199b..4aa8307a9b8f 100644 --- a/boards/px4/fmu-v5/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5/nuttx-config/scripts/script.ld @@ -104,20 +104,20 @@ SECTIONS PROVIDE(_boot_signature = 0); /* Make a hole for the ToC and signature */ - toc (NOLOAD) : { + .toc (NOLOAD) : { *(.main_toc) *(.main_toc_sig) FILL(0xff); - . = ALIGN(8); + . = ALIGN(0x1000); } > FLASH_AXIM .vectors : { _stext = ABSOLUTE(.); *(.vectors) + . = ALIGN(32); } > FLASH_AXIM .text : { - . = ALIGN(32); /* This signature provides the bootloader with a way to delay booting */ diff --git a/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld index 540b219ff408..b68869ab9fb6 100644 --- a/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld +++ b/boards/px4/fmu-v5/nuttx-config/scripts/toc.ld @@ -36,7 +36,7 @@ SECTIONS KEEP(*(.main_toc)); /* Padd the rest */ FILL(0xff); - . = ALIGN(8); + . = 0x1000 - 64; _toc_end = ABSOLUTE(.); } > progmem @@ -52,6 +52,7 @@ SECTIONS /* The application firmware payload */ _app_start = ABSOLUTE(.); *(.firmware) + . = ALIGN(4); _app_end = ABSOLUTE(.); } > progmem diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld index 0d7c9d34199b..4aa8307a9b8f 100644 --- a/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/script.ld @@ -104,20 +104,20 @@ SECTIONS PROVIDE(_boot_signature = 0); /* Make a hole for the ToC and signature */ - toc (NOLOAD) : { + .toc (NOLOAD) : { *(.main_toc) *(.main_toc_sig) FILL(0xff); - . = ALIGN(8); + . = ALIGN(0x1000); } > FLASH_AXIM .vectors : { _stext = ABSOLUTE(.); *(.vectors) + . = ALIGN(32); } > FLASH_AXIM .text : { - . = ALIGN(32); /* This signature provides the bootloader with a way to delay booting */ diff --git a/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld index 540b219ff408..b68869ab9fb6 100644 --- a/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld +++ b/boards/px4/fmu-v5x/nuttx-config/scripts/toc.ld @@ -36,7 +36,7 @@ SECTIONS KEEP(*(.main_toc)); /* Padd the rest */ FILL(0xff); - . = ALIGN(8); + . = 0x1000 - 64; _toc_end = ABSOLUTE(.); } > progmem @@ -52,6 +52,7 @@ SECTIONS /* The application firmware payload */ _app_start = ABSOLUTE(.); *(.firmware) + . = ALIGN(4); _app_end = ABSOLUTE(.); } > progmem From e93a4df907b53e895d9e3f82d4f0faa3a5790734 Mon Sep 17 00:00:00 2001 From: Jari Nippula Date: Thu, 11 Aug 2022 08:24:44 +0300 Subject: [PATCH 009/273] fmuv5x: include board_ctrl.h --- boards/px4/fmu-v5x/src/board_config.h | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v5x/src/board_config.h b/boards/px4/fmu-v5x/src/board_config.h index 281c769f2646..096f344e9c91 100644 --- a/boards/px4/fmu-v5x/src/board_config.h +++ b/boards/px4/fmu-v5x/src/board_config.h @@ -43,6 +43,7 @@ * Included Files ****************************************************************************************************/ +#include #include #include #include From 19cfd3c90f1ccb5fb976cd110f5c345eed2f7c66 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Wed, 25 Jan 2023 17:54:07 +0400 Subject: [PATCH 010/273] Set logger buffer to 8k for fmu-v5x We are running short of RAM, and don't need 64k buffer for it Signed-off-by: Jukka Laitinen --- boards/px4/fmu-v5x/init/rc.board_defaults | 2 ++ 1 file changed, 2 insertions(+) diff --git a/boards/px4/fmu-v5x/init/rc.board_defaults b/boards/px4/fmu-v5x/init/rc.board_defaults index ba812e4b7bfd..b9a040d9a3a0 100644 --- a/boards/px4/fmu-v5x/init/rc.board_defaults +++ b/boards/px4/fmu-v5x/init/rc.board_defaults @@ -19,3 +19,5 @@ param set-default SENS_EN_INA226 1 param set-default SYS_USE_IO 1 safety_button start + +set LOGGER_BUF 8 From 191bc15b3ee20c57fc3380e6652276f8023bdebd Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Thu, 13 Apr 2023 14:56:54 +0300 Subject: [PATCH 011/273] Link board_bus_info into px4_platform Separate bus info into own library also for pixhawk 5x and link it always to px4_platform for real targets Signed-off-by: Jukka Laitinen --- boards/px4/fmu-v5x/src/CMakeLists.txt | 9 +++++++-- platforms/common/CMakeLists.txt | 4 ++++ 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/boards/px4/fmu-v5x/src/CMakeLists.txt b/boards/px4/fmu-v5x/src/CMakeLists.txt index e07012a91592..def8804acf95 100644 --- a/boards/px4/fmu-v5x/src/CMakeLists.txt +++ b/boards/px4/fmu-v5x/src/CMakeLists.txt @@ -31,15 +31,19 @@ # ############################################################################ +add_library(board_bus_info + i2c.cpp + spi.cpp +) +add_dependencies(board_bus_info nuttx_context) + add_library(drivers_board can.c - i2c.cpp init.cpp led.c manifest.c mtd.cpp sdio.c - spi.cpp timer_config.cpp usb.c toc.c @@ -56,5 +60,6 @@ target_link_libraries(drivers_board nuttx_arch # sdio nuttx_drivers # sdio px4_layer + board_bus_info platform_gpio_mcp23009 ) diff --git a/platforms/common/CMakeLists.txt b/platforms/common/CMakeLists.txt index a6e06b9d4735..fb9cd36cd457 100644 --- a/platforms/common/CMakeLists.txt +++ b/platforms/common/CMakeLists.txt @@ -60,6 +60,10 @@ if(NOT "${PX4_BOARD}" MATCHES "io-v2") add_subdirectory(uORB) endif() +if(NOT "${PX4_PLATFORM}" MATCHES "posix") + target_link_libraries(px4_platform board_bus_info) +endif() + add_subdirectory(px4_work_queue) add_subdirectory(work_queue) From 0864599b4c74461d11f6a27fd6adfcc622bb725c Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Tue, 13 Sep 2022 09:45:06 +0300 Subject: [PATCH 012/273] px4_work_queue: Fix work queue atomic sections for NuttX user space User space code cannot use critical sections, use a semaphore in that case. The kernel side still uses critical sections. Note: This cannot be done by ifdef-flagging, as the user-/kernel side use the same work_queue.a library. --- .../px4_work_queue/WorkQueue.hpp | 11 ++++ platforms/nuttx/src/px4/common/CMakeLists.txt | 1 + .../include/px4_platform/atomic_block.h | 59 +++++++++++++++++++ platforms/nuttx/src/px4/common/px4_atomic.cpp | 59 +++++++++++++++++++ .../src/px4/common/px4_protected_layers.cmake | 1 + platforms/nuttx/src/px4/common/usr_atomic.cpp | 59 +++++++++++++++++++ 6 files changed, 190 insertions(+) create mode 100644 platforms/nuttx/src/px4/common/include/px4_platform/atomic_block.h create mode 100644 platforms/nuttx/src/px4/common/px4_atomic.cpp create mode 100644 platforms/nuttx/src/px4/common/usr_atomic.cpp diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueue.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueue.hpp index f2a66bb8983c..5381e76a5f14 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueue.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueue.hpp @@ -43,6 +43,10 @@ #include #include +#ifdef __PX4_NUTTX +# include +#endif + namespace px4 { @@ -84,9 +88,16 @@ class WorkQueue : public IntrusiveSortedListNode #ifdef __PX4_NUTTX // In NuttX work can be enqueued from an ISR +#ifdef CONFIG_BUILD_FLAT void work_lock() { _flags = enter_critical_section(); } void work_unlock() { leave_critical_section(_flags); } irqstate_t _flags; +#else + // For non-flat targets, work is enqueued by user threads as well + void work_lock() { _atomic.start(); } + void work_unlock() { _atomic.finish(); } + atomic_block _atomic; +#endif #else // loop as the wait may be interrupted by a signal void work_lock() { do {} while (px4_sem_wait(&_qlock) != 0); } diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index ab16e77a0e30..e0cef6502b4d 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -44,6 +44,7 @@ if(NOT PX4_BOARD MATCHES "io-v2") gpio.c print_load.cpp tasks.cpp + px4_atomic.cpp px4_nuttx_impl.cpp px4_init.cpp px4_manifest.cpp diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/atomic_block.h b/platforms/nuttx/src/px4/common/include/px4_platform/atomic_block.h new file mode 100644 index 000000000000..f95d08ed858c --- /dev/null +++ b/platforms/nuttx/src/px4/common/include/px4_platform/atomic_block.h @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2022 Technology Innovation Institute. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include + +#include + +#include + +namespace px4 +{ + +class atomic_block +{ +public: + atomic_block(); + ~atomic_block(); + void start(); + void finish(); +private: + union { + px4_sem_t _lock; + irqstate_t _irqlock; + }; +}; + +} diff --git a/platforms/nuttx/src/px4/common/px4_atomic.cpp b/platforms/nuttx/src/px4/common/px4_atomic.cpp new file mode 100644 index 000000000000..819dbc6ecc8b --- /dev/null +++ b/platforms/nuttx/src/px4/common/px4_atomic.cpp @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2022 Technology Innovation Institute. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +namespace px4 +{ + +atomic_block::atomic_block(void) +{ + _irqlock = 0; +} + +atomic_block::~atomic_block(void) +{ + +} + +void atomic_block::start(void) +{ + _irqlock = enter_critical_section(); +} + +void atomic_block::finish(void) +{ + leave_critical_section(_irqlock); +} + +} diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index 7f76502e6842..c7a9b56ce064 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -12,6 +12,7 @@ add_library(px4_layer px4_userspace_init.cpp px4_usr_crypto.cpp px4_mtd.cpp + usr_atomic.cpp usr_board_ctrl.c usr_hrt.cpp usr_mcu_version.cpp diff --git a/platforms/nuttx/src/px4/common/usr_atomic.cpp b/platforms/nuttx/src/px4/common/usr_atomic.cpp new file mode 100644 index 000000000000..b1221e4e1132 --- /dev/null +++ b/platforms/nuttx/src/px4/common/usr_atomic.cpp @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2022 Technology Innovation Institute. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +namespace px4 +{ + +atomic_block::atomic_block(void) +{ + px4_sem_init(&_lock, 0, 1); +} + +atomic_block::~atomic_block(void) +{ + px4_sem_destroy(&_lock); +} + +void atomic_block::start(void) +{ + do {} while (px4_sem_wait(&_lock) != 0); +} + +void atomic_block::finish(void) +{ + px4_sem_post(&_lock); +} + +} From a69f22fec801b23ddd05f3153c293fceea7dae90 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 23 Nov 2022 11:11:38 +0200 Subject: [PATCH 013/273] platforms/nuttx: Add wrapper for queue.h For some reason the queue.h header was moved, add this wrapper so posix and nuttx builds can both still use #include --- platforms/nuttx/NuttX/include/queue.h | 38 +++++++++++++++++++++++++ platforms/nuttx/cmake/px4_impl_os.cmake | 1 + 2 files changed, 39 insertions(+) create mode 100644 platforms/nuttx/NuttX/include/queue.h diff --git a/platforms/nuttx/NuttX/include/queue.h b/platforms/nuttx/NuttX/include/queue.h new file mode 100644 index 000000000000..1b8819873f45 --- /dev/null +++ b/platforms/nuttx/NuttX/include/queue.h @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * Copyright (c) 2022 Technology Innovation Institute. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/* Wrapper for nuttx/queue.h */ + +#include diff --git a/platforms/nuttx/cmake/px4_impl_os.cmake b/platforms/nuttx/cmake/px4_impl_os.cmake index 4c5cbab4ef6c..e4b14c5410e7 100644 --- a/platforms/nuttx/cmake/px4_impl_os.cmake +++ b/platforms/nuttx/cmake/px4_impl_os.cmake @@ -62,6 +62,7 @@ function(px4_os_add_flags) ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/${CONFIG_ARCH}/src/common ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/apps/include + ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/include ) From da6b62ae37e532f5727ab1da490b2de50f65fb0e Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Wed, 14 Sep 2022 14:22:18 +0400 Subject: [PATCH 014/273] Fix crc32.h include paths for new NuttX Signed-off-by: Jukka Laitinen --- platforms/nuttx/src/px4/common/progmem_dump.c | 2 +- src/drivers/px4io/px4io.cpp | 4 ++++ src/drivers/px4io/px4io_uploader.cpp | 4 ++++ src/lib/parameters/flashparams/flashfs.c | 4 ++++ src/lib/parameters/parameters.cpp | 4 ++++ src/modules/mavlink/mavlink_ftp.cpp | 4 ++++ 6 files changed, 21 insertions(+), 1 deletion(-) diff --git a/platforms/nuttx/src/px4/common/progmem_dump.c b/platforms/nuttx/src/px4/common/progmem_dump.c index e37a6dd697e6..f360f9b68719 100644 --- a/platforms/nuttx/src/px4/common/progmem_dump.c +++ b/platforms/nuttx/src/px4/common/progmem_dump.c @@ -51,7 +51,7 @@ #include #include -#include +#include #ifdef CONFIG_BOARD_CRASHDUMP diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 21c0a53b2bfc..7aac86b123dc 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -45,7 +45,11 @@ #include #include +#if defined(__PX4_NUTTX) +#include +#else #include +#endif #include #include diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index 4010e0d5133e..17ae86a507f5 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -55,7 +55,11 @@ #include #include +#if defined(__PX4_NUTTX) +#include +#else #include +#endif #include "uploader.h" diff --git a/src/lib/parameters/flashparams/flashfs.c b/src/lib/parameters/flashparams/flashfs.c index a692b62048dc..bbbab3a0abb8 100644 --- a/src/lib/parameters/flashparams/flashfs.c +++ b/src/lib/parameters/flashparams/flashfs.c @@ -44,7 +44,11 @@ #include #include +#if defined(__PX4_NUTTX) +#include +#else #include +#endif #include #include #include diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index 84a5da768287..c1f85147d780 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -47,7 +47,11 @@ #include #include +#if defined(__PX4_NUTTX) +#include +#else #include +#endif #include #include diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 9d078b16b090..5770880a0572 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -34,7 +34,11 @@ /// @file mavlink_ftp.cpp /// @author px4dev, Don Gagne +#if defined(__PX4_NUTTX) +#include +#else #include +#endif #include #include #include From 08093e8b4284224fe9f590d67ee12e76e6090ea6 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Wed, 7 Dec 2022 13:46:37 +0400 Subject: [PATCH 015/273] src/lib/cdev/posix/cdev_platform.cpp: change fds.sem -> fds.arg acc. to the nuttx poll_fds type Signed-off-by: Jukka Laitinen --- src/lib/cdev/posix/cdev_platform.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/cdev/posix/cdev_platform.cpp b/src/lib/cdev/posix/cdev_platform.cpp index 0a977a1bba16..bcf3783fb641 100644 --- a/src/lib/cdev/posix/cdev_platform.cpp +++ b/src/lib/cdev/posix/cdev_platform.cpp @@ -363,7 +363,7 @@ extern "C" { bool fd_pollable = false; for (unsigned int i = 0; i < nfds; ++i) { - fds[i].sem = &sem; + fds[i].arg = &sem; fds[i].revents = 0; fds[i].priv = nullptr; From 460c97e83f75ebd99a783b2117d564fa6f5fdc47 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 25 Mar 2022 11:46:50 +0200 Subject: [PATCH 016/273] [TO_UPSTREAM] Fix uORB linking for protected build Signed-off-by: Jukka Laitinen --- platforms/common/uORB/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/common/uORB/CMakeLists.txt b/platforms/common/uORB/CMakeLists.txt index c151d051c747..6330132cb03d 100644 --- a/platforms/common/uORB/CMakeLists.txt +++ b/platforms/common/uORB/CMakeLists.txt @@ -72,7 +72,7 @@ if (NOT DEFINED CONFIG_BUILD_FLAT AND "${PX4_PLATFORM}" MATCHES "nuttx") ${SRCS_COMMON} ${SRCS_KERNEL} ) - target_link_libraries(uORB_kernel PRIVATE cdev uorb_msgs nuttx_mm) + target_link_libraries(uORB_kernel PRIVATE cdev uorb_msgs nuttx_kmm) target_compile_options(uORB_kernel PRIVATE ${MAX_CUSTOM_OPT_LEVEL} -D__KERNEL__) # User side library in nuttx kernel/protected build From bc20a6681cac9be46a2931ec6e448f1effba5950 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 23 Nov 2022 12:57:26 +0200 Subject: [PATCH 017/273] lib/cdev: struct pollfd no longer has a member called *sem The member sem was changed to a "more flexible" member called *arg. Currently the contents of arg is the semaphore handle, so just cast it to correct type to fix the build error and wait for a disaster to happen when this no longer applies... --- platforms/common/include/px4_platform_common/posix.h | 2 +- src/lib/cdev/CDev.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/platforms/common/include/px4_platform_common/posix.h b/platforms/common/include/px4_platform_common/posix.h index e4d639919072..29c83ff2c6c6 100644 --- a/platforms/common/include/px4_platform_common/posix.h +++ b/platforms/common/include/px4_platform_common/posix.h @@ -92,7 +92,7 @@ typedef struct { px4_pollevent_t revents; /* The output event flags */ /* Required for PX4 compatibility */ - px4_sem_t *sem; /* Pointer to semaphore used to post output event */ + px4_sem_t *arg; /* Pointer to semaphore used to post output event */ void *priv; /* For use by drivers */ } px4_pollfd_struct_t; diff --git a/src/lib/cdev/CDev.cpp b/src/lib/cdev/CDev.cpp index b5bcce2dd34b..c19a028ad4d8 100644 --- a/src/lib/cdev/CDev.cpp +++ b/src/lib/cdev/CDev.cpp @@ -289,7 +289,7 @@ CDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup) /* yes? post the notification */ if (fds->revents != 0) { - px4_sem_post(fds->sem); + px4_sem_post((px4_sem_t *)fds->arg); } } @@ -336,7 +336,7 @@ CDev::poll_notify_one(px4_pollfd_struct_t *fds, px4_pollevent_t events) PX4_DEBUG(" Events fds=%p %0x %0x %0x", fds, fds->revents, fds->events, events); if (fds->revents != 0) { - px4_sem_post(fds->sem); + px4_sem_post((px4_sem_t *)fds->arg); } } From ae2fce11ab6a1e34b2966f1f21610e54a2bb0b71 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 7 Dec 2022 14:09:05 +0200 Subject: [PATCH 018/273] px4_userspace_init: Initialize px4 logger for user space --- platforms/nuttx/src/px4/common/px4_userspace_init.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp index f5d9882ca23a..56cdcc21735e 100644 --- a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include @@ -56,6 +57,8 @@ extern "C" void px4_userspace_init(void) uorb_start(); + px4_log_initialize(); + #if defined(CONFIG_SYSTEM_CDCACM) cdcacm_init(); #endif From bb34aae3d7ab1a0a4a2b00b90e37f25f08e26164 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Mon, 2 May 2022 12:52:05 +0400 Subject: [PATCH 019/273] uORB: Define subscription base class destructors as virtual Just ot make sure that there are no memory leaks if the objects are deleted via a base class pointer Signed-off-by: Jukka Laitinen --- platforms/common/uORB/Subscription.hpp | 2 +- platforms/common/uORB/SubscriptionInterval.hpp | 2 +- src/drivers/cyphal/legacy_data_types | 1 - 3 files changed, 2 insertions(+), 3 deletions(-) delete mode 160000 src/drivers/cyphal/legacy_data_types diff --git a/platforms/common/uORB/Subscription.hpp b/platforms/common/uORB/Subscription.hpp index 71c8809ad229..30bc61dee90b 100644 --- a/platforms/common/uORB/Subscription.hpp +++ b/platforms/common/uORB/Subscription.hpp @@ -107,7 +107,7 @@ class Subscription return *this; } - ~Subscription() + virtual ~Subscription() { unsubscribe(); } diff --git a/platforms/common/uORB/SubscriptionInterval.hpp b/platforms/common/uORB/SubscriptionInterval.hpp index 31d1b0a7af12..f68231346768 100644 --- a/platforms/common/uORB/SubscriptionInterval.hpp +++ b/platforms/common/uORB/SubscriptionInterval.hpp @@ -83,7 +83,7 @@ class SubscriptionInterval SubscriptionInterval() : _subscription{nullptr} {} - ~SubscriptionInterval() = default; + virtual ~SubscriptionInterval() = default; bool subscribe() { return _subscription.subscribe(); } void unsubscribe() { _subscription.unsubscribe(); } diff --git a/src/drivers/cyphal/legacy_data_types b/src/drivers/cyphal/legacy_data_types deleted file mode 160000 index 36a01e428b11..000000000000 --- a/src/drivers/cyphal/legacy_data_types +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 36a01e428b110ff84c8babe5b65667b5e3037d5e From 2fe7b4810a8431a18317c0d943f80dfcfb324586 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 22 Apr 2022 13:45:18 +0400 Subject: [PATCH 020/273] platforms/common/uORB/uORB.h: Add definition for orb_sub_t and handle check functions Signed-off-by: Jukka Laitinen --- platforms/common/uORB/uORB.h | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/platforms/common/uORB/uORB.h b/platforms/common/uORB/uORB.h index 7fdbb699d1f8..a48302f15f03 100644 --- a/platforms/common/uORB/uORB.h +++ b/platforms/common/uORB/uORB.h @@ -128,6 +128,12 @@ int uorb_top(char **topic_filter, int num_filters); * publisher. */ typedef void *orb_advert_t; +typedef int orb_sub_t; + +static inline bool orb_advert_valid(orb_advert_t handle) {return handle != NULL;} +static const orb_advert_t ORB_ADVERT_INVALID = NULL; +static inline bool orb_sub_valid(orb_sub_t handle) {return handle >= 0;} +static const orb_sub_t ORB_SUB_INVALID = -1; /** * @see uORB::Manager::orb_advertise() @@ -189,27 +195,27 @@ static inline int orb_publish_auto(const struct orb_metadata *meta, orb_advert_t /** * @see uORB::Manager::orb_subscribe() */ -extern int orb_subscribe(const struct orb_metadata *meta) __EXPORT; +extern orb_sub_t orb_subscribe(const struct orb_metadata *meta) __EXPORT; /** * @see uORB::Manager::orb_subscribe_multi() */ -extern int orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) __EXPORT; +extern orb_sub_t orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) __EXPORT; /** * @see uORB::Manager::orb_unsubscribe() */ -extern int orb_unsubscribe(int handle) __EXPORT; +extern int orb_unsubscribe(orb_sub_t handle) __EXPORT; /** * @see uORB::Manager::orb_copy() */ -extern int orb_copy(const struct orb_metadata *meta, int handle, void *buffer) __EXPORT; +extern int orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buffer) __EXPORT; /** * @see uORB::Manager::orb_check() */ -extern int orb_check(int handle, bool *updated) __EXPORT; +extern int orb_check(orb_sub_t handle, bool *updated) __EXPORT; /** * @see uORB::Manager::orb_exists() @@ -227,12 +233,12 @@ extern int orb_group_count(const struct orb_metadata *meta) __EXPORT; /** * @see uORB::Manager::orb_set_interval() */ -extern int orb_set_interval(int handle, unsigned interval) __EXPORT; +extern int orb_set_interval(orb_sub_t handle, unsigned interval) __EXPORT; /** * @see uORB::Manager::orb_get_interval() */ -extern int orb_get_interval(int handle, unsigned *interval) __EXPORT; +extern int orb_get_interval(orb_sub_t handle, unsigned *interval) __EXPORT; /** * Returns the C type string from a short type in o_fields metadata, or nullptr From 369aefcfe66835fe684d886d6f680789dad4b3ea Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Tue, 19 Apr 2022 16:00:45 +0400 Subject: [PATCH 021/273] change subscriber id:s from int to orb_sub_t Signed-off-by: Jukka Laitinen --- platforms/common/uORB/uORB.cpp | 14 ++++---- .../frsky_telemetry/frsky_telemetry.cpp | 2 +- src/drivers/telemetry/hott/messages.cpp | 12 +++---- src/examples/px4_simple_app/px4_simple_app.c | 2 +- .../ArmAuthorization/ArmAuthorization.cpp | 2 +- src/modules/gimbal/input_mavlink.cpp | 32 +++++++++---------- src/modules/gimbal/input_mavlink.h | 16 +++++----- src/modules/gimbal/input_rc.cpp | 4 +-- src/modules/gimbal/input_rc.h | 2 +- src/modules/logger/log_writer_mavlink.cpp | 4 +-- src/modules/logger/log_writer_mavlink.h | 2 +- src/modules/logger/logger.cpp | 10 +++--- src/modules/navigator/navigator.h | 6 ++-- .../simulator_mavlink/SimulatorMavlink.hpp | 2 +- .../temperature_calibration/accel.cpp | 2 +- .../temperature_calibration/accel.h | 2 +- .../temperature_calibration/baro.cpp | 2 +- .../temperature_calibration/baro.h | 2 +- .../temperature_calibration/common.h | 4 +-- .../temperature_calibration/gyro.cpp | 4 +-- .../temperature_calibration/gyro.h | 4 +-- .../temperature_calibration/task.cpp | 2 +- src/systemcmds/tests/test_rc.cpp | 7 ++-- 23 files changed, 70 insertions(+), 69 deletions(-) diff --git a/platforms/common/uORB/uORB.cpp b/platforms/common/uORB/uORB.cpp index 734b8d83f1b4..461a002905d0 100644 --- a/platforms/common/uORB/uORB.cpp +++ b/platforms/common/uORB/uORB.cpp @@ -143,27 +143,27 @@ int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void return uORB::Manager::get_instance()->orb_publish(meta, handle, data); } -int orb_subscribe(const struct orb_metadata *meta) +orb_sub_t orb_subscribe(const struct orb_metadata *meta) { return uORB::Manager::get_instance()->orb_subscribe(meta); } -int orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) +orb_sub_t orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) { return uORB::Manager::get_instance()->orb_subscribe_multi(meta, instance); } -int orb_unsubscribe(int handle) +int orb_unsubscribe(orb_sub_t handle) { return uORB::Manager::get_instance()->orb_unsubscribe(handle); } -int orb_copy(const struct orb_metadata *meta, int handle, void *buffer) +int orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buffer) { return uORB::Manager::get_instance()->orb_copy(meta, handle, buffer); } -int orb_check(int handle, bool *updated) +int orb_check(orb_sub_t handle, bool *updated) { return uORB::Manager::get_instance()->orb_check(handle, updated); } @@ -184,12 +184,12 @@ int orb_group_count(const struct orb_metadata *meta) return instance; } -int orb_set_interval(int handle, unsigned interval) +int orb_set_interval(orb_sub_t handle, unsigned interval) { return uORB::Manager::get_instance()->orb_set_interval(handle, interval); } -int orb_get_interval(int handle, unsigned *interval) +int orb_get_interval(orb_sub_t handle, unsigned *interval) { return uORB::Manager::get_instance()->orb_get_interval(handle, interval); } diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp index 1924b3529fbe..9310e9413a16 100644 --- a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp +++ b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp @@ -396,7 +396,7 @@ static int frsky_telemetry_thread_main(int argc, char *argv[]) float filtered_alt = NAN; float last_baro_alt = 0.f; - int airdata_sub = orb_subscribe(ORB_ID(vehicle_air_data)); + orb_sub_t airdata_sub = orb_subscribe(ORB_ID(vehicle_air_data)); uint32_t lastBATV_ms = 0; uint32_t lastCUR_ms = 0; diff --git a/src/drivers/telemetry/hott/messages.cpp b/src/drivers/telemetry/hott/messages.cpp index 96c2dd338685..5a4c7a6af32d 100644 --- a/src/drivers/telemetry/hott/messages.cpp +++ b/src/drivers/telemetry/hott/messages.cpp @@ -58,12 +58,12 @@ /* The board is very roughly 5 deg warmer than the surrounding air */ #define BOARD_TEMP_OFFSET_DEG 5 -static int _battery_sub = -1; -static int _gps_sub = -1; -static int _home_sub = -1; -static int _airdata_sub = -1; -static int _airspeed_sub = -1; -static int _esc_sub = -1; +static orb_sub_t _battery_sub = ORB_SUB_INVALID; +static orb_sub_t _gps_sub = ORB_SUB_INVALID; +static orb_sub_t _home_sub = ORB_SUB_INVALID; +static orb_sub_t _airdata_sub = ORB_SUB_INVALID; +static orb_sub_t _airspeed_sub = ORB_SUB_INVALID; +static orb_sub_t _esc_sub = ORB_SUB_INVALID; static orb_advert_t _esc_pub = nullptr; diff --git a/src/examples/px4_simple_app/px4_simple_app.c b/src/examples/px4_simple_app/px4_simple_app.c index 25e89efcf1f3..806784159eba 100644 --- a/src/examples/px4_simple_app/px4_simple_app.c +++ b/src/examples/px4_simple_app/px4_simple_app.c @@ -59,7 +59,7 @@ int px4_simple_app_main(int argc, char *argv[]) PX4_INFO("Hello Sky!"); /* subscribe to vehicle_acceleration topic */ - int sensor_sub_fd = orb_subscribe(ORB_ID(vehicle_acceleration)); + orb_sub_t sensor_sub_fd = orb_subscribe(ORB_ID(vehicle_acceleration)); /* limit the update rate to 5 Hz */ orb_set_interval(sensor_sub_fd, 200); diff --git a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp index bfcff4a3aead..a9975f225445 100644 --- a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp +++ b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp @@ -46,7 +46,7 @@ using namespace time_literals; static orb_advert_t *mavlink_log_pub; -static int command_ack_sub = -1; +static orb_sub_t command_ack_sub = ORB_SUB_INVALID; static hrt_abstime auth_timeout; static hrt_abstime auth_req_time; diff --git a/src/modules/gimbal/input_mavlink.cpp b/src/modules/gimbal/input_mavlink.cpp index 78cf6ae806f7..5216bfef64e5 100644 --- a/src/modules/gimbal/input_mavlink.cpp +++ b/src/modules/gimbal/input_mavlink.cpp @@ -51,11 +51,11 @@ InputMavlinkROI::InputMavlinkROI(Parameters ¶meters) : InputMavlinkROI::~InputMavlinkROI() { - if (_vehicle_roi_sub >= 0) { + if (orb_sub_valid(_vehicle_roi_sub)) { orb_unsubscribe(_vehicle_roi_sub); } - if (_position_setpoint_triplet_sub >= 0) { + if (orb_sub_valid(_position_setpoint_triplet_sub)) { orb_unsubscribe(_position_setpoint_triplet_sub); } } @@ -64,13 +64,13 @@ int InputMavlinkROI::initialize() { _vehicle_roi_sub = orb_subscribe(ORB_ID(vehicle_roi)); - if (_vehicle_roi_sub < 0) { + if (!orb_sub_valid(_vehicle_roi_sub)) { return -errno; } _position_setpoint_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); - if (_position_setpoint_triplet_sub < 0) { + if (!orb_sub_valid(_position_setpoint_triplet_sub)) { return -errno; } @@ -171,14 +171,14 @@ InputMavlinkCmdMount::InputMavlinkCmdMount(Parameters ¶meters) : InputMavlinkCmdMount::~InputMavlinkCmdMount() { - if (_vehicle_command_sub >= 0) { + if (orb_sub_valid(_vehicle_command_sub)) { orb_unsubscribe(_vehicle_command_sub); } } int InputMavlinkCmdMount::initialize() { - if ((_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command))) < 0) { + if (!orb_sub_valid(_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)))) { return -errno; } @@ -379,23 +379,23 @@ InputMavlinkGimbalV2::InputMavlinkGimbalV2(Parameters ¶meters) : InputMavlinkGimbalV2::~InputMavlinkGimbalV2() { - if (_vehicle_roi_sub >= 0) { + if (orb_sub_valid(_vehicle_roi_sub)) { orb_unsubscribe(_vehicle_roi_sub); } - if (_position_setpoint_triplet_sub >= 0) { + if (orb_sub_valid(_position_setpoint_triplet_sub)) { orb_unsubscribe(_position_setpoint_triplet_sub); } - if (_gimbal_manager_set_attitude_sub >= 0) { + if (orb_sub_valid(_gimbal_manager_set_attitude_sub)) { orb_unsubscribe(_gimbal_manager_set_attitude_sub); } - if (_vehicle_command_sub >= 0) { + if (orb_sub_valid(_vehicle_command_sub)) { orb_unsubscribe(_vehicle_command_sub); } - if (_gimbal_manager_set_manual_control_sub >= 0) { + if (orb_sub_valid(_gimbal_manager_set_manual_control_sub)) { orb_unsubscribe(_gimbal_manager_set_manual_control_sub); } } @@ -410,27 +410,27 @@ int InputMavlinkGimbalV2::initialize() { _vehicle_roi_sub = orb_subscribe(ORB_ID(vehicle_roi)); - if (_vehicle_roi_sub < 0) { + if (!orb_sub_valid(_vehicle_roi_sub)) { return -errno; } _position_setpoint_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); - if (_position_setpoint_triplet_sub < 0) { + if (!orb_sub_valid(_position_setpoint_triplet_sub)) { return -errno; } _gimbal_manager_set_attitude_sub = orb_subscribe(ORB_ID(gimbal_manager_set_attitude)); - if (_gimbal_manager_set_attitude_sub < 0) { + if (!orb_sub_valid(_gimbal_manager_set_attitude_sub)) { return -errno; } - if ((_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command))) < 0) { + if (!orb_sub_valid(_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)))) { return -errno; } - if ((_gimbal_manager_set_manual_control_sub = orb_subscribe(ORB_ID(gimbal_manager_set_manual_control))) < 0) { + if (!orb_sub_valid(_gimbal_manager_set_manual_control_sub = orb_subscribe(ORB_ID(gimbal_manager_set_manual_control)))) { return -errno; } diff --git a/src/modules/gimbal/input_mavlink.h b/src/modules/gimbal/input_mavlink.h index 04264410d7d1..59e6b9d5b827 100644 --- a/src/modules/gimbal/input_mavlink.h +++ b/src/modules/gimbal/input_mavlink.h @@ -68,8 +68,8 @@ class InputMavlinkROI : public InputBase private: void _read_control_data_from_position_setpoint_sub(ControlData &control_data); - int _vehicle_roi_sub = -1; - int _position_setpoint_triplet_sub = -1; + orb_sub_t _vehicle_roi_sub = ORB_SUB_INVALID; + orb_sub_t _position_setpoint_triplet_sub = ORB_SUB_INVALID; uint8_t _cur_roi_mode {vehicle_roi_s::ROI_NONE}; }; @@ -89,7 +89,7 @@ class InputMavlinkCmdMount : public InputBase UpdateResult _process_command(ControlData &control_data, const vehicle_command_s &vehicle_command); void _ack_vehicle_command(const vehicle_command_s &cmd); - int _vehicle_command_sub = -1; + orb_sub_t _vehicle_command_sub = ORB_SUB_INVALID; }; class InputMavlinkGimbalV2 : public InputBase @@ -118,11 +118,11 @@ class InputMavlinkGimbalV2 : public InputBase void _stream_gimbal_manager_status(const ControlData &control_data); void _read_control_data_from_position_setpoint_sub(ControlData &control_data); - int _vehicle_roi_sub = -1; - int _gimbal_manager_set_attitude_sub = -1; - int _gimbal_manager_set_manual_control_sub = -1; - int _position_setpoint_triplet_sub = -1; - int _vehicle_command_sub = -1; + orb_sub_t _vehicle_roi_sub = ORB_SUB_INVALID; + orb_sub_t _gimbal_manager_set_attitude_sub = ORB_SUB_INVALID; + orb_sub_t _gimbal_manager_set_manual_control_sub = ORB_SUB_INVALID; + orb_sub_t _position_setpoint_triplet_sub = ORB_SUB_INVALID; + orb_sub_t _vehicle_command_sub = ORB_SUB_INVALID; uORB::Subscription _gimbal_device_attitude_status_sub{ORB_ID(gimbal_device_attitude_status)}; uORB::Publication _gimbal_manager_info_pub{ORB_ID(gimbal_manager_information)}; diff --git a/src/modules/gimbal/input_rc.cpp b/src/modules/gimbal/input_rc.cpp index c512cda254ee..60ecf620c00a 100644 --- a/src/modules/gimbal/input_rc.cpp +++ b/src/modules/gimbal/input_rc.cpp @@ -51,7 +51,7 @@ InputRC::InputRC(Parameters ¶meters) : InputRC::~InputRC() { - if (_manual_control_setpoint_sub >= 0) { + if (orb_sub_valid(_manual_control_setpoint_sub)) { orb_unsubscribe(_manual_control_setpoint_sub); } } @@ -60,7 +60,7 @@ int InputRC::initialize() { _manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); - if (_manual_control_setpoint_sub < 0) { + if (!orb_sub_valid(_manual_control_setpoint_sub)) { return -errno; } diff --git a/src/modules/gimbal/input_rc.h b/src/modules/gimbal/input_rc.h index 2bf0c2f51f05..5483cab6314a 100644 --- a/src/modules/gimbal/input_rc.h +++ b/src/modules/gimbal/input_rc.h @@ -59,7 +59,7 @@ class InputRC : public InputBase virtual UpdateResult _read_control_data_from_subscription(ControlData &control_data, bool already_active); float _get_aux_value(const manual_control_setpoint_s &manual_control_setpoint, int channel_idx); - int _manual_control_setpoint_sub{-1}; + orb_sub_t _manual_control_setpoint_sub{ORB_SUB_INVALID}; float _last_set_aux_values[3] {}; }; diff --git a/src/modules/logger/log_writer_mavlink.cpp b/src/modules/logger/log_writer_mavlink.cpp index 1c2a7b4bc499..5322aef074e0 100644 --- a/src/modules/logger/log_writer_mavlink.cpp +++ b/src/modules/logger/log_writer_mavlink.cpp @@ -57,14 +57,14 @@ bool LogWriterMavlink::init() LogWriterMavlink::~LogWriterMavlink() { - if (_ulog_stream_ack_sub >= 0) { + if (orb_sub_valid(_ulog_stream_ack_sub)) { orb_unsubscribe(_ulog_stream_ack_sub); } } void LogWriterMavlink::start_log() { - if (_ulog_stream_ack_sub == -1) { + if (!orb_sub_valid(_ulog_stream_ack_sub)) { _ulog_stream_ack_sub = orb_subscribe(ORB_ID(ulog_stream_ack)); } diff --git a/src/modules/logger/log_writer_mavlink.h b/src/modules/logger/log_writer_mavlink.h index ad6d80fa3bc6..8aabe2d79235 100644 --- a/src/modules/logger/log_writer_mavlink.h +++ b/src/modules/logger/log_writer_mavlink.h @@ -78,7 +78,7 @@ class LogWriterMavlink ulog_stream_s _ulog_stream_data{}; uORB::Publication _ulog_stream_pub{ORB_ID(ulog_stream)}; - int _ulog_stream_ack_sub{-1}; + orb_sub_t _ulog_stream_ack_sub{ORB_SUB_INVALID}; bool _need_reliable_transfer{false}; bool _is_started{false}; }; diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index d2a6b906d735..016ec0b76b64 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -655,12 +655,12 @@ void Logger::run() /* timer_semaphore use case is a signal */ px4_sem_setprotocol(&_timer_callback_data.semaphore, SEM_PRIO_NONE); - int polling_topic_sub = -1; + orb_sub_t polling_topic_sub = ORB_SUB_INVALID; if (_polling_topic_meta) { polling_topic_sub = orb_subscribe(_polling_topic_meta); - if (polling_topic_sub < 0) { + if (orb_sub_invalid(polling_topic_sub)) { PX4_ERR("Failed to subscribe (%i)", errno); } @@ -683,7 +683,7 @@ void Logger::run() hrt_abstime next_subscribe_check = 0; int next_subscribe_topic_index = -1; // this is used to distribute the checks over time - if (polling_topic_sub >= 0) { + if (orb_sub_valid(polling_topic_sub)) { _lockstep_component = px4_lockstep_register_component(); } @@ -890,7 +890,7 @@ void Logger::run() update_params(); // wait for next loop iteration... - if (polling_topic_sub >= 0) { + if (orb_sub_valid(polling_topic_sub)) { px4_lockstep_progress(_lockstep_component); px4_pollfd_struct_t fds[1]; @@ -931,7 +931,7 @@ void Logger::run() // stop the writer thread _writer.thread_stop(); - if (polling_topic_sub >= 0) { + if (orb_sub_valid(polling_topic_sub)) { orb_unsubscribe(polling_topic_sub); } diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index b62bffe3349b..2bc822f647d2 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -309,9 +309,9 @@ class Navigator : public ModuleBase, public ModuleParams private: - int _local_pos_sub{-1}; - int _mission_sub{-1}; - int _vehicle_status_sub{-1}; + orb_sub_t _local_pos_sub{ORB_SUB_INVALID}; + orb_sub_t _mission_sub{ORB_SUB_INVALID}; + orb_sub_t _vehicle_status_sub{ORB_SUB_INVALID}; uORB::SubscriptionData _position_controller_status_sub{ORB_ID(position_controller_status)}; diff --git a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp index ee4118a302d1..16d04f514489 100644 --- a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp +++ b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp @@ -263,7 +263,7 @@ class SimulatorMavlink : public ModuleParams std::default_random_engine _gen{}; // uORB subscription handlers - int _actuator_outputs_sub{-1}; + orb_sub_t _actuator_outputs_sub{ORB_SUB_INVALID}; actuator_outputs_s _actuator_outputs{}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; diff --git a/src/modules/temperature_compensation/temperature_calibration/accel.cpp b/src/modules/temperature_compensation/temperature_calibration/accel.cpp index 9dc6c071f86f..f5328d705caa 100644 --- a/src/modules/temperature_compensation/temperature_calibration/accel.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/accel.cpp @@ -68,7 +68,7 @@ TemperatureCalibrationAccel::~TemperatureCalibrationAccel() } } -int TemperatureCalibrationAccel::update_sensor_instance(PerSensorData &data, int sensor_sub) +int TemperatureCalibrationAccel::update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub) { bool finished = data.hot_soaked; diff --git a/src/modules/temperature_compensation/temperature_calibration/accel.h b/src/modules/temperature_compensation/temperature_calibration/accel.h index f464bb0cb564..02bac51e3bfc 100644 --- a/src/modules/temperature_compensation/temperature_calibration/accel.h +++ b/src/modules/temperature_compensation/temperature_calibration/accel.h @@ -49,7 +49,7 @@ class TemperatureCalibrationAccel : public TemperatureCalibrationCommon<3, 3> private: - virtual inline int update_sensor_instance(PerSensorData &data, int sensor_sub); + virtual inline int update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub); inline int finish_sensor_instance(PerSensorData &data, int sensor_index); }; diff --git a/src/modules/temperature_compensation/temperature_calibration/baro.cpp b/src/modules/temperature_compensation/temperature_calibration/baro.cpp index 4d1dc7be9050..3b573a3aee52 100644 --- a/src/modules/temperature_compensation/temperature_calibration/baro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/baro.cpp @@ -68,7 +68,7 @@ TemperatureCalibrationBaro::~TemperatureCalibrationBaro() } } -int TemperatureCalibrationBaro::update_sensor_instance(PerSensorData &data, int sensor_sub) +int TemperatureCalibrationBaro::update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub) { bool finished = data.hot_soaked; diff --git a/src/modules/temperature_compensation/temperature_calibration/baro.h b/src/modules/temperature_compensation/temperature_calibration/baro.h index fc74e3033da4..226b7a7d77cd 100644 --- a/src/modules/temperature_compensation/temperature_calibration/baro.h +++ b/src/modules/temperature_compensation/temperature_calibration/baro.h @@ -52,7 +52,7 @@ class TemperatureCalibrationBaro : public TemperatureCalibrationCommon<1, POLYFI private: - virtual int update_sensor_instance(PerSensorData &data, int sensor_sub); + virtual int update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub); inline int finish_sensor_instance(PerSensorData &data, int sensor_index); }; diff --git a/src/modules/temperature_compensation/temperature_calibration/common.h b/src/modules/temperature_compensation/temperature_calibration/common.h index 442ed01af310..dae2ee1f4580 100644 --- a/src/modules/temperature_compensation/temperature_calibration/common.h +++ b/src/modules/temperature_compensation/temperature_calibration/common.h @@ -188,8 +188,8 @@ class TemperatureCalibrationCommon : public TemperatureCalibrationBase * update a single sensor instance * @return 0 when done, 1 not finished yet, <0 for an error */ - virtual int update_sensor_instance(PerSensorData &data, int sensor_sub) = 0; + virtual int update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub) = 0; unsigned _num_sensor_instances{0}; - int _sensor_subs[SENSOR_COUNT_MAX]; + orb_sub_t _sensor_subs[SENSOR_COUNT_MAX]; }; diff --git a/src/modules/temperature_compensation/temperature_calibration/gyro.cpp b/src/modules/temperature_compensation/temperature_calibration/gyro.cpp index 0f0f9c4a1efc..e75637333765 100644 --- a/src/modules/temperature_compensation/temperature_calibration/gyro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/gyro.cpp @@ -45,7 +45,7 @@ #include TemperatureCalibrationGyro::TemperatureCalibrationGyro(float min_temperature_rise, float min_start_temperature, - float max_start_temperature, int gyro_subs[], int num_gyros) + float max_start_temperature, orb_sub_t gyro_subs[], int num_gyros) : TemperatureCalibrationCommon(min_temperature_rise, min_start_temperature, max_start_temperature) { for (int i = 0; i < num_gyros; ++i) { @@ -55,7 +55,7 @@ TemperatureCalibrationGyro::TemperatureCalibrationGyro(float min_temperature_ris _num_sensor_instances = num_gyros; } -int TemperatureCalibrationGyro::update_sensor_instance(PerSensorData &data, int sensor_sub) +int TemperatureCalibrationGyro::update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub) { bool finished = data.hot_soaked; diff --git a/src/modules/temperature_compensation/temperature_calibration/gyro.h b/src/modules/temperature_compensation/temperature_calibration/gyro.h index c6f9a5df47f3..f64e5cd0a939 100644 --- a/src/modules/temperature_compensation/temperature_calibration/gyro.h +++ b/src/modules/temperature_compensation/temperature_calibration/gyro.h @@ -40,7 +40,7 @@ class TemperatureCalibrationGyro : public TemperatureCalibrationCommon<3, 3> { public: TemperatureCalibrationGyro(float min_temperature_rise, float min_start_temperature, float max_start_temperature, - int gyro_subs[], int num_gyros); + orb_sub_t gyro_subs[], int num_gyros); virtual ~TemperatureCalibrationGyro() {} /** @@ -50,7 +50,7 @@ class TemperatureCalibrationGyro : public TemperatureCalibrationCommon<3, 3> private: - virtual int update_sensor_instance(PerSensorData &data, int sensor_sub); + virtual int update_sensor_instance(PerSensorData &data, orb_sub_t sensor_sub); inline int finish_sensor_instance(PerSensorData &data, int sensor_index); }; diff --git a/src/modules/temperature_compensation/temperature_calibration/task.cpp b/src/modules/temperature_compensation/temperature_calibration/task.cpp index 7328784522f7..c9e298b94088 100644 --- a/src/modules/temperature_compensation/temperature_calibration/task.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/task.cpp @@ -100,7 +100,7 @@ class TemperatureCalibration void TemperatureCalibration::task_main() { // subscribe to all gyro instances - int gyro_sub[SENSOR_COUNT_MAX] {-1, -1, -1}; + orb_sub_t gyro_sub[SENSOR_COUNT_MAX] {ORB_SUB_INVALID, ORB_SUB_INVALID, ORB_SUB_INVALID}; px4_pollfd_struct_t fds[SENSOR_COUNT_MAX] {}; unsigned num_gyro = orb_group_count(ORB_ID(sensor_gyro)); diff --git a/src/systemcmds/tests/test_rc.cpp b/src/systemcmds/tests/test_rc.cpp index 97f70651152f..c9a4beb73050 100644 --- a/src/systemcmds/tests/test_rc.cpp +++ b/src/systemcmds/tests/test_rc.cpp @@ -37,6 +37,7 @@ */ #include +#include #include @@ -59,7 +60,7 @@ int test_rc(int argc, char *argv[]) { - int _rc_sub = orb_subscribe(ORB_ID(input_rc)); + orb_sub_t _rc_sub = orb_subscribe(ORB_ID(input_rc)); /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */ struct input_rc_s rc_input; @@ -85,7 +86,7 @@ int test_rc(int argc, char *argv[]) rc_last.channel_count = rc_input.channel_count; /* poll descriptor */ - struct pollfd fds[2]; + px4_pollfd_struct_t fds[2]; fds[0].fd = _rc_sub; fds[0].events = POLLIN; fds[1].fd = 0; @@ -93,7 +94,7 @@ int test_rc(int argc, char *argv[]) while (true) { - int ret = poll(fds, 2, 200); + int ret = px4_poll(fds, 2, 200); if (ret > 0) { From b8043fe691c60b7615c44ef728b524300b45ab0f Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Mon, 25 Apr 2022 14:22:41 +0400 Subject: [PATCH 022/273] Change orb_sub_t into pointer type Signed-off-by: Jukka Laitinen --- platforms/common/uORB/uORB.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/platforms/common/uORB/uORB.h b/platforms/common/uORB/uORB.h index a48302f15f03..75f3715b9aea 100644 --- a/platforms/common/uORB/uORB.h +++ b/platforms/common/uORB/uORB.h @@ -128,12 +128,12 @@ int uorb_top(char **topic_filter, int num_filters); * publisher. */ typedef void *orb_advert_t; -typedef int orb_sub_t; +typedef void *orb_sub_t; static inline bool orb_advert_valid(orb_advert_t handle) {return handle != NULL;} static const orb_advert_t ORB_ADVERT_INVALID = NULL; -static inline bool orb_sub_valid(orb_sub_t handle) {return handle >= 0;} -static const orb_sub_t ORB_SUB_INVALID = -1; +static inline bool orb_sub_valid(orb_sub_t handle) {return handle != NULL;} +static const orb_sub_t ORB_SUB_INVALID = NULL; /** * @see uORB::Manager::orb_advertise() From 73cda71ff90c527567e9c1da0d7df73a8919aa1a Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Wed, 27 Apr 2022 10:55:23 +0400 Subject: [PATCH 023/273] Change orb_publish interface and intialization of advertiser handles Change all advertiser handle initializations from nullptr to ORB_ADVERT_INVALID and passing of handles via pointer in orb_publish Signed-off-by: Jukka Laitinen --- .../src/drivers/spektrum_rc/spektrum_rc.cpp | 2 +- platforms/common/events.cpp | 6 +-- platforms/common/px4_log.cpp | 6 +-- platforms/common/uORB/PublicationMulti.hpp | 2 +- platforms/common/uORB/uORB.cpp | 4 +- platforms/common/uORB/uORB.h | 4 +- .../uORB/uORB_tests/uORBTest_UnitTest.cpp | 32 ++++++++-------- src/drivers/camera_trigger/camera_trigger.cpp | 2 +- .../distance_sensor/mappydot/MappyDot.cpp | 4 +- src/drivers/distance_sensor/mb12xx/mb12xx.cpp | 4 +- src/drivers/distance_sensor/pga460/pga460.cpp | 4 +- src/drivers/telemetry/hott/messages.cpp | 6 +-- src/drivers/uavcan/sensors/sensor_bridge.cpp | 4 +- .../px4_mavlink_debug/px4_mavlink_debug.cpp | 8 ++-- src/examples/px4_simple_app/px4_simple_app.c | 2 +- src/lib/adsb/AdsbConflict.cpp | 2 +- .../CollisionPreventionTest.cpp | 38 +++++++++---------- src/lib/drivers/smbus_sbs/SBS.hpp | 2 +- src/lib/parameters/ParameterTest.cpp | 2 +- src/lib/parameters/parameters.cpp | 6 +-- src/lib/systemlib/mavlink_log.cpp | 4 +- src/modules/commander/Commander.cpp | 10 ++--- src/modules/commander/Commander.hpp | 2 + src/modules/commander/commander_helper.cpp | 10 ++--- src/modules/commander/mag_calibration.cpp | 6 +-- .../fw_autotune_attitude_control.cpp | 4 +- .../BlockLocalPositionEstimator.cpp | 2 +- src/modules/logger/logger.cpp | 6 +-- src/modules/manual_control/ManualControl.cpp | 4 +- src/modules/replay/Replay.cpp | 10 ++--- src/modules/replay/Replay.hpp | 2 +- 31 files changed, 101 insertions(+), 99 deletions(-) diff --git a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp index c2405de1fede..c1ebf31a2ffc 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/spektrum_rc/spektrum_rc.cpp @@ -187,7 +187,7 @@ void task_main(int argc, char *argv[]) } else { if (print_msg) { PX4_INFO("Spektrum RC: Publishing input_rc"); } - orb_publish(ORB_ID(input_rc), rc_pub, &input_rc); + orb_publish(ORB_ID(input_rc), &rc_pub, &input_rc); } } diff --git a/platforms/common/events.cpp b/platforms/common/events.cpp index c4d6867020c0..969cd2c51e58 100644 --- a/platforms/common/events.cpp +++ b/platforms/common/events.cpp @@ -38,7 +38,7 @@ #include #include -static orb_advert_t orb_event_pub = nullptr; +static orb_advert_t orb_event_pub = ORB_ADVERT_INVALID; static pthread_mutex_t publish_event_mutex = PTHREAD_MUTEX_INITIALIZER; static uint16_t event_sequence{events::initial_event_sequence}; @@ -57,8 +57,8 @@ void send(EventType &event) pthread_mutex_lock(&publish_event_mutex); event.event_sequence = ++event_sequence; // Set the sequence here so we're able to detect uORB queue overflows - if (orb_event_pub != nullptr) { - orb_publish(ORB_ID(event), orb_event_pub, &event); + if (orb_advert_valid(orb_event_pub)) { + orb_publish(ORB_ID(event), &orb_event_pub, &event); } else { orb_event_pub = orb_advertise_queue(ORB_ID(event), &event, event_s::ORB_QUEUE_LENGTH); diff --git a/platforms/common/px4_log.cpp b/platforms/common/px4_log.cpp index 8e733b5ee4c1..84480d3ca7a6 100644 --- a/platforms/common/px4_log.cpp +++ b/platforms/common/px4_log.cpp @@ -55,7 +55,7 @@ static LogHistory g_log_history; #endif -static orb_advert_t orb_log_message_pub = nullptr; +static orb_advert_t orb_log_message_pub = ORB_ADVERT_INVALID; __EXPORT const char *__px4_log_level_str[_PX4_LOG_LEVEL_PANIC + 1] = { "DEBUG", "INFO", "WARN", "ERROR", "PANIC" }; @@ -178,7 +178,7 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char } /* publish an orb log message */ - if (level >= _PX4_LOG_LEVEL_INFO && orb_log_message_pub) { //publish all messages + if (level >= _PX4_LOG_LEVEL_INFO && orb_advert_valid(orb_log_message_pub)) { //publish all messages log_message_s log_message; @@ -199,7 +199,7 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char va_end(argptr); log_message.text[max_length - 1] = 0; //ensure 0-termination log_message.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(log_message), orb_log_message_pub, &log_message); + orb_publish(ORB_ID(log_message), &orb_log_message_pub, &log_message); } } diff --git a/platforms/common/uORB/PublicationMulti.hpp b/platforms/common/uORB/PublicationMulti.hpp index bc275940b604..e7d3b3014ae5 100644 --- a/platforms/common/uORB/PublicationMulti.hpp +++ b/platforms/common/uORB/PublicationMulti.hpp @@ -89,7 +89,7 @@ class PublicationMulti : public PublicationBase advertise(); } - return (orb_publish(get_topic(), _handle, &data) == PX4_OK); + return (orb_publish(get_topic(), &_handle, &data) == PX4_OK); } int get_instance() diff --git a/platforms/common/uORB/uORB.cpp b/platforms/common/uORB/uORB.cpp index 461a002905d0..508a24f31137 100644 --- a/platforms/common/uORB/uORB.cpp +++ b/platforms/common/uORB/uORB.cpp @@ -138,9 +138,9 @@ int orb_unadvertise(orb_advert_t handle) return uORB::Manager::get_instance()->orb_unadvertise(handle); } -int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) +int orb_publish(const struct orb_metadata *meta, orb_advert_t *handle, const void *data) { - return uORB::Manager::get_instance()->orb_publish(meta, handle, data); + return uORB::Manager::get_instance()->orb_publish(meta, *handle, data); } orb_sub_t orb_subscribe(const struct orb_metadata *meta) diff --git a/platforms/common/uORB/uORB.h b/platforms/common/uORB/uORB.h index 75f3715b9aea..72eec7ad7d33 100644 --- a/platforms/common/uORB/uORB.h +++ b/platforms/common/uORB/uORB.h @@ -165,7 +165,7 @@ extern int orb_unadvertise(orb_advert_t handle) __EXPORT; /** * @see uORB::Manager::orb_publish() */ -extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT; +extern int orb_publish(const struct orb_metadata *meta, orb_advert_t *handle, const void *data) __EXPORT; /** * Advertise as the publisher of a topic. @@ -186,7 +186,7 @@ static inline int orb_publish_auto(const struct orb_metadata *meta, orb_advert_t } } else { - return orb_publish(meta, *handle, data); + return orb_publish(meta, handle, data); } return -1; diff --git a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp index bc7cda513297..9458b2bb26ab 100644 --- a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp +++ b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp @@ -289,7 +289,7 @@ int uORBTest::UnitTest::test_single() t.val = 2; - if (PX4_OK != orb_publish(ORB_ID(orb_test), ptopic, &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_test), &ptopic, &t)) { return test_fail("publish failed"); } @@ -344,13 +344,13 @@ int uORBTest::UnitTest::test_multi() t.val = 103; - if (PX4_OK != orb_publish(ORB_ID(orb_multitest), _pfd[0], &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_multitest), &_pfd[0], &t)) { return test_fail("mult. pub0 fail"); } t.val = 203; - if (PX4_OK != orb_publish(ORB_ID(orb_multitest), _pfd[1], &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_multitest), &_pfd[1], &t)) { return test_fail("mult. pub1 fail"); } @@ -422,7 +422,7 @@ int uORBTest::UnitTest::pub_test_multi2_main() data_topic.timestamp = hrt_absolute_time(); data_topic.val = data_next_idx; - orb_publish(ORB_ID(orb_test_medium_multi), orb_pub[data_next_idx], &data_topic); + orb_publish(ORB_ID(orb_test_medium_multi), &orb_pub[data_next_idx], &data_topic); // PX4_WARN("publishing msg (idx=%i, t=%" PRIu64 ")", data_next_idx, data_topic.time); data_next_idx = (data_next_idx + 1) % num_instances; @@ -533,13 +533,13 @@ int uORBTest::UnitTest::test_multi_reversed() t.val = 204; - if (PX4_OK != orb_publish(ORB_ID(orb_multitest), _pfd[2], &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_multitest), &_pfd[2], &t)) { return test_fail("mult. pub0 fail"); } t.val = 304; - if (PX4_OK != orb_publish(ORB_ID(orb_multitest), _pfd[3], &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_multitest), &_pfd[3], &t)) { return test_fail("mult. pub1 fail"); } @@ -598,7 +598,7 @@ int uORBTest::UnitTest::test_wrap_around() } t.val = 0; - orb_publish(ORB_ID(orb_test_medium_wrap_around), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); int sfd = orb_subscribe(ORB_ID(orb_test_medium_wrap_around)); @@ -648,7 +648,7 @@ int uORBTest::UnitTest::test_wrap_around() for (int i = 0; i < queue_size - 2; ++i) { t.val = i; - orb_publish(ORB_ID(orb_test_medium_wrap_around), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); } for (int i = 0; i < queue_size - 2; ++i) { @@ -676,7 +676,7 @@ int uORBTest::UnitTest::test_wrap_around() for (int i = 0; i < queue_size + overflow_by; ++i) { t.val = i; - orb_publish(ORB_ID(orb_test_medium_wrap_around), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); } for (int i = 0; i < queue_size; ++i) { @@ -691,7 +691,7 @@ int uORBTest::UnitTest::test_wrap_around() SET_GENERTATION(); t.val = queue_size; - orb_publish(ORB_ID(orb_test_medium_wrap_around), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); CHECK_UPDATED(-1); CHECK_COPY(u.val, t.val); @@ -704,7 +704,7 @@ int uORBTest::UnitTest::test_wrap_around() #undef SET_GENERTATION t.val = 943; - orb_publish(ORB_ID(orb_test_medium_wrap_around), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); CHECK_UPDATED(-1); CHECK_COPY(u.val, t.val); @@ -878,7 +878,7 @@ int uORBTest::UnitTest::test_queue() for (int i = 0; i < queue_size - 2; ++i) { t.val = i; - orb_publish(ORB_ID(orb_test_medium_queue), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_queue), &ptopic, &t); } for (int i = 0; i < queue_size - 2; ++i) { @@ -893,7 +893,7 @@ int uORBTest::UnitTest::test_queue() for (int i = 0; i < queue_size + overflow_by; ++i) { t.val = i; - orb_publish(ORB_ID(orb_test_medium_queue), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_queue), &ptopic, &t); } for (int i = 0; i < queue_size; ++i) { @@ -911,7 +911,7 @@ int uORBTest::UnitTest::test_queue() } t.val = 943; - orb_publish(ORB_ID(orb_test_medium_queue), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_queue), &ptopic, &t); CHECK_UPDATED(-1); CHECK_COPY(u.val, t.val); @@ -953,7 +953,7 @@ int uORBTest::UnitTest::pub_test_queue_main() int burst_counter = 0; while (burst_counter++ < queue_size / 2 + 7) { //make interval non-boundary aligned - orb_publish(ORB_ID(orb_test_medium_queue_poll), ptopic, &t); + orb_publish(ORB_ID(orb_test_medium_queue_poll), &ptopic, &t); ++t.val; } @@ -1068,7 +1068,7 @@ int uORBTest::UnitTest::latency_test(bool print) ++t.val; t.timestamp = hrt_absolute_time(); - if (PX4_OK != orb_publish(ORB_ID(orb_test_medium), pfd0, &t)) { + if (PX4_OK != orb_publish(ORB_ID(orb_test_medium), &pfd0, &t)) { return test_fail("mult. pub0 timing fail"); } diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index c03e63aca45a..4fcbf0aa493f 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -852,7 +852,7 @@ CameraTrigger::engage(void *arg) trigger.feedback = false; trigger.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trigger); + orb_publish(ORB_ID(camera_trigger), &trig->_trigger_pub, &trigger); // increment frame count trig->_trigger_seq++; diff --git a/src/drivers/distance_sensor/mappydot/MappyDot.cpp b/src/drivers/distance_sensor/mappydot/MappyDot.cpp index 3144237ab899..db314c1f47ed 100644 --- a/src/drivers/distance_sensor/mappydot/MappyDot.cpp +++ b/src/drivers/distance_sensor/mappydot/MappyDot.cpp @@ -196,7 +196,7 @@ class MappyDot : public device::I2C, public ModuleParams, public I2CSPIDriver((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1F; /* announce the esc if needed, just publish else */ - if (_esc_pub != nullptr) { - orb_publish(ORB_ID(esc_status), _esc_pub, &esc); + if (orb_advert_valid(_esc_pub)) { + orb_publish(ORB_ID(esc_status), &_esc_pub, &esc); } else { _esc_pub = orb_advertise(ORB_ID(esc_status), &esc); diff --git a/src/drivers/uavcan/sensors/sensor_bridge.cpp b/src/drivers/uavcan/sensors/sensor_bridge.cpp index 023a16cf1d05..636cc18ed0cf 100644 --- a/src/drivers/uavcan/sensors/sensor_bridge.cpp +++ b/src/drivers/uavcan/sensors/sensor_bridge.cpp @@ -211,7 +211,7 @@ UavcanSensorBridgeBase::publish(const int node_id, const void *report) channel->node_id = node_id; DEVICE_LOG("node %d instance %d ok", channel->node_id, channel->instance); - if (channel->orb_advert == nullptr) { + if (!orb_advert_valid(channel->orb_advert)) { DEVICE_LOG("uORB advertise failed. Out of instances?"); *channel = uavcan_bridge::Channel(); _out_of_channels = true; @@ -223,7 +223,7 @@ UavcanSensorBridgeBase::publish(const int node_id, const void *report) assert(channel != nullptr); - (void)orb_publish(_orb_topic, channel->orb_advert, report); + (void)orb_publish(_orb_topic, &channel->orb_advert, report); } uavcan_bridge::Channel *UavcanSensorBridgeBase::get_channel_for_node(int node_id) diff --git a/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp b/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp index 97047f074842..568526c74310 100644 --- a/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp +++ b/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp @@ -93,19 +93,19 @@ int px4_mavlink_debug_main(int argc, char *argv[]) /* send one named value */ dbg_key.value = value_counter; dbg_key.timestamp = timestamp_us; - orb_publish(ORB_ID(debug_key_value), pub_dbg_key, &dbg_key); + orb_publish(ORB_ID(debug_key_value), &pub_dbg_key, &dbg_key); /* send one indexed value */ dbg_ind.value = 0.5f * value_counter; dbg_ind.timestamp = timestamp_us; - orb_publish(ORB_ID(debug_value), pub_dbg_ind, &dbg_ind); + orb_publish(ORB_ID(debug_value), &pub_dbg_ind, &dbg_ind); /* send one vector */ dbg_vect.x = 1.0f * value_counter; dbg_vect.y = 2.0f * value_counter; dbg_vect.z = 3.0f * value_counter; dbg_vect.timestamp = timestamp_us; - orb_publish(ORB_ID(debug_vect), pub_dbg_vect, &dbg_vect); + orb_publish(ORB_ID(debug_vect), &pub_dbg_vect, &dbg_vect); /* send one array */ for (size_t i = 0; i < debug_array_s::ARRAY_SIZE; i++) { @@ -113,7 +113,7 @@ int px4_mavlink_debug_main(int argc, char *argv[]) } dbg_array.timestamp = timestamp_us; - orb_publish(ORB_ID(debug_array), pub_dbg_array, &dbg_array); + orb_publish(ORB_ID(debug_array), &pub_dbg_array, &dbg_array); warnx("sent one more value.."); diff --git a/src/examples/px4_simple_app/px4_simple_app.c b/src/examples/px4_simple_app/px4_simple_app.c index 806784159eba..72e8abcf51e5 100644 --- a/src/examples/px4_simple_app/px4_simple_app.c +++ b/src/examples/px4_simple_app/px4_simple_app.c @@ -115,7 +115,7 @@ int px4_simple_app_main(int argc, char *argv[]) att.q[1] = accel.xyz[1]; att.q[2] = accel.xyz[2]; - orb_publish(ORB_ID(vehicle_attitude), att_pub, &att); + orb_publish(ORB_ID(vehicle_attitude), &att_pub, &att); } /* there could be more file descriptors here, in the form like: diff --git a/src/lib/adsb/AdsbConflict.cpp b/src/lib/adsb/AdsbConflict.cpp index cb40f27a7df6..09b4ee94a413 100644 --- a/src/lib/adsb/AdsbConflict.cpp +++ b/src/lib/adsb/AdsbConflict.cpp @@ -383,7 +383,7 @@ void AdsbConflict::fake_traffic(const char *callsign, float distance, float dire #endif /* BOARD_HAS_NO_UUID */ - orb_publish(ORB_ID(transponder_report), fake_traffic_report_publisher, &tr); + orb_publish(ORB_ID(transponder_report), &fake_traffic_report_publisher, &tr); } diff --git a/src/lib/collision_prevention/CollisionPreventionTest.cpp b/src/lib/collision_prevention/CollisionPreventionTest.cpp index 9de0a208aa00..ef8cc169438f 100644 --- a/src/lib/collision_prevention/CollisionPreventionTest.cpp +++ b/src/lib/collision_prevention/CollisionPreventionTest.cpp @@ -170,8 +170,8 @@ TEST_F(CollisionPreventionTest, testBehaviorOnWithObstacleMessage) // WHEN: we publish the message and set the parameter and then run the setpoint modification orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); orb_advert_t vehicle_attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &attitude); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); - orb_publish(ORB_ID(vehicle_attitude), vehicle_attitude_pub, &attitude); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); + orb_publish(ORB_ID(vehicle_attitude), &vehicle_attitude_pub, &attitude); matrix::Vector2f modified_setpoint1 = original_setpoint1; matrix::Vector2f modified_setpoint2 = original_setpoint2; cp.modifySetpoint(modified_setpoint1, max_speed, curr_pos, curr_vel); @@ -228,8 +228,8 @@ TEST_F(CollisionPreventionTest, testBehaviorOnWithDistanceMessage) // WHEN: we publish the message and set the parameter and then run the setpoint modification orb_advert_t distance_sensor_pub = orb_advertise(ORB_ID(distance_sensor), &message); orb_advert_t vehicle_attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &attitude); - orb_publish(ORB_ID(distance_sensor), distance_sensor_pub, &message); - orb_publish(ORB_ID(vehicle_attitude), vehicle_attitude_pub, &attitude); + orb_publish(ORB_ID(distance_sensor), &distance_sensor_pub, &message); + orb_publish(ORB_ID(vehicle_attitude), &vehicle_attitude_pub, &attitude); //WHEN: We run the setpoint modification matrix::Vector2f modified_setpoint1 = original_setpoint1; @@ -302,8 +302,8 @@ TEST_F(CollisionPreventionTest, testPurgeOldData) // WHEN: we publish the message and set the parameter and then run the setpoint modification orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); orb_advert_t vehicle_attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &attitude); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); - orb_publish(ORB_ID(vehicle_attitude), vehicle_attitude_pub, &attitude); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); + orb_publish(ORB_ID(vehicle_attitude), &vehicle_attitude_pub, &attitude); for (int i = 0; i < 10; i++) { @@ -312,7 +312,7 @@ TEST_F(CollisionPreventionTest, testPurgeOldData) mocked_time = mocked_time + 100000; //advance time by 0.1 seconds message_lost_data.timestamp = mocked_time; - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message_lost_data); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message_lost_data); //at iteration 8 change the CP_GO_NO_DATA to True if (i == 8) { @@ -380,8 +380,8 @@ TEST_F(CollisionPreventionTest, testNoRangeData) // WHEN: we publish the message and set the parameter and then run the setpoint modification orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); orb_advert_t vehicle_attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &attitude); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); - orb_publish(ORB_ID(vehicle_attitude), vehicle_attitude_pub, &attitude); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); + orb_publish(ORB_ID(vehicle_attitude), &vehicle_attitude_pub, &attitude); for (int i = 0; i < 10; i++) { @@ -437,7 +437,7 @@ TEST_F(CollisionPreventionTest, noBias) // WHEN: we publish the message and set the parameter and then run the setpoint modification orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); matrix::Vector2f modified_setpoint = original_setpoint; cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); orb_unadvertise(obstacle_distance_pub); @@ -492,7 +492,7 @@ TEST_F(CollisionPreventionTest, outsideFOV) matrix::Vector2f original_setpoint = {10.f * cosf(angle_rad), 10.f * sinf(angle_rad)}; matrix::Vector2f modified_setpoint = original_setpoint; message.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); //THEN: if the resulting setpoint demands velocities bigger zero, it must lie inside the FOV @@ -567,7 +567,7 @@ TEST_F(CollisionPreventionTest, goNoData) //THEN: As soon as the range data contains any valid number, flying outside the FOV is allowed message.timestamp = hrt_absolute_time(); orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); modified_setpoint = original_setpoint; cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); @@ -606,7 +606,7 @@ TEST_F(CollisionPreventionTest, jerkLimit) // AND: we publish the message and set the parameter and then run the setpoint modification orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &message); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &message); matrix::Vector2f modified_setpoint_default_jerk = original_setpoint; cp.modifySetpoint(modified_setpoint_default_jerk, max_speed, curr_pos, curr_vel); orb_unadvertise(obstacle_distance_pub); @@ -1112,8 +1112,8 @@ TEST_F(CollisionPreventionTest, overlappingSensors) //WHEN: we publish the long range sensor message orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &long_range_msg); orb_advert_t vehicle_attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &attitude); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &long_range_msg); - orb_publish(ORB_ID(vehicle_attitude), vehicle_attitude_pub, &attitude); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &long_range_msg); + orb_publish(ORB_ID(vehicle_attitude), &vehicle_attitude_pub, &attitude); matrix::Vector2f modified_setpoint = original_setpoint; cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); @@ -1123,10 +1123,10 @@ TEST_F(CollisionPreventionTest, overlappingSensors) // CASE 2 // WHEN: we publish the short range message followed by a long range message short_range_msg.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &short_range_msg); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &short_range_msg); cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); long_range_msg.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &long_range_msg); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &long_range_msg); cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); // THEN: the internal map data should contain the short range measurement @@ -1135,10 +1135,10 @@ TEST_F(CollisionPreventionTest, overlappingSensors) // CASE 3 // WHEN: we publish the short range message with values out of range followed by a long range message short_range_msg_no_obstacle.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &short_range_msg_no_obstacle); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &short_range_msg_no_obstacle); cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); long_range_msg.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(obstacle_distance), obstacle_distance_pub, &long_range_msg); + orb_publish(ORB_ID(obstacle_distance), &obstacle_distance_pub, &long_range_msg); cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); // THEN: the internal map data should contain the short range measurement diff --git a/src/lib/drivers/smbus_sbs/SBS.hpp b/src/lib/drivers/smbus_sbs/SBS.hpp index 176928923af0..ad817e983ad9 100644 --- a/src/lib/drivers/smbus_sbs/SBS.hpp +++ b/src/lib/drivers/smbus_sbs/SBS.hpp @@ -321,6 +321,6 @@ void SMBUS_SBS_BaseClass::RunImpl() // Only publish if no errors. if (!ret) { - orb_publish(ORB_ID(battery_status), _batt_topic, &new_report); + orb_publish(ORB_ID(battery_status), &_batt_topic, &new_report); } } diff --git a/src/lib/parameters/ParameterTest.cpp b/src/lib/parameters/ParameterTest.cpp index b0e04923e915..c3a16f02c386 100644 --- a/src/lib/parameters/ParameterTest.cpp +++ b/src/lib/parameters/ParameterTest.cpp @@ -92,7 +92,7 @@ TEST_F(ParameterTest, testUorbSendReceive) // WHEN we send the message orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); - ASSERT_TRUE(obstacle_distance_pub != nullptr); + ASSERT_TRUE(orb_advert_valid(obstacle_distance_pub)); // THEN: the subscriber should receive the message sub_obstacle_distance.update(); diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index c1f85147d780..818c4a9b0a78 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -117,7 +117,7 @@ UT_array *param_custom_default_values{nullptr}; const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr}; /** parameter update topic handle */ -static orb_advert_t param_topic = nullptr; +static orb_advert_t param_topic = ORB_ADVERT_INVALID; static unsigned int param_instance = 0; // the following implements an RW-lock using 2 semaphores (used as mutexes). It gives @@ -264,11 +264,11 @@ param_notify_changes() pup.custom_default = params_custom_default.count(); pup.timestamp = hrt_absolute_time(); - if (param_topic == nullptr) { + if (!orb_advert_valid(param_topic)) { param_topic = orb_advertise(ORB_ID(parameter_update), &pup); } else { - orb_publish(ORB_ID(parameter_update), param_topic, &pup); + orb_publish(ORB_ID(parameter_update), ¶m_topic, &pup); } } diff --git a/src/lib/systemlib/mavlink_log.cpp b/src/lib/systemlib/mavlink_log.cpp index d31136f21530..9526e9934434 100644 --- a/src/lib/systemlib/mavlink_log.cpp +++ b/src/lib/systemlib/mavlink_log.cpp @@ -69,8 +69,8 @@ __EXPORT void mavlink_vasprintf(int severity, orb_advert_t *mavlink_log_pub, con vsnprintf((char *)log_msg.text, sizeof(log_msg.text), fmt, ap); va_end(ap); - if (*mavlink_log_pub != nullptr) { - orb_publish(ORB_ID(mavlink_log), *mavlink_log_pub, &log_msg); + if (orb_advert_valid(*mavlink_log_pub)) { + orb_publish(ORB_ID(mavlink_log), mavlink_log_pub, &log_msg); } else { *mavlink_log_pub = orb_advertise_queue(ORB_ID(mavlink_log), &log_msg, mavlink_log_s::ORB_QUEUE_LENGTH); diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index a9061ad33ba1..8ca650156535 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -98,7 +98,7 @@ static constexpr bool operator ==(const actuator_armed_s &a, const actuator_arme static_assert(sizeof(actuator_armed_s) == 16, "actuator_armed equality operator review"); #if defined(BOARD_HAS_POWER_CONTROL) -static orb_advert_t tune_control_pub = nullptr; +static orb_advert_t tune_control_pub = ORB_ADVERT_INVALID; static void play_power_button_down_tune() { @@ -111,10 +111,10 @@ static void stop_tune() tune_control_s tune_control{}; tune_control.tune_override = true; tune_control.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control); + orb_publish(ORB_ID(tune_control), &tune_control_pub, &tune_control); } -static orb_advert_t power_button_state_pub = nullptr; +static orb_advert_t power_button_state_pub = ORB_ADVERT_INVALID; static int power_button_state_notification_cb(board_power_button_state_notification_e request) { // Note: this can be called from IRQ handlers, so we publish a message that will be handled @@ -147,8 +147,8 @@ static int power_button_state_notification_cb(board_power_button_state_notificat return ret; } - if (power_button_state_pub != nullptr) { - orb_publish(ORB_ID(power_button_state), power_button_state_pub, &button_state); + if (!orb_advert_valid(power_button_state_pub)) { + orb_publish(ORB_ID(power_button_state), &power_button_state_pub, &button_state); } else { PX4_ERR("power_button_state_pub not properly initialized"); diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 3678b9ea9d77..a29ac4b65411 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -33,6 +33,8 @@ #pragma once +#include + /* Helper classes */ #include "Arming/ArmStateMachine/ArmStateMachine.hpp" #include "failure_detector/FailureDetector.hpp" diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index f642541fb74b..6460fabcdae4 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -127,7 +127,7 @@ static hrt_abstime blink_msg_end = 0; static int fd_leds{-1}; static led_control_s led_control {}; -static orb_advert_t led_control_pub = nullptr; +static orb_advert_t led_control_pub = ORB_ADVERT_INVALID; // Static array that defines the duration of each tune, 0 if it's a repeating tune (therefore no fixed duration) static unsigned int tune_durations[tune_control_s::NUMBER_OF_TUNES] {}; @@ -139,7 +139,7 @@ static hrt_abstime tune_end = 0; static uint8_t tune_current = tune_control_s::TUNE_ID_STOP; static tune_control_s tune_control {}; -static orb_advert_t tune_control_pub = nullptr; +static orb_advert_t tune_control_pub = ORB_ADVERT_INVALID; int buzzer_init() @@ -169,7 +169,7 @@ void set_tune_override(const int tune_id) tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT; tune_control.tune_override = true; tune_control.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control); + orb_publish(ORB_ID(tune_control), &tune_control_pub, &tune_control); } void set_tune(const int tune_id) @@ -204,7 +204,7 @@ void set_tune(const int tune_id) tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT; tune_control.tune_override = false; tune_control.timestamp = current_time; - orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control); + orb_publish(ORB_ID(tune_control), &tune_control_pub, &tune_control); tune_current = tune_id; @@ -390,7 +390,7 @@ void rgbled_set_color_and_mode(uint8_t color, uint8_t mode, uint8_t blinks, uint led_control.num_blinks = blinks; led_control.priority = prio; led_control.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(led_control), led_control_pub, &led_control); + orb_publish(ORB_ID(led_control), &led_control_pub, &led_control); } void rgbled_set_color_and_mode(uint8_t color, uint8_t mode) diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index fcb35ca78242..b2895ddbb079 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -417,11 +417,11 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta } } - if (worker_data->mag_worker_data_pub == nullptr) { + if (!orb_advert_valid(worker_data->mag_worker_data_pub)) { worker_data->mag_worker_data_pub = orb_advertise(ORB_ID(mag_worker_data), &status); } else { - orb_publish(ORB_ID(mag_worker_data), worker_data->mag_worker_data_pub, &status); + orb_publish(ORB_ID(mag_worker_data), &worker_data->mag_worker_data_pub, &status); } calibration_counter_side++; @@ -484,7 +484,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma mag_worker_data_t worker_data{}; - worker_data.mag_worker_data_pub = nullptr; + worker_data.mag_worker_data_pub = ORB_ADVERT_INVALID; // keep and update the existing calibration when we are not doing a full 6-axis calibration worker_data.append_to_existing_calibration = cal_mask < ((1 << 6) - 1); diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index ec274f28dac2..1dfdad7a1384 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -466,7 +466,7 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now) break; } - orb_advert_t mavlink_log_pub = nullptr; + orb_advert_t mavlink_log_pub = ORB_ADVERT_INVALID; mavlink_log_info(&mavlink_log_pub, "Autotune returned to idle"); _state = state::idle; _param_fw_at_start.set(false); @@ -482,7 +482,7 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now) if (now - _state_start_time > 20_s || (_param_fw_at_man_aux.get() && !_aux_switch_en) || _start_flight_mode != _nav_state) { - orb_advert_t mavlink_log_pub = nullptr; + orb_advert_t mavlink_log_pub = ORB_ADVERT_INVALID; mavlink_log_critical(&mavlink_log_pub, "Autotune aborted before finishing"); _state = state::fail; _state_start_time = now; diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 508a5427549f..4c42073297bf 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -5,7 +5,7 @@ #include #include -orb_advert_t mavlink_log_pub = nullptr; +orb_advert_t mavlink_log_pub = ORB_ADVERT_INVALID; // required standard deviation of estimate for estimator to publish data static const uint32_t EST_STDDEV_XY_VALID = 2.0; // 2.0 m diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 016ec0b76b64..50753c1e697f 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -660,7 +660,7 @@ void Logger::run() if (_polling_topic_meta) { polling_topic_sub = orb_subscribe(_polling_topic_meta); - if (orb_sub_invalid(polling_topic_sub)) { + if (!orb_sub_valid(polling_topic_sub)) { PX4_ERR("Failed to subscribe (%i)", errno); } @@ -935,9 +935,9 @@ void Logger::run() orb_unsubscribe(polling_topic_sub); } - if (_mavlink_log_pub) { + if (orb_advert_valid(_mavlink_log_pub)) { orb_unadvertise(_mavlink_log_pub); - _mavlink_log_pub = nullptr; + _mavlink_log_pub = ORB_ADVERT_INVALID; } px4_unregister_shutdown_hook(&Logger::request_stop_static); diff --git a/src/modules/manual_control/ManualControl.cpp b/src/modules/manual_control/ManualControl.cpp index c3b42c258e2c..7f24098032b2 100644 --- a/src/modules/manual_control/ManualControl.cpp +++ b/src/modules/manual_control/ManualControl.cpp @@ -104,7 +104,7 @@ void ManualControl::Run() _param_man_arm_gesture.set(0); // disable arm gesture _param_man_arm_gesture.commit(); - orb_advert_t mavlink_log_pub = nullptr; + orb_advert_t mavlink_log_pub = ORB_ADVERT_INVALID; mavlink_log_critical(&mavlink_log_pub, "Arm stick gesture disabled if arm switch in use\t") /* EVENT * @description MAN_ARM_GESTURE is now set to disable arm/disarm stick gesture. @@ -126,7 +126,7 @@ void ManualControl::Run() airmode = 1; // change to roll/pitch airmode param_set(param_mc_airmode, &airmode); - orb_advert_t mavlink_log_pub = nullptr; + orb_advert_t mavlink_log_pub = ORB_ADVERT_INVALID; mavlink_log_critical(&mavlink_log_pub, "Yaw Airmode requires disabling the stick arm gesture\t") /* EVENT * @description MC_AIRMODE is now set to roll/pitch airmode. diff --git a/src/modules/replay/Replay.cpp b/src/modules/replay/Replay.cpp index 6218b09e00da..6c7a4a972468 100644 --- a/src/modules/replay/Replay.cpp +++ b/src/modules/replay/Replay.cpp @@ -933,9 +933,9 @@ Replay::run() subscription->compat = nullptr; } - if (subscription->orb_advert) { + if (orb_advert_valid(subscription->orb_advert)) { orb_unadvertise(subscription->orb_advert); - subscription->orb_advert = nullptr; + subscription->orb_advert = ORB_ADVERT_INVALID; } } @@ -1015,8 +1015,8 @@ Replay::publishTopic(Subscription &sub, void *data) data = sub.compat->apply(data); } - if (sub.orb_advert) { - orb_publish(sub.orb_meta, sub.orb_advert, data); + if (orb_advert_valid(sub.orb_advert)) { + orb_publish(sub.orb_meta, &sub.orb_advert, data); published = true; } else { @@ -1035,7 +1035,7 @@ Replay::publishTopic(Subscription &sub, void *data) if (subscription->orb_meta) { if (strcmp(sub.orb_meta->o_name, subscription->orb_meta->o_name) == 0 && - subscription->orb_advert && subscription->multi_id == sub.multi_id - 1) { + orb_advert_valid(subscription->orb_advert) && subscription->multi_id == sub.multi_id - 1) { advertised = true; } } diff --git a/src/modules/replay/Replay.hpp b/src/modules/replay/Replay.hpp index 94ecc9d416fd..ea32a720a5ad 100644 --- a/src/modules/replay/Replay.hpp +++ b/src/modules/replay/Replay.hpp @@ -128,7 +128,7 @@ class Replay : public ModuleBase struct Subscription { const orb_metadata *orb_meta = nullptr; ///< if nullptr, this subscription is invalid - orb_advert_t orb_advert = nullptr; + orb_advert_t orb_advert = ORB_ADVERT_INVALID; uint8_t multi_id; int timestamp_offset; ///< marks the field of the timestamp From 556c3a3d7bae73b10e23e944df211006b30eeb88 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Sun, 27 Nov 2022 03:04:54 +0400 Subject: [PATCH 024/273] platforms/common/uORB/SubscriptionBlocking.hpp: Fix CLOCK_REALTIME -> CLOCK_MONOTONIC in SITL Signed-off-by: Jukka Laitinen --- platforms/common/uORB/SubscriptionBlocking.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/platforms/common/uORB/SubscriptionBlocking.hpp b/platforms/common/uORB/SubscriptionBlocking.hpp index 7ec29e329b6e..2df473e00c42 100644 --- a/platforms/common/uORB/SubscriptionBlocking.hpp +++ b/platforms/common/uORB/SubscriptionBlocking.hpp @@ -129,7 +129,11 @@ class SubscriptionBlocking : public SubscriptionCallback // Calculate an absolute time in the future struct timespec ts; +#if defined(CONFIG_ARCH_BOARD_PX4_SITL) + px4_clock_gettime(CLOCK_MONOTONIC, &ts); +#else px4_clock_gettime(CLOCK_REALTIME, &ts); +#endif uint64_t nsecs = ts.tv_nsec + (timeout_us * 1000); static constexpr unsigned billion = (1000 * 1000 * 1000); ts.tv_sec += nsecs / billion; From 0bb76ffe8d8f5b906bceececa02571f7e80f9847 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Mon, 4 Apr 2022 11:21:47 +0400 Subject: [PATCH 025/273] Re-write uORB around posix shm Signed-off-by: Jukka Laitinen --- cmake/px4_add_module.cmake | 6 +- platforms/common/apps.cpp.in | 2 + .../include/px4_platform_common/posix.h | 23 +- platforms/common/uORB/CMakeLists.txt | 50 +- platforms/common/uORB/IndexedStack.hpp | 143 +++ platforms/common/uORB/ORBSet.hpp | 32 +- platforms/common/uORB/Publication.hpp | 12 +- platforms/common/uORB/PublicationMulti.hpp | 2 +- platforms/common/uORB/Subscription.cpp | 38 +- platforms/common/uORB/Subscription.hpp | 27 +- .../common/uORB/SubscriptionBlocking.hpp | 2 +- .../common/uORB/SubscriptionCallback.hpp | 78 +- .../common/uORB/SubscriptionInterval.hpp | 12 +- platforms/common/uORB/uORB.cpp | 64 +- platforms/common/uORB/uORB.h | 59 +- platforms/common/uORB/uORBDeviceNode.cpp | 851 +++++++++++++----- platforms/common/uORB/uORBDeviceNode.hpp | 348 +++---- platforms/common/uORB/uORBManager.cpp | 816 ++++++++--------- platforms/common/uORB/uORBManager.hpp | 410 +++++---- platforms/common/uORB/uORBManagerUsr.cpp | 349 ------- platforms/common/uORB/uORBUtils.cpp | 4 +- .../uORB/uORB_tests/uORBTest_UnitTest.cpp | 51 +- .../uORB/uORB_tests/uORBTest_UnitTest.hpp | 1 - .../src/px4/common/px4_userspace_init.cpp | 2 - platforms/posix/src/px4/common/main.cpp | 2 + src/systemcmds/uorb/CMakeLists.txt | 1 + .../systemcmds/uorb}/uORBDeviceMaster.cpp | 197 +--- .../systemcmds/uorb}/uORBDeviceMaster.hpp | 53 +- src/systemcmds/uorb/uorb.cpp | 23 +- 29 files changed, 1854 insertions(+), 1804 deletions(-) create mode 100644 platforms/common/uORB/IndexedStack.hpp delete mode 100644 platforms/common/uORB/uORBManagerUsr.cpp rename {platforms/common/uORB => src/systemcmds/uorb}/uORBDeviceMaster.cpp (67%) rename {platforms/common/uORB => src/systemcmds/uorb}/uORBDeviceMaster.hpp (70%) diff --git a/cmake/px4_add_module.cmake b/cmake/px4_add_module.cmake index 5c0ee1153d68..79f3f92c1fe8 100644 --- a/cmake/px4_add_module.cmake +++ b/cmake/px4_add_module.cmake @@ -166,12 +166,12 @@ function(px4_add_module) endif() if(NOT DYNAMIC) - target_link_libraries(${MODULE} PRIVATE prebuild_targets px4_platform systemlib perf) + target_link_libraries(${MODULE} PRIVATE prebuild_targets px4_platform systemlib perf uORB) if (${PX4_PLATFORM} STREQUAL "nuttx" AND NOT CONFIG_BUILD_FLAT AND KERNEL) - target_link_libraries(${MODULE} PRIVATE kernel_parameters_interface px4_kernel_layer uORB_kernel) + target_link_libraries(${MODULE} PRIVATE kernel_parameters_interface px4_kernel_layer) set_property(GLOBAL APPEND PROPERTY PX4_KERNEL_MODULE_LIBRARIES ${MODULE}) else() - target_link_libraries(${MODULE} PRIVATE parameters_interface px4_layer uORB) + target_link_libraries(${MODULE} PRIVATE parameters_interface px4_layer) set_property(GLOBAL APPEND PROPERTY PX4_MODULE_LIBRARIES ${MODULE}) endif() set_property(GLOBAL APPEND PROPERTY PX4_MODULE_PATHS ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/platforms/common/apps.cpp.in b/platforms/common/apps.cpp.in index 11d1c50d9f97..c42d79c85d3c 100644 --- a/platforms/common/apps.cpp.in +++ b/platforms/common/apps.cpp.in @@ -2,6 +2,7 @@ #include #include #include +#include #include "apps.h" @@ -43,6 +44,7 @@ void list_builtins(apps_map_type &apps) int shutdown_main(int argc, char *argv[]) { printf("Exiting NOW.\n"); + uORB::Manager::terminate(); system_exit(0); } diff --git a/platforms/common/include/px4_platform_common/posix.h b/platforms/common/include/px4_platform_common/posix.h index 29c83ff2c6c6..221757c08a91 100644 --- a/platforms/common/include/px4_platform_common/posix.h +++ b/platforms/common/include/px4_platform_common/posix.h @@ -45,19 +45,21 @@ #include #include #include +#include #include "sem.h" #define PX4_F_RDONLY 1 #define PX4_F_WRONLY 2 +typedef orb_poll_struct_t px4_pollfd_struct_t; +typedef orb_pollevent_t px4_pollevent_t; +#define px4_poll orb_poll + #ifdef __PX4_NUTTX #include -typedef struct pollfd px4_pollfd_struct_t; -typedef pollevent_t px4_pollevent_t; - #if defined(__cplusplus) #define _GLOBAL :: #else @@ -68,7 +70,6 @@ typedef pollevent_t px4_pollevent_t; #define px4_ioctl _GLOBAL ioctl #define px4_write _GLOBAL write #define px4_read _GLOBAL read -#define px4_poll _GLOBAL poll #define px4_access _GLOBAL access #define px4_getpid _GLOBAL getpid @@ -83,19 +84,6 @@ typedef pollevent_t px4_pollevent_t; __BEGIN_DECLS -typedef short px4_pollevent_t; - -typedef struct { - /* This part of the struct is POSIX-like */ - int fd; /* The descriptor being polled */ - px4_pollevent_t events; /* The input event flags */ - px4_pollevent_t revents; /* The output event flags */ - - /* Required for PX4 compatibility */ - px4_sem_t *arg; /* Pointer to semaphore used to post output event */ - void *priv; /* For use by drivers */ -} px4_pollfd_struct_t; - #ifndef POLLIN #define POLLIN (0x01) #endif @@ -118,7 +106,6 @@ __EXPORT int px4_close(int fd); __EXPORT ssize_t px4_read(int fd, void *buffer, size_t buflen); __EXPORT ssize_t px4_write(int fd, const void *buffer, size_t buflen); __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg); -__EXPORT int px4_poll(px4_pollfd_struct_t *fds, unsigned int nfds, int timeout); __EXPORT int px4_access(const char *pathname, int mode); __EXPORT px4_task_t px4_getpid(void); diff --git a/platforms/common/uORB/CMakeLists.txt b/platforms/common/uORB/CMakeLists.txt index 6330132cb03d..36378b61268e 100644 --- a/platforms/common/uORB/CMakeLists.txt +++ b/platforms/common/uORB/CMakeLists.txt @@ -34,9 +34,7 @@ # this includes the generated topics directory include_directories(${CMAKE_CURRENT_BINARY_DIR}) -set(SRCS) - -set(SRCS_COMMON +px4_add_library(uORB ORBSet.hpp Publication.hpp PublicationMulti.hpp @@ -50,55 +48,17 @@ set(SRCS_COMMON uORBCommon.hpp uORBCommunicator.hpp uORBManager.hpp + uORBManager.cpp uORBUtils.cpp uORBUtils.hpp - uORBDeviceMaster.hpp - uORBDeviceNode.hpp - ) - -set(SRCS_KERNEL - uORBDeviceMaster.cpp uORBDeviceNode.cpp - uORBManager.cpp - ) - -set(SRCS_USER - uORBManagerUsr.cpp + uORBDeviceNode.hpp ) -if (NOT DEFINED CONFIG_BUILD_FLAT AND "${PX4_PLATFORM}" MATCHES "nuttx") - # Kernel side library in nuttx kernel/protected build - px4_add_library(uORB_kernel - ${SRCS_COMMON} - ${SRCS_KERNEL} - ) - target_link_libraries(uORB_kernel PRIVATE cdev uorb_msgs nuttx_kmm) - target_compile_options(uORB_kernel PRIVATE ${MAX_CUSTOM_OPT_LEVEL} -D__KERNEL__) - - # User side library in nuttx kernel/protected build - px4_add_library(uORB - ${SRCS_COMMON} - ${SRCS_USER} - ) -elseif("${PX4_PLATFORM}" MATCHES "nuttx") - - # Library for NuttX (flat build, posix...) - px4_add_library(uORB - ${SRCS_COMMON} - ${SRCS_KERNEL} - ) - target_link_libraries(uORB PRIVATE cdev nuttx_mm) -else() - - # Library for all other targets (posix...) - px4_add_library(uORB - ${SRCS_COMMON} - ${SRCS_KERNEL} - ) - target_link_libraries(uORB PRIVATE cdev) +if ("${PX4_PLATFORM}" MATCHES "posix") + target_link_libraries(uORB PRIVATE rt) endif() -target_link_libraries(uORB PRIVATE uorb_msgs) target_compile_options(uORB PRIVATE ${MAX_CUSTOM_OPT_LEVEL}) if(PX4_TESTING) diff --git a/platforms/common/uORB/IndexedStack.hpp b/platforms/common/uORB/IndexedStack.hpp new file mode 100644 index 000000000000..a17a7829dbec --- /dev/null +++ b/platforms/common/uORB/IndexedStack.hpp @@ -0,0 +1,143 @@ +#pragma once + +#include + +/* + * This is a single-linked list/stack which items can be accessed via handle of + * type H. The handle can be either an index (int8_t) to a pre-allocated list, + * or a direct pointer to the item. The items should have a "next" member + * variable of the intended handle type. +*/ + +template class IndexedStack; + +/* The list can be used via the IndexedStackHandle element */ + +template +class IndexedStackHandle +{ +public: + IndexedStackHandle(class IndexedStack &stack) : _stack(stack) {} + + void push(H handle) { _stack.push(handle);} + H pop() { return _stack.pop(); } + void push_free(H handle) { _stack.push_free(handle); } + H pop_free() { return _stack.pop_free(); } + bool rm(H handle) { return _stack.rm(handle); } + H head() {return _stack._head;} + H next(H handle) {return peek(handle)->next;} + bool empty() {return !_stack.handle_valid(_stack.head());} + T *peek(H handle) { return _stack.handle_valid(handle) ? _stack.peek(handle) : nullptr; } + bool handle_valid(H handle) {return _stack.handle_valid(handle); } + +private: + + class IndexedStack &_stack; +}; + + +/* The actual implementation of the list. This supports two types of handles; + * void * for NuttX flat build / single process environment + * int8_t for share memory / communication between processes + */ + +template +class IndexedStack +{ +public: + friend class IndexedStackHandle; + + IndexedStack() + { + clear_handle(_head); + clear_handle(_free_head); + init_freelist(_free_head); + } + +private: + void push(H handle) { push(handle, _head);} + H pop() { return pop(_head); } + void push_free(H handle) { push(handle, _free_head); } + H pop_free() { return pop(_free_head); } + + bool rm(H handle) + { + H p = _head; + H r; clear_handle(r); + + if (!handle_valid(handle) || + !handle_valid(p)) { + return r; + } + + if (p == handle) { + // remove the first item + T *item = peek(_head); + _head = item->next; + r = p; + + } else { + while (handle_valid((r = peek(p)->next))) { + if (r == handle) { + T *prev = peek(p); + T *item = peek(r); + // remove the item + prev->next = item->next; + break; + } + + p = r; + } + } + + return handle_valid(r) ? true : false; + } + + /* Helper functions for constructor; initialize the list of free items */ + void init_freelist(int8_t handle) + { + /* Add all items into free list */ + IndexedStackHandle self(*this); + + for (int8_t i = 0; i < S ; i++) { + self.push_free(i); + } + + _free_head = S - 1; + } + + void init_freelist(void *handle) {} + + /* Push & pop internal implementations for actual and freelist */ + void push(H handle, H &head) + { + if (handle_valid(handle)) { + T *item = peek(handle); + item->next = head; + head = handle; + } + } + + H pop(H &head) + { + H ret = head; + + if (handle_valid(ret)) { + T *item = peek(head); + head = item->next; + } + + return ret; + } + + T *peek(int8_t handle) { return &_item[handle]; } + T *peek(void *handle) { return static_cast(handle); } + static bool handle_valid(int8_t handle) { return handle >= 0; } + static bool handle_valid(void *handle) { return handle != nullptr; } + static void clear_handle(int8_t &x) { x = -1; }; + static void clear_handle(void *&x) { x = nullptr; }; + + H _head; + H _free_head; + T _item[S]; +}; diff --git a/platforms/common/uORB/ORBSet.hpp b/platforms/common/uORB/ORBSet.hpp index 28e283c7b9e7..118284308852 100644 --- a/platforms/common/uORB/ORBSet.hpp +++ b/platforms/common/uORB/ORBSet.hpp @@ -33,12 +33,14 @@ #pragma once +#include + class ORBSet { public: struct Node { Node *next{nullptr}; - const char *node_name{nullptr}; + orb_advert_t handle{ORB_ADVERT_INVALID}; }; ORBSet() = default; @@ -49,8 +51,6 @@ class ORBSet unlinkNext(_top); if (_top->next == nullptr) { - free((void *)_top->node_name); - _top->node_name = nullptr; delete _top; _top = nullptr; @@ -58,7 +58,7 @@ class ORBSet } } - void insert(const char *node_name) + void insert(const orb_advert_t &handle) { Node **p; @@ -79,36 +79,31 @@ class ORBSet } _end->next = nullptr; - _end->node_name = strdup(node_name); + _end->handle = handle; } - bool find(const char *node_name) + orb_advert_t find(const char *node_name) { Node *p = _top; while (p) { - if (strcmp(p->node_name, node_name) == 0) { - return true; + if (strcmp(uORB::DeviceNode::get_name(p->handle), node_name) == 0) { + return p->handle; } p = p->next; } - return false; + return ORB_ADVERT_INVALID; } bool erase(const char *node_name) { Node *p = _top; - if (_top && (strcmp(_top->node_name, node_name) == 0)) { + if (_top && (strcmp(uORB::DeviceNode::get_name(_top->handle), node_name) == 0)) { p = _top->next; - if (_top->node_name) { - free((void *)_top->node_name); - _top->node_name = nullptr; - } - delete _top; _top = p; @@ -120,7 +115,7 @@ class ORBSet } while (p->next) { - if (strcmp(p->next->node_name, node_name) == 0) { + if (strcmp(uORB::DeviceNode::get_name(p->next->handle), node_name) == 0) { unlinkNext(p); return true; } @@ -142,11 +137,6 @@ class ORBSet a->next = b->next; - if (b->node_name) { - free((void *)b->node_name); - b->node_name = nullptr; - } - delete b; b = nullptr; } diff --git a/platforms/common/uORB/Publication.hpp b/platforms/common/uORB/Publication.hpp index 7547e3b7faf3..9f7763c033eb 100644 --- a/platforms/common/uORB/Publication.hpp +++ b/platforms/common/uORB/Publication.hpp @@ -70,19 +70,19 @@ class PublicationBase { public: - bool advertised() const { return _handle != nullptr; } + bool advertised() const { return orb_advert_valid(_handle); } bool unadvertise() { return (Manager::orb_unadvertise(_handle) == PX4_OK); } - orb_id_t get_topic() const { return get_orb_meta(_orb_id); } + orb_id_t get_topic() const { return _meta; } protected: - PublicationBase(ORB_ID id) : _orb_id(id) {} + PublicationBase(ORB_ID id) : _meta(get_orb_meta(id)) {} ~PublicationBase() { - if (_handle != nullptr) { + if (orb_advert_valid(_handle)) { // don't automatically unadvertise queued publications (eg vehicle_command) if (Manager::orb_get_queue_size(_handle) == 1) { unadvertise(); @@ -90,8 +90,8 @@ class PublicationBase } } - orb_advert_t _handle{nullptr}; - const ORB_ID _orb_id; + orb_advert_t _handle{ORB_ADVERT_INVALID}; + const orb_id_t _meta; }; /** diff --git a/platforms/common/uORB/PublicationMulti.hpp b/platforms/common/uORB/PublicationMulti.hpp index e7d3b3014ae5..3510013880cc 100644 --- a/platforms/common/uORB/PublicationMulti.hpp +++ b/platforms/common/uORB/PublicationMulti.hpp @@ -89,7 +89,7 @@ class PublicationMulti : public PublicationBase advertise(); } - return (orb_publish(get_topic(), &_handle, &data) == PX4_OK); + return (Manager::orb_publish(get_topic(), _handle, &data) == PX4_OK); } int get_instance() diff --git a/platforms/common/uORB/Subscription.cpp b/platforms/common/uORB/Subscription.cpp index 9c17cab378d2..6fe7ffb1ee44 100644 --- a/platforms/common/uORB/Subscription.cpp +++ b/platforms/common/uORB/Subscription.cpp @@ -36,26 +36,24 @@ * */ +#include #include "Subscription.hpp" -#include +#include "uORBManager.hpp" namespace uORB { -bool Subscription::subscribe() +bool Subscription::subscribe(bool advertise) { - // check if already subscribed - if (_node != nullptr) { + if (orb_advert_valid(_node)) { return true; } - if (_orb_id != ORB_ID::INVALID && uORB::Manager::get_instance()) { - unsigned initial_generation; - void *node = uORB::Manager::orb_add_internal_subscriber(_orb_id, _instance, &initial_generation); + if (_orb_id != ORB_ID::INVALID) { + _node = uORB::Manager::orb_add_internal_subscriber(_orb_id, _instance, &_last_generation, advertise); - if (node) { - _node = node; - _last_generation = initial_generation; + if (orb_advert_valid(_node)) { + _advertiser = advertise; return true; } } @@ -65,22 +63,30 @@ bool Subscription::subscribe() void Subscription::unsubscribe() { - if (_node != nullptr) { - uORB::Manager::orb_remove_internal_subscriber(_node); + if (orb_advert_valid(_node)) { + uORB::Manager::orb_remove_internal_subscriber(_node, _advertiser); } - _node = nullptr; _last_generation = 0; } bool Subscription::ChangeInstance(uint8_t instance) { if (instance != _instance) { - if (uORB::Manager::orb_device_node_exists(_orb_id, _instance)) { - // if desired new instance exists, unsubscribe from current + // Subscribe to the new existing node + unsigned generation; + + if (orb_exists(get_topic(), instance) != PX4_OK) { + return false; + } + + orb_advert_t new_node = uORB::Manager::orb_add_internal_subscriber(_orb_id, instance, &generation, false); + + if (orb_advert_valid(new_node)) { unsubscribe(); + _node = new_node; _instance = instance; - subscribe(); + _last_generation = generation; return true; } diff --git a/platforms/common/uORB/Subscription.hpp b/platforms/common/uORB/Subscription.hpp index 30bc61dee90b..6850e280d5e3 100644 --- a/platforms/common/uORB/Subscription.hpp +++ b/platforms/common/uORB/Subscription.hpp @@ -45,13 +45,10 @@ #include #include "uORBManager.hpp" -#include "uORBUtils.hpp" namespace uORB { -class SubscriptionCallback; - // Base subscription wrapper class class Subscription { @@ -112,25 +109,13 @@ class Subscription unsubscribe(); } - bool subscribe(); + bool subscribe(bool advertise = false); void unsubscribe(); - bool valid() const { return _node != nullptr; } + bool valid() const { return orb_advert_valid(_node); } bool advertised() { - if (valid()) { - return Manager::is_advertised(_node); - } - - // try to initialize - if (subscribe()) { - // check again if valid - if (valid()) { - return Manager::is_advertised(_node); - } - } - - return false; + return Manager::has_publisher(_orb_id, _instance); } /** @@ -186,16 +171,18 @@ class Subscription protected: friend class SubscriptionCallback; + friend class SubscriptionPollable; friend class SubscriptionCallbackWorkItem; - void *get_node() { return _node; } + orb_advert_t &get_node() { return _node; } - void *_node{nullptr}; + orb_advert_t _node{ORB_ADVERT_INVALID}; unsigned _last_generation{0}; /**< last generation the subscriber has seen */ ORB_ID _orb_id{ORB_ID::INVALID}; uint8_t _instance{0}; + bool _advertiser{false}; }; // Subscription wrapper class with data diff --git a/platforms/common/uORB/SubscriptionBlocking.hpp b/platforms/common/uORB/SubscriptionBlocking.hpp index 2df473e00c42..ae6fc704faf1 100644 --- a/platforms/common/uORB/SubscriptionBlocking.hpp +++ b/platforms/common/uORB/SubscriptionBlocking.hpp @@ -105,7 +105,7 @@ class SubscriptionBlocking : public SubscriptionCallback */ bool updatedBlocking(uint32_t timeout_us = 0) { - if (!_registered) { + if (!registered()) { registerCallback(); } diff --git a/platforms/common/uORB/SubscriptionCallback.hpp b/platforms/common/uORB/SubscriptionCallback.hpp index 942a9fbe17d3..b1fe664e4385 100644 --- a/platforms/common/uORB/SubscriptionCallback.hpp +++ b/platforms/common/uORB/SubscriptionCallback.hpp @@ -39,14 +39,14 @@ #pragma once #include -#include #include +#include namespace uORB { // Subscription wrapper class with callbacks on new publications -class SubscriptionCallback : public SubscriptionInterval, public ListNode +class SubscriptionCallback : public SubscriptionInterval { public: /** @@ -68,36 +68,29 @@ class SubscriptionCallback : public SubscriptionInterval, public ListNode -#include - -#include "uORBDeviceNode.hpp" -#include "uORBManager.hpp" -#include "uORBUtils.hpp" +#include +#include +#include #include "Subscription.hpp" -#include - namespace uORB { @@ -85,7 +81,7 @@ class SubscriptionInterval virtual ~SubscriptionInterval() = default; - bool subscribe() { return _subscription.subscribe(); } + bool subscribe(bool create = false) { return _subscription.subscribe(create); } void unsubscribe() { _subscription.unsubscribe(); } bool advertised() { return _subscription.advertised(); } diff --git a/platforms/common/uORB/uORB.cpp b/platforms/common/uORB/uORB.cpp index 508a24f31137..d09be27d6326 100644 --- a/platforms/common/uORB/uORB.cpp +++ b/platforms/common/uORB/uORB.cpp @@ -40,7 +40,7 @@ #include "uORBManager.hpp" #include "uORBCommon.hpp" - +#include "Publication.hpp" #include #include @@ -50,11 +50,11 @@ #include #endif -static uORB::DeviceMaster *g_dev = nullptr; +static bool initialized = false; int uorb_start(void) { - if (g_dev != nullptr) { + if (initialized) { PX4_WARN("already loaded"); /* user wanted to start uorb, its already running, no error */ return 0; @@ -65,51 +65,13 @@ int uorb_start(void) return -ENOMEM; } -#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT) || defined(__KERNEL__) - /* create the driver */ - g_dev = uORB::Manager::get_instance()->get_device_master(); - - if (g_dev == nullptr) { - return -errno; - } - -#endif - + initialized = true; return OK; } -int uorb_status(void) +int orb_poll(orb_poll_struct_t *fds, unsigned int nfds, int timeout) { -#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT) || defined(__KERNEL__) - - if (g_dev != nullptr) { - g_dev->printStatistics(); - - } else { - PX4_INFO("uorb is not running"); - } - -#else - boardctl(ORBIOCDEVMASTERCMD, ORB_DEVMASTER_STATUS); -#endif - return OK; -} - -int uorb_top(char **topic_filter, int num_filters) -{ -#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT) || defined(__KERNEL__) - - if (g_dev != nullptr) { - g_dev->showTop(topic_filter, num_filters); - - } else { - PX4_INFO("uorb is not running"); - } - -#else - boardctl(ORBIOCDEVMASTERCMD, ORB_DEVMASTER_TOP); -#endif - return OK; + return uORB::Manager::get_instance()->orb_poll(fds, nfds, timeout); } orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) @@ -135,12 +97,12 @@ orb_advert_t orb_advertise_multi_queue(const struct orb_metadata *meta, const vo int orb_unadvertise(orb_advert_t handle) { - return uORB::Manager::get_instance()->orb_unadvertise(handle); + return uORB::Manager::orb_unadvertise(handle); } int orb_publish(const struct orb_metadata *meta, orb_advert_t *handle, const void *data) { - return uORB::Manager::get_instance()->orb_publish(meta, *handle, data); + return uORB::Manager::orb_publish(meta, *handle, data); } orb_sub_t orb_subscribe(const struct orb_metadata *meta) @@ -160,7 +122,7 @@ int orb_unsubscribe(orb_sub_t handle) int orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buffer) { - return uORB::Manager::get_instance()->orb_copy(meta, handle, buffer); + return uORB::Manager::orb_copy(meta, handle, buffer); } int orb_check(orb_sub_t handle, bool *updated) @@ -170,14 +132,14 @@ int orb_check(orb_sub_t handle, bool *updated) int orb_exists(const struct orb_metadata *meta, int instance) { - return uORB::Manager::get_instance()->orb_exists(meta, instance); + return uORB::Manager::orb_exists(meta, instance); } int orb_group_count(const struct orb_metadata *meta) { unsigned instance = 0; - while (uORB::Manager::get_instance()->orb_exists(meta, instance) == OK) { + while (orb_exists(meta, instance) == OK) { ++instance; }; @@ -186,12 +148,12 @@ int orb_group_count(const struct orb_metadata *meta) int orb_set_interval(orb_sub_t handle, unsigned interval) { - return uORB::Manager::get_instance()->orb_set_interval(handle, interval); + return uORB::Manager::orb_set_interval(handle, interval); } int orb_get_interval(orb_sub_t handle, unsigned *interval) { - return uORB::Manager::get_instance()->orb_get_interval(handle, interval); + return uORB::Manager::orb_get_interval(handle, interval); } const char *orb_get_c_type(unsigned char short_type) diff --git a/platforms/common/uORB/uORB.h b/platforms/common/uORB/uORB.h index 72eec7ad7d33..2006ef08ebcd 100644 --- a/platforms/common/uORB/uORB.h +++ b/platforms/common/uORB/uORB.h @@ -56,6 +56,7 @@ struct orb_metadata { typedef const struct orb_metadata *orb_id_t; + /** * Maximum number of multi topic instances. This must be <= 10 (because it's the last char of the node path) */ @@ -114,27 +115,55 @@ typedef const struct orb_metadata *orb_id_t; __BEGIN_DECLS int uorb_start(void); -int uorb_status(void); -int uorb_top(char **topic_filter, int num_filters); /** * ORB topic advertiser handle. - * - * Advertiser handles are global; once obtained they can be shared freely - * and do not need to be closed or released. - * - * This permits publication from interrupt context and other contexts where - * a file-descriptor-based handle would not otherwise be in scope for the - * publisher. */ -typedef void *orb_advert_t; -typedef void *orb_sub_t; -static inline bool orb_advert_valid(orb_advert_t handle) {return handle != NULL;} -static const orb_advert_t ORB_ADVERT_INVALID = NULL; +typedef struct { + void *node; +#ifndef CONFIG_BUILD_FLAT + void *data; +#endif + size_t data_size; +} orb_advert_t; + +/** + * ORB topic subscriber handle. + */ + +typedef void *orb_sub_t; + +/** + * Helper functions to initialize and check the handles + */ + +static inline bool orb_advert_valid(orb_advert_t handle) {return handle.node != NULL;} +#ifndef CONFIG_BUILD_FLAT +static const orb_advert_t ORB_ADVERT_INVALID = {NULL, NULL, 0}; +#else +static const orb_advert_t ORB_ADVERT_INVALID = {NULL, 0}; +#endif static inline bool orb_sub_valid(orb_sub_t handle) {return handle != NULL;} static const orb_sub_t ORB_SUB_INVALID = NULL; +/** + * orb_poll struct + */ + +typedef short orb_pollevent_t; +typedef struct { + /* This part of the struct is POSIX-like */ + orb_sub_t fd; /* The polling subscriber handle */ + orb_pollevent_t events; /* The input event flags */ + orb_pollevent_t revents; /* The output event flags */ +} orb_poll_struct_t; + +/** + * @see uORB::Manager::orb_poll() + */ +extern int orb_poll(orb_poll_struct_t *fds, unsigned int nfds, int timeout) __EXPORT; + /** * @see uORB::Manager::orb_advertise() */ @@ -178,10 +207,10 @@ extern int orb_publish(const struct orb_metadata *meta, orb_advert_t *handle, co static inline int orb_publish_auto(const struct orb_metadata *meta, orb_advert_t *handle, const void *data, int *instance) { - if (!*handle) { + if (!orb_advert_valid(*handle)) { *handle = orb_advertise_multi(meta, data, instance); - if (*handle) { + if (orb_advert_valid(*handle)) { return 0; } diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index 7cc5c9bd3eb0..8665dd98bc90 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -31,6 +31,9 @@ * ****************************************************************************/ +#include +#include + #include "uORBDeviceNode.hpp" #include "uORBUtils.hpp" @@ -43,10 +46,176 @@ #endif /* CONFIG_ORB_COMMUNICATOR */ #if defined(__PX4_NUTTX) +#include #include +#include +#endif + +#include +#include + +// This is a speed optimization for nuttx flat build +#ifdef CONFIG_BUILD_FLAT +#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section() +#define ATOMIC_LEAVE px4_leave_critical_section(flags) +#else +#define ATOMIC_ENTER lock() +#define ATOMIC_LEAVE unlock() +#endif + +// Every subscriber thread has it's own list of cached subscriptions +uORB::DeviceNode::MappingCache::MappingCacheListItem *uORB::DeviceNode::MappingCache::g_cache = + nullptr; + +// This lock protects the subscription cache list from concurrent accesses by the threads in the same process +px4_sem_t uORB::DeviceNode::MappingCache::g_cache_lock; + +orb_advert_t uORB::DeviceNode::MappingCache::get(ORB_ID orb_id, uint8_t instance) +{ + lock(); + + MappingCacheListItem *item = g_cache; + + while (item && + (orb_id != node(item->handle)->id() || + instance != node(item->handle)->get_instance())) { + item = item->next; + } + + unlock(); + + return item != nullptr ? item->handle : ORB_ADVERT_INVALID; +} + +orb_advert_t uORB::DeviceNode::MappingCache::map_node(ORB_ID orb_id, uint8_t instance, int shm_fd) +{ + + // Check if it is already mapped + orb_advert_t handle = get(orb_id, instance); + + if (orb_advert_valid(handle)) { + return handle; + } + + lock(); + + // Not mapped yet, map it + void *ptr = mmap(0, sizeof(uORB::DeviceNode), PROT_READ | PROT_WRITE, MAP_SHARED, shm_fd, 0); + + if (ptr != MAP_FAILED) { + // In NuttX flat and protected builds we can just drop the mappings + // to save some kernel memory. There is no MMU, and the memory is + // there until the shm object is unlinked +#if defined(CONFIG_BUILD_FLAT) + munmap(ptr, sizeof(uORB::DeviceNode)); #endif -static uORB::SubscriptionInterval *filp_to_subscription(cdev::file_t *filp) { return static_cast(filp->f_priv); } + // Create a list item and add to the beginning of the list + handle.node = ptr; + MappingCacheListItem *item = new MappingCacheListItem{g_cache, handle}; + + if (item) { + g_cache = item; + } + } + + unlock(); + + return handle; +} + +#if !defined(CONFIG_BUILD_FLAT) +orb_advert_t uORB::DeviceNode::MappingCache::map_data(orb_advert_t handle, int shm_fd, size_t size, bool publisher) +{ + lock(); + + MappingCacheListItem *item = g_cache; + + while (item && + handle.node != item->handle.node) { + item = item->next; + } + + if (item != nullptr) { + + if (item->handle.data != nullptr && item->handle.data_size == size) { + // Mapped already, return the mapping + handle = item->handle; + + } else { + // Drop any old mapping if exists + if (handle.data != nullptr) { + munmap(handle.data, handle.data_size); + } + + // Map the data with new size + if (shm_fd >= 0 && size > 0) { + handle.data = mmap(0, size, publisher ? PROT_WRITE : PROT_READ, MAP_SHARED, shm_fd, 0); + + if (handle.data == MAP_FAILED) { + handle.data = nullptr; + handle.data_size = 0; + PX4_ERR("MMAP fail\n"); + + } else { + handle.data_size = size; + } + + } else { + handle.data = nullptr; + handle.data_size = 0; + } + + item->handle = handle; + } + } + + unlock(); + + return handle; +} +#endif + +bool uORB::DeviceNode::MappingCache::del(const orb_advert_t &handle) +{ + MappingCacheListItem *prev = nullptr; + + lock(); + + MappingCacheListItem *item = g_cache; + + while (item && + handle.node != item->handle.node) { + prev = item; + item = item->next; + } + + if (item != nullptr) { + if (prev == nullptr) { + // Remove the first item + g_cache = item->next; + + } else { + prev->next = item->next; + } + + munmap(handle.node, sizeof(DeviceNode)); + +#ifndef CONFIG_BUILD_FLAT + + if (handle.data) { + munmap(handle.data, handle.data_size); + } + +#endif + + delete (item); + } + + unlock(); + + return item != nullptr ? true : false; +} // round up to nearest power of two // Such as 0 => 1, 1 => 1, 2 => 2 ,3 => 4, 10 => 16, 60 => 64, 65...255 => 128 @@ -73,210 +242,389 @@ static inline uint8_t round_pow_of_two_8(uint8_t n) return value + 1; } -uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path, - uint8_t queue_size) : - CDev(strdup(path)), // success is checked in CDev::init - _meta(meta), - _instance(instance), - _queue_size(round_pow_of_two_8(queue_size)) +orb_advert_t uORB::DeviceNode::nodeOpen(const ORB_ID id, const uint8_t instance, bool create) { + /* + * Generate the path to the node and try to open it. + */ + + orb_advert_t handle = MappingCache::get(id, instance); + + if (orb_advert_valid(handle)) { + return handle; + } + + char nodepath[orb_maxpath]; + int inst = instance; + int ret = uORB::Utils::node_mkpath(nodepath, get_orb_meta(id), &inst); + bool created = false; + + if (ret != OK) { + return handle; + } + + // First, try to create the node. This will fail if it already exists + + int shm_fd = -1; + + if (create) { + shm_fd = shm_open(nodepath, O_CREAT | O_RDWR | O_EXCL, 0666); + + if (shm_fd >= 0) { + + // If the creation succeeded, set the size of the shm region + if (ftruncate(shm_fd, sizeof(uORB::DeviceNode)) != 0) { + ::close(shm_fd); + shm_fd = -1; + PX4_ERR("truncate fail!\n"); + + } else { + created = true; + } + } + } + + if (shm_fd < 0) { + // Now try to open an existing one + + shm_fd = shm_open(nodepath, O_RDWR, 0666); + } + + if (shm_fd < 0) { + // We were not able to create a new node or open an existing one + return handle; + } + + handle = MappingCache::map_node(id, instance, shm_fd); + + // No need to keep the fd any more, close it + + ::close(shm_fd); + + if (orb_advert_valid(handle) && created) { + // construct the new node in the region + new (node(handle)) uORB::DeviceNode(id, instance, nodepath); + } + + return handle; } -uORB::DeviceNode::~DeviceNode() +int uORB::DeviceNode::nodeClose(orb_advert_t &handle) { - free(_data); + if (!orb_advert_valid(handle)) { + return PX4_ERROR; + } - const char *devname = get_devname(); + if (node(handle)->_publisher_count == 0) { + node(handle)->_queue_size = 0; + node(handle)->_data_valid = false; - if (devname) { -#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT) - kmm_free((void *)devname); + // Delete the data +#ifdef CONFIG_BUILD_FLAT + free(node(handle)->_data); + node(handle)->_data = nullptr; #else - free((void *)devname); + shm_unlink(node(handle)->get_devname() + 1); + MappingCache::map_data(handle, -1, 0, false); #endif + + // If there are no more subscribers, delete the node and its mapping + if (node(handle)->_subscriber_count == 0) { + + // Close the Node object + shm_unlink(node(handle)->get_devname()); + + // Uninitialize the node + delete (node(handle)); + + // Delete the mappings for this process + MappingCache::del(handle); + } } + + handle = ORB_ADVERT_INVALID; + + return PX4_OK; } -int -uORB::DeviceNode::open(cdev::file_t *filp) +orb_advert_t uORB::DeviceNode::orb_advertise(const ORB_ID id, int instance, unsigned queue_size, + bool publisher) { - /* is this a publisher? */ - if (filp->f_oflags == PX4_F_WRONLY) { + /* Open the node, if it exists or create a new one */ - lock(); - mark_as_advertised(); - unlock(); + orb_advert_t handle; + handle = nodeOpen(id, instance, true); - /* now complete the open */ - return CDev::open(filp); + if (orb_advert_valid(handle)) { + node(handle)->advertise(publisher, queue_size); } - /* is this a new subscriber? */ - if (filp->f_oflags == PX4_F_RDONLY) { + return handle; +} - /* allocate subscriber data */ - SubscriptionInterval *sd = new SubscriptionInterval(_meta, 0, _instance); +int uORB::DeviceNode::advertise(bool publisher, uint8_t queue_size) +{ + int ret = -1; - if (nullptr == sd) { - return -ENOMEM; - } + ret = ++_advertiser_count; - filp->f_priv = (void *)sd; + if (publisher) { + ret = ++_publisher_count; + } - int ret = CDev::open(filp); + update_queue_size(queue_size); - if (ret != PX4_OK) { - PX4_ERR("CDev::open failed"); - delete sd; - } + return ret; +} - return ret; +int uORB::DeviceNode::orb_unadvertise(orb_advert_t &handle, bool publisher) +{ + int ret = -1; + + if (orb_advert_valid(handle)) { + ret = node(handle)->unadvertise(publisher); + nodeClose(handle); } - if (filp->f_oflags == 0) { - return CDev::open(filp); + return ret; +} + +int uORB::DeviceNode::unadvertise(bool publisher) +{ + int ret = -1; + + ret = --_advertiser_count; + + if (publisher) { + --_publisher_count; } - /* can only be pub or sub, not both */ - return -EINVAL; + return ret; } -int -uORB::DeviceNode::close(cdev::file_t *filp) +uORB::DeviceNode::DeviceNode(const ORB_ID id, const uint8_t instance, const char *path) : + _orb_id(id), + _instance(instance) { - if (filp->f_oflags == PX4_F_RDONLY) { /* subscriber */ - SubscriptionInterval *sd = filp_to_subscription(filp); - delete sd; +#if defined(CONFIG_BUILD_FLAT) + _devname = strdup(path); +#else + + if (strnlen(path, sizeof(_devname)) == sizeof(_devname)) { + PX4_ERR("node path too long %s", path); } - return CDev::close(filp); + strncpy(_devname, path, sizeof(_devname)); +#endif + + int ret = px4_sem_init(&_lock, 1, 1); + + if (ret != 0) { + PX4_DEBUG("SEM INIT FAIL: ret %d", ret); + } } -ssize_t -uORB::DeviceNode::read(cdev::file_t *filp, char *buffer, size_t buflen) +uORB::DeviceNode::~DeviceNode() { - /* if the caller's buffer is the wrong size, that's an error */ - if (buflen != _meta->o_size) { - return -EIO; + px4_sem_destroy(&_lock); + +#if defined(CONFIG_BUILD_FLAT) + + // Delete all the allocated free callback items. + // There should not be any left in use, since the node is + // deleted only if there are no more publishers or subscribers registered + + IndexedStackHandle callbacks(_callbacks); + uorb_cb_handle_t handle = callbacks.pop_free(); + + while (callbacks.handle_valid(handle)) { + delete (static_cast(callbacks.peek(handle))); + handle = callbacks.pop_free(); } - return filp_to_subscription(filp)->copy(buffer) ? _meta->o_size : 0; + free(_devname); +#endif } -ssize_t -uORB::DeviceNode::write(cdev::file_t *filp, const char *buffer, size_t buflen) +/* Map the node data to the memory space of publisher or subscriber */ + +void uORB::DeviceNode::remap_data(orb_advert_t &handle, size_t new_size, bool publisher) { - /* - * Writes are legal from interrupt context as long as the - * object has already been initialised from thread context. - * - * Writes outside interrupt context will allocate the object - * if it has not yet been allocated. - * - * Note that filp will usually be NULL. - */ - if (nullptr == _data) { + // In NuttX flat and protected builds, just malloc the data (from user heap) + // and store + // the pointer. This saves us the inodes in the + // kernel side. Otherwise the same logic would work -#ifdef __PX4_NUTTX +#ifdef CONFIG_BUILD_FLAT - if (!up_interrupt_context()) { -#endif /* __PX4_NUTTX */ + // Data size has changed, re-allocate (remap) by publisher + // The remapping may happen only on the first write, + // when the handle.data_size==0 - lock(); + if (publisher && handle.data_size == 0) { + free(_data); + _data = malloc(new_size); + } - /* re-check size */ - if (nullptr == _data) { - const size_t data_size = _meta->o_size * _queue_size; - _data = (uint8_t *) px4_cache_aligned_alloc(data_size); - memset(_data, 0, data_size); - } + if (_data != nullptr) { + handle.data_size = new_size; - unlock(); + } else { + handle.data_size = 0; + } -#ifdef __PX4_NUTTX - } +#else + + // Open the data, the data shm name is the same as device node's except for leading '_' + int oflag = publisher ? O_RDWR | O_CREAT : O_RDONLY; + int shm_fd = shm_open(get_devname() + 1, oflag, 0666); -#endif /* __PX4_NUTTX */ + // and mmap it + if (shm_fd >= 0) { - /* failed or could not allocate */ - if (nullptr == _data) { - return -ENOMEM; + // For the publisher, set the new data size + if (publisher && handle.data_size == 0) { + if (ftruncate(shm_fd, new_size) != 0) { + ::close(shm_fd); + PX4_ERR("Setting advertise size failed\n"); + return; + } } + + handle = MappingCache::map_data(handle, shm_fd, new_size, publisher); + + // Close the shm, there is no need to leave it open + ::close(shm_fd); } - /* If write size does not match, that is an error */ - if (_meta->o_size != buflen) { - return -EIO; +#endif +} + +/** + * Copies data and the corresponding generation + * from a node to the buffer provided. + * + * @param dst + * The buffer into which the data is copied. + * @param generation + * The generation that was copied. + * @return bool + * Returns true if the data was copied. + */ +bool uORB::DeviceNode::copy(void *dst, orb_advert_t &handle, unsigned &generation) +{ + if (dst == nullptr || !_data_valid) { + return false; } - /* Perform an atomic copy. */ + size_t o_size = get_meta()->o_size; + size_t data_size = _queue_size * o_size; + ATOMIC_ENTER; - /* wrap-around happens after ~49 days, assuming a publisher rate of 1 kHz */ - unsigned generation = _generation.fetch_add(1); - memcpy(_data + (_meta->o_size * (generation % _queue_size)), buffer, _meta->o_size); + if (data_size != handle.data_size) { + remap_data(handle, data_size, false); - // callbacks - for (auto item : _callbacks) { - item->call(); + if (node_data(handle) == nullptr) { + ATOMIC_LEAVE; + return false; + } } - /* Mark at least one data has been published */ - _data_valid = true; + if (_queue_size == 1) { + memcpy(dst, node_data(handle), o_size); + generation = _generation.load(); + + } else { + const unsigned current_generation = _generation.load(); + + if (current_generation == generation) { + /* The subscriber already read the latest message, but nothing new was published yet. + * Return the previous message + */ + --generation; + } + + /* Compatible with normal and overflow conditions */ + if (current_generation - generation > _queue_size) { + /* Reader is too far behind: some messages are lost */ + generation = current_generation - _queue_size; + } + + memcpy(dst, ((uint8_t *)node_data(handle)) + (o_size * (generation % _queue_size)), o_size); + + ++generation; + } ATOMIC_LEAVE; - /* notify any poll waiters */ - poll_notify(POLLIN); + return true; - return _meta->o_size; } -int -uORB::DeviceNode::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) +ssize_t +uORB::DeviceNode::write(const char *buffer, const orb_metadata *meta, orb_advert_t &handle) { - switch (cmd) { - case ORBIOCUPDATED: { - ATOMIC_ENTER; - *(bool *)arg = filp_to_subscription(filp)->updated(); - ATOMIC_LEAVE; - return PX4_OK; - } + size_t o_size = meta->o_size; - case ORBIOCSETINTERVAL: - filp_to_subscription(filp)->set_interval_us(arg); - return PX4_OK; + /* If data size has changed, re-map the data */ + size_t data_size = _queue_size * o_size; - case ORBIOCGADVERTISER: - *(uintptr_t *)arg = (uintptr_t)this; - return PX4_OK; + /* Perform an atomic copy. */ + ATOMIC_ENTER; - case ORBIOCSETQUEUESIZE: { - lock(); - int ret = update_queue_size(arg); - unlock(); - return ret; - } + if (data_size != handle.data_size) { + remap_data(handle, data_size, true); + } - case ORBIOCGETINTERVAL: - *(unsigned *)arg = filp_to_subscription(filp)->get_interval_us(); - return PX4_OK; + if (node_data(handle) == nullptr) { + ATOMIC_LEAVE; + return -ENOMEM; + } - case ORBIOCISADVERTISED: - *(unsigned long *)arg = _advertised; + /* wrap-around happens after ~49 days, assuming a publisher rate of 1 kHz */ + unsigned generation = _generation.fetch_add(1); - return PX4_OK; + memcpy(((uint8_t *)node_data(handle)) + o_size * (generation % _queue_size), buffer, o_size); + + /* Mark at least one data has been published */ + _data_valid = true; + + uORB::DeviceNode *n = node(handle); + IndexedStackHandle callbacks(n->_callbacks); - default: - /* give it to the superclass */ - return CDev::ioctl(filp, cmd, arg); + uorb_cb_handle_t cb = callbacks.head(); + + while (callbacks.handle_valid(cb)) { + EventWaitItem *item = callbacks.peek(cb); + + if (item->interval_us == 0 || hrt_elapsed_time(&item->last_update) >= item->interval_us) { + if (item->subscriber != nullptr) { +#ifdef CONFIG_BUILD_FLAT + item->subscriber->call(); +#else + Manager::queueCallback(item->subscriber); +#endif + } + + // Release poll waiters (and callback threads in non-flat builds) + if (item->lock != -1) { + Manager::unlockThread(item->lock); + } + } + + cb = callbacks.next(cb); } + + ATOMIC_LEAVE; + + return o_size; } ssize_t -uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data) +uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t &handle, const void *data) { - uORB::DeviceNode *devnode = (uORB::DeviceNode *)handle; + uORB::DeviceNode *devnode = node(handle); int ret; /* check if the device handle is initialized and data is valid */ @@ -286,18 +634,13 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v } /* check if the orb meta data matches the publication */ - if (devnode->_meta->o_id != meta->o_id) { + if (static_cast(devnode->id()) != meta->o_id) { errno = EINVAL; return PX4_ERROR; } - /* call the devnode write method with no file pointer */ - ret = devnode->write(nullptr, (const char *)data, meta->o_size); - - if (ret < 0) { - errno = -ret; - return PX4_ERROR; - } + /* call the devnode write method */ + ret = devnode->write((const char *)data, meta, handle); if (ret != (int)meta->o_size) { errno = EIO; @@ -322,30 +665,6 @@ uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const v return PX4_OK; } -int uORB::DeviceNode::unadvertise(orb_advert_t handle) -{ - if (handle == nullptr) { - return -EINVAL; - } - - uORB::DeviceNode *devnode = (uORB::DeviceNode *)handle; - - /* - * We are cheating a bit here. First, with the current implementation, we can only - * have multiple publishers for instance 0. In this case the caller will have - * instance=nullptr and _published has no effect at all. Thus no unadvertise is - * necessary. - * In case of multiple instances, we have at most 1 publisher per instance and - * we can signal an instance as 'free' by setting _published to false. - * We never really free the DeviceNode, for this we would need reference counting - * of subscribers and publishers. But we also do not have a leak since future - * publishers reuse the same DeviceNode object. - */ - devnode->_advertised = false; - - return PX4_OK; -} - #ifdef CONFIG_ORB_COMMUNICATOR int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta) { @@ -359,28 +678,9 @@ int16_t uORB::DeviceNode::topic_advertised(const orb_metadata *meta) } #endif /* CONFIG_ORB_COMMUNICATOR */ -px4_pollevent_t -uORB::DeviceNode::poll_state(cdev::file_t *filp) -{ - // If the topic appears updated to the subscriber, say so. - return filp_to_subscription(filp)->updated() ? POLLIN : 0; -} - -void -uORB::DeviceNode::poll_notify_one(px4_pollfd_struct_t *fds, px4_pollevent_t events) -{ - // If the topic looks updated to the subscriber, go ahead and notify them. - if (filp_to_subscription((cdev::file_t *)fds->priv)->updated()) { - CDev::poll_notify_one(fds, events); - } -} - bool uORB::DeviceNode::print_statistics(int max_topic_length) { - if (!_advertised) { - return false; - } lock(); @@ -390,15 +690,40 @@ uORB::DeviceNode::print_statistics(int max_topic_length) unlock(); - PX4_INFO_RAW("%-*s %2i %4i %2i %4i %s\n", max_topic_length, get_meta()->o_name, (int)instance, (int)sub_count, - queue_size, get_meta()->o_size, get_devname()); + const orb_metadata *meta = get_meta(); + + PX4_INFO_RAW("%-*s %2i %4i %2i %4i %s\n", max_topic_length, meta->o_name, (int)instance, (int)sub_count, + queue_size, meta->o_size, get_devname()); return true; } -void uORB::DeviceNode::add_internal_subscriber() +orb_advert_t uORB::DeviceNode::add_subscriber(ORB_ID orb_id, uint8_t instance, + unsigned *initial_generation, bool advertise) { - lock(); + orb_advert_t handle; + + if (advertise) { + handle = orb_advertise(orb_id, instance, 0, false); + + } else { + handle = nodeOpen(orb_id, instance, false); + } + + if (orb_advert_valid(handle)) { + node(handle)->_add_subscriber(initial_generation); + + } else { + *initial_generation = 0; + } + + return handle; +} + + +void uORB::DeviceNode::_add_subscriber(unsigned *initial_generation) +{ + *initial_generation = _generation.load() - (_data_valid ? 1 : 0); _subscriber_count++; #ifdef CONFIG_ORB_COMMUNICATOR @@ -406,72 +731,84 @@ void uORB::DeviceNode::add_internal_subscriber() if (ch != nullptr && _subscriber_count > 0) { unlock(); //make sure we cannot deadlock if add_subscription calls back into DeviceNode - ch->add_subscription(_meta->o_name, 1); - - } else -#endif /* CONFIG_ORB_COMMUNICATOR */ + ch->add_subscription(get_name(), 1); - { - unlock(); } + +#endif /* CONFIG_ORB_COMMUNICATOR */ } -void uORB::DeviceNode::remove_internal_subscriber() + +int8_t uORB::DeviceNode::remove_subscriber(orb_advert_t &handle, bool advertiser) { - lock(); - _subscriber_count--; + int8_t ret = _subscriber_count--; + + if (advertiser) { + orb_unadvertise(handle, false); + + } else { + nodeClose(handle); + + } #ifdef CONFIG_ORB_COMMUNICATOR uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator(); - if (ch != nullptr && _subscriber_count == 0) { - unlock(); //make sure we cannot deadlock if remove_subscription calls back into DeviceNode - ch->remove_subscription(_meta->o_name); + if (ch != nullptr && ret == 0) { + ch->remove_subscription(get_meta()->o_name); - } else -#endif /* CONFIG_ORB_COMMUNICATOR */ - { - unlock(); } + +#endif /* ORB_COMMUNICATOR */ + + return ret; } #ifdef CONFIG_ORB_COMMUNICATOR -int16_t uORB::DeviceNode::process_add_subscription() +int16_t uORB::DeviceNode::process_add_subscription(orb_advert_t &handle) { // if there is already data in the node, send this out to // the remote entity. // send the data to the remote entity. uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator(); + const orb_metadata *meta = get_meta(); - if (_data != nullptr && ch != nullptr) { // _data will not be null if there is a publisher. - ch->send_message(_meta->o_name, _meta->o_size, _data); + if (ch != nullptr) { + ch->send_message(meta->o_name, meta->o_size, (uint8_t *)node_data(handle)); } return PX4_OK; } -int16_t uORB::DeviceNode::process_remove_subscription() +int16_t uORB::DeviceNode::process_remove_subscription(orb_advert_t &handle) { return PX4_OK; } -int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data) +int16_t uORB::DeviceNode::process_received_message(orb_advert_t &handle, int32_t length, uint8_t *data) { int16_t ret = -1; - if (length != (int32_t)(_meta->o_size)) { - PX4_ERR("Received '%s' with DataLength[%d] != ExpectedLen[%d]", _meta->o_name, (int)length, (int)_meta->o_size); + if (!orb_advert_valid(handle)) { + return ret; + } + + const orb_metadata *meta = get_meta(); + + if (length != (int32_t)(meta->o_size)) { + PX4_ERR("Received '%s' with DataLength[%d] != ExpectedLen[%d]", meta->o_name, (int)length, + (int)meta->o_size); return PX4_ERROR; } - /* call the devnode write method with no file pointer */ - ret = write(nullptr, (const char *)data, _meta->o_size); + /* call the devnode write method */ + ret = write((const char *)data, meta, handle); if (ret < 0) { return PX4_ERROR; } - if (ret != (int)_meta->o_size) { + if (ret != (int)meta->o_size) { errno = EIO; return PX4_ERROR; } @@ -482,57 +819,87 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data int uORB::DeviceNode::update_queue_size(unsigned int queue_size) { - if (_queue_size == queue_size) { + // subscribers may advertise the node, but not set the queue_size + if (queue_size == 0) { return PX4_OK; } - //queue size is limited to 255 for the single reason that we use uint8 to store it - if (_data || _queue_size > queue_size || queue_size > 255) { + queue_size = round_pow_of_two_8(queue_size); + + // queue size is limited to 255 for the single reason that we use uint8 to store it + if (queue_size > 255) { return PX4_ERROR; } - _queue_size = round_pow_of_two_8(queue_size); + _queue_size = queue_size; + return PX4_OK; } -unsigned uORB::DeviceNode::get_initial_generation() +//TODO: make this a normal member function +uorb_cb_handle_t +uORB::DeviceNode::register_callback(orb_advert_t &node_handle, uORB::SubscriptionCallback *callback_sub, + int8_t poll_lock, hrt_abstime last_update, uint32_t interval_us) { - ATOMIC_ENTER; + uORB::DeviceNode *n = node(node_handle); - // If there any previous publications allow the subscriber to read them - unsigned generation = _generation.load() - (_data_valid ? 1 : 0); + n->lock(); - ATOMIC_LEAVE; +#ifndef CONFIG_BUILD_FLAT + // Get the cb lock for this process from the Manager + int8_t lock = poll_lock == -1 ? Manager::getCallbackLock() : poll_lock; +#else + int8_t lock = poll_lock; +#endif - return generation; -} + // TODO: Check for duplicate registrations? -bool -uORB::DeviceNode::register_callback(uORB::SubscriptionCallback *callback_sub) -{ - if (callback_sub != nullptr) { - ATOMIC_ENTER; - - // prevent duplicate registrations - for (auto existing_callbacks : _callbacks) { - if (callback_sub == existing_callbacks) { - ATOMIC_LEAVE; - return true; - } - } + IndexedStackHandle callbacks(n->_callbacks); + uorb_cb_handle_t i = callbacks.pop_free(); + EventWaitItem *item = callbacks.peek(i); - _callbacks.add(callback_sub); - ATOMIC_LEAVE; - return true; +#ifdef CONFIG_BUILD_FLAT + + if (!item) { + item = new EventWaitItem; + i = item; + } + +#endif + + if (item != nullptr) { + item->lock = lock; + item->subscriber = callback_sub; + item->last_update = last_update; + item->interval_us = interval_us; + + callbacks.push(i); + + } else { + PX4_ERR("register fail\n"); } - return false; + n->unlock(); + + return i; } +//TODO: make this a normal member function? void -uORB::DeviceNode::unregister_callback(uORB::SubscriptionCallback *callback_sub) +uORB::DeviceNode::unregister_callback(orb_advert_t &node_handle, uorb_cb_handle_t cb_handle) { - ATOMIC_ENTER; - _callbacks.remove(callback_sub); - ATOMIC_LEAVE; + uORB::DeviceNode *n = node(node_handle); + + n->lock(); + + IndexedStackHandle callbacks(n->_callbacks); + + if (!callbacks.rm(cb_handle)) { + PX4_ERR("unregister fail\n"); + + } else { + callbacks.push_free(cb_handle); + } + + n->unlock(); } diff --git a/platforms/common/uORB/uORBDeviceNode.hpp b/platforms/common/uORB/uORBDeviceNode.hpp index c5c5bb22c0c8..1067337fdeea 100644 --- a/platforms/common/uORB/uORBDeviceNode.hpp +++ b/platforms/common/uORB/uORBDeviceNode.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. + * Copyight (c) 2012-2016 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,37 +33,59 @@ #pragma once -#include "uORBCommon.hpp" -#include "uORBDeviceMaster.hpp" +#include +#include +#include +#include +#include +#include -#include +#include "uORB.h" +#include "uORBCommon.hpp" +#include +#include -#include #include #include #include -namespace uORB -{ -class DeviceNode; -class DeviceMaster; -class Manager; -class SubscriptionCallback; -} +#include "IndexedStack.hpp" + +#if defined(CONFIG_BUILD_FLAT) +#define MAX_EVENT_WAITERS 0 // dynamic +typedef void *uorb_cb_handle_t; +#define UORB_INVALID_CB_HANDLE nullptr +#define uorb_cb_handle_valid(x) ((x) != nullptr) +#else +#define MAX_EVENT_WAITERS 6 +#define UORB_INVALID_CB_HANDLE -1 +typedef int8_t uorb_cb_handle_t; +#define uorb_cb_handle_valid(x) ((x) >= 0) +#endif + +#define CB_LIST_T struct EventWaitItem, uorb_cb_handle_t, MAX_EVENT_WAITERS namespace uORBTest { class UnitTest; } +namespace uORB +{ + +class SubscriptionCallback; + /** * Per-object device instance. */ -class uORB::DeviceNode : public cdev::CDev, public IntrusiveSortedListNode +class DeviceNode { public: - DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path, uint8_t queue_size = 1); - virtual ~DeviceNode(); + // Open a node, either existing or create a new one + static orb_advert_t nodeOpen(const ORB_ID id, const uint8_t instance, bool create); + static int nodeClose(orb_advert_t &handle); + + ~DeviceNode(); // no copy, assignment, move, move assignment DeviceNode(const DeviceNode &) = delete; @@ -74,56 +96,25 @@ class uORB::DeviceNode : public cdev::CDev, public IntrusiveSortedListNodeget_name(); - static int unadvertise(orb_advert_t handle); + } else { + return nullptr; + } + } -#ifdef CONFIG_ORB_COMMUNICATOR /** * processes a request for topic advertisement from remote * @param meta @@ -140,53 +131,40 @@ class uORB::DeviceNode : public cdev::CDev, public IntrusiveSortedListNode(_meta->o_id); } + ORB_ID id() const { return _orb_id; } - const char *get_name() const { return _meta->o_name; } + const char *get_name() const { return get_orb_meta(_orb_id)->o_name; } uint8_t get_instance() const { return _instance; } @@ -231,82 +212,133 @@ class uORB::DeviceNode : public cdev::CDev, public IntrusiveSortedListNodeo_size); - generation = _generation.load(); - ATOMIC_LEAVE; - return true; - - } else { - ATOMIC_ENTER; - const unsigned current_generation = _generation.load(); - - if (current_generation == generation) { - /* The subscriber already read the latest message, but nothing new was published yet. - * Return the previous message - */ - --generation; - } - - // Compatible with normal and overflow conditions - if (!is_in_range(current_generation - _queue_size, generation, current_generation - 1)) { - // Reader is too far behind: some messages are lost - generation = current_generation - _queue_size; - } - - memcpy(dst, _data + (_meta->o_size * (generation % _queue_size)), _meta->o_size); - ATOMIC_LEAVE; - - ++generation; - - return true; - } - } - - return false; + bool copy(void *dst, orb_advert_t &handle, unsigned &generation); - } + static void orb_callback(int signo, siginfo_t *si_info, void *data); - // add item to list of work items to schedule on node update - bool register_callback(SubscriptionCallback *callback_sub); + static uorb_cb_handle_t register_callback(orb_advert_t &node_handle, SubscriptionCallback *callback_sub, + int8_t poll_lock, + hrt_abstime last_update, uint32_t interval_us); - // remove item from list of work items - void unregister_callback(SubscriptionCallback *callback_sub); + static void unregister_callback(orb_advert_t &node_handle, uorb_cb_handle_t cb_handle); -protected: + void *operator new (size_t, void *p) + { + return p; + } - px4_pollevent_t poll_state(cdev::file_t *filp) override; + void operator delete (void *p) + { + } - void poll_notify_one(px4_pollfd_struct_t *fds, px4_pollevent_t events) override; + const char *get_devname() const {return _devname;} private: friend uORBTest::UnitTest; - const orb_metadata *_meta; /**< object metadata information */ + //const orb_metadata *_meta; /**< object metadata information */ + const ORB_ID _orb_id; - uint8_t *_data{nullptr}; /**< allocated object buffer */ bool _data_valid{false}; /**< At least one valid data */ px4::atomic _generation{0}; /**< object generation count */ - List _callbacks; - const uint8_t _instance; /**< orb multi instance identifier */ - bool _advertised{false}; /**< has ever been advertised (not necessarily published data yet) */ - uint8_t _queue_size; /**< maximum number of elements in the queue */ - int8_t _subscriber_count{0}; + struct EventWaitItem { + struct SubscriptionCallback *subscriber; + hrt_abstime last_update; + uint32_t interval_us; + int8_t lock; + uorb_cb_handle_t next; // List ptr + }; + IndexedStack _callbacks; -// Determine the data range - static inline bool is_in_range(unsigned left, unsigned value, unsigned right) - { - if (right > left) { - return (left <= value) && (value <= right); + inline ssize_t write(const char *buffer, const orb_metadata *meta, orb_advert_t &handle); + static int callback_thread(int argc, char *argv[]); + struct SubscriptionCallback *callback_sub; - } else { // Maybe the data overflowed and a wraparound occurred - return (left <= value) || (value <= right); + class MappingCache + { + public: + struct MappingCacheListItem { + MappingCacheListItem *next; + orb_advert_t handle; + }; + + // This list is process specific in kernel build and global in in flat + static MappingCacheListItem *g_cache; + static px4_sem_t g_cache_lock; + + static void init(void) + { + static bool initialized = false; + + if (!initialized) { + px4_sem_init(&g_cache_lock, 0, 1); + initialized = true; + } } - } + static orb_advert_t get(ORB_ID orb_id, uint8_t instance); + static orb_advert_t map_node(ORB_ID orb_id, uint8_t instance, int shm_fd); + static orb_advert_t map_data(orb_advert_t handle, int shm_fd, size_t size, bool publisher); + static bool del(const orb_advert_t &handle); + + static void lock() + { + init(); + do {} while (px4_sem_wait(&g_cache_lock) != 0); + } + static void unlock() { px4_sem_post(&g_cache_lock); } + }; + + const uint8_t _instance; /**< orb multi instance identifier */ + uint8_t _queue_size{0}; /**< maximum number of elements in the queue */ + int8_t _subscriber_count{0}; /**< how many subscriptions there are */ + int8_t _publisher_count{0}; /**< how many publishers have advertised this topic */ + int8_t _advertiser_count{0}; /**< how many total advertisers this topic has */ + + DeviceNode(const ORB_ID id, const uint8_t instance, const char *path); + + int advertise(bool publisher, uint8_t queue_size); + int unadvertise(bool publisher); + + /** + * Change the size of the queue. + * @return PX4_OK if queue size successfully set + */ + int update_queue_size(unsigned int queue_size); + + void _add_subscriber(unsigned *initial_generation); + + /** + * Each device node instance has its own lock/semaphore. + * + * Note that we must loop as the wait may be interrupted by a signal. + * + * Careful: lock() calls cannot be nested! + */ + void lock() { do {} while (px4_sem_wait(&_lock) != 0); } + + /** + * Release the device node lock. + */ + void unlock() { px4_sem_post(&_lock); } + + void remap_data(orb_advert_t &handle, size_t new_size, bool advertiser); + + inline static DeviceNode *node(const orb_advert_t &handle) { return static_cast(handle.node); } +#ifdef CONFIG_BUILD_FLAT + inline static void *node_data(const orb_advert_t &handle) { return node(handle)->_data; } +#else + inline static void *node_data(const orb_advert_t &handle) { return handle.data; } +#endif + + px4_sem_t _lock; /**< lock to protect access to all class members */ + +#ifdef CONFIG_BUILD_FLAT + char *_devname; + void *_data{nullptr}; +#else + char _devname[NAME_MAX + 1]; +#endif }; +} //namespace uORB diff --git a/platforms/common/uORB/uORBManager.cpp b/platforms/common/uORB/uORBManager.cpp index 5b5530694b94..f1697cd05fc1 100644 --- a/platforms/common/uORB/uORBManager.cpp +++ b/platforms/common/uORB/uORBManager.cpp @@ -31,8 +31,11 @@ * ****************************************************************************/ +#include #include #include +#include +#include #include #include @@ -40,13 +43,16 @@ #include #include -#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT) && defined(__KERNEL__) -#include -#endif - #include "uORBDeviceNode.hpp" #include "uORBUtils.hpp" #include "uORBManager.hpp" +#include "SubscriptionCallback.hpp" + +#ifndef CONFIG_FS_SHMFS_VFS_PATH +#define CONFIG_FS_SHMFS_VFS_PATH "/dev/shm" +#endif + +static const char uORBManagerName[] = "_uORB_Manager"; #ifdef CONFIG_ORB_COMMUNICATOR pthread_mutex_t uORB::Manager::_communicator_mutex = PTHREAD_MUTEX_INITIALIZER; @@ -54,23 +60,95 @@ pthread_mutex_t uORB::Manager::_communicator_mutex = PTHREAD_MUTEX_INITIALIZER; uORB::Manager *uORB::Manager::_Instance = nullptr; +// This is the per-process lock for callback thread +#ifndef CONFIG_BUILD_FLAT +int8_t uORB::Manager::per_process_lock = -1; +pid_t uORB::Manager::per_process_cb_thread = -1; +#endif + +void uORB::Manager::cleanup() +{ + // TODO: This is operating system dependent. Works on linux and NuttX + DIR *shm_dir = opendir(CONFIG_FS_SHMFS_VFS_PATH); + struct dirent *next_file; + + // Delete all uorb shm allocations + while ((next_file = readdir(shm_dir)) != nullptr) { + // build the path for each file in the folder + if (!strncmp(next_file->d_name, "orb_", 4) || + !strncmp(next_file->d_name, "_orb_", 5)) { + shm_unlink(next_file->d_name); + } + } + + closedir(shm_dir); + + // Delete manager shm allocations + shm_unlink(uORBManagerName); +} + bool uORB::Manager::initialize() { if (_Instance == nullptr) { - _Instance = new uORB::Manager(); + + // Cleanup from previous execution, in case some shm files are left + cleanup(); + + // Create a shared memory segment for uORB Manager and initialize a new manager into it + int shm_fd = shm_open(uORBManagerName, O_CREAT | O_RDWR, 0666); + + if (shm_fd >= 0) { + // If the creation succeeded, set the size + if (ftruncate(shm_fd, sizeof(uORB::Manager)) == 0) { + // mmap the shared memory region + void *ptr = mmap(0, sizeof(uORB::Manager), PROT_READ | PROT_WRITE, MAP_SHARED, shm_fd, 0); + _Instance = new (ptr) uORB::Manager(); + + for (auto &publisher : _Instance->g_has_publisher) { + publisher = 0; + } + } + } } -#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT) && defined(__KERNEL__) +#if defined(CONFIG_FS_SHMFS_WRPROTECT) px4_register_boardct_ioctl(_ORBIOCDEVBASE, orb_ioctl); #endif + return _Instance != nullptr; } +void uORB::Manager::map_instance() +{ + if (_Instance == nullptr) { + + // Open the existing manager + int shm_fd = shm_open(uORBManagerName, O_RDWR, 0666); + + if (shm_fd >= 0) { + // mmap the shared memory region + void *ptr = mmap(0, sizeof(uORB::Manager), PROT_READ | PROT_WRITE, MAP_SHARED, shm_fd, 0); + + if (ptr != MAP_FAILED) { + _Instance = (uORB::Manager *)ptr; + } + } + } + + if (_Instance == nullptr) { + PX4_ERR("FATAL: Can't get uORB manager"); + } +} + bool uORB::Manager::terminate() { + // We don't delete or unmap the Manager. Cleanup will + // unlink the SHM, and all the mappings are dropped when the + // processes exit + + cleanup(); + if (_Instance != nullptr) { - delete _Instance; - _Instance = nullptr; return true; } @@ -79,9 +157,11 @@ bool uORB::Manager::terminate() uORB::Manager::Manager() { + int ret; + #ifdef ORB_USE_PUBLISHER_RULES const char *file_name = PX4_STORAGEDIR"/orb_publisher.rules"; - int ret = readPublisherRulesFromFile(file_name, _publisher_rule); + ret = readPublisherRulesFromFile(file_name, _publisher_rule); if (ret == PX4_OK) { _has_publisher_rules = true; @@ -93,180 +173,46 @@ uORB::Manager::Manager() #endif /* ORB_USE_PUBLISHER_RULES */ -} + ret = px4_sem_init(&_lock, 1, 1); -uORB::Manager::~Manager() -{ - delete _device_master; -} + if (ret != 0) { + PX4_DEBUG("SEM INIT FAIL: ret %d", ret); + } -uORB::DeviceMaster *uORB::Manager::get_device_master() -{ - if (!_device_master) { - _device_master = new DeviceMaster(); + ret = px4_sem_init(&_callback_lock, 1, 1); - if (_device_master == nullptr) { - PX4_ERR("Failed to allocate DeviceMaster"); - errno = ENOMEM; - } + if (ret != 0) { + PX4_DEBUG("SEM INIT FAIL: ret %d", ret); } - return _device_master; + g_sem_pool.init(); } -#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT) && defined(__KERNEL__) -int uORB::Manager::orb_ioctl(unsigned int cmd, unsigned long arg) +uORB::Manager::~Manager() { - int ret = PX4_OK; - - switch (cmd) { - case ORBIOCDEVEXISTS: { - orbiocdevexists_t *data = (orbiocdevexists_t *)arg; - - if (data->check_advertised) { - if (uORB::Manager::get_instance()) { - data->ret = uORB::Manager::get_instance()->orb_exists(get_orb_meta(data->orb_id), data->instance); - - } else { - data->ret = PX4_ERROR; - } - - } else { - data->ret = uORB::Manager::orb_device_node_exists(data->orb_id, data->instance) ? PX4_OK : PX4_ERROR; - } - } - break; - - case ORBIOCDEVADVERTISE: { - orbiocdevadvertise_t *data = (orbiocdevadvertise_t *)arg; - uORB::DeviceMaster *dev = uORB::Manager::get_instance()->get_device_master(); - - if (dev) { - data->ret = dev->advertise(data->meta, data->is_advertiser, data->instance); - - } else { - data->ret = PX4_ERROR; - } - } - break; - - case ORBIOCDEVUNADVERTISE: { - orbiocdevunadvertise_t *data = (orbiocdevunadvertise_t *)arg; - data->ret = uORB::Manager::orb_unadvertise(data->handle); - } - break; - - case ORBIOCDEVPUBLISH: { - orbiocdevpublish_t *data = (orbiocdevpublish_t *)arg; - data->ret = uORB::Manager::orb_publish(data->meta, data->handle, data->data); - } - break; - - case ORBIOCDEVADDSUBSCRIBER: { - orbiocdevaddsubscriber_t *data = (orbiocdevaddsubscriber_t *)arg; - data->handle = uORB::Manager::orb_add_internal_subscriber(data->orb_id, data->instance, data->initial_generation); - } - break; - - case ORBIOCDEVREMSUBSCRIBER: { - uORB::Manager::orb_remove_internal_subscriber(reinterpret_cast(arg)); - } - break; - - case ORBIOCDEVQUEUESIZE: { - orbiocdevqueuesize_t *data = (orbiocdevqueuesize_t *)arg; - data->size = uORB::Manager::orb_get_queue_size(data->handle); - } - break; - - case ORBIOCDEVDATACOPY: { - orbiocdevdatacopy_t *data = (orbiocdevdatacopy_t *)arg; - data->ret = uORB::Manager::orb_data_copy(data->handle, data->dst, data->generation, data->only_if_updated); - } - break; - - case ORBIOCDEVREGCALLBACK: { - orbiocdevregcallback_t *data = (orbiocdevregcallback_t *)arg; - data->registered = uORB::Manager::register_callback(data->handle, data->callback_sub); - } - break; - - case ORBIOCDEVUNREGCALLBACK: { - orbiocdevunregcallback_t *data = (orbiocdevunregcallback_t *)arg; - uORB::Manager::unregister_callback(data->handle, data->callback_sub); - } - break; - - case ORBIOCDEVGETINSTANCE: { - orbiocdevgetinstance_t *data = (orbiocdevgetinstance_t *)arg; - data->instance = uORB::Manager::orb_get_instance(data->handle); - } - break; - - case ORBIOCDEVMASTERCMD: { - uORB::DeviceMaster *dev = uORB::Manager::get_instance()->get_device_master(); - - if (dev) { - if (arg == ORB_DEVMASTER_TOP) { - dev->showTop(nullptr, 0); - - } else { - dev->printStatistics(); - } - } - } - break; - - case ORBIOCDEVUPDATESAVAIL: { - orbiocdevupdatesavail_t *data = (orbiocdevupdatesavail_t *)arg; - data->ret = updates_available(data->handle, data->last_generation); - } - break; - - case ORBIOCDEVISADVERTISED: { - orbiocdevisadvertised_t *data = (orbiocdevisadvertised_t *)arg; - data->ret = is_advertised(data->handle); - } - break; - - default: - ret = -ENOTTY; - } - - return ret; + px4_sem_destroy(&_lock); + px4_sem_destroy(&_callback_lock); } -#endif int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance) { - if (meta == nullptr) { - return PX4_ERROR; - } - - int ret = PX4_ERROR; - // instance valid range: [0, ORB_MULTI_MAX_INSTANCES) - if ((instance < 0) || (instance > (ORB_MULTI_MAX_INSTANCES - 1))) { - return ret; + if ((instance < 0) || (instance > (ORB_MULTI_MAX_INSTANCES - 1)) || meta == nullptr) { + return PX4_ERROR; } - uORB::DeviceMaster *dev = uORB::Manager::get_instance()->get_device_master(); - - if (dev) { - uORB::DeviceNode *node = dev->getDeviceNode(meta, instance); - - if (node != nullptr) { - if (node->is_advertised()) { - return PX4_OK; - } - } + // meta != nullptr + // orb is advertised by a publisher + if (meta != nullptr && + has_publisher(static_cast(meta->o_id), instance)) { + return PX4_OK; } - return ret; + return PX4_ERROR; } orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, - unsigned int queue_size) + uint8_t queue_size) { #ifdef ORB_USE_PUBLISHER_RULES @@ -278,124 +224,130 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, if (_publisher_rule.ignore_other_topics) { if (!findTopic(_publisher_rule, meta->o_name)) { PX4_DEBUG("not allowing %s to publish topic %s", prog_name, meta->o_name); - return (orb_advert_t)_Instance; + return ORB_ADVERT_INVALID; } } } else { if (findTopic(_publisher_rule, meta->o_name)) { PX4_DEBUG("not allowing %s to publish topic %s", prog_name, meta->o_name); - return (orb_advert_t)_Instance; + return ORB_ADVERT_INVALID; } } } #endif /* ORB_USE_PUBLISHER_RULES */ - /* open the node as an advertiser */ - int fd = node_open(meta, true, instance); + // Calculate the wanted instance + unsigned group_tries = 0; - if (fd == PX4_ERROR) { - PX4_ERR("%s advertise failed (%i)", meta->o_name, errno); - return nullptr; - } + lock(); + + while (group_tries < ORB_MULTI_MAX_INSTANCES) { - /* Set the queue size. This must be done before the first publication; thus it fails if - * this is not the first advertiser. - */ - int result = px4_ioctl(fd, ORBIOCSETQUEUESIZE, (unsigned long)queue_size); + // is not advertised by a publisher or is a single instance publisher + if (!has_publisher(static_cast(meta->o_id), group_tries) || !instance) { + break; + } - if (result < 0 && queue_size > 1) { - PX4_WARN("orb_advertise_multi: failed to set queue size"); + group_tries++; } - /* get the advertiser handle and close the node */ - orb_advert_t advertiser; + if (group_tries == ORB_MULTI_MAX_INSTANCES) { + unlock(); + PX4_ERR("%s: too many instances (%d)", meta->o_name, group_tries); + return ORB_ADVERT_INVALID; + } - result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser); - px4_close(fd); + orb_advert_t handle = uORB::DeviceNode::orb_advertise(static_cast(meta->o_id), group_tries, queue_size, true); - if (result == PX4_ERROR) { - PX4_WARN("px4_ioctl ORBIOCGADVERTISER failed. fd = %d", fd); - return nullptr; + if (instance != nullptr) { + *instance = group_tries; } -#ifdef CONFIG_ORB_COMMUNICATOR + // Cache existence of this node instance globally + if (orb_advert_valid(handle)) { + set_has_publisher(static_cast(meta->o_id), group_tries); - // Advertise to the remote side, but only if it is a local topic. Otherwise - // we will generate an advertisement loop. - if (_remote_topics.find(meta->o_name) == false) { +#ifdef CONFIG_ORB_COMMUNICATOR + // For remote systems call over and inform them uORB::DeviceNode::topic_advertised(meta); +#endif /* CONFIG_ORB_COMMUNICATOR */ + + } else { + PX4_ERR("orb_advertise_multi failed %s", meta->o_name); } -#endif /* CONFIG_ORB_COMMUNICATOR */ + unlock(); /* the advertiser may perform an initial publish to initialise the object */ - if (data != nullptr) { - result = orb_publish(meta, advertiser, data); + + if (data != nullptr && orb_advert_valid(handle)) { + int result = orb_publish(meta, handle, data); if (result == PX4_ERROR) { PX4_ERR("orb_publish failed %s", meta->o_name); - return nullptr; + orb_unadvertise(handle); } } - return advertiser; + return handle; } -int uORB::Manager::orb_unadvertise(orb_advert_t handle) +int uORB::Manager::orb_unadvertise(orb_advert_t &handle) { -#ifdef ORB_USE_PUBLISHER_RULES - - if (handle == _Instance) { - return PX4_OK; //pretend success + if (!orb_advert_valid(handle)) { + return PX4_ERROR; } -#endif /* ORB_USE_PUBLISHER_RULES */ + ORB_ID id = static_cast(node(handle)->id()); + uint8_t instance = node(handle)->get_instance(); - return uORB::DeviceNode::unadvertise(handle); -} + Manager *manager = get_instance(); -int uORB::Manager::orb_subscribe(const struct orb_metadata *meta) -{ - return node_open(meta, false); -} + manager->lock(); -int uORB::Manager::orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) -{ - int inst = instance; - return node_open(meta, false, &inst); + bool unadvertised = uORB::DeviceNode::orb_unadvertise(handle, true) >= 0; + + // Node is deleted and handle invalidated, if the last advertiser goes away + + if (!orb_advert_valid(handle) || node(handle)->publisher_count() == 0) { + manager->unset_has_publisher(id, instance); + } + + manager->unlock(); + + return unadvertised ? PX4_OK : PX4_ERROR; } -int uORB::Manager::orb_unsubscribe(int fd) +// Should only be called from old interface +orb_sub_t uORB::Manager::orb_subscribe(const struct orb_metadata *meta) { - return px4_close(fd); + return orb_subscribe_multi(meta, 0); } -int uORB::Manager::orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) +// Should only be called from old interface +orb_sub_t uORB::Manager::orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) { -#ifdef ORB_USE_PUBLISHER_RULES + uORB::SubscriptionInterval *sub = new uORB::SubscriptionPollable(meta, instance); - if (handle == _Instance) { - return PX4_OK; //pretend success + if (sub && !sub->valid()) { + // subscribe and advertise the topic + sub->subscribe(true); } -#endif /* ORB_USE_PUBLISHER_RULES */ - - return uORB::DeviceNode::publish(meta, handle, data); + return sub; } -int uORB::Manager::orb_copy(const struct orb_metadata *meta, int handle, void *buffer) +int uORB::Manager::orb_unsubscribe(orb_sub_t handle) { - int ret; - - ret = px4_read(handle, buffer, meta->o_size); - - if (ret < 0) { - return PX4_ERROR; - } + delete (static_cast(handle)); + return PX4_OK; +} - if (ret != (int)meta->o_size) { +int uORB::Manager::orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buffer) +{ + if (!(static_cast(handle))->copy(buffer)) { errno = EIO; return PX4_ERROR; } @@ -403,190 +355,218 @@ int uORB::Manager::orb_copy(const struct orb_metadata *meta, int handle, void *b return PX4_OK; } -int uORB::Manager::orb_check(int handle, bool *updated) +int uORB::Manager::orb_check(orb_sub_t handle, bool *updated) { - /* Set to false here so that if `px4_ioctl` fails to false. */ - *updated = false; - return px4_ioctl(handle, ORBIOCUPDATED, (unsigned long)(uintptr_t)updated); + *updated = ((uORB::SubscriptionInterval *)handle)->updated(); + return PX4_OK; } -int uORB::Manager::orb_set_interval(int handle, unsigned interval) +int uORB::Manager::orb_set_interval(orb_sub_t handle, unsigned interval) { - return px4_ioctl(handle, ORBIOCSETINTERVAL, interval * 1000); + ((uORB::SubscriptionInterval *)handle)->set_interval_us(interval * 1000); + return PX4_OK; } -int uORB::Manager::orb_get_interval(int handle, unsigned *interval) +int uORB::Manager::orb_get_interval(orb_sub_t handle, unsigned *interval) { - int ret = px4_ioctl(handle, ORBIOCGETINTERVAL, (unsigned long)interval); - *interval /= 1000; - return ret; + *interval = ((uORB::SubscriptionInterval *)handle)->get_interval_us() / 1000; + return PX4_OK; } - -bool uORB::Manager::orb_device_node_exists(ORB_ID orb_id, uint8_t instance) +int uORB::Manager::orb_poll(orb_poll_struct_t *fds, unsigned int nfds, int timeout) { - DeviceMaster *device_master = uORB::Manager::get_instance()->get_device_master(); + SubscriptionPollable *sub; - return device_master != nullptr && - device_master->deviceNodeExists(orb_id, instance); -} + // Get a poll semaphore from the global pool + int8_t lock_idx = g_sem_pool.reserve(); -void *uORB::Manager::orb_add_internal_subscriber(ORB_ID orb_id, uint8_t instance, unsigned *initial_generation) -{ - uORB::DeviceNode *node = nullptr; - DeviceMaster *device_master = uORB::Manager::get_instance()->get_device_master(); + if (lock_idx < 0) { + PX4_ERR("Out of thread locks"); + return -1; + } + + // Any orb updated already? + bool err = false; + int count = 0; - if (device_master != nullptr) { - node = device_master->getDeviceNode(get_orb_meta(orb_id), instance); + for (unsigned i = 0; i < nfds; i++) { + fds[i].revents = 0; - if (node) { - node->add_internal_subscriber(); - *initial_generation = node->get_initial_generation(); + if ((fds[i].events & POLLIN) == POLLIN) { + sub = static_cast(fds[i].fd); + sub->registerPoll(lock_idx); + + if (sub->updated()) { + fds[i].revents = POLLIN; + count++; + } } } - return node; -} + // If none of the orbs were updated before registration, go to sleep. + // If some orb was updated after registration, but not yet refelected in "updated", the semaphore is already released. So there is no race in here. -void uORB::Manager::orb_remove_internal_subscriber(void *node_handle) -{ - static_cast(node_handle)->remove_internal_subscriber(); -} + if (count == 0) { -uint8_t uORB::Manager::orb_get_queue_size(const void *node_handle) { return static_cast(node_handle)->get_queue_size(); } + // First advertiser will wake us up, or it might have happened already + // during registration above -bool uORB::Manager::orb_data_copy(void *node_handle, void *dst, unsigned &generation, bool only_if_updated) -{ - if (!is_advertised(node_handle)) { - return false; + int ret; + + if (timeout < 0) { + // Wait event until interrupted by a signal + ret = g_sem_pool.take_interruptible(lock_idx); + + } else { + // Wait event for a maximum timeout time + struct timespec to; +#if defined(CONFIG_ARCH_BOARD_PX4_SITL) + px4_clock_gettime(CLOCK_MONOTONIC, &to); +#else + px4_clock_gettime(CLOCK_REALTIME, &to); +#endif + hrt_abstime now = ts_to_abstime(&to); + abstime_to_ts(&to, now + (hrt_abstime)timeout * 1000); + ret = g_sem_pool.take_timedwait(lock_idx, &to); + } + + if (ret != 0 && errno != ETIMEDOUT && errno != EINTR) { + PX4_ERR("poll on %d timeout %d FAIL errno %d\n", lock_idx, timeout, errno); + err = true; + } } - if (only_if_updated && !static_cast(node_handle)->updates_available(generation)) { - return false; + count = 0; + + for (unsigned i = 0; i < nfds; i++) { + if ((fds[i].events & POLLIN) == POLLIN) { + sub = static_cast(fds[i].fd); + sub->unregisterPoll(); + + if (sub->updated()) { + fds[i].revents |= POLLIN; + count++; + } + } } - return static_cast(node_handle)->copy(dst, generation); -} + // recover from releasing multiple times + g_sem_pool.set(lock_idx, 0); + g_sem_pool.free(lock_idx); -// add item to list of work items to schedule on node update -bool uORB::Manager::register_callback(void *node_handle, SubscriptionCallback *callback_sub) -{ - return static_cast(node_handle)->register_callback(callback_sub); + return err ? -1 : count; } -// remove item from list of work items -void uORB::Manager::unregister_callback(void *node_handle, SubscriptionCallback *callback_sub) -{ - static_cast(node_handle)->unregister_callback(callback_sub); -} +#ifndef CONFIG_BUILD_FLAT -uint8_t uORB::Manager::orb_get_instance(const void *node_handle) +int8_t +uORB::Manager::launchCallbackThread() { - if (node_handle) { - return static_cast(node_handle)->get_instance(); + per_process_lock = Manager::getThreadLock(); + + if (per_process_lock < 0) { + PX4_ERR("Out of thread locks\n"); + return -1; } - return -1; -} + if (per_process_cb_thread == -1) { + per_process_cb_thread = px4_task_spawn_cmd("orb_callback", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 1, + 1024, + callback_thread, + nullptr); -/* These are optimized by inlining in NuttX Flat build */ -#if !defined(CONFIG_BUILD_FLAT) -unsigned uORB::Manager::updates_available(const void *node_handle, unsigned last_generation) -{ - return is_advertised(node_handle) ? static_cast(node_handle)->updates_available( - last_generation) : 0; -} + if (per_process_cb_thread < 0) { + PX4_ERR("callback thread creation failed\n"); + Manager::freeThreadLock(per_process_lock); + return -1; + } + } -bool uORB::Manager::is_advertised(const void *node_handle) -{ - return static_cast(node_handle)->is_advertised(); + return per_process_lock; } -#endif -int uORB::Manager::node_open(const struct orb_metadata *meta, bool advertiser, int *instance) +int +uORB::Manager::callback_thread(int argc, char *argv[]) { - char path[orb_maxpath]; - int fd = -1; - int ret = PX4_ERROR; + while (true) { + lockThread(per_process_lock); - /* - * If meta is null, the object was not defined, i.e. it is not - * known to the system. We can't advertise/subscribe such a thing. - */ - if (nullptr == meta) { - errno = ENOENT; - return PX4_ERROR; + SubscriptionCallback *sub = _Instance->_callback_ptr; + _Instance->unlock_callbacks(); + + // Pass nullptr to this thread to exit + if (sub == nullptr) { + break; + } + + sub->call(); } - /* if we have an instance and are an advertiser, we will generate a new node and set the instance, - * so we do not need to open here */ - if (!instance || !advertiser) { - /* - * Generate the path to the node and try to open it. - */ - ret = uORB::Utils::node_mkpath(path, meta, instance); + Manager::freeThreadLock(per_process_lock); + per_process_lock = -1; - if (ret != OK) { - errno = -ret; - return PX4_ERROR; - } + return 0; +} + +#endif - /* open the path as either the advertiser or the subscriber */ - fd = px4_open(path, advertiser ? PX4_F_WRONLY : PX4_F_RDONLY); - } else { - *instance = 0; +void uORB::Manager::GlobalSemPool::init(void) +{ + for (auto &sem : _global_sem) { + sem.init(); } - /* we may need to advertise the node... */ - if (fd < 0) { + px4_sem_init(&_semLock, 1, 1); +} - ret = PX4_ERROR; +void uORB::Manager::GlobalSemPool::free(int8_t i) +{ + lock(); - if (get_device_master()) { - ret = _device_master->advertise(meta, advertiser, instance); - } + _global_sem[i].in_use = false; - /* it's OK if it already exists */ - if ((ret != PX4_OK) && (EEXIST == errno)) { - ret = PX4_OK; - } + unlock(); +} - if (ret == PX4_OK) { - /* update the path, as it might have been updated during the node advertise call */ - ret = uORB::Utils::node_mkpath(path, meta, instance); +int8_t uORB::Manager::GlobalSemPool::reserve() +{ + lock(); - /* on success, try to open again */ - if (ret == PX4_OK) { - fd = px4_open(path, (advertiser) ? PX4_F_WRONLY : PX4_F_RDONLY); + // Find the first free lock + int8_t i; - } else { - errno = -ret; - return PX4_ERROR; - } + for (i = 0; i < NUM_GLOBAL_SEMS; i++) { + if (!_global_sem[i].in_use) { + break; } } - if (fd < 0) { - errno = EIO; - return PX4_ERROR; + // Check that we got one + if (i == NUM_GLOBAL_SEMS) { + PX4_ERR("Out of global locks"); + unlock(); + return -1; } - /* everything has been OK, we can return the handle now */ - return fd; + // Mark this one as in use + _global_sem[i].in_use = true; + + unlock(); + + return i; } #ifdef CONFIG_ORB_COMMUNICATOR void uORB::Manager::set_uorb_communicator(uORBCommunicator::IChannel *channel) { - pthread_mutex_lock(&_communicator_mutex); + _comm_channel = channel; - if (channel != nullptr) { - channel->register_handler(this); - _comm_channel = channel; + if (_comm_channel != nullptr) { + _comm_channel->register_handler(this); } - - pthread_mutex_unlock(&_communicator_mutex); } uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator() @@ -598,30 +578,8 @@ uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator() return temp; } -int16_t uORB::Manager::process_remote_topic(const char *topic_name) +const struct orb_metadata *uORB::Manager::topic_name_to_meta(const char *topic_name) { - PX4_DEBUG("entering process_remote_topic: name: %s", topic_name); - - // Look to see if we already have a node for this topic - char nodepath[orb_maxpath]; - int ret = uORB::Utils::node_mkpath(nodepath, topic_name); - - if (ret == OK) { - DeviceMaster *device_master = get_device_master(); - - if (device_master) { - uORB::DeviceNode *node = device_master->getDeviceNode(nodepath); - - if (node) { - PX4_INFO("Marking DeviceNode(%s) as advertised in process_remote_topic", topic_name); - node->mark_as_advertised(); - _remote_topics.insert(topic_name); - return 0; - } - } - } - - // We didn't find a node so we need to create it via an advertisement const struct orb_metadata *const *topic_list = orb_get_topics(); orb_id_t topic_ptr = nullptr; @@ -632,43 +590,63 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name) } } - if (topic_ptr) { - PX4_INFO("Advertising remote topic %s", topic_name); - _remote_topics.insert(topic_name); - // Add some queue depth when advertising remote topics. These - // topics may get aggregated and thus delivered in a batch that - // requires some buffering in a queue. - orb_advertise(topic_ptr, nullptr, 5); + return topic_ptr; +} - } else { +int16_t uORB::Manager::process_remote_topic(const char *topic_name) +{ + PX4_DEBUG("entering process_remote_topic: name: %s", topic_name); + + int16_t rc = 0; + + const struct orb_metadata *meta = topic_name_to_meta(topic_name); + + if (meta == nullptr) { PX4_INFO("process_remote_topic meta not found for %s\n", topic_name); + _remote_topics.erase(topic_name); + return -1; } - return 0; + _Instance->lock(); + + orb_advert_t handle = orb_advertise(meta, nullptr); + + _Instance->unlock(); + + if (orb_advert_valid(handle)) { + PX4_INFO("Advertising remote publisher %s", topic_name); + _remote_topics.insert(handle); + + } else { + PX4_INFO("Advertisement failed"); + rc = -1; + } + + return rc; } int16_t uORB::Manager::process_add_subscription(const char *messageName) { PX4_DEBUG("entering Manager_process_add_subscription: name: %s", messageName); - int16_t rc = 0; - char nodepath[orb_maxpath]; - int ret = uORB::Utils::node_mkpath(nodepath, messageName); - DeviceMaster *device_master = get_device_master(); + int16_t rc = -1; - if (ret == OK && device_master) { - uORB::DeviceNode *node = device_master->getDeviceNode(nodepath); + const struct orb_metadata *meta = topic_name_to_meta(messageName); + + if (meta == nullptr) { + return rc; + } - if (node == nullptr) { - PX4_DEBUG("DeviceNode(%s) not created yet", messageName); + orb_advert_t handle = DeviceNode::nodeOpen(static_cast(meta->o_id), 0, false); - } else { - // node is present. - node->process_add_subscription(); - } + if (!orb_advert_valid(handle)) { + PX4_DEBUG("DeviceNode(%s) not created yet", messageName); } else { - rc = -1; + // node is present. + + node(handle)->process_add_subscription(handle); + rc = 0; } return rc; @@ -677,23 +655,24 @@ int16_t uORB::Manager::process_add_subscription(const char *messageName) int16_t uORB::Manager::process_remove_subscription(const char *messageName) { int16_t rc = -1; - char nodepath[orb_maxpath]; - int ret = uORB::Utils::node_mkpath(nodepath, messageName); - DeviceMaster *device_master = get_device_master(); - if (ret == OK && device_master) { - uORB::DeviceNode *node = device_master->getDeviceNode(nodepath); + const struct orb_metadata *meta = topic_name_to_meta(messageName); - // get the node name. - if (node == nullptr) { - PX4_DEBUG("[posix-uORB::Manager::process_remove_subscription(%d)]Error No existing subscriber found for message: [%s]", - __LINE__, messageName); + if (meta == nullptr) { + PX4_DEBUG("DeviceNode(%s) meta not found", messageName); + return rc; + } - } else { - // node is present. - node->process_remove_subscription(); - rc = 0; - } + orb_advert_t handle = DeviceNode::nodeOpen(static_cast(meta->o_id), 0, false); + + if (!orb_advert_valid(handle)) { + PX4_DEBUG("[posix-uORB::Manager::process_remove_subscription(%d)]Error No existing subscriber found for message: [%s]", + __LINE__, messageName); + + } else { + // node is present. + node(handle)->process_remove_subscription(handle); + rc = 0; } return rc; @@ -702,22 +681,16 @@ int16_t uORB::Manager::process_remove_subscription(const char *messageName) int16_t uORB::Manager::process_received_message(const char *messageName, int32_t length, uint8_t *data) { int16_t rc = -1; - char nodepath[orb_maxpath]; - int ret = uORB::Utils::node_mkpath(nodepath, messageName); - DeviceMaster *device_master = get_device_master(); - if (ret == OK && device_master) { - uORB::DeviceNode *node = device_master->getDeviceNode(nodepath); + orb_advert_t handle = _remote_topics.find(messageName); - // get the node name. - if (node == nullptr) { - PX4_DEBUG("No existing subscriber found for message: [%s] nodepath:[%s]", messageName, nodepath); + if (!orb_advert_valid(handle)) { + PX4_DEBUG("No existing subscriber found for message: [%s]", messageName); - } else { - // node is present. - node->process_received_message(length, data); - rc = 0; - } + } else { + // node is present. + node(handle)->process_received_message(handle, length, data); + rc = 0; } return rc; @@ -862,4 +835,5 @@ int uORB::Manager::readPublisherRulesFromFile(const char *file_name, PublisherRu fclose(fp); return ret; } + #endif /* ORB_USE_PUBLISHER_RULES */ diff --git a/platforms/common/uORB/uORBManager.hpp b/platforms/common/uORB/uORBManager.hpp index 1c2870b1eecd..e5497f956807 100644 --- a/platforms/common/uORB/uORBManager.hpp +++ b/platforms/common/uORB/uORBManager.hpp @@ -31,12 +31,13 @@ * ****************************************************************************/ -#ifndef _uORBManager_hpp_ -#define _uORBManager_hpp_ +#pragma once + +#include +#include #include "uORBDeviceNode.hpp" #include "uORBCommon.hpp" -#include "uORBDeviceMaster.hpp" #include // For ORB_ID enum #include @@ -47,119 +48,17 @@ #include "uORBCommunicator.hpp" #endif /* CONFIG_ORB_COMMUNICATOR */ +#define NUM_GLOBAL_SEMS 40 + namespace uORB { -class Manager; -class SubscriptionCallback; -} - - -/* - * IOCTLs for manager to access device nodes using - * a handle - */ - -#define _ORBIOCDEV(_n) (_PX4_IOC(_ORBIOCDEVBASE, _n)) -#define ORBIOCDEVEXISTS _ORBIOCDEV(30) -typedef struct orbiocdevexists { - const ORB_ID orb_id; - const uint8_t instance; - const bool check_advertised; - int ret; -} orbiocdevexists_t; - -#define ORBIOCDEVADVERTISE _ORBIOCDEV(31) -typedef struct orbiocadvertise { - const struct orb_metadata *meta; - bool is_advertiser; - int *instance; - int ret; -} orbiocdevadvertise_t; - -#define ORBIOCDEVUNADVERTISE _ORBIOCDEV(32) -typedef struct orbiocunadvertise { - void *handle; - int ret; -} orbiocdevunadvertise_t; - -#define ORBIOCDEVPUBLISH _ORBIOCDEV(33) -typedef struct orbiocpublish { - const struct orb_metadata *meta; - orb_advert_t handle; - const void *data; - int ret; -} orbiocdevpublish_t; - -#define ORBIOCDEVADDSUBSCRIBER _ORBIOCDEV(34) -typedef struct { - const ORB_ID orb_id; - const uint8_t instance; - unsigned *initial_generation; - void *handle; -} orbiocdevaddsubscriber_t; - -#define ORBIOCDEVREMSUBSCRIBER _ORBIOCDEV(35) - -#define ORBIOCDEVQUEUESIZE _ORBIOCDEV(36) -typedef struct { - const void *handle; - uint8_t size; -} orbiocdevqueuesize_t; - -#define ORBIOCDEVDATACOPY _ORBIOCDEV(37) -typedef struct { - void *handle; - void *dst; - unsigned generation; - bool only_if_updated; - bool ret; -} orbiocdevdatacopy_t; - -#define ORBIOCDEVREGCALLBACK _ORBIOCDEV(38) -typedef struct { - void *handle; - class uORB::SubscriptionCallback *callback_sub; - bool registered; -} orbiocdevregcallback_t; - -#define ORBIOCDEVUNREGCALLBACK _ORBIOCDEV(39) -typedef struct { - void *handle; - class uORB::SubscriptionCallback *callback_sub; -} orbiocdevunregcallback_t; - -#define ORBIOCDEVGETINSTANCE _ORBIOCDEV(40) -typedef struct { - const void *handle; - uint8_t instance; -} orbiocdevgetinstance_t; - -#define ORBIOCDEVUPDATESAVAIL _ORBIOCDEV(41) -typedef struct { - const void *handle; - unsigned last_generation; - unsigned ret; -} orbiocdevupdatesavail_t; - -#define ORBIOCDEVISADVERTISED _ORBIOCDEV(42) -typedef struct { - const void *handle; - bool ret; -} orbiocdevisadvertised_t; - -typedef enum { - ORB_DEVMASTER_STATUS = 0, - ORB_DEVMASTER_TOP = 1 -} orbiocdevmastercmd_t; -#define ORBIOCDEVMASTERCMD _ORBIOCDEV(45) - /** * This is implemented as a singleton. This class manages creating the * uORB nodes for each uORB topics and also implements the behavor of the * uORB Api's. */ -class uORB::Manager +class Manager #ifdef CONFIG_ORB_COMMUNICATOR : public uORBCommunicator::IChannelRxHandler #endif /* CONFIG_ORB_COMMUNICATOR */ @@ -181,22 +80,16 @@ class uORB::Manager /** * Method to get the singleton instance for the uORB::Manager. - * Make sure initialize() is called first. * @return uORB::Manager* */ - static uORB::Manager *get_instance() { return _Instance; } - - /** - * Get the DeviceMaster. If it does not exist, - * it will be created and initialized. - * Note: the first call to this is not thread-safe. - * @return nullptr if initialization failed (and errno will be set) - */ - uORB::DeviceMaster *get_device_master(); + static uORB::Manager *get_instance() + { + if (_Instance == nullptr) { + map_instance(); + } -#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT) && defined(__KERNEL__) - static int orb_ioctl(unsigned int cmd, unsigned long arg); -#endif + return _Instance; + } // ==== uORB interface methods ==== /** @@ -259,7 +152,7 @@ class uORB::Manager * this function will return nullptr and set errno to ENOENT. */ orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, - unsigned int queue_size = 1); + uint8_t queue_size = 1); /** * Unadvertise a topic. @@ -267,7 +160,7 @@ class uORB::Manager * @param handle handle returned by orb_advertise or orb_advertise_multi. * @return 0 on success */ - static int orb_unadvertise(orb_advert_t handle); + static int orb_unadvertise(orb_advert_t &handle); /** * Publish new data to a topic. @@ -282,12 +175,12 @@ class uORB::Manager * @param data A pointer to the data to be published. * @return OK on success, PX4_ERROR otherwise with errno set accordingly. */ - static int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data); + static int orb_publish(const struct orb_metadata *meta, orb_advert_t &handle, const void *data) {return uORB::DeviceNode::publish(meta, handle, data);} /** * Subscribe to a topic. * - * The returned value is a file descriptor that can be passed to poll() + * The returned value is a handle that can be passed to orb_poll() * in order to wait for updates to a topic, as well as topic_read, * orb_check. * @@ -312,12 +205,12 @@ class uORB::Manager * @return PX4_ERROR on error, otherwise returns a handle * that can be used to read and update the topic. */ - int orb_subscribe(const struct orb_metadata *meta); + orb_sub_t orb_subscribe(const struct orb_metadata *meta); /** * Subscribe to a multi-instance of a topic. * - * The returned value is a file descriptor that can be passed to poll() + * The returned value is a handle that can be passed to orb_poll() * in order to wait for updates to a topic, as well as topic_read, * orb_check. * @@ -344,13 +237,13 @@ class uORB::Manager * @param instance The instance of the topic. Instance 0 matches the * topic of the orb_subscribe() call, higher indices * are for topics created with orb_advertise_multi(). - * @return PX4_ERROR on error, otherwise returns a handle + * @return returns a handle * that can be used to read and update the topic. * If the topic in question is not known (due to an * ORB_DEFINE_OPTIONAL with no corresponding ORB_DECLARE) - * this function will return -1 and set errno to ENOENT. + * this function will return an invalid handle and set errno to ENOENT. */ - int orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance); + orb_sub_t orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance); /** * Unsubscribe from a topic. @@ -358,14 +251,14 @@ class uORB::Manager * @param handle A handle returned from orb_subscribe. * @return OK on success, PX4_ERROR otherwise with errno set accordingly. */ - int orb_unsubscribe(int handle); + static int orb_unsubscribe(orb_sub_t handle); /** * Fetch data from a topic. * * This is the only operation that will reset the internal marker that * indicates that a topic has been updated for a subscriber. Once poll - * or check return indicating that an updaet is available, this call + * or check return indicating that an update is available, this call * must be used to update the subscription. * * @param meta The uORB metadata (usually from the ORB_ID() macro) @@ -376,7 +269,7 @@ class uORB::Manager * using the data. * @return OK on success, PX4_ERROR otherwise with errno set accordingly. */ - int orb_copy(const struct orb_metadata *meta, int handle, void *buffer); + static int orb_copy(const struct orb_metadata *meta, orb_sub_t handle, void *buffer); /** * Check whether a topic has been published to since the last orb_copy. @@ -394,7 +287,7 @@ class uORB::Manager * @return OK if the check was successful, PX4_ERROR otherwise with * errno set accordingly. */ - int orb_check(int handle, bool *updated); + static int orb_check(orb_sub_t handle, bool *updated); /** * Check if a topic has already been created and published (advertised) @@ -403,7 +296,7 @@ class uORB::Manager * @param instance ORB instance * @return OK if the topic exists, PX4_ERROR otherwise. */ - int orb_exists(const struct orb_metadata *meta, int instance); + static int orb_exists(const struct orb_metadata *meta, int instance); /** * Set the minimum interval between which updates are seen for a subscription. @@ -423,8 +316,7 @@ class uORB::Manager * @param interval An interval period in milliseconds. * @return OK on success, PX4_ERROR otherwise with ERRNO set accordingly. */ - int orb_set_interval(int handle, unsigned interval); - + static int orb_set_interval(orb_sub_t handle, unsigned interval); /** * Get the minimum interval between which updates are seen for a subscription. @@ -435,37 +327,80 @@ class uORB::Manager * @param interval The returned interval period in milliseconds. * @return OK on success, PX4_ERROR otherwise with ERRNO set accordingly. */ - int orb_get_interval(int handle, unsigned *interval); + static int orb_get_interval(orb_sub_t handle, unsigned *interval); - static bool orb_device_node_exists(ORB_ID orb_id, uint8_t instance); + int orb_poll(orb_poll_struct_t *fds, unsigned int nfds, int timeout); - static void *orb_add_internal_subscriber(ORB_ID orb_id, uint8_t instance, unsigned *initial_generation); - - static void orb_remove_internal_subscriber(void *node_handle); + static orb_advert_t orb_add_internal_subscriber(ORB_ID orb_id, uint8_t instance, unsigned *initial_generation, + bool advertise) + { + if (!advertise && !has_publisher(orb_id, instance)) { + return ORB_ADVERT_INVALID; + } - static uint8_t orb_get_queue_size(const void *node_handle); + _Instance->lock(); + orb_advert_t handle = uORB::DeviceNode::add_subscriber(orb_id, instance, initial_generation, advertise); + _Instance->unlock(); - static bool orb_data_copy(void *node_handle, void *dst, unsigned &generation, bool only_if_updated); + return handle; + } - static bool register_callback(void *node_handle, SubscriptionCallback *callback_sub); + static void orb_remove_internal_subscriber(orb_advert_t &node_handle, bool advertiser) + { + _Instance->lock(); + node(node_handle)->remove_subscriber(node_handle, advertiser); + _Instance->unlock(); + } - static void unregister_callback(void *node_handle, SubscriptionCallback *callback_sub); + static uint8_t orb_get_queue_size(const orb_advert_t &node_handle) {return node(node_handle)->get_queue_size();} - static uint8_t orb_get_instance(const void *node_handle); + static bool orb_data_copy(orb_advert_t &node_handle, void *dst, unsigned &generation, + bool only_if_updated) + { + if (!orb_advert_valid(node_handle) || + (only_if_updated && !node(node_handle)->updates_available(generation))) { + return false; + } -#if defined(CONFIG_BUILD_FLAT) - /* These are optimized by inlining in NuttX Flat build */ - static unsigned updates_available(const void *node_handle, unsigned last_generation) { return is_advertised(node_handle) ? static_cast(node_handle)->updates_available(last_generation) : 0; } + return node(node_handle)->copy(dst, node_handle, generation); + } - static bool is_advertised(const void *node_handle) { return static_cast(node_handle)->is_advertised(); } +#ifndef CONFIG_BUILD_FLAT + static uint8_t getCallbackLock() + { + uint8_t cbLock; -#else - static unsigned updates_available(const void *node_handle, unsigned last_generation); + // TODO: think about if this needs protection, maybe not use the + // same lock as for node advertise/subscribe - static bool is_advertised(const void *node_handle); + _Instance->lock(); + cbLock = per_process_lock >= 0 ? per_process_lock : launchCallbackThread(); + _Instance->unlock(); + return cbLock; + } #endif + static uint8_t orb_get_instance(orb_advert_t &node_handle) + { + if (orb_advert_valid(node_handle)) { + return node(node_handle)->get_instance(); + } + + return -1; + } + + static unsigned updates_available(const orb_advert_t &node_handle, unsigned last_generation) + { + return node(node_handle)->updates_available(last_generation); + } + + static bool has_publisher(ORB_ID orb_id, uint8_t instance) + { + return (get_instance()->g_has_publisher[static_cast(orb_id)] & (1 << instance)) != 0; + } + #ifdef CONFIG_ORB_COMMUNICATOR + /** * Method to set the uORBCommunicator::IChannel instance. * @param comm_channel @@ -483,15 +418,43 @@ class uORB::Manager #endif /* CONFIG_ORB_COMMUNICATOR */ + void *operator new (size_t, void *p) + { + return p; + } + + void operator delete (void *p) + { + munmap(p, sizeof(uORB::Manager)); + } + + static void lockThread(int idx) + { + _Instance->g_sem_pool.take(idx); + } + + static void unlockThread(int idx) + { + _Instance->g_sem_pool.release(idx); + } + + static void freeThreadLock(int i) {_Instance->g_sem_pool.free(i);} + + static int8_t getThreadLock() {return _Instance->g_sem_pool.reserve();} + + static void queueCallback(class SubscriptionCallback *sub) + { + _Instance->lock_callbacks(); + _Instance->_callback_ptr = sub; + // The manager is unlocked in callback thread + } + private: // class methods + inline static uORB::DeviceNode *node(orb_advert_t handle) {return static_cast(handle.node);} - /** - * Common implementation for orb_advertise and orb_subscribe. - * - * Handles creation of the object and the initial publication for - * advertisers. - */ - int node_open(const struct orb_metadata *meta, bool advertiser, int *instance = nullptr); + static void cleanup(); + static int callback_thread(int argc, char *argv[]); + static int8_t launchCallbackThread(); private: // data members static Manager *_Instance; @@ -505,13 +468,34 @@ class uORB::Manager ORBSet _remote_topics; #endif /* CONFIG_ORB_COMMUNICATOR */ - DeviceMaster *_device_master{nullptr}; - private: //class methods Manager(); - virtual ~Manager(); + ~Manager(); + + /** + * Lock against node concurrent node creation + */ + void lock() { do {} while (px4_sem_wait(&_lock) != 0); } + + /** + * Release the node creation lock + */ + void unlock() { px4_sem_post(&_lock); } + + px4_sem_t _lock; #ifdef CONFIG_ORB_COMMUNICATOR + /** + * Helper function to find orb_metadata struct by topic name + * @param topic_name + * This represents the uORB message Name (topic); This message Name should be + * globally unique. + * @return + * pointer to struct orb_metadata + * nullptr = failure + */ + const struct orb_metadata *topic_name_to_meta(const char *topic_name); + /** * Interface to process a received topic advertisement from remote. * @param topic_name @@ -598,12 +582,104 @@ class uORB::Manager * @return 0 on success, <0 otherwise */ int readPublisherRulesFromFile(const char *file_name, PublisherRule &rule); - PublisherRule _publisher_rule; bool _has_publisher_rules = false; #endif /* ORB_USE_PUBLISHER_RULES */ -}; + /** + * Method to map the singleton instance for the uORB::Manager + * to the processes address space. Make sure initialize() is called first. + */ + static void map_instance(); + + void set_has_publisher(ORB_ID orb_id, uint8_t instance) + { + static_assert(sizeof(g_has_publisher[0]) * 8 >= ORB_MULTI_MAX_INSTANCES); + g_has_publisher[static_cast(orb_id)] |= (1 << instance); + } + + void unset_has_publisher(ORB_ID orb_id, uint8_t instance) + { + static_assert(sizeof(g_has_publisher[0]) * 8 >= ORB_MULTI_MAX_INSTANCES); + g_has_publisher[static_cast(orb_id)] &= ~(1 << instance); + } + + // Global cache for advertised uORB node instances + uint16_t g_has_publisher[ORB_TOPICS_COUNT + 1]; + + // This (system global) variable is used to pass the subsriber + // pointer to the callback thread. This is in Manager, since + // it needs to be mapped for both advertisers and the subscribers + class SubscriptionCallback *_callback_ptr {nullptr}; + + // This mutex protects the above pointer for one writer at a time + px4_sem_t _callback_lock; + + void lock_callbacks() { do {} while (px4_sem_wait(&_callback_lock) != 0); } + void unlock_callbacks() { px4_sem_post(&_callback_lock); } + + // A global pool of semaphores for + // 1) poll locks + // 2) callback thread signalling (except in NuttX flat build) -#endif /* _uORBManager_hpp_ */ + class GlobalSemPool + { + public: + void init(); + int8_t reserve(); + void free(int8_t i); + + void set(int8_t i, int val) {_global_sem[i].set(val);} + void take(int8_t i) { do {} while (_global_sem[i].take() != 0); } + int take_interruptible(int8_t i) { return _global_sem[i].take(); } + int take_timedwait(int8_t i, struct timespec *abstime) { return _global_sem[i].take_timedwait(abstime); } + void release(int8_t i) {_global_sem[i].release(); } + + class GlobalLock + { + public: + void init() + { + px4_sem_init(&_sem, 1, 0); +#if __PX4_NUTTX + sem_setprotocol(&_sem, SEM_PRIO_NONE); +#endif + in_use = false; + } + void set(int val) + { + px4_sem_destroy(&_sem); + px4_sem_init(&_sem, 1, val); +#if __PX4_NUTTX + sem_setprotocol(&_sem, SEM_PRIO_NONE); +#endif + } + int take() {return px4_sem_wait(&_sem);} + int take_timedwait(struct timespec *abstime) { return px4_sem_timedwait(&_sem, abstime); } + void release() {px4_sem_post(&_sem); } + + bool in_use{false}; + + private: + struct SubscriptionCallback *subscriber; + px4_sem_t _sem; + }; + private: + + void lock() + { + do {} while (px4_sem_wait(&_semLock) != 0); + } + void unlock() { px4_sem_post(&_semLock); } + + GlobalLock _global_sem[NUM_GLOBAL_SEMS]; + px4_sem_t _semLock; + } g_sem_pool; + +#ifndef CONFIG_BUILD_FLAT + static int8_t per_process_lock; + static pid_t per_process_cb_thread; +#endif +}; +} // namespace uORB diff --git a/platforms/common/uORB/uORBManagerUsr.cpp b/platforms/common/uORB/uORBManagerUsr.cpp deleted file mode 100644 index af00dbb9ba58..000000000000 --- a/platforms/common/uORB/uORBManagerUsr.cpp +++ /dev/null @@ -1,349 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include "uORBDeviceNode.hpp" -#include "uORBUtils.hpp" -#include "uORBManager.hpp" - -uORB::Manager *uORB::Manager::_Instance = nullptr; - -bool uORB::Manager::initialize() -{ - if (_Instance == nullptr) { - _Instance = new uORB::Manager(); - } - - return _Instance != nullptr; -} - -bool uORB::Manager::terminate() -{ - if (_Instance != nullptr) { - delete _Instance; - _Instance = nullptr; - return true; - } - - return false; -} - -uORB::Manager::Manager() -{ -} - -uORB::Manager::~Manager() -{ -} - -int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance) -{ - // instance valid range: [0, ORB_MULTI_MAX_INSTANCES) - if ((instance < 0) || (instance > (ORB_MULTI_MAX_INSTANCES - 1))) { - return PX4_ERROR; - } - - orbiocdevexists_t data = {static_cast(meta->o_id), static_cast(instance), true, PX4_ERROR}; - boardctl(ORBIOCDEVEXISTS, reinterpret_cast(&data)); - - return data.ret; -} - -orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, - unsigned int queue_size) -{ - /* open the node as an advertiser */ - int fd = node_open(meta, true, instance); - - if (fd == PX4_ERROR) { - PX4_ERR("%s advertise failed (%i)", meta->o_name, errno); - return nullptr; - } - - /* Set the queue size. This must be done before the first publication; thus it fails if - * this is not the first advertiser. - */ - int result = px4_ioctl(fd, ORBIOCSETQUEUESIZE, (unsigned long)queue_size); - - if (result < 0 && queue_size > 1) { - PX4_WARN("orb_advertise_multi: failed to set queue size"); - } - - /* get the advertiser handle and close the node */ - orb_advert_t advertiser; - - result = px4_ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser); - px4_close(fd); - - if (result == PX4_ERROR) { - PX4_WARN("px4_ioctl ORBIOCGADVERTISER failed. fd = %d", fd); - return nullptr; - } - - /* the advertiser may perform an initial publish to initialise the object */ - if (data != nullptr) { - result = orb_publish(meta, advertiser, data); - - if (result == PX4_ERROR) { - PX4_ERR("orb_publish failed %s", meta->o_name); - return nullptr; - } - } - - return advertiser; -} - -int uORB::Manager::orb_unadvertise(orb_advert_t handle) -{ - orbiocdevunadvertise_t data = {handle, PX4_ERROR}; - boardctl(ORBIOCDEVUNADVERTISE, reinterpret_cast(&data)); - - return data.ret; -} - -int uORB::Manager::orb_subscribe(const struct orb_metadata *meta) -{ - return node_open(meta, false); -} - -int uORB::Manager::orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance) -{ - int inst = instance; - return node_open(meta, false, &inst); -} - -int uORB::Manager::orb_unsubscribe(int fd) -{ - return px4_close(fd); -} - -int uORB::Manager::orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) -{ - orbiocdevpublish_t d = {meta, handle, data, PX4_ERROR}; - boardctl(ORBIOCDEVPUBLISH, reinterpret_cast(&d)); - - return d.ret; -} - -int uORB::Manager::orb_copy(const struct orb_metadata *meta, int handle, void *buffer) -{ - int ret; - - ret = px4_read(handle, buffer, meta->o_size); - - if (ret < 0) { - return PX4_ERROR; - } - - if (ret != (int)meta->o_size) { - errno = EIO; - return PX4_ERROR; - } - - return PX4_OK; -} - -int uORB::Manager::orb_check(int handle, bool *updated) -{ - /* Set to false here so that if `px4_ioctl` fails to false. */ - *updated = false; - return px4_ioctl(handle, ORBIOCUPDATED, (unsigned long)(uintptr_t)updated); -} - -int uORB::Manager::orb_set_interval(int handle, unsigned interval) -{ - return px4_ioctl(handle, ORBIOCSETINTERVAL, interval * 1000); -} - -int uORB::Manager::orb_get_interval(int handle, unsigned *interval) -{ - int ret = px4_ioctl(handle, ORBIOCGETINTERVAL, (unsigned long)interval); - *interval /= 1000; - return ret; -} - -int uORB::Manager::node_open(const struct orb_metadata *meta, bool advertiser, int *instance) -{ - char path[orb_maxpath]; - int fd = -1; - int ret = PX4_ERROR; - - /* - * If meta is null, the object was not defined, i.e. it is not - * known to the system. We can't advertise/subscribe such a thing. - */ - if (nullptr == meta) { - errno = ENOENT; - return PX4_ERROR; - } - - /* if we have an instance and are an advertiser, we will generate a new node and set the instance, - * so we do not need to open here */ - if (!instance || !advertiser) { - /* - * Generate the path to the node and try to open it. - */ - ret = uORB::Utils::node_mkpath(path, meta, instance); - - if (ret != OK) { - errno = -ret; - return PX4_ERROR; - } - - /* open the path as either the advertiser or the subscriber */ - fd = px4_open(path, advertiser ? PX4_F_WRONLY : PX4_F_RDONLY); - - } else { - *instance = 0; - } - - /* we may need to advertise the node... */ - if (fd < 0) { - ret = PX4_ERROR; - - orbiocdevadvertise_t data = {meta, advertiser, instance, PX4_ERROR}; - boardctl(ORBIOCDEVADVERTISE, (unsigned long)&data); - ret = data.ret; - - /* it's OK if it already exists */ - if ((ret != PX4_OK) && (EEXIST == errno)) { - ret = PX4_OK; - } - - if (ret == PX4_OK) { - /* update the path, as it might have been updated during the node advertise call */ - ret = uORB::Utils::node_mkpath(path, meta, instance); - - /* on success, try to open again */ - if (ret == PX4_OK) { - fd = px4_open(path, (advertiser) ? PX4_F_WRONLY : PX4_F_RDONLY); - - } else { - errno = -ret; - return PX4_ERROR; - } - } - } - - if (fd < 0) { - errno = EIO; - return PX4_ERROR; - } - - /* everything has been OK, we can return the handle now */ - return fd; -} - -bool uORB::Manager::orb_device_node_exists(ORB_ID orb_id, uint8_t instance) -{ - orbiocdevexists_t data = {orb_id, instance, false, 0}; - boardctl(ORBIOCDEVEXISTS, reinterpret_cast(&data)); - - return data.ret == PX4_OK ? true : false; -} - -void *uORB::Manager::orb_add_internal_subscriber(ORB_ID orb_id, uint8_t instance, unsigned *initial_generation) -{ - orbiocdevaddsubscriber_t data = {orb_id, instance, initial_generation, nullptr}; - boardctl(ORBIOCDEVADDSUBSCRIBER, reinterpret_cast(&data)); - - return data.handle; -} - -void uORB::Manager::orb_remove_internal_subscriber(void *node_handle) -{ - boardctl(ORBIOCDEVREMSUBSCRIBER, reinterpret_cast(node_handle)); -} - -uint8_t uORB::Manager::orb_get_queue_size(const void *node_handle) -{ - orbiocdevqueuesize_t data = {node_handle, 0}; - boardctl(ORBIOCDEVQUEUESIZE, reinterpret_cast(&data)); - - return data.size; -} - -bool uORB::Manager::orb_data_copy(void *node_handle, void *dst, unsigned &generation, bool only_if_updated) -{ - orbiocdevdatacopy_t data = {node_handle, dst, generation, only_if_updated, false}; - boardctl(ORBIOCDEVDATACOPY, reinterpret_cast(&data)); - generation = data.generation; - - return data.ret; -} - -bool uORB::Manager::register_callback(void *node_handle, SubscriptionCallback *callback_sub) -{ - orbiocdevregcallback_t data = {node_handle, callback_sub, false}; - boardctl(ORBIOCDEVREGCALLBACK, reinterpret_cast(&data)); - - return data.registered; -} - -void uORB::Manager::unregister_callback(void *node_handle, SubscriptionCallback *callback_sub) -{ - orbiocdevunregcallback_t data = {node_handle, callback_sub}; - boardctl(ORBIOCDEVUNREGCALLBACK, reinterpret_cast(&data)); -} - -uint8_t uORB::Manager::orb_get_instance(const void *node_handle) -{ - orbiocdevgetinstance_t data = {node_handle, 0}; - boardctl(ORBIOCDEVGETINSTANCE, reinterpret_cast(&data)); - - return data.instance; -} - -unsigned uORB::Manager::updates_available(const void *node_handle, unsigned last_generation) -{ - orbiocdevupdatesavail_t data = {node_handle, last_generation, 0}; - boardctl(ORBIOCDEVUPDATESAVAIL, reinterpret_cast(&data)); - return data.ret; -} - -bool uORB::Manager::is_advertised(const void *node_handle) -{ - orbiocdevisadvertised_t data = {node_handle, false}; - boardctl(ORBIOCDEVISADVERTISED, reinterpret_cast(&data)); - return data.ret; -} diff --git a/platforms/common/uORB/uORBUtils.cpp b/platforms/common/uORB/uORBUtils.cpp index fc9a88095f2d..c37dcc0873ef 100644 --- a/platforms/common/uORB/uORBUtils.cpp +++ b/platforms/common/uORB/uORBUtils.cpp @@ -45,7 +45,7 @@ int uORB::Utils::node_mkpath(char *buf, const struct orb_metadata *meta, int *in index = *instance; } - len = snprintf(buf, orb_maxpath, "/%s/%s%d", "obj", meta->o_name, index); + len = snprintf(buf, orb_maxpath, "_orb_%s%d", meta->o_name, index); if (len >= orb_maxpath) { return -ENAMETOOLONG; @@ -62,7 +62,7 @@ int uORB::Utils::node_mkpath(char *buf, const char *orbMsgName) unsigned index = 0; - len = snprintf(buf, orb_maxpath, "/%s/%s%d", "obj", orbMsgName, index); + len = snprintf(buf, orb_maxpath, "_orb_%s%d", orbMsgName, index); if (len >= orb_maxpath) { return -ENAMETOOLONG; diff --git a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp index 9458b2bb26ab..d9f2e7cd8776 100644 --- a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp +++ b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp @@ -56,7 +56,7 @@ int uORBTest::UnitTest::pubsublatency_main() /* wakeup source(s) */ px4_pollfd_struct_t fds[1] {}; - int test_multi_sub = orb_subscribe_multi(ORB_ID(orb_test_medium), 0); + orb_sub_t test_multi_sub = orb_subscribe_multi(ORB_ID(orb_test_medium), 0); orb_test_medium_s t{}; @@ -258,13 +258,13 @@ int uORBTest::UnitTest::test_single() t.val = 0; ptopic = orb_advertise(ORB_ID(orb_test), &t); - if (ptopic == nullptr) { + if (!orb_advert_valid(ptopic)) { return test_fail("advertise failed: %d", errno); } - int sfd = orb_subscribe(ORB_ID(orb_test)); + orb_sub_t sfd = orb_subscribe(ORB_ID(orb_test)); - if (sfd < 0) { + if (!orb_sub_valid(sfd)) { return test_fail("subscribe failed: %d", errno); } @@ -355,7 +355,7 @@ int uORBTest::UnitTest::test_multi() } /* subscribe to both topics and ensure valid data is received */ - int sfd0 = orb_subscribe_multi(ORB_ID(orb_multitest), 0); + orb_sub_t sfd0 = orb_subscribe_multi(ORB_ID(orb_multitest), 0); if (PX4_OK != orb_copy(ORB_ID(orb_multitest), sfd0, &u)) { return test_fail("sub #0 copy failed: %d", errno); @@ -365,7 +365,7 @@ int uORBTest::UnitTest::test_multi() return test_fail("sub #0 val. mismatch: %d", u.val); } - int sfd1 = orb_subscribe_multi(ORB_ID(orb_multitest), 1); + orb_sub_t sfd1 = orb_subscribe_multi(ORB_ID(orb_multitest), 1); if (PX4_OK != orb_copy(ORB_ID(orb_multitest), sfd1, &u)) { return test_fail("sub #1 copy failed: %d", errno); @@ -449,7 +449,7 @@ int uORBTest::UnitTest::test_multi2() _thread_should_exit = false; const int num_instances = 3; - int orb_data_fd[num_instances] {-1, -1, -1}; + orb_sub_t orb_data_fd[num_instances] {ORB_SUB_INVALID, ORB_SUB_INVALID, ORB_SUB_INVALID}; int orb_data_next = 0; for (int i = 0; i < num_instances; ++i) { @@ -476,7 +476,7 @@ int uORBTest::UnitTest::test_multi2() px4_usleep(1000); bool updated = false; - int orb_data_cur_fd = orb_data_fd[orb_data_next]; + orb_sub_t orb_data_cur_fd = orb_data_fd[orb_data_next]; orb_check(orb_data_cur_fd, &updated); if (updated) { @@ -508,9 +508,9 @@ int uORBTest::UnitTest::test_multi_reversed() /* For these tests 0 and 1 instances are taken from before, therefore continue with 2 and 3. */ /* Subscribe first and advertise afterwards. */ - int sfd2 = orb_subscribe_multi(ORB_ID(orb_multitest), 2); + orb_sub_t sfd2 = orb_subscribe_multi(ORB_ID(orb_multitest), 2); - if (sfd2 < 0) { + if (!orb_sub_valid(sfd2)) { return test_fail("sub. id2: ret: %d", sfd2); } @@ -551,7 +551,7 @@ int uORBTest::UnitTest::test_multi_reversed() return test_fail("sub #3 val. mismatch: %d", u.val); } - int sfd3 = orb_subscribe_multi(ORB_ID(orb_multitest), 3); + orb_sub_t sfd3 = orb_subscribe_multi(ORB_ID(orb_multitest), 3); if (PX4_OK != orb_copy(ORB_ID(orb_multitest), sfd3, &u)) { return test_fail("sub #3 copy failed: %d", errno); @@ -570,20 +570,21 @@ int uORBTest::UnitTest::test_wrap_around() orb_test_medium_s t{}; orb_test_medium_s u{}; - orb_advert_t ptopic{nullptr}; + orb_advert_t ptopic{ORB_ADVERT_INVALID}; bool updated{false}; // Advertise but not publish topics, only generate device_node, which is convenient for modifying DeviceNode::_generation const int queue_size = 16; ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_wrap_around), nullptr, queue_size); - if (ptopic == nullptr) { + if (!orb_advert_valid(ptopic)) { return test_fail("advertise failed: %d", errno); } - auto node = uORB::Manager::get_instance()->get_device_master()->getDeviceNode(ORB_ID(orb_test_medium_wrap_around), 0); + orb_advert_t handle = uORB::DeviceNode::nodeOpen(ORB_ID::orb_test_medium_wrap_around, 0, false); + auto node = static_cast(handle.node); - if (node == nullptr) { + if (!orb_advert_valid(handle)) { return test_fail("get device node failed."); } @@ -600,9 +601,9 @@ int uORBTest::UnitTest::test_wrap_around() t.val = 0; orb_publish(ORB_ID(orb_test_medium_wrap_around), &ptopic, &t); - int sfd = orb_subscribe(ORB_ID(orb_test_medium_wrap_around)); + orb_sub_t sfd = orb_subscribe(ORB_ID(orb_test_medium_wrap_around)); - if (sfd < 0) { + if (!orb_sub_valid(sfd)) { return test_fail("subscribe failed: %d", errno); } @@ -822,9 +823,9 @@ int uORBTest::UnitTest::test_queue() orb_advert_t ptopic{nullptr}; bool updated{false}; - int sfd = orb_subscribe(ORB_ID(orb_test_medium_queue)); + orb_sub_t sfd = orb_subscribe(ORB_ID(orb_test_medium_queue)); - if (sfd < 0) { + if (!orb_sub_valid(sfd)) { return test_fail("subscribe failed: %d", errno); } @@ -832,7 +833,7 @@ int uORBTest::UnitTest::test_queue() orb_test_medium_s t{}; ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue), &t, queue_size); - if (ptopic == nullptr) { + if (!orb_advert_valid(ptopic)) { return test_fail("advertise failed: %d", errno); } @@ -934,10 +935,10 @@ int uORBTest::UnitTest::pub_test_queue_entry(int argc, char *argv[]) int uORBTest::UnitTest::pub_test_queue_main() { orb_test_medium_s t{}; - orb_advert_t ptopic{nullptr}; + orb_advert_t ptopic{ORB_ADVERT_INVALID}; const int queue_size = 50; - if ((ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue_poll), &t, queue_size)) == nullptr) { + if (!orb_advert_valid(ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue_poll), &t, queue_size))) { _thread_should_exit = true; return test_fail("advertise failed: %d", errno); } @@ -974,9 +975,9 @@ int uORBTest::UnitTest::test_queue_poll_notify() test_note("Testing orb queuing (poll & notify)"); orb_test_medium_s t{}; - int sfd = -1; + orb_sub_t sfd = ORB_SUB_INVALID; - if ((sfd = orb_subscribe(ORB_ID(orb_test_medium_queue_poll))) < 0) { + if (!orb_sub_valid(sfd = orb_subscribe(ORB_ID(orb_test_medium_queue_poll)))) { return test_fail("subscribe failed: %d", errno); } @@ -1042,7 +1043,7 @@ int uORBTest::UnitTest::latency_test(bool print) orb_advert_t pfd0 = orb_advertise(ORB_ID(orb_test_medium), &t); - if (pfd0 == nullptr) { + if (!orb_advert_valid(pfd0)) { return test_fail("orb_advertise failed (%i)", errno); } diff --git a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.hpp b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.hpp index 908eeca9c7e2..7f93d9f8a732 100644 --- a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.hpp +++ b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.hpp @@ -35,7 +35,6 @@ #define _uORBTest_UnitTest_hpp_ #include -#include #include #include #include diff --git a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp index 56cdcc21735e..7db9bbd1c72a 100644 --- a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp @@ -55,8 +55,6 @@ extern "C" void px4_userspace_init(void) px4::WorkQueueManagerStart(); - uorb_start(); - px4_log_initialize(); #if defined(CONFIG_SYSTEM_CDCACM) diff --git a/platforms/posix/src/px4/common/main.cpp b/platforms/posix/src/px4/common/main.cpp index db6bfe850b41..9c2b78b56d08 100644 --- a/platforms/posix/src/px4/common/main.cpp +++ b/platforms/posix/src/px4/common/main.cpp @@ -79,6 +79,8 @@ #include "px4_daemon/server.h" #include "px4_daemon/pxh.h" +#include + #define MODULE_NAME "px4" static const char *LOCK_FILE_PATH = "/tmp/px4_lock"; diff --git a/src/systemcmds/uorb/CMakeLists.txt b/src/systemcmds/uorb/CMakeLists.txt index 2c1362394b47..238c0059a956 100644 --- a/src/systemcmds/uorb/CMakeLists.txt +++ b/src/systemcmds/uorb/CMakeLists.txt @@ -36,5 +36,6 @@ px4_add_module( COMPILE_FLAGS SRCS uorb.cpp + uORBDeviceMaster.cpp DEPENDS ) diff --git a/platforms/common/uORB/uORBDeviceMaster.cpp b/src/systemcmds/uorb/uORBDeviceMaster.cpp similarity index 67% rename from platforms/common/uORB/uORBDeviceMaster.cpp rename to src/systemcmds/uorb/uORBDeviceMaster.cpp index c39e4572db5e..a5eaa191fd44 100644 --- a/platforms/common/uORB/uORBDeviceMaster.cpp +++ b/src/systemcmds/uorb/uORBDeviceMaster.cpp @@ -32,9 +32,9 @@ ****************************************************************************/ #include "uORBDeviceMaster.hpp" -#include "uORBDeviceNode.hpp" -#include "uORBManager.hpp" -#include "uORBUtils.hpp" +#include +#include +#include #include #include @@ -45,6 +45,12 @@ #include #endif // PX4_QURT +#ifndef CONFIG_FS_SHMFS_VFS_PATH +#define CONFIG_FS_SHMFS_VFS_PATH "/dev/shm" +#endif + +#include + uORB::DeviceMaster::DeviceMaster() { px4_sem_init(&_lock, 0, 1); @@ -55,115 +61,6 @@ uORB::DeviceMaster::~DeviceMaster() px4_sem_destroy(&_lock); } -int uORB::DeviceMaster::advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance) -{ - int ret = PX4_ERROR; - - char nodepath[orb_maxpath]; - - /* construct a path to the node - this also checks the node name */ - ret = uORB::Utils::node_mkpath(nodepath, meta, instance); - - if (ret != PX4_OK) { - return ret; - } - - ret = PX4_ERROR; - - /* try for topic groups */ - const unsigned max_group_tries = (instance != nullptr) ? ORB_MULTI_MAX_INSTANCES : 1; - unsigned group_tries = 0; - - if (instance) { - /* for an advertiser, this will be 0, but a for subscriber that requests a certain instance, - * we do not want to start with 0, but with the instance the subscriber actually requests. - */ - group_tries = *instance; - - if (group_tries >= max_group_tries) { - return -ENOMEM; - } - } - - SmartLock smart_lock(_lock); - - do { - /* if path is modifyable change try index */ - if (instance != nullptr) { - /* replace the number at the end of the string */ - nodepath[strlen(nodepath) - 1] = '0' + group_tries; - *instance = group_tries; - } - - /* construct the new node, passing the ownership of path to it */ - uORB::DeviceNode *node = new uORB::DeviceNode(meta, group_tries, nodepath); - - /* if we didn't get a device, that's bad */ - if (node == nullptr) { - return -ENOMEM; - } - - /* initialise the node - this may fail if e.g. a node with this name already exists */ - ret = node->init(); - - /* if init failed, discard the node and its name */ - if (ret != PX4_OK) { - delete node; - - if (ret == -EEXIST) { - /* if the node exists already, get the existing one and check if it's advertised. */ - uORB::DeviceNode *existing_node = getDeviceNodeLocked(meta, group_tries); - - /* - * We can claim an existing node in these cases: - * - The node is not advertised (yet). It means there is already one or more subscribers or it was - * unadvertised. - * - We are a single-instance advertiser requesting the first instance. - * (Usually we don't end up here, but we might in case of a race condition between 2 - * advertisers). - * - We are a subscriber requesting a certain instance. - * (Also we usually don't end up in that case, but we might in case of a race condtion - * between an advertiser and subscriber). - */ - bool is_single_instance_advertiser = is_advertiser && !instance; - - if (existing_node != nullptr && - (!existing_node->is_advertised() || is_single_instance_advertiser || !is_advertiser)) { - if (is_advertiser) { - /* Set as advertised to avoid race conditions (otherwise 2 multi-instance advertisers - * could get the same instance). - */ - existing_node->mark_as_advertised(); - } - - ret = PX4_OK; - - } else { - /* otherwise: already advertised, keep looking */ - } - } - - } else { - if (is_advertiser) { - node->mark_as_advertised(); - } - - // add to the node map. - _node_list.add(node); - _node_exists[node->get_instance()].set((uint8_t)node->id(), true); - } - - group_tries++; - - } while (ret != PX4_OK && (group_tries < max_group_tries)); - - if (ret != PX4_OK && group_tries >= max_group_tries) { - ret = -ENOMEM; - } - - return ret; -} - void uORB::DeviceMaster::printStatistics() { /* Add all nodes to a list while locked, and then print them in unlocked state, to avoid potential @@ -190,6 +87,7 @@ void uORB::DeviceMaster::printStatistics() DeviceNodeStatisticsData *prev = cur_node; cur_node = cur_node->next; + munmap(prev->node, sizeof(uORB::DeviceNode)); delete prev; } } @@ -207,7 +105,36 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, } } - for (const auto &node : _node_list) { + DIR *shm_dir = opendir(CONFIG_FS_SHMFS_VFS_PATH); + struct dirent *shm; + const char orb_name_prefix[] = "_orb_"; + + while ((shm = readdir(shm_dir)) != nullptr) { + + if (strncmp(orb_name_prefix, shm->d_name, sizeof(orb_name_prefix) - 1)) { + continue; + } + + void *ptr = nullptr; + uORB::DeviceNode *node = nullptr; + + // open and mmap the shared memory segment + int shm_fd = shm_open(shm->d_name, O_RDWR, 0666); + + if (shm_fd >= 0) { + ptr = mmap(0, sizeof(uORB::DeviceNode), PROT_READ, MAP_SHARED, shm_fd, 0); + } + + if (ptr != MAP_FAILED) { + node = static_cast(ptr); + } + + close(shm_fd); + + if (node == nullptr) { + PX4_ERR("Failed to MMAP an existing node\n"); + continue; + } ++num_topics; @@ -219,6 +146,8 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, } if (cur_node) { + // currently nuttx creates a new mapping on every mmap. TODO: check linux + munmap(node, sizeof(uORB::DeviceNode)); continue; } @@ -226,12 +155,13 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, bool matched = false; for (int i = 0; i < num_filters; ++i) { - if (strstr(node->get_meta()->o_name, topic_filter[i])) { + if (strstr(node->get_name(), topic_filter[i])) { matched = true; } } if (!matched) { + munmap(node, sizeof(uORB::DeviceNode)); continue; } } @@ -260,6 +190,7 @@ int uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node, last_node->last_pub_msg_count = last_node->node->updates_available(0); } + closedir(shm_dir); return 0; } @@ -293,12 +224,6 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters) lock(); - if (_node_list.empty()) { - unlock(); - PX4_INFO("no active topics"); - return; - } - DeviceNodeStatisticsData *first_node = nullptr; DeviceNodeStatisticsData *cur_node = nullptr; size_t max_topic_name_length = 0; @@ -424,36 +349,8 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters) while (cur_node) { DeviceNodeStatisticsData *next_node = cur_node->next; - delete cur_node; + munmap(cur_node->node, sizeof(uORB::DeviceNode)); + delete (cur_node); cur_node = next_node; } } - -#undef CLEAR_LINE - -uORB::DeviceNode *uORB::DeviceMaster::getDeviceNode(const char *nodepath) -{ - lock(); - - for (uORB::DeviceNode *node : _node_list) { - if (strcmp(node->get_devname(), nodepath) == 0) { - unlock(); - return node; - } - } - - unlock(); - - return nullptr; -} - -uORB::DeviceNode *uORB::DeviceMaster::getDeviceNodeLocked(const struct orb_metadata *meta, const uint8_t instance) -{ - for (uORB::DeviceNode *node : _node_list) { - if ((strcmp(node->get_name(), meta->o_name) == 0) && (node->get_instance() == instance)) { - return node; - } - } - - return nullptr; -} diff --git a/platforms/common/uORB/uORBDeviceMaster.hpp b/src/systemcmds/uorb/uORBDeviceMaster.hpp similarity index 70% rename from platforms/common/uORB/uORBDeviceMaster.hpp rename to src/systemcmds/uorb/uORBDeviceMaster.hpp index 94c97e61dfc9..f8f34c56ac8e 100644 --- a/platforms/common/uORB/uORBDeviceMaster.hpp +++ b/src/systemcmds/uorb/uORBDeviceMaster.hpp @@ -35,7 +35,7 @@ #include -#include "uORBCommon.hpp" +#include #include #include @@ -64,42 +64,8 @@ using px4::AtomicBitset; class uORB::DeviceMaster { public: - - int advertise(const struct orb_metadata *meta, bool is_advertiser, int *instance); - - /** - * Public interface for getDeviceNodeLocked(). Takes care of synchronization. - * @return node if exists, nullptr otherwise - */ - uORB::DeviceNode *getDeviceNode(const char *node_name); - uORB::DeviceNode *getDeviceNode(const struct orb_metadata *meta, const uint8_t instance) - { - if (meta == nullptr) { - return nullptr; - } - - if (!deviceNodeExists(static_cast(meta->o_id), instance)) { - return nullptr; - } - - lock(); - uORB::DeviceNode *node = getDeviceNodeLocked(meta, instance); - unlock(); - - //We can safely return the node that can be used by any thread, because - //a DeviceNode never gets deleted. - return node; - - } - - bool deviceNodeExists(ORB_ID id, const uint8_t instance) - { - if ((id == ORB_ID::INVALID) || (instance > ORB_MULTI_MAX_INSTANCES - 1)) { - return false; - } - - return _node_exists[instance][(uint8_t)id]; - } + DeviceMaster(); + ~DeviceMaster(); /** * Print statistics for each existing topic. @@ -116,9 +82,6 @@ class uORB::DeviceMaster void showTop(char **topic_filter, int num_filters); private: - // Private constructor, uORB::Manager takes care of its creation - DeviceMaster(); - ~DeviceMaster(); struct DeviceNodeStatisticsData { DeviceNode *node; @@ -132,16 +95,6 @@ class uORB::DeviceMaster friend class uORB::Manager; - /** - * Find a node give its name. - * _lock must already be held when calling this. - * @return node if exists, nullptr otherwise - */ - uORB::DeviceNode *getDeviceNodeLocked(const struct orb_metadata *meta, const uint8_t instance); - - IntrusiveSortedList _node_list; - AtomicBitset _node_exists[ORB_MULTI_MAX_INSTANCES]; - px4_sem_t _lock; /**< lock to protect access to all class members (also for derived classes) */ void lock() { do {} while (px4_sem_wait(&_lock) != 0); } diff --git a/src/systemcmds/uorb/uorb.cpp b/src/systemcmds/uorb/uorb.cpp index b9fb565c143b..8a4561c28996 100644 --- a/src/systemcmds/uorb/uorb.cpp +++ b/src/systemcmds/uorb/uorb.cpp @@ -38,10 +38,28 @@ #include #include +#include "uORBDeviceMaster.hpp" + extern "C" { __EXPORT int uorb_main(int argc, char *argv[]); } static void usage(); +static int uorb_status(void) +{ + uORB::DeviceMaster dev; + dev.printStatistics(); + + return OK; +} + +static int uorb_top(char **topic_filter, int num_filters) +{ + uORB::DeviceMaster dev; + dev.showTop(topic_filter, num_filters); + + return OK; +} + int uorb_main(int argc, char *argv[]) { if (argc < 2) { @@ -49,10 +67,7 @@ int uorb_main(int argc, char *argv[]) return -1; } - if (!strcmp(argv[1], "start")) { - return uorb_start(); - - } else if (!strcmp(argv[1], "status")) { + if (!strcmp(argv[1], "status")) { return uorb_status(); } else if (!strcmp(argv[1], "top")) { From 03a97380531d8a2684d7eb0e82d12d43409cdace Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Tue, 20 Dec 2022 15:36:32 +0200 Subject: [PATCH 026/273] uORB/uORBManager: Use adjusted stack size for orb_callback --- platforms/common/uORB/uORBManager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/common/uORB/uORBManager.cpp b/platforms/common/uORB/uORBManager.cpp index f1697cd05fc1..19a743f8c4a6 100644 --- a/platforms/common/uORB/uORBManager.cpp +++ b/platforms/common/uORB/uORBManager.cpp @@ -473,7 +473,7 @@ uORB::Manager::launchCallbackThread() per_process_cb_thread = px4_task_spawn_cmd("orb_callback", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 1, - 1024, + PX4_STACK_ADJUSTED(1024), callback_thread, nullptr); From 2c74e7ded2da92f3cf5662875d21357440dc9490 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Tue, 17 Jan 2023 15:25:16 +0200 Subject: [PATCH 027/273] uORB/uORBManager: Add simple "is client alive"-test to manager If the client is clearly not executing the callbacks, unregister it to: - Free the resource - Prevent posting the semaphore over its limit (which causes a crash) The unresponsive clients are removed one at a time, to keep the removal mechanism light weight. --- platforms/common/uORB/uORBDeviceNode.cpp | 15 ++++++++++++++- platforms/common/uORB/uORBManager.hpp | 10 +++++++++- 2 files changed, 23 insertions(+), 2 deletions(-) diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index 8665dd98bc90..e4611c4cdbb9 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -570,6 +570,9 @@ uORB::DeviceNode::write(const char *buffer, const orb_metadata *meta, orb_advert /* If data size has changed, re-map the data */ size_t data_size = _queue_size * o_size; + /* Remove single unresponsive entry at a time (if any) */ + uorb_cb_handle_t remove_cb = UORB_INVALID_CB_HANDLE; + /* Perform an atomic copy. */ ATOMIC_ENTER; @@ -609,7 +612,12 @@ uORB::DeviceNode::write(const char *buffer, const orb_metadata *meta, orb_advert // Release poll waiters (and callback threads in non-flat builds) if (item->lock != -1) { - Manager::unlockThread(item->lock); + if (Manager::isThreadAlive(item->lock)) { + Manager::unlockThread(item->lock); + + } else { + remove_cb = cb; + } } } @@ -618,6 +626,11 @@ uORB::DeviceNode::write(const char *buffer, const orb_metadata *meta, orb_advert ATOMIC_LEAVE; + if (callbacks.handle_valid(remove_cb)) { + PX4_ERR("Removing subscriber due to inactivity\n"); + unregister_callback(handle, remove_cb); + } + return o_size; } diff --git a/platforms/common/uORB/uORBManager.hpp b/platforms/common/uORB/uORBManager.hpp index e5497f956807..bd4655327315 100644 --- a/platforms/common/uORB/uORBManager.hpp +++ b/platforms/common/uORB/uORBManager.hpp @@ -49,6 +49,7 @@ #endif /* CONFIG_ORB_COMMUNICATOR */ #define NUM_GLOBAL_SEMS 40 +#define SUB_ALIVE_SEM_MAX_VALUE 100 namespace uORB { @@ -449,6 +450,12 @@ class Manager // The manager is unlocked in callback thread } + static bool isThreadAlive(int idx) + { + int value = _Instance->g_sem_pool.value(idx); + return value <= SUB_ALIVE_SEM_MAX_VALUE; + } + private: // class methods inline static uORB::DeviceNode *node(orb_advert_t handle) {return static_cast(handle.node);} @@ -635,6 +642,7 @@ class Manager int take_interruptible(int8_t i) { return _global_sem[i].take(); } int take_timedwait(int8_t i, struct timespec *abstime) { return _global_sem[i].take_timedwait(abstime); } void release(int8_t i) {_global_sem[i].release(); } + int value(int8_t i) { return _global_sem[i].value(); } class GlobalLock { @@ -658,7 +666,7 @@ class Manager int take() {return px4_sem_wait(&_sem);} int take_timedwait(struct timespec *abstime) { return px4_sem_timedwait(&_sem, abstime); } void release() {px4_sem_post(&_sem); } - + int value() { int value; px4_sem_getvalue(&_sem, &value); return value; } bool in_use{false}; private: From 92457fbe351b197884002d589e9e04ff696d2c10 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Mon, 2 Oct 2023 15:20:50 +0300 Subject: [PATCH 028/273] uorb: Move global _callback_ptr to per thread callback pointer There is one semaphore lock per thread already, this same mechanism can be used to pass the callbacks too. --- platforms/common/uORB/uORBDeviceNode.cpp | 2 +- platforms/common/uORB/uORBManager.cpp | 10 +----- platforms/common/uORB/uORBManager.hpp | 45 +++++++++++++----------- 3 files changed, 27 insertions(+), 30 deletions(-) diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index e4611c4cdbb9..eed0df30c110 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -606,7 +606,7 @@ uORB::DeviceNode::write(const char *buffer, const orb_metadata *meta, orb_advert #ifdef CONFIG_BUILD_FLAT item->subscriber->call(); #else - Manager::queueCallback(item->subscriber); + Manager::queueCallback(item->subscriber, item->lock); #endif } diff --git a/platforms/common/uORB/uORBManager.cpp b/platforms/common/uORB/uORBManager.cpp index 19a743f8c4a6..43b2f6a70444 100644 --- a/platforms/common/uORB/uORBManager.cpp +++ b/platforms/common/uORB/uORBManager.cpp @@ -179,19 +179,12 @@ uORB::Manager::Manager() PX4_DEBUG("SEM INIT FAIL: ret %d", ret); } - ret = px4_sem_init(&_callback_lock, 1, 1); - - if (ret != 0) { - PX4_DEBUG("SEM INIT FAIL: ret %d", ret); - } - g_sem_pool.init(); } uORB::Manager::~Manager() { px4_sem_destroy(&_lock); - px4_sem_destroy(&_callback_lock); } int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance) @@ -493,8 +486,7 @@ uORB::Manager::callback_thread(int argc, char *argv[]) while (true) { lockThread(per_process_lock); - SubscriptionCallback *sub = _Instance->_callback_ptr; - _Instance->unlock_callbacks(); + SubscriptionCallback *sub = dequeueCallback(per_process_lock); // Pass nullptr to this thread to exit if (sub == nullptr) { diff --git a/platforms/common/uORB/uORBManager.hpp b/platforms/common/uORB/uORBManager.hpp index bd4655327315..54227ad9caac 100644 --- a/platforms/common/uORB/uORBManager.hpp +++ b/platforms/common/uORB/uORBManager.hpp @@ -443,13 +443,20 @@ class Manager static int8_t getThreadLock() {return _Instance->g_sem_pool.reserve();} - static void queueCallback(class SubscriptionCallback *sub) + static void queueCallback(class SubscriptionCallback *sub, int idx) { - _Instance->lock_callbacks(); - _Instance->_callback_ptr = sub; + _Instance->g_sem_pool.cb_lock(idx); + _Instance->g_sem_pool.cb_set(idx, sub); // The manager is unlocked in callback thread } + static class SubscriptionCallback *dequeueCallback(int idx) + { + class SubscriptionCallback *sub = _Instance->g_sem_pool.cb_get(idx); + _Instance->g_sem_pool.cb_unlock(idx); + return sub; + } + static bool isThreadAlive(int idx) { int value = _Instance->g_sem_pool.value(idx); @@ -615,17 +622,6 @@ class Manager // Global cache for advertised uORB node instances uint16_t g_has_publisher[ORB_TOPICS_COUNT + 1]; - // This (system global) variable is used to pass the subsriber - // pointer to the callback thread. This is in Manager, since - // it needs to be mapped for both advertisers and the subscribers - class SubscriptionCallback *_callback_ptr {nullptr}; - - // This mutex protects the above pointer for one writer at a time - px4_sem_t _callback_lock; - - void lock_callbacks() { do {} while (px4_sem_wait(&_callback_lock) != 0); } - void unlock_callbacks() { px4_sem_post(&_callback_lock); } - // A global pool of semaphores for // 1) poll locks // 2) callback thread signalling (except in NuttX flat build) @@ -644,14 +640,21 @@ class Manager void release(int8_t i) {_global_sem[i].release(); } int value(int8_t i) { return _global_sem[i].value(); } + void cb_lock(int8_t i) { do {} while (_global_sem[i].cb_lock() != 0); } + void cb_unlock(int8_t i) { _global_sem[i].cb_unlock(); } + void cb_set(int8_t i, struct SubscriptionCallback *callback_ptr) { _global_sem[i].cb_set(callback_ptr); } + struct SubscriptionCallback *cb_get(int8_t i) { return _global_sem[i].cb_get(); } + class GlobalLock { public: void init() { px4_sem_init(&_sem, 1, 0); + px4_sem_init(&_lock, 1, 1); #if __PX4_NUTTX sem_setprotocol(&_sem, SEM_PRIO_NONE); + sem_setprotocol(&_lock, SEM_PRIO_NONE); #endif in_use = false; } @@ -669,16 +672,18 @@ class Manager int value() { int value; px4_sem_getvalue(&_sem, &value); return value; } bool in_use{false}; + int cb_lock() { return px4_sem_wait(&_lock); } + void cb_unlock() { px4_sem_post(&_lock); } + void cb_set(struct SubscriptionCallback *callback_ptr) { _callback_ptr = callback_ptr; } + struct SubscriptionCallback *cb_get() { return _callback_ptr; } private: - struct SubscriptionCallback *subscriber; - px4_sem_t _sem; + struct SubscriptionCallback *_callback_ptr {nullptr}; + px4_sem_t _sem; /* For signaling to the callback thread */ + px4_sem_t _lock; /* For signaling back from the callback thread */ }; private: - void lock() - { - do {} while (px4_sem_wait(&_semLock) != 0); - } + void lock() { do {} while (px4_sem_wait(&_semLock) != 0); } void unlock() { px4_sem_post(&_semLock); } GlobalLock _global_sem[NUM_GLOBAL_SEMS]; From 0e80c6b3dc13df1f693ff1d3c13b011bc45b8952 Mon Sep 17 00:00:00 2001 From: Jari Nippula Date: Tue, 5 Sep 2023 14:44:56 +0300 Subject: [PATCH 029/273] Print error if device name too long --- platforms/common/uORB/uORBDeviceNode.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index eed0df30c110..3c6ebd6e8766 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -259,6 +259,10 @@ orb_advert_t uORB::DeviceNode::nodeOpen(const ORB_ID id, const uint8_t instance, int ret = uORB::Utils::node_mkpath(nodepath, get_orb_meta(id), &inst); bool created = false; + if (ret == -ENAMETOOLONG || strlen(nodepath) > _POSIX_NAME_MAX) { + PX4_ERR("Device node name too long! '%s'", get_orb_meta(id)->o_name); + } + if (ret != OK) { return handle; } From da0d63630b50dd0176619ebe2bba38c7f76fa6e6 Mon Sep 17 00:00:00 2001 From: Jari Nippula Date: Wed, 13 Sep 2023 09:22:19 +0300 Subject: [PATCH 030/273] uorb: _POSIX_NAME_MAX -> NAME_MAX In SITL case the _POSIX_NAME_MAX is only 14, so it fails for every topic. Use NAME_MAX instead to get correct maximum filename value for both posix and nuttx cases. --- platforms/common/uORB/uORBDeviceNode.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/platforms/common/uORB/uORBDeviceNode.cpp b/platforms/common/uORB/uORBDeviceNode.cpp index 3c6ebd6e8766..b6869ef56229 100644 --- a/platforms/common/uORB/uORBDeviceNode.cpp +++ b/platforms/common/uORB/uORBDeviceNode.cpp @@ -259,8 +259,9 @@ orb_advert_t uORB::DeviceNode::nodeOpen(const ORB_ID id, const uint8_t instance, int ret = uORB::Utils::node_mkpath(nodepath, get_orb_meta(id), &inst); bool created = false; - if (ret == -ENAMETOOLONG || strlen(nodepath) > _POSIX_NAME_MAX) { - PX4_ERR("Device node name too long! '%s'", get_orb_meta(id)->o_name); + if (ret == -ENAMETOOLONG || strlen(nodepath) > NAME_MAX) { + PX4_ERR("Device node name too long! '%s' (len: %lu vs. NAME_MAX: %lu)", + get_orb_meta(id)->o_name, ((long unsigned int) strlen(nodepath)), ((long unsigned int) NAME_MAX)); } if (ret != OK) { From 7446b60329b85107e615d0d70c3366e97ce63b5d Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 22 Apr 2022 16:56:40 +0400 Subject: [PATCH 031/273] cdev: remove poll interface Signed-off-by: Jukka Laitinen --- src/lib/cdev/CDev.cpp | 190 ------------------------- src/lib/cdev/CDev.hpp | 64 --------- src/lib/cdev/nuttx/cdev_platform.cpp | 15 +- src/lib/cdev/posix/cdev_platform.cpp | 116 +-------------- src/lib/cdev/test/cdevtest_example.cpp | 101 ------------- 5 files changed, 2 insertions(+), 484 deletions(-) diff --git a/src/lib/cdev/CDev.cpp b/src/lib/cdev/CDev.cpp index c19a028ad4d8..0b90dc845c45 100644 --- a/src/lib/cdev/CDev.cpp +++ b/src/lib/cdev/CDev.cpp @@ -67,10 +67,6 @@ CDev::~CDev() unregister_driver(_devname); } - if (_pollset) { - delete[](_pollset); - } - px4_sem_destroy(&_lock); } @@ -191,190 +187,4 @@ CDev::close(file_t *filep) return ret; } -int -CDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup) -{ - PX4_DEBUG("CDev::Poll %s", setup ? "setup" : "teardown"); - int ret = PX4_OK; - - if (setup) { - /* - * Save the file pointer in the pollfd for the subclass' - * benefit. - */ - fds->priv = (void *)filep; - PX4_DEBUG("CDev::poll: fds->priv = %p", filep); - - /* - * Lock against poll_notify() and possibly other callers (protect _pollset). - */ - ATOMIC_ENTER; - - /* - * Try to store the fds for later use and handle array resizing. - */ - while ((ret = store_poll_waiter(fds)) == -ENFILE) { - - // No free slot found. Resize the pollset. This is expensive, but it's only needed initially. - - if (_max_pollwaiters >= 256 / 2) { //_max_pollwaiters is uint8_t - ret = -ENOMEM; - break; - } - - const uint8_t new_count = _max_pollwaiters > 0 ? _max_pollwaiters * 2 : 1; - px4_pollfd_struct_t **prev_pollset = _pollset; - -#ifdef __PX4_NUTTX - // malloc uses a semaphore, we need to call it enabled IRQ's - px4_leave_critical_section(flags); -#endif - px4_pollfd_struct_t **new_pollset = new px4_pollfd_struct_t *[new_count]; - -#ifdef __PX4_NUTTX - flags = px4_enter_critical_section(); -#endif - - if (prev_pollset == _pollset) { - // no one else updated the _pollset meanwhile, so we're good to go - if (!new_pollset) { - ret = -ENOMEM; - break; - } - - if (_max_pollwaiters > 0) { - memset(new_pollset + _max_pollwaiters, 0, sizeof(px4_pollfd_struct_t *) * (new_count - _max_pollwaiters)); - memcpy(new_pollset, _pollset, sizeof(px4_pollfd_struct_t *) * _max_pollwaiters); - } - - _pollset = new_pollset; - _pollset[_max_pollwaiters] = fds; - _max_pollwaiters = new_count; - - // free the previous _pollset (we need to unlock here which is fine because we don't access _pollset anymore) -#ifdef __PX4_NUTTX - px4_leave_critical_section(flags); -#endif - - if (prev_pollset) { - delete[](prev_pollset); - } - -#ifdef __PX4_NUTTX - flags = px4_enter_critical_section(); -#endif - - // Success - ret = PX4_OK; - break; - } - -#ifdef __PX4_NUTTX - px4_leave_critical_section(flags); -#endif - // We have to retry - delete[] new_pollset; -#ifdef __PX4_NUTTX - flags = px4_enter_critical_section(); -#endif - } - - if (ret == PX4_OK) { - - /* - * Check to see whether we should send a poll notification - * immediately. - */ - fds->revents |= fds->events & poll_state(filep); - - /* yes? post the notification */ - if (fds->revents != 0) { - px4_sem_post((px4_sem_t *)fds->arg); - } - - } - - ATOMIC_LEAVE; - - } else { - ATOMIC_ENTER; - /* - * Handle a teardown request. - */ - ret = remove_poll_waiter(fds); - ATOMIC_LEAVE; - } - - return ret; -} - -void -CDev::poll_notify(px4_pollevent_t events) -{ - PX4_DEBUG("CDev::poll_notify events = %0x", events); - - /* lock against poll() as well as other wakeups */ - ATOMIC_ENTER; - - for (unsigned i = 0; i < _max_pollwaiters; i++) { - if (nullptr != _pollset[i]) { - poll_notify_one(_pollset[i], events); - } - } - - ATOMIC_LEAVE; -} - -void -CDev::poll_notify_one(px4_pollfd_struct_t *fds, px4_pollevent_t events) -{ - PX4_DEBUG("CDev::poll_notify_one"); - - /* update the reported event set */ - fds->revents |= fds->events & events; - - PX4_DEBUG(" Events fds=%p %0x %0x %0x", fds, fds->revents, fds->events, events); - - if (fds->revents != 0) { - px4_sem_post((px4_sem_t *)fds->arg); - } -} - -int -CDev::store_poll_waiter(px4_pollfd_struct_t *fds) -{ - // Look for a free slot. - PX4_DEBUG("CDev::store_poll_waiter"); - - for (unsigned i = 0; i < _max_pollwaiters; i++) { - if (nullptr == _pollset[i]) { - - /* save the pollfd */ - _pollset[i] = fds; - - return PX4_OK; - } - } - - return -ENFILE; -} - -int -CDev::remove_poll_waiter(px4_pollfd_struct_t *fds) -{ - PX4_DEBUG("CDev::remove_poll_waiter"); - - for (unsigned i = 0; i < _max_pollwaiters; i++) { - if (fds == _pollset[i]) { - - _pollset[i] = nullptr; - return PX4_OK; - - } - } - - PX4_DEBUG("poll: bad fd state"); - return -EINVAL; -} - } // namespace cdev diff --git a/src/lib/cdev/CDev.hpp b/src/lib/cdev/CDev.hpp index 071ae618fe97..41818f5fb630 100644 --- a/src/lib/cdev/CDev.hpp +++ b/src/lib/cdev/CDev.hpp @@ -148,19 +148,6 @@ class __EXPORT CDev */ virtual int ioctl(file_t *filep, int cmd, unsigned long arg) { return -ENOTTY; }; - /** - * Perform a poll setup/teardown operation. - * - * This is handled internally and should not normally be overridden. - * - * @param filep Pointer to the internal file structure. - * @param fds Poll descriptor being waited on. - * @param setup True if this is establishing a request, false if - * it is being torn down. - * @return OK on success, or -errno otherwise. - */ - int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup); - /** * Get the device name. * @@ -175,38 +162,6 @@ class __EXPORT CDev */ static const px4_file_operations_t fops; - /** - * Check the current state of the device for poll events from the - * perspective of the file. - * - * This function is called by the default poll() implementation when - * a poll is set up to determine whether the poll should return immediately. - * - * The default implementation returns no events. - * - * @param filep The file that's interested. - * @return The current set of poll events. - */ - virtual px4_pollevent_t poll_state(file_t *filep) { return 0; } - - /** - * Report new poll events. - * - * This function should be called anytime the state of the device changes - * in a fashion that might be interesting to a poll waiter. - * - * @param events The new event(s) being announced. - */ - void poll_notify(px4_pollevent_t events); - - /** - * Internal implementation of poll_notify. - * - * @param fds A poll waiter to notify. - * @param events The event(s) to send to the waiter. - */ - virtual void poll_notify_one(px4_pollfd_struct_t *fds, px4_pollevent_t events); - /** * Notification of the first open. * @@ -273,29 +228,10 @@ class __EXPORT CDev private: const char *_devname{nullptr}; /**< device node name */ - px4_pollfd_struct_t **_pollset{nullptr}; - bool _registered{false}; /**< true if device name was registered */ - uint8_t _max_pollwaiters{0}; /**< size of the _pollset array */ uint16_t _open_count{0}; /**< number of successful opens */ - /** - * Store a pollwaiter in a slot where we can find it later. - * - * Expands the pollset as required. Must be called with the driver locked. - * - * @return OK, or -errno on error. - */ - inline int store_poll_waiter(px4_pollfd_struct_t *fds); - - /** - * Remove a poll waiter. - * - * @return OK, or -errno on error. - */ - inline int remove_poll_waiter(px4_pollfd_struct_t *fds); - }; } // namespace cdev diff --git a/src/lib/cdev/nuttx/cdev_platform.cpp b/src/lib/cdev/nuttx/cdev_platform.cpp index 39de49a55c05..3d0c01e5ae0d 100644 --- a/src/lib/cdev/nuttx/cdev_platform.cpp +++ b/src/lib/cdev/nuttx/cdev_platform.cpp @@ -60,7 +60,6 @@ static ssize_t cdev_read(file_t *filp, char *buffer, size_t buflen); static ssize_t cdev_write(file_t *filp, const char *buffer, size_t buflen); static off_t cdev_seek(file_t *filp, off_t offset, int whence); static int cdev_ioctl(file_t *filp, int cmd, unsigned long arg); -static int cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup); /** * Character device indirection table. @@ -78,7 +77,7 @@ read : cdev_read, write : cdev_write, seek : cdev_seek, ioctl : cdev_ioctl, -poll : cdev_poll, +poll : nullptr, #ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS unlink : nullptr #endif @@ -156,16 +155,4 @@ cdev_ioctl(file_t *filp, int cmd, unsigned long arg) return cdev->ioctl(filp, cmd, arg); } -static int -cdev_poll(file_t *filp, px4_pollfd_struct_t *fds, bool setup) -{ - if ((filp->f_inode->i_flags & FSNODEFLAG_DELETED) != 0) { - return -ENODEV; - } - - cdev::CDev *cdev = (cdev::CDev *)(filp->f_inode->i_private); - - return cdev->poll(filp, fds, setup); -} - } // namespace cdev diff --git a/src/lib/cdev/posix/cdev_platform.cpp b/src/lib/cdev/posix/cdev_platform.cpp index bcf3783fb641..4f17d473e7d7 100644 --- a/src/lib/cdev/posix/cdev_platform.cpp +++ b/src/lib/cdev/posix/cdev_platform.cpp @@ -76,8 +76,7 @@ class VFile : public cdev::CDev ssize_t write(cdev::file_t *handlep, const char *buffer, size_t buflen) override { - // ignore what was written, but let pollers know something was written - poll_notify(POLLIN); + // ignore what was written return buflen; } }; @@ -329,119 +328,6 @@ extern "C" { return ret; } - int px4_poll(px4_pollfd_struct_t *fds, unsigned int nfds, int timeout) - { - if (nfds == 0) { - PX4_WARN("px4_poll with no fds"); - return -1; - } - - px4_sem_t sem; - int count = 0; - int ret = -1; - - const unsigned NAMELEN = 32; - char thread_name[NAMELEN] {}; - -#ifndef __PX4_QURT - int nret = pthread_getname_np(pthread_self(), thread_name, NAMELEN); - - if (nret || thread_name[0] == 0) { - PX4_WARN("failed getting thread name"); - } - -#endif - - PX4_DEBUG("Called px4_poll timeout = %d", timeout); - - px4_sem_init(&sem, 0, 0); - - // sem use case is a signal - px4_sem_setprotocol(&sem, SEM_PRIO_NONE); - - // Go through all fds and check them for a pollable state - bool fd_pollable = false; - - for (unsigned int i = 0; i < nfds; ++i) { - fds[i].arg = &sem; - fds[i].revents = 0; - fds[i].priv = nullptr; - - cdev::CDev *dev = getFile(fds[i].fd); - - // If fd is valid - if (dev) { - PX4_DEBUG("%s: px4_poll: CDev->poll(setup) %d", thread_name, fds[i].fd); - ret = dev->poll(&filemap[fds[i].fd], &fds[i], true); - - if (ret < 0) { - PX4_WARN("%s: px4_poll() error: %s", thread_name, strerror(errno)); - break; - } - - if (ret >= 0) { - fd_pollable = true; - } - } - } - - // If any FD can be polled, lock the semaphore and - // check for new data - if (fd_pollable) { - if (timeout > 0) { - // Get the current time - struct timespec ts; - // Note, we can't actually use CLOCK_MONOTONIC on macOS - // but that's hidden and implemented in px4_clock_gettime. - px4_clock_gettime(CLOCK_MONOTONIC, &ts); - - // Calculate an absolute time in the future - const unsigned billion = (1000 * 1000 * 1000); - uint64_t nsecs = ts.tv_nsec + ((uint64_t)timeout * 1000 * 1000); - ts.tv_sec += nsecs / billion; - nsecs -= (nsecs / billion) * billion; - ts.tv_nsec = nsecs; - - ret = px4_sem_timedwait(&sem, &ts); - - if (ret && errno != ETIMEDOUT) { - PX4_WARN("%s: px4_poll() sem error: %s", thread_name, strerror(errno)); - } - - } else if (timeout < 0) { - px4_sem_wait(&sem); - } - - // We have waited now (or not, depending on timeout), - // go through all fds and count how many have data - for (unsigned int i = 0; i < nfds; ++i) { - - cdev::CDev *dev = getFile(fds[i].fd); - - // If fd is valid - if (dev) { - PX4_DEBUG("%s: px4_poll: CDev->poll(teardown) %d", thread_name, fds[i].fd); - ret = dev->poll(&filemap[fds[i].fd], &fds[i], false); - - if (ret < 0) { - PX4_WARN("%s: px4_poll() 2nd poll fail", thread_name); - break; - } - - if (fds[i].revents) { - count += 1; - } - } - } - } - - px4_sem_destroy(&sem); - - // Return the positive count if present, - // return the negative error number if failed - return (count) ? count : ret; - } - int px4_access(const char *pathname, int mode) { if (mode != F_OK) { diff --git a/src/lib/cdev/test/cdevtest_example.cpp b/src/lib/cdev/test/cdevtest_example.cpp index 48bed08d0b82..9944ff746b4e 100644 --- a/src/lib/cdev/test/cdevtest_example.cpp +++ b/src/lib/cdev/test/cdevtest_example.cpp @@ -162,9 +162,6 @@ ssize_t CDevNode::write(cdev::file_t *handlep, const char *buffer, size_t buflen _write_offset++; } - // ignore what was written, but let pollers know something was written - poll_notify(POLLIN); - return buflen; } @@ -191,59 +188,6 @@ CDevExample::~CDevExample() } } -int CDevExample::do_poll(int fd, int timeout, int iterations, int delayms_after_poll) -{ - int pollret, readret; - int loop_count = 0; - char readbuf[10]; - px4_pollfd_struct_t fds[1]; - - fds[0].fd = fd; - fds[0].events = POLLIN; - fds[0].revents = 0; - - bool mustblock = (timeout < 0); - - // Test indefinte blocking poll - while ((!appState.exitRequested()) && (loop_count < iterations)) { - pollret = px4_poll(fds, 1, timeout); - - if (pollret < 0) { - PX4_ERR("Reader: px4_poll failed %d FAIL", pollret); - goto fail; - } - - PX4_INFO("Reader: px4_poll returned %d", pollret); - - if (pollret) { - readret = px4_read(fd, readbuf, 10); - - if (readret != 1) { - if (mustblock) { - PX4_ERR("Reader: read failed %d FAIL", readret); - goto fail; - - } else { - PX4_INFO("Reader: read failed %d FAIL", readret); - } - - } else { - readbuf[readret] = '\0'; - PX4_INFO("Reader: px4_poll returned %d, read '%s' PASS", pollret, readbuf); - } - } - - if (delayms_after_poll) { - px4_usleep(delayms_after_poll * 1000); - } - - loop_count++; - } - - return 0; -fail: - return 1; -} int CDevExample::main() { appState.setRunning(true); @@ -277,52 +221,7 @@ int CDevExample::main() int ret = 0; - PX4_INFO("TEST: BLOCKING POLL ---------------"); - - if (do_poll(fd, -1, 3, 0)) { - ret = 1; - goto fail2; - } - - PX4_INFO("TEST: ZERO TIMEOUT POLL -----------"); - - if (do_poll(fd, 0, 3, 0)) { - ret = 1; - goto fail2; - goto fail2; - } - - PX4_INFO("TEST: ZERO TIMEOUT POLL -----------"); - - if (do_poll(fd, 0, 3, 0)) { - ret = 1; - goto fail2; - goto fail2; - } - - PX4_INFO("TEST: ZERO TIMEOUT POLL -----------"); - - if (do_poll(fd, 0, 3, 0)) { - ret = 1; - goto fail2; - } - - PX4_INFO("TEST: 100ms TIMEOUT POLL -----------"); - - if (do_poll(fd, 0, 30, 100)) { - ret = 1; - goto fail2; - } - - PX4_INFO("TEST: 1 SEC TIMOUT POLL ------------"); - - if (do_poll(fd, 1000, 3, 0)) { - ret = 1; - goto fail2; - } - PX4_INFO("TEST: waiting for writer to stop"); -fail2: g_exit = true; px4_close(fd); PX4_INFO("TEST: waiting for writer to stop"); From 0b603183c025282a36f5d9f01639af98d99eee63 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 22 Apr 2022 16:40:13 +0400 Subject: [PATCH 032/273] src/systemcmds/topic_listener: Change topic listener to poll only on uorb Polling uorb is different than polling stdin due to non-file nature of uorb now Signed-off-by: Jukka Laitinen --- .../topic_listener/listener_main.cpp | 53 +++++++++---------- .../topic_listener/topic_listener.hpp | 2 +- 2 files changed, 26 insertions(+), 29 deletions(-) diff --git a/src/systemcmds/topic_listener/listener_main.cpp b/src/systemcmds/topic_listener/listener_main.cpp index b4db038c1254..4534406fa6f9 100644 --- a/src/systemcmds/topic_listener/listener_main.cpp +++ b/src/systemcmds/topic_listener/listener_main.cpp @@ -39,6 +39,7 @@ #include #include +#include #include @@ -68,7 +69,7 @@ void listener(const orb_id_t &id, unsigned num_msgs, int topic_instance, if (instances == 1) { PX4_INFO_RAW("\nTOPIC: %s\n", id->o_name); - int sub = orb_subscribe(id); + orb_sub_t sub = orb_subscribe(id); listener_print_topic(id, sub); orb_unsubscribe(sub); @@ -78,7 +79,7 @@ void listener(const orb_id_t &id, unsigned num_msgs, int topic_instance, for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { if (orb_exists(id, i) == PX4_OK) { PX4_INFO_RAW("\nInstance %d:\n", i); - int sub = orb_subscribe_multi(id, i); + orb_sub_t sub = orb_subscribe_multi(id, i); listener_print_topic(id, sub); orb_unsubscribe(sub); } @@ -100,55 +101,51 @@ void listener(const orb_id_t &id, unsigned num_msgs, int topic_instance, return; } - int sub = orb_subscribe_multi(id, topic_instance); + orb_sub_t sub = orb_subscribe_multi(id, topic_instance); orb_set_interval(sub, topic_interval); unsigned msgs_received = 0; - struct pollfd fds[2] {}; - // Poll for user input (for q or escape) - fds[0].fd = 0; /* stdin */ - fds[0].events = POLLIN; + px4_pollfd_struct_t fds[1] {}; // Poll the UOrb subscription - fds[1].fd = sub; - fds[1].events = POLLIN; + fds[0].fd = sub; + fds[0].events = POLLIN; - while (msgs_received < num_msgs) { + int time = 0; - if (poll(&fds[0], 2, int(MESSAGE_TIMEOUT_S * 1000)) > 0) { + while (msgs_received < num_msgs) { - // Received character from stdin - if (fds[0].revents & POLLIN) { - char c = 0; - int ret = read(0, &c, 1); + char c = 0; + int ret = read(0, &c, 1); - if (ret) { - return; - } + if (ret) { - switch (c) { - case 0x03: // ctrl-c - case 0x1b: // esc - case 'q': - return; - /* not reached */ - } + switch (c) { + case 0x03: // ctrl-c + case 0x1b: // esc + case 'q': + return; + /* not reached */ } + } + if (px4_poll(&fds[0], 1, 50) > 0) { // Received message from subscription - if (fds[1].revents & POLLIN) { + + if (fds[0].revents & POLLIN) { msgs_received++; PX4_INFO_RAW("\nTOPIC: %s instance %d #%d\n", id->o_name, topic_instance, msgs_received); - int ret = listener_print_topic(id, sub); + ret = listener_print_topic(id, sub); if (ret != PX4_OK) { PX4_ERR("listener callback failed (%i)", ret); } } + } - } else { + if (time += 50 > MESSAGE_TIMEOUT_S * 1000) { PX4_INFO_RAW("Waited for %.1f seconds without a message. Giving up.\n", (double) MESSAGE_TIMEOUT_S); break; } diff --git a/src/systemcmds/topic_listener/topic_listener.hpp b/src/systemcmds/topic_listener/topic_listener.hpp index 1131f4276fea..dda3816501b4 100644 --- a/src/systemcmds/topic_listener/topic_listener.hpp +++ b/src/systemcmds/topic_listener/topic_listener.hpp @@ -50,7 +50,7 @@ #include #include -inline int listener_print_topic(const orb_id_t &orb_id, int subscription) +inline int listener_print_topic(const orb_id_t &orb_id, orb_sub_t subscription) { static constexpr int max_size = 512; alignas(8) char container[max_size]; From 5105bd046ee0055168cd96c363625d13cbd64363 Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 15 Mar 2023 12:14:23 +0200 Subject: [PATCH 033/273] platforms/xx: Fix some simple dependencies - uORB depends on uorb_msgs (get_orb_meta) - px4_platform_init() should not call param_init, if param module is disabled - px4_protected_layers re-organize the link_library commands into one - reboot does not need to explicitly add px4_platform, it gets it anyway --- platforms/common/uORB/CMakeLists.txt | 1 + platforms/nuttx/src/px4/common/px4_init.cpp | 2 ++ .../src/px4/common/px4_protected_layers.cmake | 15 +++++---------- src/systemcmds/reboot/CMakeLists.txt | 2 -- 4 files changed, 8 insertions(+), 12 deletions(-) diff --git a/platforms/common/uORB/CMakeLists.txt b/platforms/common/uORB/CMakeLists.txt index 36378b61268e..b044acb9ae7c 100644 --- a/platforms/common/uORB/CMakeLists.txt +++ b/platforms/common/uORB/CMakeLists.txt @@ -60,6 +60,7 @@ if ("${PX4_PLATFORM}" MATCHES "posix") endif() target_compile_options(uORB PRIVATE ${MAX_CUSTOM_OPT_LEVEL}) +target_link_libraries(uORB PRIVATE uorb_msgs) if(PX4_TESTING) add_subdirectory(uORB_tests) diff --git a/platforms/nuttx/src/px4/common/px4_init.cpp b/platforms/nuttx/src/px4/common/px4_init.cpp index fb371b9093a9..2885203bcb9e 100644 --- a/platforms/nuttx/src/px4/common/px4_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_init.cpp @@ -127,7 +127,9 @@ int px4_platform_init() hrt_ioctl_init(); #endif +#ifdef CONFIG_SYSTEMCMDS_PARAM param_init(); +#endif /* configure CPU load estimation */ #ifdef CONFIG_SCHED_INSTRUMENTATION diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index c7a9b56ce064..634f5b726543 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -19,6 +19,8 @@ add_library(px4_layer ) target_link_libraries(px4_layer + PUBLIC + board_bus_info PRIVATE m nuttx_c @@ -36,11 +38,6 @@ add_library(px4_board_ctrl add_dependencies(px4_board_ctrl nuttx_context px4_kernel_builtin_list_target) target_compile_options(px4_board_ctrl PRIVATE -D__KERNEL__) -target_link_libraries(px4_layer - PUBLIC - board_bus_info -) - # Build the kernel side px4_kernel_layer add_library(px4_kernel_layer @@ -48,6 +45,9 @@ add_library(px4_kernel_layer ) target_link_libraries(px4_kernel_layer + PUBLIC + px4_board_ctrl + board_bus_info PRIVATE ${KERNEL_LIBS} nuttx_kc @@ -55,11 +55,6 @@ target_link_libraries(px4_kernel_layer nuttx_kmm ) -target_link_libraries(px4_kernel_layer - PUBLIC - board_bus_info -) - if (DEFINED PX4_CRYPTO) target_link_libraries(px4_kernel_layer PUBLIC crypto_backend) target_link_libraries(px4_layer PUBLIC crypto_backend_interface) diff --git a/src/systemcmds/reboot/CMakeLists.txt b/src/systemcmds/reboot/CMakeLists.txt index 60f4cee88951..ecc7b64870a2 100644 --- a/src/systemcmds/reboot/CMakeLists.txt +++ b/src/systemcmds/reboot/CMakeLists.txt @@ -36,7 +36,5 @@ px4_add_module( COMPILE_FLAGS SRCS reboot.cpp - DEPENDS - px4_platform ) From 22a2705b8d0541e3044f613d2cc41cf64244978c Mon Sep 17 00:00:00 2001 From: Ville Juven Date: Wed, 23 Aug 2023 13:17:18 +0300 Subject: [PATCH 034/273] platforms/nuttx: nuttx_drivers needs nuttx_mm on link interface Fixes build error: arm-none-eabi/bin/ld: NuttX/nuttx/drivers/libdrivers.a(pipe_common.o): in function `pipecommon_close': nuttx/drivers/pipes/pipe_common.c:381: undefined reference to `circbuf_uninit' --- platforms/nuttx/CMakeLists.txt | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/platforms/nuttx/CMakeLists.txt b/platforms/nuttx/CMakeLists.txt index 3926f237336b..7a371e7275ec 100644 --- a/platforms/nuttx/CMakeLists.txt +++ b/platforms/nuttx/CMakeLists.txt @@ -242,8 +242,6 @@ if (NOT CONFIG_BUILD_FLAT) else() - target_link_libraries(nuttx_c INTERFACE nuttx_sched) # nxsched_get_streams - target_link_libraries(nuttx_arch INTERFACE drivers_board @@ -251,8 +249,9 @@ else() arch_board_reset ) + target_link_libraries(nuttx_c INTERFACE nuttx_sched) target_link_libraries(nuttx_c INTERFACE nuttx_drivers) - target_link_libraries(nuttx_drivers INTERFACE nuttx_c) + target_link_libraries(nuttx_drivers INTERFACE nuttx_c nuttx_fs nuttx_mm) target_link_libraries(nuttx_xx INTERFACE nuttx_c) target_link_libraries(nuttx_fs INTERFACE nuttx_c) From cea57332e04ea01cf9ae125509dec5e71cc936f8 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 15 Sep 2023 10:16:20 +0300 Subject: [PATCH 035/273] Add boards/ssrc targets as submodules Signed-off-by: Jukka Laitinen --- .gitmodules | 12 ++++++++++++ boards/ssrc/saluki-pi | 1 + boards/ssrc/saluki-v1 | 1 + boards/ssrc/saluki-v2 | 1 + boards/ssrc/saluki-v3 | 1 + 5 files changed, 16 insertions(+) create mode 160000 boards/ssrc/saluki-pi create mode 160000 boards/ssrc/saluki-v1 create mode 160000 boards/ssrc/saluki-v2 create mode 160000 boards/ssrc/saluki-v3 diff --git a/.gitmodules b/.gitmodules index e353c5fd8c17..82e6c77faadb 100644 --- a/.gitmodules +++ b/.gitmodules @@ -62,3 +62,15 @@ path = src/modules/uxrce_dds_client/Micro-XRCE-DDS-Client url = https://github.com/PX4/Micro-XRCE-DDS-Client.git branch = px4 +[submodule "boards/ssrc/saluki-v1"] + path = boards/ssrc/saluki-v1 + url = ../saluki-v1.git +[submodule "boards/ssrc/saluki-v2"] + path = boards/ssrc/saluki-v2 + url = ../saluki-v2.git +[submodule "boards/ssrc/saluki-pi"] + path = boards/ssrc/saluki-pi + url = ../saluki-pi.git +[submodule "boards/ssrc/saluki-v3"] + path = boards/ssrc/saluki-v3 + url = ../saluki-v3.git diff --git a/boards/ssrc/saluki-pi b/boards/ssrc/saluki-pi new file mode 160000 index 000000000000..be40fdde59b8 --- /dev/null +++ b/boards/ssrc/saluki-pi @@ -0,0 +1 @@ +Subproject commit be40fdde59b86f7119fbf068ee35790bfa252a61 diff --git a/boards/ssrc/saluki-v1 b/boards/ssrc/saluki-v1 new file mode 160000 index 000000000000..7fc117c24336 --- /dev/null +++ b/boards/ssrc/saluki-v1 @@ -0,0 +1 @@ +Subproject commit 7fc117c243366836809c573ccadd326c749308ab diff --git a/boards/ssrc/saluki-v2 b/boards/ssrc/saluki-v2 new file mode 160000 index 000000000000..6e5545d6cb62 --- /dev/null +++ b/boards/ssrc/saluki-v2 @@ -0,0 +1 @@ +Subproject commit 6e5545d6cb623d832eb1ec397566780dc41590fe diff --git a/boards/ssrc/saluki-v3 b/boards/ssrc/saluki-v3 new file mode 160000 index 000000000000..774547eb859d --- /dev/null +++ b/boards/ssrc/saluki-v3 @@ -0,0 +1 @@ +Subproject commit 774547eb859d3b4bec55dff01fdff79e640aff26 From 90ad141f3a80f91c1f2afe5747cae85906f8fd1a Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 15 Sep 2023 13:04:19 +0300 Subject: [PATCH 036/273] Add boards/ssrc/icicle target for building for icicle board Signed-off-by: Jukka Laitinen --- boards/ssrc/icicle/bootloader.px4board | 7 + boards/ssrc/icicle/bootloader_readme.txt | 13 + boards/ssrc/icicle/default.px4board | 87 +++ boards/ssrc/icicle/firmware.prototype | 13 + .../icicle/MPFS_ICICLE_KIT_BASE_DESIGN.job | Bin 0 -> 12119970 bytes .../MPFS_ICICLE_KIT_BASE_DESIGN_job.digest | 5 + boards/ssrc/icicle/fpga/icicle/README.md | 1 + boards/ssrc/icicle/include/board_type.h | 16 + boards/ssrc/icicle/init/rc.board_defaults | 15 + boards/ssrc/icicle/init/rc.board_mavlink | 4 + boards/ssrc/icicle/init/rc.board_paths | 1 + boards/ssrc/icicle/init/rc.board_sensors | 24 + boards/ssrc/icicle/nuttx-config/Kconfig | 4 + .../icicle/nuttx-config/bootloader/defconfig | 96 +++ .../ssrc/icicle/nuttx-config/include/board.h | 113 ++++ .../nuttx-config/include/board_liberodefs.h | 618 ++++++++++++++++++ .../nuttx-config/include/board_memorymap.h | 108 +++ boards/ssrc/icicle/nuttx-config/nsh/defconfig | 181 +++++ .../nuttx-config/scripts/bootloader_script.ld | 168 +++++ .../icicle/nuttx-config/scripts/script.ld | 125 ++++ .../ssrc/icicle/nuttx-config/scripts/toc.ld | 62 ++ boards/ssrc/icicle/src/CMakeLists.txt | 101 +++ boards/ssrc/icicle/src/board_config.h | 160 +++++ boards/ssrc/icicle/src/bootloader_main.c | 144 ++++ boards/ssrc/icicle/src/hw_config.h | 133 ++++ boards/ssrc/icicle/src/i2c.cpp | 39 ++ boards/ssrc/icicle/src/init.c | 334 ++++++++++ boards/ssrc/icicle/src/init_entrypt.c | 72 ++ boards/ssrc/icicle/src/led.c | 101 +++ boards/ssrc/icicle/src/manifest.c | 144 ++++ boards/ssrc/icicle/src/mpfs_composite.c | 305 +++++++++ boards/ssrc/icicle/src/mpfs_domain.c | 190 ++++++ boards/ssrc/icicle/src/mpfs_emmcsd.c | 117 ++++ boards/ssrc/icicle/src/mpfs_ihc.c | 75 +++ boards/ssrc/icicle/src/mpfs_pwm.c | 102 +++ boards/ssrc/icicle/src/mpfs_spinor.c | 131 ++++ boards/ssrc/icicle/src/mpfs_userspace.c | 113 ++++ boards/ssrc/icicle/src/mtd.cpp | 75 +++ boards/ssrc/icicle/src/spi.cpp | 59 ++ boards/ssrc/icicle/src/spi_drv.cpp | 118 ++++ boards/ssrc/icicle/src/toc.c | 99 +++ 41 files changed, 4273 insertions(+) create mode 100644 boards/ssrc/icicle/bootloader.px4board create mode 100644 boards/ssrc/icicle/bootloader_readme.txt create mode 100644 boards/ssrc/icicle/default.px4board create mode 100644 boards/ssrc/icicle/firmware.prototype create mode 100644 boards/ssrc/icicle/fpga/icicle/MPFS_ICICLE_KIT_BASE_DESIGN.job create mode 100644 boards/ssrc/icicle/fpga/icicle/MPFS_ICICLE_KIT_BASE_DESIGN_job.digest create mode 100644 boards/ssrc/icicle/fpga/icicle/README.md create mode 100644 boards/ssrc/icicle/include/board_type.h create mode 100644 boards/ssrc/icicle/init/rc.board_defaults create mode 100644 boards/ssrc/icicle/init/rc.board_mavlink create mode 100644 boards/ssrc/icicle/init/rc.board_paths create mode 100644 boards/ssrc/icicle/init/rc.board_sensors create mode 100644 boards/ssrc/icicle/nuttx-config/Kconfig create mode 100644 boards/ssrc/icicle/nuttx-config/bootloader/defconfig create mode 100644 boards/ssrc/icicle/nuttx-config/include/board.h create mode 100644 boards/ssrc/icicle/nuttx-config/include/board_liberodefs.h create mode 100644 boards/ssrc/icicle/nuttx-config/include/board_memorymap.h create mode 100644 boards/ssrc/icicle/nuttx-config/nsh/defconfig create mode 100644 boards/ssrc/icicle/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/ssrc/icicle/nuttx-config/scripts/script.ld create mode 100644 boards/ssrc/icicle/nuttx-config/scripts/toc.ld create mode 100644 boards/ssrc/icicle/src/CMakeLists.txt create mode 100644 boards/ssrc/icicle/src/board_config.h create mode 100644 boards/ssrc/icicle/src/bootloader_main.c create mode 100644 boards/ssrc/icicle/src/hw_config.h create mode 100644 boards/ssrc/icicle/src/i2c.cpp create mode 100644 boards/ssrc/icicle/src/init.c create mode 100644 boards/ssrc/icicle/src/init_entrypt.c create mode 100644 boards/ssrc/icicle/src/led.c create mode 100644 boards/ssrc/icicle/src/manifest.c create mode 100644 boards/ssrc/icicle/src/mpfs_composite.c create mode 100644 boards/ssrc/icicle/src/mpfs_domain.c create mode 100644 boards/ssrc/icicle/src/mpfs_emmcsd.c create mode 100644 boards/ssrc/icicle/src/mpfs_ihc.c create mode 100644 boards/ssrc/icicle/src/mpfs_pwm.c create mode 100644 boards/ssrc/icicle/src/mpfs_spinor.c create mode 100755 boards/ssrc/icicle/src/mpfs_userspace.c create mode 100644 boards/ssrc/icicle/src/mtd.cpp create mode 100644 boards/ssrc/icicle/src/spi.cpp create mode 100644 boards/ssrc/icicle/src/spi_drv.cpp create mode 100644 boards/ssrc/icicle/src/toc.c diff --git a/boards/ssrc/icicle/bootloader.px4board b/boards/ssrc/icicle/bootloader.px4board new file mode 100644 index 000000000000..36034e3299d2 --- /dev/null +++ b/boards/ssrc/icicle/bootloader.px4board @@ -0,0 +1,7 @@ +CONFIG_BOARD_TOOLCHAIN="riscv64-unknown-elf" +CONFIG_BOARD_ARCHITECTURE="rv64gc" +CONFIG_BOARD_ROMFSROOT="" +CONFIG_BOARD_CRYPTO=y +CONFIG_DRIVERS_SW_CRYPTO=y +CONFIG_DRIVERS_STUB_KEYSTORE=y +CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub" diff --git a/boards/ssrc/icicle/bootloader_readme.txt b/boards/ssrc/icicle/bootloader_readme.txt new file mode 100644 index 000000000000..ebfd0d3dadb5 --- /dev/null +++ b/boards/ssrc/icicle/bootloader_readme.txt @@ -0,0 +1,13 @@ +1. build icicle bootloader: + +- Set PATH to point to a working riscv64-unknown-elf-gcc +- $ make ssrc_icicle_bootloader + +2. flash the icicle bootloader to eNVM + + + +$ cp /build/ssrc_icicle_bootloader/ssrc_icicle_bootloader.elf . +$ sudo SC_INSTALL_DIR= FPGENPROG=/Libero/bin64/fpgenprog java -jar $SC_INSTALL_DIR/extras/mpfs/mpfsBootmodeProgrammer.jar --bootmode 1 ssrc_icicle_bootloader.elf + +3. use px_uploader.py to flash the px4 binary diff --git a/boards/ssrc/icicle/default.px4board b/boards/ssrc/icicle/default.px4board new file mode 100644 index 000000000000..42c677fa5f31 --- /dev/null +++ b/boards/ssrc/icicle/default.px4board @@ -0,0 +1,87 @@ +CONFIG_BOARD_TOOLCHAIN="riscv64-unknown-elf" +CONFIG_BOARD_ARCHITECTURE="rv64gc" +CONFIG_BOARD_CRYPTO=y +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS2" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_DRIVERS_SW_CRYPTO=y +CONFIG_DRIVERS_STUB_KEYSTORE=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PWM_ESC=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y + +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL_L1=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_MICRODDS_CLIENT=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y +CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/key0.pub" +CONFIG_PUBLIC_KEY2="../../../Tools/test_keys/rsa2048.pub" diff --git a/boards/ssrc/icicle/firmware.prototype b/boards/ssrc/icicle/firmware.prototype new file mode 100644 index 000000000000..c370b014daf3 --- /dev/null +++ b/boards/ssrc/icicle/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1500, + "magic": "Icicle", + "description": "Firmware for the Icicle board", + "image": "", + "build_time": 0, + "summary": "SSRC/Icicle", + "version": "0.1", + "image_size": 0, + "image_maxsize": 5242880, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ssrc/icicle/fpga/icicle/MPFS_ICICLE_KIT_BASE_DESIGN.job b/boards/ssrc/icicle/fpga/icicle/MPFS_ICICLE_KIT_BASE_DESIGN.job new file mode 100644 index 0000000000000000000000000000000000000000..80f45aacebd09c30dc0fe7dc4cc43a53ba6ccaaa GIT binary patch literal 12119970 zcmd42V~{OD!=>9i-F@1&ZQHhO+qP}nwr$(C?bCMm?Qgz`iFxlt%%A(`?ug2@SFL=q zvNED}Rb}LsmJ?Cb6&Dm2loHmJ6j#y};8zsZ6%tky7nPy0ur>J0KtuOe+SUe7#?}Q7 zj~2oeAQ z062iAuf8I)Ez1k&uLJ(wAb&RvaXDQTVFg8TSsBJ9MgV~StbNan>>>gO03gx?0Py#> zwwbZMk+B1fo3+)owx#Vs2g(;E@-F8P%xwH5d{9%MjJdqvCZhr|CFtS_3(*#lQ_1P7 z?kOmY_yluJ%S`AZETfwzspUuWRbDdm+u_Rwx2Gxp+3Sulu=gT{>6GTHs1T|;;A^*c_dnVZkyRV?6J{}nOh%3^sXIvLLs z=1^lMjb386ynC&r()m&2zA)4&^1wQ z?~Lz!hjy&AO!Y>?!w^mM;n#35H?>i(tuiJ3dovmh}h@9N$ zdPG@ku&Y1yush>S#wTp)8&PeaAu+2^ZfUD^D0{?h2(Da_fQRRA>lih)M*IIT?luQX z;?x~uiW^%+?YnEby+*FK+I8YI*?FB-@eM#5PFDKGe)MI;x~qLKgs*ud`Y`=uJoM}$ zhaZMI)qCV)a(ZB+?dIMH^61INH$L}vujBfEJx;>zW!e=MM23ESBFTb=2*hC+>e##oWjB-o?4+M${+Ld%B`T z$#f09Z>{s$@KE*|&RQ_qLy8cJqQsf)WXxrJNEqxum-{}?Z^rT{G+xg&YkGUXc zwYA27G{h(uDJ_7m&Ez2fj~eNraI}5CcC!|96)AE^r2}v8cW1g&KWR4t6yrQUC*L~1 z)vRx{J)e#(O!aR@MBi>2)$(zopR;Tm&Fts<>+oBwk;@@?zUk^Igf@>nH}D5$kN00K zo!^08{2E<*v5Ju>)fB5zkM&7Q_W9IZ$`z|=+UueT=H1fR-AJA=q0Cj#KFDgGq0Y5&@9vpWb{D0n))H zUfZ+lFDVNELiIu)%jKd@1@_R&Bwc6#!mG za!Od&>xW7ADv+MXuaDs&mgHp)1<{9?+zJmNJK%xa+}Ju7NlDpYn#T`&a`-`nr9}qd zFDqd?x(`n-rWz+&;CbF20HQDw%BH?rJRh)}rJ{C0rxm3B#yXIj)%kQl3P!2YzS@2~ z-N*0n8I?gOC|_rf`m4rnG=`Zmb7r7Ngj}lgW<(3qWzHN;Q-``MXDz>bjmQfoMKscO z4THr=gdGO%5y-zEkBcR^@(7NDd?KDo|@?pWF7v}Rcm~|X`qFhvLK^{-^MBF z5#h}K7CAHj_3gLNQ_BM#1foVmG3&46!wdo4pre`#(f4P8f^5=P%Yz;Svi^+*|5xO% z?+*h7>GVqh4+3GMp`7*A@qvYaa{N;NGy0_<2Z6MIqk%d;)DX~)-zZq$pXQhP?}+<1 z`aKqG2&l(z6sYfy0|oi`+aTB=(Ep5ZLqOkuqfmW+p5N$~f*l0%{-u7q@!ydj6B-5| z1{5qFbO?CdpFt3@z z7z>XlF5a19AK;F^yXqm*-tRR}r}Ax>jn7N2cJR~SH!fRM^Pz|Nr721Nn?8>HAM{hf z2<-^qL7+$X0qWs@;YfG?g#(D`h4~?cfQuP~`7!;9QJA07ub71SIsJ-Rm|xPbScLgC z{fbqX-_ozxg!w)Girp_43NGgG%l(SeFZU}hzud35{c^wJ@yq>+*Dv=gKEK?r`2BKW z;9>#4+^+=va=#Mt%l%5&FZU}Ezg$?EPLx`*=vjTUXt(0Hy&|nl)vUk1dRZEpUQI%x zq)4krpM>5@x}YNybU%qm~&z)N2F01)e#T(wHc;y@*JaklR$w zoI&l-{f}jf;=H6q^xqK6kCrNrlQ(Xb;@dQoFv$CvVkM%J*u$fe;*4Yn1b_Qg(XOa( zj(&HXJuyO9*yAOqF^m8f4~ATjG_O08?DyMY83?h9NLWxCwv@Mqh*TzcP2$Z`5bY^t zl7c9j2c6%up~9&Xa8N@xJ_%g-jB~d_AHF;^B1#`k$(K0Ao@7^l;uh_#b0l{vi!w=c zEt6n0#xV||5F{HJ4B}8p(g?uCi9>vEMD%h3zgGU&CJphi6VuBn{95H-n>@tl{%Z|> zt@^J`8RBdIwGO{l``4!avc%4Lp9vgtKH}J9y+trdx(Z+uwB^9ZsZ0L%k{AEqV|4sO zHU6-INpN&%V!ZO*qn$4jmvhs8Q3?L6f1O(%Z?5giO5q(*-}Y5_vkS*Qfu5@y3bC=u z8kC7`3c~bdlI3{H9m*mgPSLiHnnfVz7`Ds3{YYye=8+}uK(9VC{Ew3#yz^-CZImDQpzeJGUD*s=1PYl?XwN!~U1Xzt!if;AV ztIwpLD$YfQ(}OSyCKZvV-`277iz8n2nBd!&kf?e19l1Y<< z11}{b%*6vMEe9%8e&#(2mKPrDCW#t6DCZI9%-1BDT*oiUEAv_&`}8Q8S4FKT5nBe) z5V9zXx93lmN&k*G!~(t2iFo(UW1^{h^}!}$FL);-xWd}_)7s~JOpYI2s~@9*r>;t0uT38wurIa7-c zv}e~~=RpuJhM?o`6BAdQ9Ulv=^&4NH_--*y054Moy}#-iq5XM6Hm z`q$oXjj}1IqioQbi@=(z(>`@5ICB(eckYLsRShrqe5#d#K#itK=yd~3w)xP#I!5@| zdgAG-Ss5e|z{W(jN=k6Zt2l^#lnM1}a5ueit^u%EthT82hv#6X$>k&Fqu{>S&*0mUR@$V*jq1}+*U2-?kGwl#{7`p&99TjFr~TRl z5@cwjc5U0U1$TXYA@A9*Fl`BzhU4phh0=gMMv`4?25%Y;lo$}XeXW)8m$W+r{v$tg z6yL3#W4zBE)jccCAD@IbMJhZ71H$LnG{8MP1N^gHfUQ=#PS!>KpOa z?7ofsnXMc@S!#%(MPZ8--T39cVka^RD+*x!32s}VRB6_#1(9YF@~>NP*e=J~*662w z87=;`%KgN&C(f|N7h3{uLNV7EHG^G7$EXv*8cu4_4LU6dn`zygU55`gG-%PKLrETUHQn4#G#}V*MS`8IE}PvdqJr4=d$2U)fAX9z6TEq+h^1SuyGQg|38$#4YGLJG(nDWyBdN6H{55TjOP0 zGmWS4sMakKr1MKmL>JHrBZLPa_Je6hvUCddCSOaGm~OHXBqM0fwQ~yNLRwCRyf{ir zlCMLysV4{Y8n#l)IqKVdDCUiniya*|* z7|kKqZ=-RAoQ^vsQJ|u3r``SpO^>O6?CxB}_St;j2ey_p+M&=C&h}taWzKAzDCMrt z>}H*D=~1H4+4j#YT3=#WqIoZBC|Rb)NNy7w^q+S3wr-YD=QOzF&st?ss8S0!IUSlhoXh$!HWRMp3i>1f6lXeqs?y3G8Ax^hS0Da* z$4b~h?J4M4QeJ^nBd%8c9^sw5H+%7=p8SJ@;){Y<6H$H;;jJtzh5Y?d(S@6PJ)AkY zlP;Od%i@BD^Jre4F+^R_UD3hN^T*dkT9|m<+WJ5YHM+<_mun5tu|-O3s(EmAt5%EO z;OKSV;Lu?sV(m7pWIIk*K~vYhn2p@RqOx`%S0{Lpl=8y%02F(HSaV&|6*Vk{M}1it zwN^TSt&1S~YA&eq)2>B%C|fkrlmf#ymN6ZscFO7l&RdLYg9-cQ3)ryDr|_y3QDhun zlPvxO)@0Q4?C1YA+Ysc=cmFZn2EfoC3`}6Yh=J=)iGsXMU zu3!u4x<02-@#*-Ki@U2c4PYyiOx@$0b?Ux5 zZTs9sIGPIqe=J+h-kp0M((+v3%P@p9f!@^1TdyC3YKWfky(n$G(|DR~Uq{vOBil>D zEr$0e?{9?RYR&9{vT2;umcd+3A>(boCen@!3_j%kBz%}ebbuJExv%w?Ey_!8>*wv| z%hSiZ_g9aPZg1`G>Q6nbPcsa`p$RF=c($%xo!9xb8qkYoh4^4+X?DVsxIZ1 z@VsD1<4kQi%ZNMDbK%;Tw4>@xZBioZ=gN5~n6Kx~^G>&eZ=!e9X=x|Rh2AM6OfDCi zDX)|@nCYxN$t4f24o9fs^Qv9T4QbZ{=Er$tz}MUn?b$NZu#2o$j!GqzkHy${ydJL* zpZpo3&Id@!a^iyibmOOy0TRj!VZKq%$LxH;$kQUiCz<@?GThP%!wNpAf6=~RfqHtD zs)+Kvn@@dnq$>V^_7X-c<%Amw9PYMI3J=%;pVpiA7w&sTZ};=cPo;nFpP&DE-v2!e zwY}dDyx*mquRqW4cbRg&#Iv_bZ)0bo1D^;!JmjyH9laTE=Hs(`wZvb3Bd3#}3%Rg1 zULNeYr&blA?hl_ax8Yt6dx}AVT$vu9`-4!9i@CWtT^FW8JaYHzW(@!cbyMw8eosWg*ZvY=5 z=>z5@4t<5O|E#oL`Lwu4!yEi28gnmd~(_IpkIfkKd6`BvVWQ# zet)3}Z~HuZs9ZpO!(ziq*LT-el8{IUa^PI0ydqmeVlk% z6$}*N@@Pqsa(a`+E)XC|FvMJUFI|GM6sgLe{8I$O=lIQL zyu=cQH=~z9Ar5tuA|;0$_l+@JA-%Pp#v$iPxN=5O+_=MCPkgv3WX#?U%3?KBJ7)%K zlmh{2R}=i8X>RP@PHC!k=41DHO{IBDL^rVg6Bx`$O5WM-smFbHe0hAxaptP!li`?a z32gT6+Hh}fB`oKp#TIK-Q}sH@b@LC5X^j&)`&>f5sg3D!L~ULjKl<T-7fE((r@Wik?V@pvA_yO@)1o18 zB?a2XngIWRj54sJOaa%I1GB4zFfcwn5Ku$(L|*`gFg?Slh%I1)r6J-9Rkmpsz%9Hp zi>L%T{uK}9_uRP{zqYpiTDB(6`PduwZ+7M9Gqwfw1F4dola+)aU?(&xEqAYX*r_u9 zX02n{-X}8(a62W)j8D-%fio3neItrlsvbpp!c&SFzj=v%Xg}M+Q3MD)1tU|uQY$x$ zv|HH6cx6#78-E57zyOKR{W@5-;2(_`Y6K_oa_cN!dg(+?eSdr*pNLso_xSje_`Iyu zxOAEA!4tcblR7j+>vcFV_|siAJ<2F&v@kP(pg~}MRGqeo-HvMD=iF%6)lJzR{(U1z zh5p!GH1$c_^AQ)o<6V;>b~9qv_AQ72x*{JOP9||SKL0?>2!uv1wGiZJyZ?D^7{G!2 zY+-jggj7N-t*`TF6eob4~fxzqpUA7|S!0H_y-P#?g zZ4Mv2mp(e4a~^|tcAQ@|hGVR~$FfbV^Xv<=9;N-1qXa5MM*sGqRA?#oK;1q4@hApL zZONfo8sH2N2@&a~g%g(eTWa^z2@qQ3M~Ewyv6{o)W<9@g4|EOWrawNn6HdE88j1WC(yB1-OGf(MVO-9&#GLqNjunl=n!P$I%Oe(dA1 zp?*%o!V93vpeUrCtM_orm14j_usmAP?nMPE>OCdlOsAnZwAnp`w?nllrCu>VTLG5z z`6%(vVuDYO)~e~#Pf+cUCJXgC$aqymNB$$yhwL-5)~%B2fPeF9FfVpYJme|?5>X=7 z7<#4EK-HdZw91*Pg=+wy$Wap2yK$k?$JrV2TKL6wr^FF5wM zu}euvomv`!+KoE<$FY_MQO!iS5hCH*0vg?=r0z%F@m;FyH~;PSDmZYeJyJ$_rB#w# z@EMWB&Gbm{8ifzAtNwWMN{q&qAX0m&=5ryHqdVJ+6&d#o)tPb(Ed zw*zwHq=_m@@RVFn#FlToQ?`QJ5L!zi?ojIrz=B27cNLBrv||t}9%8Z%QF(7b&wq?E zp2NJUEYwpvBjwurvb@{@HR|}c3SMVTg25^fuNd%;Sm@;o9Xgb|oyeP18pmZL3 zVt}_)E#?UN3qaw}{#={J;7A`xVNB0}khxD~APqoLFF}+7U*vy4?X=11e~={eBD!X( z46M!s8s8suP-zs|w6ZGjWD|`(584_Syo1AX;o!oq?{n6)-gNYZyFPc9rjnlgS%zQf zY~*N)&Zns7M|#xthb_XyHk7V|;zGKT#~YFK^%SKJ5S8^(*YwsSJ!HIu1>$1r@ZvJI zE~vcCuTNN+xhFf6QOmniC(Gfw@1Z*JkV;iyz zd7b@P^W=O=h@pY=EyF_)opz5uRH52N%RjA|D|XFv7~n?m$x+>r2RLq%D0(^7(JtW# z(o5?UN)H@UY(cUCe2U9PrJ|%dcTew(zzcrk4)sV%Xm~`7m*zfr=ES<>0ti$0Tb<}cRy~d2$L0;Tf>26GJ)ehP^uU0-1B*$kL|Lh~XtY?T}63UELFkY1t zP>fXuEH!3`N5}}|i+Yf*u6!w>(4uT~$a)L9b}OY%j9L5;gj?1x^hAe#MZPaeLT@l8f#h2`$oeG9f)^FhCj}yEY){BZcyHj3F1NjXS!9#GvwBuTUATd-sqMqwQ$hH zx|z&Nzbe1(|GYW`j_iaKcER#`o;sXL-Mn&+t_-~x{@(kBwf=4+23;f4MTFjK z?l9zh{evJy^QGo+EFUdm!osGNl3fwW__}JIBZ5Cqzb%k5JQD3GE*i6dhkR4IL!Ox# zUNki3It?JM=(e|l6ZoI-tQ&C^&oX~&gRK(J2re)lwrz*Z{^`V(T8l}o@x?j_2z~)627H?gJDro zTs*u0!jX?G?;HRgv=(?o9ibWb$43t<1XrbdEdX_HmcN%5^aK0(uh|a7;f~s-0(T4c zkqfWP03@~IoUJLm9&Xm?jf?ja+k|%}D{(_6V4Pl}wk@@iF7=GG6V7;z{04u>pVi|+ z14~4wj~I@?H>Tx?lE-;R50mB1@%KN^uoo){NiDWj6uz<}0t<3wJF~m`U-zGll$*kT zAf5{6q%UQ~Skoi3!wei4M&ejP+vF#Y2!?l>n3~GB1S3zScpv&6BkA0cQffO%rK!6H z%pdoV|C;hI){I_m51VG{EwezTjcgYUYNQcQ-4V@eMLs)utFzLK>;T4=z=w5M#G#=^ zckII_E%}<0g>=>UEDm@)E${YO$Q!^vVtq3_U+n;t#gq=)E9x|24LarQ-6JPrQdNIi z`7tIe6yk+}&eA??zfJG2A2<@RTn7L(4X9EBTLxydUpkz{k7~4@MUN{W*Dl;P)~8Wk zSRm{f*e=S^o!0||i>XQLxm=CkRiQd1q;-&|3{{2P2{@Bj(*=8FI~?o{TT+^2y%c%S zruXS=0|v|_{6+G=xXS={b!gWebCyWCX-9TBM7@5W2QkJQa$~yZ%BgPqB z*{bg@=p@CI|LplQ*G2VwUBn01p0trlp6E*kqvlD%%ye#az@BLZ7FR7xVE*mJIDWVM zEkMn|+F9FaLq%}TqO@rD;3lAWxw~dE@7#1PkJ11{ed_d4%lq@rnG#MiI1D^5Ue;jI zHUm5|sVDXq8C2~`meHMu3Fs~*2&=zmxp*(Ci((N46;tI{iU4PU-N~u zk+q9#j7qbzx&RD^Roix%@+4y^Z2H~0Jh%3WqtT_!eJ>Xrq;NHY7Y;zU(N5(DI|4n? zL)V$Oa*^}bf=W_4z?hX43X(10982Mj@1k^IO2cbd&UBhwq(9T$n8sTF4$192+myy5>>s?5h#sQM@bA?KZY;Z|oRkt0N=HJ2 zmOm_*4>IodsCiEx?@gpa&1Hd=QfU2~5<7j2W|zM-zGA#J&JJv8w6tFaONpldp98=)s=Gjn+`gIG88THGe^7t-o% z8?d@T{-@!c3k26l11icO+va15SrMWNv9sh+Z^Gh$b^F^gicgb3Df{Mdpglgmrmw(wpHC0=_$ciZ8YkI6EtR-;Qf5dxfpL-Ls|Lltvd2rIHM7bHj+avb)xh z-83ZJPgt<4Fi#Gjxb!xe7?iWjC+m7BYsa>je59yToA=VxiuL1qZA*XjLQf;$xbxK} z9#dklF&4n^Zs90KuMFML&`Jv?YtL`~UCXlQrMbGS>ZSiLM%Ef4d zmN}<4EduwI=T`n0Ps|=ef?%m$VtjJ4&xjGIoS^V(5&t<(5kh(@{GjRn(hU<@U^<9? zE>OAoRd!>IGJBDWNjP4p^}Sy++-zcT>a_w7`Gl?sLmT==D)>5eXsC9LQaa&XLc z!80H8HuSPN7{i_RfRmn}&7i>ru%Eiq9}M`J9X*D3HURjj2d`*nR@=FOJg}5ZW5%M$ zsqWwYBvWQjGz7Y4EH<6-3FiVLwwh{9WnR( zUKJUT?F!_RGUvMuWwhMkVhRJr*PYv1tMR0Ix>r;q7U60uNz>PwWm*h(j2Enf-Qm`< zEZ5aE0Ojgk1dMb>B44O{*-8Tn_h4H2B1Qg##mE{_ccNl4xz(IbMD_CEi-4v6JE^Ni z{$Q@KKQDt&Aa@$e!_)5Y?|jEI6DF)xJr?zx4HuPfnPVvFoHAiKoyobwvU|)36E@8RT~8r(sP5BDdgm z(bVD0J>>s3+{(w!)`Tiq=*ib$c#BL?CX=Bv>TbEI+$Zzk@6VWXxp%9FL+Bo(@RoA! zrxqFkAYx7WgjuD6>^1u2QM44(c+M5@`t7I7;-&fi6z(~oA4=;WU}B$~9r_%z-X`u_ zEXnquG0g|oG<}~cozwP@ALhizt?2Euzd_7FY~Ep0%mM_c2)PDXw}HgXjLzGNk~1PR ziZu-37287a%ER!1)xSZ#Qp|;4XlhpSA-Rx0j+9|{lt;w;{m0>lO&WLLP`B7}sw8%S zbvbdfbccs*vylw&L+o(d2!s@tIn>3N_p`Efaz-Y8G8chY94Uqnonsu?g}VOj;nkOz zKuM4Z9s_8a@9|bREmFvbm=nbTpOG5lJM>RD@N=khn$~6!c58?U2ExQ@%e@4X@{P1} zQJ`{fayi>0B{IFqWDk3fK1~4~iP=^QN{KXxuW&Lww3(Y&7N|&*Qs;~Z=dJL-dh-5> zy>|pnH+oN<9%qn=6X^4V%M7u1T5~b6e9<1u=krqsOx#cB4?{1#s(FaHj8K^R5D!_c z8BDAW6TIZ?Vc!v7safUtBiA8Y*J_Yjn$H0io9}1NGmf0lafOXjh8mx0QZm&bi%s*f zP*=WxHm&k`hjBZm?KHfew9H$^&FsVZHabFwTFWbSe<*9B1_=OjBj%yBHz6P=oTUKJ*q~K2ZllHEAYOj|zocPa;Q4H8^yVo=2r3)waY98= zn8XMA7HV|e21gt`S@`F?ju;ti9UoM$3(-C!a;vPRN(3^nIT8 zYH_Ow23roHkc#{(2H~OIEJn@()v#){zup*4X8Y{)j`yETN1w&*e&I!Lsu5D*?uzJ{ z_BAcZG;P8=9T854bP zVtKpPgz;Xu!%a9>Cpc(v>@#Fx5Y_ zq~?-KvJ_=VP07K~G726&80;`~DO=1mB%NsWrHS25$Wm@@3`ENm#;iam@l5r+61zYr zt+CNlG6*i$_Y9JBirqBoIFaeJ70G?}?w$0>8lC%Tt^`i7H`fl|UKlUuI=$2$FeG2h zk0?E==_rlFl%fOb*D6ihWC)-}LsGVBHCOe(+LE_~h}2ZqfTi0MrUWhjwC?gCZQS+t zeqQ#fi42y#0z*Ep5`@44WgfkxQm9R2P7-qJ+$;%#c$2G(koh9r@XDpCMLE--XIqb+ zp1!;5l+leo4dLEje6@5xG!nMSyi~tySn8~sl$@Oav*-waHor1f8P=mxmJhURZx^4( zfN)dZn0ohK{s#f!IR594#b`n>OA#o1EUDOFz4kX-So9%J_q+}vCM*d1 zw|PId;II$TB;T9PsF_sJwi=6eFLn9JsuUsW9`(ycupQR8N~6dORu>c})-4y9b!K!n zt>gHLK7HG>e$vL^z1T%h(>4(m-}x9kmu6t1<%6{zMr3Y~3r~*Z%#b=JF=}^AZsw?T z9mHufOZ<<3cK4hy^0bMl#6~iWnzSrm^RvNO#b3mnE-Vhq(<0SWZ~2l7X5xfER~Q!@ z!OKqQJ-OK&1a{?+w14F{SMv*fJ5z__v`1qLkIs$pPk?qW zV4zDNL~DHyC*vj=vk!!W!?)Q*Tz@D9Y2LBEk#|%6PO{AI-?6XS`Rw|dvHqE);jipg zidq?^0VmqwfeWPp*%&BUM?V-c(XcGKcTLCnYIhfcGBdjp!8T8Z8 z;QpQi?@WtuyHS*6C?Mj)ahDJh@|Z$h2X>0W~r;sWbGrE*UCp{8Dj+f5sYo+-rM38Y|(b z#v?+?u=>)j`9#sKiVuxdBjBE3SJ%ckCkBs3?eyj~MVCTzpCQl!)(IAFo%3OGm9&^G zErPT$)#I$>C1t*QRb34H_TUCAr%_T?iU9Cj)|tOv*WXj#ne_(kU3k#1cKPH zcs!C1^|W+YmU?ec#_mOu1oR|l*+|(e`VW87%$%#1?MVzDgvLNXENrz#T76IFT??zlHc zKgUTI$PEr21*F5QLr@u|PeeraUe}tJgm&nM1L;425cgp-k%qF1h*gfT?@D2ysCQwh z(4Pm)TRaLY&b^S7$iQfMKGERCi+U2q-zYt~d|F}65nFQQc4Hr!k*(Gm_Aqfs5ke*^ z0Ei6!G0|X<=Z#N3@5E=0%obHFC5;?Mhbn)x+VbHVe>1*XA&9=l9ce%qux-VG+?7Ln za`kXI6$ifE_h=MJ2n&75WSo&c1A#|#t+)dts7@Tj)Sptbm{gc-R?2m>cvYW=uA zqYQ_rcX;xqh=~fW<2I6mm?Q?%OwV?2$K(3cuP`VdF4|;@1|xa1nzIa+5O2YTD3oZO zg-Gn#pkb_BJH51pGj({ZJFUY6F3sjm*a_=rp7{8hY#><=s0ULQxQDAXp|#IW)jm&Q zCh!NIan*JIFJQvI6C&{o<1dkxBTNzlmRl!|mO}0L1cnVA%IT>ZZG6UM!@9y|RW6I# z65&_xbp8Fc2xyQIh~AzN_ty=Y5)WjkOT-;0Ag3%e>gT&Vw*C;f2?R>I0t=_2kc=o9 zJ{;5V0@J)L<59SpK`7&e<`;>Wt>R0e?s`otaFFlCS!qv|8(NS;2MG} zGejo;0IWU)d@m{Y1JH^PTnCuhzf;mIze zR~|b~6+e4fi%)Lkv&06}^=gw6zF?iJ?do>K zcRTybqttBgWsO;b>sCax?mUewie-l;)rX;;;Cv-w%E{0(+Gv7fB4EQATk-T-Zc zCnsWaOQ3~3;omRB$({2#_Ot?i(!(fZ4N>A&>;Ni-IW{TRm>n+3ISfJLVl_j=%~XhJI5=wWhszzZH4s7Kh}Hsu0%-|#7k z`-7i;EGpioDLi|P>T&Wkjor8I29=k$<*4leWip8d7+Jo0)Zy6_lie4@ETq_DyFZZE zygh1GY!W9_7sMoBo%RptrTaHg`4=@A>d1oU)pO+YMB(-)%rco+6#Vvb-W96U>;O1(xu47j1osWkt7eT34U#9eccn zpOK1aoD}w#J)1zk(u)v(nkY2&JxI2Q*M6XGxSmQX5CJ-==0&~*Z?u7fA{@PPu86)e ztAj9nS3EONNagLw>Ivw)(etS9`(XmVfbwB_J&S(D2IAX)$e@e$_g~LsjGSfa&|!vX z@{$mm!N0$Ixxv71k{=e?b3Yg79(o2=OK*>vWQnMv7GZ zyeB$>S$|ttbHlGc=F3jIO;FwoI^pUOx}mk9?x`m3la{)*=20nQgswket0eVVkbd!> zJRN(yN+Mh=qQSpEN~Py*w3?iyx2Q$P*~2|AT5*BdS3YuPQpUT>`fGVCCETC%oYeJA z5-fd)%?TTYqvHt=Amvd>TCIPbAIbL_$DL5Rawq-ZlyiSYNu)<`6 zqM5xfegVa67l%KjjSS}muipp;&|po?RZaMrdj={Y)kK@NC0xm^G?kmly~6~TH7B|^hiDzr4Zz%rj&y&1CQLJsG1Y^Jy;GQJerUge zSw!r+usQB@c5-II{ebS1J~EihQ19r)pU<>%-IAZ%&1@oAWHn^y<5;v2+TrR&Yq|S# zRO8PBCqD};)B+S3ooLa%GT^O@&JyeoF_#4~z~TLPGQgB&8Qu)V(_(6c6$OvLs8^m) zXsmF2RrOr^H`(iCcgY1)dd!jHo^)Y+~ znVLJAB;8R&gW1Q-C#qu{caXK!ZAM^nJsTa#ID~$!Hqh+Yt#iqXxibHbhpC6DJUFt} z%)7L9^Y)I##)nk$U`4}i>$zJ)DXU*O;9P`8CM+exXUiHWSQL7D=t}p>g{U5SW8w?VF#(r z<647JequmwtvD z$d9t?X_)zjI)4HU-1~}>j}T#mwHQek(@=m7q7XEWBpC$pE1RD4%+qeuM^a$QJ2vYt zdGO}kRE?{d;nj|eEIoW362L;6p!(D<`vB`G?~rMisQYhtWgMdsA?ULfH;dS_?bwWI zNJNkC7BHIT!IuA})GvV;8uYKm4tOA9ic4NTnq9#4h+@wCn7cM_j5M4BXj8dKh#VYf=%CO>fXk!OfR@K6QnkqiEro#MlG`a2BjZ?+ zwP=}kM$|4_Fy(Iq*ht(*0S!c+RDnE_wvg#TUL>a_-Aq$H&<9z*{3BH0#Z|R6`1T}+ z9Q^^kRpz@z0GKQp zOsJNgwFBd}p8yuX-^6?VQ#l&<__&-Sqx53$kR7YcDw(CSkUa_9W z;9ycTF_AuD;+2Xo++4Y<$+n`i>m>T`bLMP;J;L ze!X^{XD%7g$JKaxq4+SXFpATpgh$cq6cQDZu2N;|K!FXFEf&!lX~b+8W37wr8Xg2c zL>NTcnAm)?rUkR$ZzFjah_r^kV#kRe9i%ig#k;OAL9o6Z8V};y|a| zU!H;78@cCCjs3-C?Wg8;o&E5$lU`*K0 zI(`Ox-2ND>>kWrsZn0A^hb>M>hj(yszOjtSb7RFv-R+e4Szpigb(+`lYi`oi`TDcT zBlOs1M3Ig#TU3t+>Sd$5hG=TSME*XU{BsG?``$5Mqf*$iQ5^+u4!s=L`FJhPg4h{{ z#ys)r&z(@mw@w-zR_~&mLP6=7GQ$W>*=-~l-1VoafbzYc!{Vh-)#h)jlF}WEXJe84 zeFb9sI-OUlm@2nP(t1u8#8{K&9TT7P=$l|LH$=pGxH^tVO`JI|p)+HGN2U`!DZP%& zIeiLsY97f(*l?Q*l?7$s7__!)Ac+l0 z7Pn4|ON*IIUp}fqLyh#Cf~em@tMYW_#*9hgf4H{kTDGDF>yZtr<22&6y^RVjdb-O@ zr$n@_$#>)V!xKJHm`7z-m9z`}9UtRR#X@U6?MgcvN(-o^WLKq?dPemfu~>3TW(G4V z5Y1d14TUT-L0K7Wn^Qx4#|g|6J4uI*vo@GbNPsylAtR)NlBnoOKw62*zczrcNv=yO zryCT}C;hDa(mr=MyN7)CR3y00As3 z1}nvk7DXcSpAHHSzZbjbq>0L7SRYC_R_%2H4{=8sH4X>h+Twil>*tZ9F@^*EjnFFg zF|cL+^u8!A3H>C=t5Z`zPSwrI#J`yf5FX4(^?ll|a7r?8jk$&IQjm@`#zWSA?&-sh z?XWnCiCeoUm~S(;6P4Ya}1d3ohggJ=h8-!28ogeD3aMeNvW@ zGeKLJ7)0Z@{D*|&L_DLk$4U*yx`7*ZT&P08XtVvCxIPNBu9H!Tc5dd9(>OoyId-Hi zKS&*BUo5}PFuPjrRDE%i__>X@V!TAt#gaYJ3@BU9+2sB?TP(K+{8Z9*4Pa6O=MM9d z7Z=)XJ(@TMU5xpp`qt~-BDvZ)ozdO5d1@>H7yq4S)#5Pd13by|ejLq)YYb!SXR8RiPe6lt$eHJz%QKoJ8lVf;3Hk(;P zT4Sd9B+_LK9!Gk-Kpqt1dy6+cobD@dnODF}9tO)sn}UdW2lM?gTpCxpU0(mUWzPSr zr~kd``Tw-eI=w%`_y4gp`v0u-zb~Br@09nP`HNH7x8^mq<`Ysl@$%bN@+fz7m+9U% z<64*V-7&E@uh}=a%9nYn7v%YVHRDxN;;T~46TtUtqVsze=kb>Hc%=6y(s*WPA>9&o ze7F8$ch6vMR2So+R{d>t=$^Il8RQ#iV-o*`Hqtq9;SKdb1^Amr>)RrG`(Aa3!Gd{c z=`)$0^rZIKo%;`NwEe+)UFn5e<@DQ$uIZwgI08);kFRkJ^&j1D8tt*0RWg@3R3#_K z+D~hqqgo|wO13u&BIGR}P6_SzqQ}rAq0k_wD9?>&Q^IOe9SEcPO-I62nv+^Ql@e}h zCt6m>ohJnv#86tNL>MGj%QIx4Ka51IOk+x*5wD+US6s>z0&F_+Y$Y2Z3I>iwy=^*!iYBB(-L#yx^m&8tRdr}_!GyLiu}D|G+2cm|`VMp)Jx0((HQRiY>707AnV`uoC6w z&7~Z3VG`#P=*Tz@(uqVv)?=VbghtKdE{<&1qJ`GH7=&|Oo;Tz;xbl^q-(U(MA~5^9 zE|PoHwkkvJ!E|xS4Et>)86q23j^goyrB5w0X=-9C3mTuq)S_h z%S7wf)-EscyoUQUcv|R}aZsLvmb06Ub%sX*WgQncneV2$;D-~@KG1NP5~D+(Bw{lm zx=Oh!GuU%67h0S~L*r7CKn%D6m(XN?u28lT^UvP`k@z()1^Eo)Pv_&gPO4ot6R;a) z@^w0oKH2^dh!xk4WMJ}^R21Y_8t%9q!rrlYud*!EU*mWfkzCR{dcFYqdqo`7iTUm4 zAfm(C2`Pl3?j=dk-`EU1-_M8_k^*rlvwgs&3YBIWz<)>$_A5AZC0}9FQMYl$9x0*W04aWY*O0r(z6174?F}6?GVcY z+)IPwTp_UZjvZi)$#i7;uvL!9G|QxWmnr$&ReK&?XotcfW?VIlZ%)^!TmTbPoHcp6 zn1IropaK_p_&JZ;= zxElnyP;-)k^IAl@Vg2>{S6;39e6^p0l^Ez8{T{SYvwly$Q4puj{ffJ+uDC?A3#R9< z5W(5a+bsq6R48GDy;MI}dDr#nQS8&yC*(T}e$uE}i4DWnVstQxaL0+2;dRm1nk$ks z%l4kDKs=fx#VtRC0@}uohX?v9-Q=hh&D88nE3VaF&x(kDNhmQ%TRsOc0X<*lKAqMl z71r1&M$Pg{d=z=I_Xdrb;-dN+e_O@2$PkAl928J^rX9RZ)=TR#W1U~2o#~n%*u#55 zpJ)fpO|^+IbatDb8&e({4twU0VTG5qH(-+pRu`h>2TESaA7Z1OX9v3;GbV;Y4x zrut;3QFo9dsy@mqF+#|Teqy_&jhsN7PD5IPKhJ?J%exhQ(yY2O$K2kGGa`^rhnu`V zgsI-DhTZ@EFP4qk%j8Ez^A>iRVdjS}wdPTQzSrg(+gNV@qJdZ4pfu|^>5lq|>!Yu6 z{Uu<2+;pdMt~&<+HIEp(5N|ZS5Xv7tXQmsw6Jl0!T)Uj{OhCag+N24nmgEySC!Fu3 zf3ZARoKi{>k=VOK1~P(>GYJ(l4&6L{ynSS`;;p|2(Pi*ueG&nUIL3nf0OSY|iffd| zYNb<;RU@E9Mf^mI29G%ev=0dY%c1ye4V7$znPRq3EX?Y6+KM~M*Ig>bBDVb0r>EJ7 z&kK4Cjgxs|nI5Y0r+GHrz~EoI(;SdLr?y*C`x0EcH`GR3J~0$8f!3-y#3^ZOMIn66 z)nv%eyJh%9E$`3MVLYHZ4?i|9=QvpwhQz-q_3H`a&yG$2z+f*HU!BZj<%D4WneI*s zZ&IHPoBZ90=pC>7HlgoU+;LuOsC2@pLnbImwy>RI!wJTC;++N2A}MTmgRQ)1<+n^aI9iD>`yvb(+uHabQG_;(5Z|hVIOxK#Z|+K7K^QLA7*4(F{fNi6z87 zkv$5Bm8sv^x2-^=? ztpW)GmgE{u#IvQCd6B@Yq(Go`wuoBu!v0eqEz1n*xSxUo+CwOD$I{lmgM4;XW z#ahM#BO$SCVcwGv23(S=JTFSZ2k{8q*oVMH*V9Bv*EM%*D1s8iyaX|Jf|ucA&o-6R z80&W%gJ_8eyL*(&50F`1gZ1R&?{GQuA3}VF4C5S21F%JGgeon2&a0*Nwn{ewCf5W%`}u@+`!g{i zo|}htgU;%@68cdkscob$KnHE7*$s&%i?2yNumBONQwYV9&u^E_={rsDmmNO=5acvV z2Q3+eu?#VWmIU|Drld$8>u)TP}M*qP_W z4#1S#kt@SC{b07onX6}sj7(bI?HnaLx*qqDkh9|zeRO7J4!&3CfBhHBjb3zAgiZla z(7pAtjdjN4ijVfEK-656_%19dEo##CL#y0<>H5%l0jA=!wdXsQ!udL1LE3fKgp@*g zY5FMRruA3b%W;NGdbDAvwHAg63Ub*dW4c={OmJAOBE}ap?aW+gSAB>QeT-F2dQHNv z8oT!>6t5O$m3h7nAvaWj0w8Jl-7;=TO5o~Dc2om@;=>Mh7AInAk2IMp(3H*gJN2OmPwI6k=+z(JZqqAD?!l-B2?@t z7<*a`+(ycWMx%~P7$%gTj6;K`!Q-^2B0h9^MfJK3XP*J|T#OTkQXwroaexwBUkeeO zk5tYHvtW|!CZ;94%BaFgFEfd_(8iG9&D|o-(}OlA6UB){wu~MuamGxp+^TDOR=bU2 z$fulcd;-tgZL&&VdyPi5da97bX?LxQrV%GeoJGJ{% z=L~*qQVKfjbeoRt`9*27trB}TetrB*TJt=38E)H`X0j1?-rcWit4dR`Ji^D}#o-_t zbIfYGxbUW3aVaptj6ID7_&)LdW@uhCSW#M<46Y1R^77U{lEbDj+!1caThd&0?8wWX zlLUljR}`r5&a*$<15vzGafxF$BzIr8Ua;S}dRV>SeryluXYt2#X&T-sDVR`LKu7t! z9LtkR(x7ZO9q4~HhL@m4bCe%%prxZKtZZN2E1mD<8pG_u_^kmdk%LM4(k3|dKOq6b z$&fv^sWlOEPM7V(a2uI3w~N=jlc1M#IO@^sOLe~`8k-~sT;16ZS*a(t7hr zdwQJnZBIpo6|4Y{9TB|7Lh)-I17_Lk{4zk03fnB(K;33Z9?t~zFa6&GHVY)+o^H2y zRmnBhoUr=vokv67*AEIMu=>ln5V)Z{Q_S=Yw;bJsmhjW|idQfl4ujs7q<18g`Hhe8|-5_XUGyWAB&*Y!k8t~x} zy_iA|j<{Pip%7STOamx$Mp)rW`zLRYGWL9)4v?`<%H8~wM)5ErjqgvZOcGljmIAH@ z*di_gtAs>t{@uk2lS1pFzL84GA#QHB^QuS2RmB$m&P4-kx24Gx;buN(Ymd1QAhL=c zL(%x11q25gd*~bcf4G4%j+uDwp}2kYXbrITjPQnAO`fh{(aSK>Xx^e*Ti`HfxmjY4 zB*E)(*ha-JXwWT?#H$_tpKkv1KZZ_cdCF5DaHAn&anyFo>!io7Cr4-|HS07j`VinN zPK<+w`F5|&O^}-HqKL%S1j%T%`6y8YtXYM|$y~vpXEaDg{p}<=C+oKUG5AKysFws+ z$|k~W!05hRs~`ezrcPFF&uOA@Q6h)6o8g2+;&~hxnTbi&PfQ$;rw8-YPGk!&3upkE z+Z+5RpewFj&iCDi?F4HVGmX+G83?HZrm*AG9MB?OP7n)du@8j+UFDHqc;iz{k{I^{ zP`FisilI4i^2d{)GYXNEa4|En0{R06lc6^!f7V8q$v%+y(QKMQq-VQah&E1`tfv?P z!}H;9#oV_?9`k$%fKuCfa_6XtSI1I!ZQFLMU#zVX9P@cFjJ>YpC|1Cm)-w|w3#Lh_ z{Byb`GI4y~X@u^tJbNO>bq;PJZDeNQ;XYCS5tnB<089)bUXmneJ$?IHQVzx6$W(rYN-3{tB!3?}yz@{Yf23ao?7s z7dj;X@sJ~9-$^2u1q(i6|=_Z7VgneUa%|^KM2!8VF1`XTESp@ZNyt^#rbJ}mqH)PTR zKilc)=mEQ?uqkd$_5;fOvpTarv+8DYCpJkmkncO2Sk+F7wE9d?VF%E6tdO#ugD>(v zdi_BxO*PA17uOa82ilF}`HQ9Y7)mTfmD0IJ0TzZ<>k;LUF2c+u5j@a$8E|SA(cZB0cO0S7qz6J@uP$8miN0nym71V6@da*$y&z(-`8x&XB}k@bB!nl!LkC6|dT3wi?`pE!~3)$0pi( zGv~&gCy7WBG7&T+OEFZG$EwpoQLT8gNr?huJ8GqXsp|{HWaK<9kQJRW#p;ub;0IYo^dIPonI4~f5Be-2`RS?p2U?JhCQ?7PAdJ~MMqfMtc^sx#o3(UHs2@J;$uWE~JWmLZ)F>l%-6vt=rAcM+ke~B&9VGr2KKW`9UOO;=hjKm0^Ih6ogjUfN-_{d`tZ%$ezjO%M3h5%^pt; ztbG~mSR}L0FLoNRX~E~gPe@jd7{FnX?0Xiwa@jsB#%)%d>_4-=7tiF*O8UygaMIYf!?BgUU*zU=&y!>VLo*v|u|OJnLY5|J>xN4kzI*Ul}|=fU!MG}!Gp(BwqrQk@^BHX(FO7fyHd!Ouy+ ziAI_|SwV(pW#WC4oh>e}kq5NZ`(*GQwqnGGlasGA$YeNXr|A=$y|P z|2FM5DrCb*>KbsGV2&ReRY3QeZyPr?(-mm6cA@c98r9?C%L;ty>Tx!Y4#Iq?amlDT zj!m{UizfDb);-Fnr?ko;t9K@NX@MM0_Y9?hg(s5{xetl*VI00<0o9#=kbIM7h~U(- zi5~rYl1`CbPT_Lc0+;C1E8~4ms&TF{#nCHV02h9MfMl`l*~wnkv*zNgV7GA1t$U90 z+O(rMGC3_s)$na25snu~07?k2-B7~9eHLUBD9d;4D#fooYAK8s5dVl_ZEVrjssA)6Ah;;(g z{G^v38HPn=*R`zI@1e6(iBJ+9BdyC4Uip$GH1jys)PuCaq;!$BA`b$W7V&wXLulG$ z&(#K|5LvEZ&ncj(q$p-!NmRu-3DzhTa9(;{oq@1 z!*=HL?^lVxlba!n#5-Su9D%7NRmz9PPU1jQ#Z+6I$pwe9Bo3)v&o)9;rPlMsQ%_N# zUH`?JfSH&)G61)d+Uj*=k68t%PHeE?b^Y!l1I^}hfNdT1@azM+Rc8DW;ArBV`$=*n zZ(d6r%Yi+D963$#x?h458_#jLagW4elt#bv#qb|xW!3NkVUlxObCl;{nrq>(j&v_q z0eC|u>)UkLt%haGSevuzrUlQVs#(AyEyR7!SV@iBo$S~Z)|0dN1;3oH7@2-fz2a+Q z$s=nsQy4w;6?O)6iAk1`leJ-<+R}CP#Q-QW*$!Yy)}H2kIrc}}aHyid>YEyPsICi# z6viM6mUu5s?ia~2Bua6RMcbUd{>gJ>7pO`Afs@m!oKlUGov(5*`)D-ehJ^AOm< z!t2S33g+Il?`2f_c9ocy5s^2rkCvOZN&PEE8=0OQi<+O*1Y-Q&v)350N?Q2oWOiEh zwdUNDQG8jtC;$MM;t(JK4P?ewXM#LNbr!FZF`ohlvX`9hx+A^Keq_u%YmuCt6%VaX zs*aM%mrR6`h70eUX_ztWA%6MM5R59yd`Fr-NW5GD;}2%-*SRv({h-=`3LAV>`-H2Z z;lLrW)9POcHDI!}OnulTWVW`~*W(AC{>WG%%zLp$pP0ek)IhIyP-2anKR`tHpjD}1 z*CN`>Ltx=enH|$T;krr2wsL}p6bN>R8stD`+Ix`exrs4=OHH!DT-x2E1jXpO0DVza zPSDXQkB)64iCl%ZZ!M-*wUo`jf|V4$OaQl>D2HyLF5+bSNzrHW{LrqZ7bA5w+=a@Y zr3iC%x|gI1&0jlR`L!~HyHNIy+vJ;^K4w@use5zhv zX@WklX^#0&Ec35Kt1#Q1EywPAoaMAVinEawKx-0AgqY-+^X&AD1iF#9jICeJ9%caa zBz3WX64bo9&_Q4te>&uaW{O4Jmurb8?iB zAZnPh(*zyUA!mB(5!~@MdCdkE-?^-NJVuHbV4Df}?n^g`r{kXIg~8v;IcscyyGy6u z9t*0(OKm9@>hXXR-gNj{y@)*TC4Pag?sEC0v!&J<9|FrN%^@$zw!V&k>@`t=a!zRu zcBycvspQ$jr|V{ z`t;A6|NM^)2pLNz3G-yS$*5Nfw5ifpFfJXvCx`f0IC<~ogce~wc5c|P2JJ&r0jWZC zh&$lSY5d7#pcCv*O2?wip98<9O%DkDlLn;-CAS*3J(5Z^KKQCq!L&CDHr+;tLnt8q zCli#oR3`gL*biND7Y{r>`3KU4Jsd-EaJOARO9>r{(e`vj;jA~FoJ3T-Mv}4HezkHV z^#UTKls~hc!p0-sZ|yu82;z3?&gDwMLr++hrH{I8==!Z01^5P5g*o<6jPjq|c$qNF z>z5;ldKZ|g&SZQqj_;h1>0TCJt`_SAWtTVlTiAV%34Jg6y24zZR1c7OwZrhJf+lwk z-XLz++Cji(dV0!vS7QbFn^#G9hs2-2UA@xZZZ#kZsMq#MI6kqq$$ul#wKIJJnC`qd2UHUEd9fh z)7N2Uz8xpLqPzhzX@LWOMY7KZaF;jX0L9^mlb{4I7x@m19V|>_07gLvvc-#W`UdT32Wup zXrhY?V)8}ZE`ot+JUvc&1PLUMe@R?TvAq&?{2Y3?mL68mShk9>&Yd}6`W9|<1o_3ad4-F{x}-T^lJfyg%V~s*Pyr;U)wm`AG1ycYJjVS? z;RLrPhYv{(q$jOObkbJ3NZ_Q3$%+aqYHc(RSa2&I8=xv6a_?Z!8o}zaa>6oaxHan` zRj@ErI)Y-{!VzO^GKf|t19VH1I{SN$nx@|wR)Cpsnc6+9t22918FpZxY!rj#mFSSE z@b|#nM6KhqZ>!Zd`*|G1t(pN=FF)bnpKVO|qJqvJCKWw2ZvW26+c@|> zPeAWYl_`5xI%!#0b{k9yW$x{uWHU!XvUyd%O#@z>llAsI7q;!$uKFNAi}`kfbs2*h zoE9M_!&K|*Z^gIpY8~q{>bXk7&KVBVX6SJ@1-_Km9%bK#J<<-WA+ce5hwB2trSomZ z{EVZSgt>eB<4Hd-9&^ju%G8q(3SW*9&sjvMdc_as7EPgQkV^!;--faCP>hjj>p4htp~3!K0{Dwdzt7Uj={K(f@i&1Xg^*_ zi4dvpbiJbL;{gK#V|igobbLTTwNl5PqbnhxJK1^flsG$1uq;Nr>29(<625z}(xAZ- z#!n_Q%hvXB63o2@B%qd_y%2h|R=m%wh18?>fXfmvnNgE`MEO1#?3D;_gLCFfAqqO! z5uhmbw8_2Xp+Y0Vr2{f}P7F;N$JYszCW?Jh69LyWyfnrM%0qxFpUsl5hHwiD@1h*5 zFFc5^$YGBJt)u{FX{h=#BnL9&U_^iaY$sO>?$W(O69iU#o)v_Fz9KfmKBhi#1#0gdXC+-^>FJ-kHHwJ_9v`({?p$ZYSg6Q5v5A^>-}Qe>nMY^{gD}oh3mb z8VPLglgs;MPoMS)<*PJg5Z}|ppQ8<1L7aQFpcFYMCyHoprb61JnK>giXq(&wftm@S zBx3_9iQmB^)gL`P7g0HpLlq6eVFVEf^C6C1j&!6qQgx;cDq0=0WOcZp+)mz@dN z+PpmoP@w$@h2uTvO^uf|N9zMe(-IXy^={1RC+s)gC%t(-@V@fIDl^j2Au;`4NPSK` zw^qPt7D1#KjZND+9&hYpW13dXxfHO@!&|WK_K-Io6Z*6xI(S-Ia6VBWp4-TI9vErC z4=BlP(~*;PK)NGuCJX+Dyvdh{kiv`~3p7yUgUTKai_Z%yLXnKl-I@i~ISrRL4!Nd* zAt7^g%wo4rkO&tR;N%keLm@ZpR4RZsNW@Mu>wsztUDFmK)p}RBK1E(OiblZCPeNu} zD#vW^^pnjWti)HeoK`B{dB3fai=^#DA*hi-6jAPK0rS7+#1`!x1Y74RIz6# zS)&RT3BJnHq3-}s+)umTVK3#}w*iuQ2nM>Nk+{tBq}RG}4Q4ZRMUIbng42<4Pad}f z%|07W*o{siqDf5+7&9|!9kcCn<-4+$nK0F{!vGDN!OCLS%^AVgcyo6ahepSzS?}Qg zb{SKJD?6R^ha^Xl^h{C$!{m58X$d3GeB{73lC(A^L8bsZHW^>o2xW{9;WDgN;?sAXOq zGb`a*+!Po6Z5l(~onh`2y8S+tBL_dXqI&wR5^ZUigI}|Li`i%<3;uzd=CtUA+n88Y z3#dW7p(i`V^iQ#q6Tq|~dZl;OS(TY%2Zzld6%)W;kxMchLw-Cg1{<_=GPxN4Q0-*` zm%UyrCy;^_2Exnl%%1O#S;}?X07=ltKir7+H`}2s?w**u4A~z~zRSt8Nu!>T7afl^ z0iS2d2M1Mo`TA|A5xanZT!8ewzSqt)IBmBfH2}>qo=Ezo9!J6k5=-S_qSmGMUXZ-M zwDJ+5*EMeiBS%-PYQ`={i)BHoAim;xRKK^k%4D8l=@P_sEbvir?PG21UC|6f6O^vT zjz6IGNg<(eL!P{JDEwqW@g4Y`vnE$5kYFVOh7+q_YJZ}%1BUOnv1!?8ib2l<%tp}U%FXM$(}1xF9=>*yzl2%xA^h)?r{e#tBto=p@(^AEcu(<)mOO zUx0oSlG#7)LioxV|Mb=%{6&WM=~lTe-QfjIckMO?wF0vlz3$qUF?0?=TX=VvjEqoj z`?6qjmtV4=zc&u$emD*nN!+E)e^7{8TM~xU*qFZkQvu{5u~cL6gImhfn;m)ST(K(5 zV?O(YkkV%h&$ba9C(xVxuta8aI1S}Tk%L8J`$*nZZexP^#TZ13(nS0gB>dsyRMDNdVuMnI>Y<<@PF#SL z1d|rAxZ`O(flaZTe|%|zJ~2~yV=>XgOwMY42o$=}AF_x01$tcQmpdLnx;OTyYM8xTXC z!nY5GJqk#ins_HW5z|;@b<8@bBJ<@d0g%kp!YfFt-(Hctbe-~{Etc&$Y2sr;35RG> z`p!=DvH$MH)jtY>)}z%#=^Qv$upM1ipEW;I8imK5b3y;Sza3nOOwh!#MlJnVVHY3L z!-V>@{b2ip&&eUstLDap$OZRgB4Fc6`T<%GID>Fxq8<@L^achZ$#~d1*ZoFt_eeb( zINxvYweHr|Kx|x*fEBqpt?_yNLnCn5>?Js%Exdi8PmWgZgc|b$&sI!!ck@x>oldJ- z3p0HjYbHP3Xv*utgrP~|NdWv&4#1E>-UUb5c`lgkAxE12ynzn zaif4<-K=j4ZbN6!K~p$a*7X`)=#|a^=jG^=_IY<(z-E`WM-d5?9Jbh_l9D{bQh%>N z=H(#q>{xLmRURxGCofRXSsZ+??FLq6+Ob*B(3h>6&hv`vHZb~Nvn$pieooyEF2#IP zqh^I*wqqLhu92A@CBYvG(2C>G8&hXo`qIXdGG~TkJzK}UAf>ouCmfs@2C(DToT`5b zgX94`3LH$YKZ9=d?m6S!ml4&U_F+Sh9Z2e!K(+jCBgMLS=|QdY37ODhbbp9844sa> zFwQjYT-{8)Vf7xH((9_mFDM_a2$Gi+Jh+_sYB>N7cXJwaY% zJI4|e#8_M5EXR`6@eT~tz?D(49<2O)k7$;ImEe`1m=jS@Q-nWq%W)l9+%ud%xk{qZ^`Kxid3IeO*OgR`I=&!;eop&mJ4c z6iT8qICE~ZILzM@xOKxbjM2-1Jt}&s)2CBMP=b`2 zJ|lL|idM#b`@^?1uzhDd4;(L}PlFdEfHf%)gSBwAHmNaU+=df{YI<{0iwuUSuR8bx z42^cJ&bRgOcw-oh?G?eKb!9T#4(6_gnmg#?(_9E)z&Z&@1OR%4-qM%5R8uweSjHp4 z=UGrd0W4WlXq)dK3^ZrzJ_EM5q_6&t$3j;JY0<^GiBJLq{Y>|y#RP4wrdh^)< zVHpf8girMvDN3Jg7RYz+ojfN*CO8t4fz@D`7Jny`+L4ckMCtiYg^`IOtJe0MBdhPt z`DPG`T&~i4R+u|KJ9qfBllIZtu6u@`6RZY#`^;HTX;y*Y?ltkDj-`P~pTtrPY}A?@BokaGar;j9g>qk! zHoVN_Fgo~7L}M^j^KLwex4BPyeFc;Gqu%R-fU%I88Odl?97)@DREaA+(Kd6v zPM+`vs_kk2S7D{d;5?O0({RevpJxsw+tGqXHyrY3!_6L zl&W_mZ%SLysZ+Je{GjVe)^3meJ3$M_xKEu>bR{3A$%BDu7%@g|@$>vBfE@!NQUiYD zEviXQTK|lCu%R0j1Of9komcd^$s7hIpgs0KCJU88yQ-#05OQm$n(OM+Tn}kER;u3`wFocH{3gK)rtn2r?6srk^=G?>LYK#xv}MI@)`h>#IG!GCn}T=k+w#Nv`+-{vB*TxhyG8-Uc^ zb$ip`BxcjoYk0DU;76?ZCeZ*R;=QHxG+<_KeWj9#|8h;n0g2 zRCfkzhl9h*Scfbuj3;KG+S~DMmG*&g^6gQp-t9bj_@E~Zx|#{!R-LSMdLAQywHl}u z2os-0oQ9!}B9(^uLWeS)jl_wvsA}vawCAgw5C}5m%iC2;&rpkeZ>uYhdfynlG$o-v zCMx~zdN~|B-l>V;VP9u6zEXy%$1uqgdoL^REIngk-ctfN{yaQvhw#MdzsGjcMKhNl zKr6Isw{GzWNE32};U8I#TXPD$GwH{dYO`&HMRF?!Hu604r~c1UJ_a!0Xbl7|NCy|m zM(&WG+-nh}dX@njNtMOt>NRT5%gaPHH|Q9}j*qHrukqxavrgSnr03FYF&y}hKc?{3 zrrX9V^gVlkEYKyOE2CxEpXWp#3Q6D>->tYiyKHHT>RG9^JFV?e8%%@hjpcxzDVC;bVd0xx7t@CfRDJlTuf$C||0dwJU-0 zZ(_5`0^=yi5__Nhasc4S09ta>u|RoCb&kljcdI@{9fyO?D1JxVu@ORW$$L2qhl*NS zgUM0vq*4*SV!0nuXn4zf4tL5)7bkVf8V&%FL&s7m!t=xR^7Xz$zWj80ghzZUlL+&G z3s-^SQbcE=81JXq+rHa2CuK`IT>+EOi%DBfack*D*s@2$OFw3;jpHv4^+rBjdTXpNHmT#L25gR5Vn+9wZMVW2 z?QEAYqfh?3&85~#ko?h=>1BrH=HTD)J{bx>aXZ{36~}#gN&0`F%YK(Q)zE9FJVWg^ ztzNf+V`dZX+b$VIWqHVR0BLVWp!5_%eTl}Qg61Q*U6?*Y_p&gCeOy79lZL&PMu3wT z!m&>SK`;6@8;>r5FH_}^CA*QfHMG-6AWb6bkm16Wi2No$D#n_EdH?*c!hSMg*r!uG zE-hji9tqn1l^d6%lqRLC1F_Z9gMPif>&PH;0{aXBBL*8l=Hb%zs}bLM2!tB$z0Vq4 zjz)*{=Nd;^3&x9BvlE>CG`PGzy3y0^c`^!ZER?s8>8va%9FX z3>i&EUyAy|BPU7XKfywv&x9Q6=Iz4DFZ(779wzZ%*aV_TzymN9KjgzH4-F@%7}}O8 zle~;%brOR2+vIh`FDhxX{ij)W%JF7(t0)^P4cQB;nus04A9CT0kClLkn*8zm&BDo; zT)`UyCeGFQ>G=tTqxY$#f#jQg)qdT8`N`3?WT@izqQe+7J(r*cSoU)&#bZ}~+QyPD zv0SAhc2Ay3i^zApJ&nI?0DSjc1BZ&!pJx>((s9ndPk{qy@S`9uV^hKM)Mx9;$a$|5 zGp?mO8S&fo&$qCI4 zhE;#@Y_B!F+X7SM_BUm8#R)gR^d)F!B7}y*Z4TGwGqQPno(=&}W-jZShaISS0vwFO zY?tG-vHZ~c$7`rOeX{stN9beWCp9u4Sv#Z3?U{4O(2zo$L~S+w0Q1K=88o=Q9~WJ2 zT(WM5@2v9ZfQE=t)v>890*JrJoCgW=tVFz1y>L;O>+pgZ3nN2&MillBT1J34fI~z_P@Cc_LPZ;Me-h!rz#`e?V&0fKZ8NL z@i+0bO!&rS%=5WXM30G_iYQu=aCq!+R=Daz$Hp6i z{BajWQeICS`Z1VyxEsf(eyHcoxkN^7Si% zv*-d;b$(NhOEo#;6=fD~3e*PB_h5*Vl^UPjO;7k#!LK=$4tI&u^q=871s~h@`w0GA zjPg47f4}|rKhl%{ybR*%24L|B$s5^Nzm*Ug(Rs=;xo(0anzBC&FEv4Zy-Q<)^E|e+ z6shEnnh@4_zG#8!;?gt*Z19mPMbD8yk`Xn`%GS+F5C=4Y7OMzb zFZUMN)Pb+en~k#$>l-AeZ!~EJ;ol3%SGmQNj-bBWKn>kjjqZj)h#rNM&}eEUz9)zu z9xCF?Y)XQs>r+%1+eK78AYiif-6>g7K#JEac?hNzmu?N`$DR+fRUl@sDTVIR5MmqT zrdWA4ckc{m05zct>5Jh?gYfPdXLj{|Z^1Tbye=Emyj8Qoa;`VS)yKr)HZBvbg~J?H z#tN6do%zH~P+BK%g%foEsiToQ?96TUXf#I@O%cH7nGpTW7x^KwI}^abWTDucBzv)$ zP__gTMwv%ySD}goYz8NgwTkSl2Wk>*ukK7Mj72ud%K3i4_ff2~HMprboC8)>|FtTd z`|NciYTsk5g@dXH!_8pQV@yvd*wQ>mJg%0JqZIpU_ow)<2AzXP+U4)S$vTveC@W+F zIH!AeqD(?kMa6HUg8bN$mk$PL_esj0 zBZP?nNst5?+IP$XyXD!po> z1$HSIG>5xOMj`BLemSmrp++33^W4ym7%v>|vBUY=u2JC>GIa@B2 z3;>?;U|dD--}G22JE4|lH$hQpsja{BFDHmmA?X`K%Xm=)@G}>b57UI{6N-H;oK@8B zfL1Vdg!ciD=WKSy$k7Xu1{ERD~jildnAG;b=J)N zg#ZdIcB9~X*&-Qn2TGt@W;8$uUA-^62OB>+kQ1;sVeZ@sB_zP6&p8~K{nR~Ya%re) zX8Wsfb~=zV;#p-{@;Rfa)4l|8wH1U>dPx`LOp-|9z!@uUZG%MEdkvrZvPi#|B%*L` zquKHJB;eCtSeiYk4rd91I-Ud{osH<6k@xb=O#@`v$ml%!S?Xl8TzcW7Tpm<+fU zCt3e@7N(LH23Du;m87t!$wV~)I~l=?D(Yt^RL<$TlO_D>L@OqG z1H2;4>X@RF_IczwXTMZS+QmswIcl2k>}mkKyfQvn4JysubN&NPGXbyY3ra# zWu+hggoJbB^#}NTOd3ZGdDnai>$et5t}}p2Jg&XS69bx~XqJ4qff)r^TXE~AWBdQ% zfo(}qzfCVTF{hRHMA5$Tczz*m?6rKqEY^#=x!={I3fFK?JoXYPOoS69*&W=d+9Ngp-|vsmTP6Ez#h;4s+aK zTul9&xXkBB$;gvES7Z*CD6QLO9f(0$U;uC2I zLjxCyA}5jN7dolhX`Qd<3U&kCYLr`p$Iaj0GVP<NjAZ{rF`V6)>)gbAV=wr*zef4)N|Z!TfJMerRx9LCVzL^JC8l;=^R z$unioF8Qng?c0R}X@$-rCLLlTsRcBIzobur63fY?;VmqV^)o`U^sI5lMJG}lGRw5m z8rn1YXUNBLb0o?)Y8?>Zk~7Vb zz91w?-%U$*kXQw#LFWb7zhAWpxQ_}r+bnj83@4|w$`40*Vwz09}6MW*AQSY;cjM@hL!0fet9RXcyWg>)95o6Pd~Ul z`@h%C8x!Xl8j%P%TCR5*H8#{g)p0%RQAP%zQxbwBDeQd&m$eUgM)xFdk)h%lBmo-d zs8!;!K8~WS2rhyXLV)7{>ze@o1o!!+Tjmd1t=sO|QlYm?phHwO7w#7$Ih1y1gYT#R z{rb=U#WF-bJoy(&PT-Z4o_U@0`2UBrHCBoE)~KXG;CAPHfRj^_I09-2-W9`8#tp{7 zG-P_cbSHX4Rp&eSomarhvH-*jyxzonJ0aZ|L~nG=){{9Cz^%dnCu*zrk`OGBp~+0D zH%eps_uHdG=08Q0pYfA#2~={p5OY18Oc*@xs`M1HWfrK;6n!n6!Az}ao~9)`rlDS< zxCA$d^Hn2JTR=XQAqP)SK-(?Iq%V8q3uhp@%6vRO)T?uOKl99)hL?gSB;?dI1DMq$!T}=Zn(ukun$k36<{?c zH`fsGfjV-F!(p*_^6?WtZ@U#GC=~%4GPl6^)Y_#hT2bifQNQ-*X$*1G_gQ-XJsL-6 zb~UNyFLGi6a%=MQF?-(#^C`QA#te1d1!VGZ?49M{$?(aJ_N2jcMe6|;=L~}6X@eo! zhIQJ+!0xk(+!*tZOz1{}lDYFXh}p^cPH*@kxy<%*NRnwhV?sw^%H8-T@@&&VV#2#> zp5qGjE!m;rA<5vAOCgT=@~wJ{A~R;ggeRVAqpQLaO#A;yBP@Eq!s3H3=1UdxDqB-^ykVFyVC9T7U{;oDZTd`LY; z;UqEJ^>)URmn9oO6ga6qevv3X7tKBR@<4#ePQgJ8BJtOtAMB(f<=ZO9OWJB&++tA#nOqu{jK)JtLhohvbmM;6`chuwTIQbGNSrR#|gC+4dtM=}q4SN*$ECUSAK3O%pM$`zPtn2*OJ_{;=?>5p4_* zRG97wzI9DA@$2cAK3(3ojLI1?CXg_`m&tupXi?fyd zwVnYuQUAF5_T(0<~LtfMx?WRL?J(j!L#{n_uUz4eb z9a8(789K@ag1wOlo>`|IGvM!5>#&e)mlfd<^Gs4Amrw7^+CV1Hj$yY0Yrw%QLRZyX zKm_>Bit+XX+zruTjA*_qNGPC(;x*GJjNTOTfMDDs5&|etEDQ8)dh(<%OuC~=b?%e? z$#tG)iV8L^^_xF1-(|FJS0$cCzAuWObch7m=3TI(O!_%e>Y~z(W0;8gg%x!Ca+89r zaRSYOEY!o1o5Y&BNX=yDty$e-hXIe@etf}A?GYF0G?Pfy^&BeqPu_0*G)R2Y0o@R7 z`hCF2IB5X}Y*gxA7XjG)D$9EmCMr>@COiZQ8rDuCE7EZ5*IE z>6swq`yo_Zy({!x>yWA0;&;d%*4f1?f~z#fnLiAV(>jqPFPvE{5q8+y9}=+PeSdrT zbrV8#!n&DWH)>kLbmoX*Po0(=fjit}u%(h7g*9|I)TD%Jh}qwzPv^7p)^gu!dPA>Z z8`%(l1}L1*4MEZ!o>xK{90z(FD;%cF?5N+I?o2J@RyMK?%(!AQd5zGTvfkIl>H86A zShDIX6N$Lqp_6&oRgzr86arkKae94mge@;gk#&;e)r-_YUsjVS-T^`pjiP?C6E5(t znlMhg9u`f@eGk!pd0)82XDAcPd4Hg{c7F|zQVYPb+B(J&17s!^mtnD$u8$u-*kgC4 zKa^pXhf~g3G%edMsf@RKx=RRtpVwTU`(;D;JTE1U<6UIMF{#ZMY@8s}8Hnl762MTQ z`DLrm7Z~);kZITa04 zHmL*6{k^Q4o$!{$TCa3`FgBQzz0UnbgYqYCI=7*CN3Xyw4)5i`oXRg>_|p+w68aOz zMz)1;sv5f67OWcOfg{QQ{>%2^EAs72VS)Qr07_&lI%=}LqpC= zDq7{HW4W65qyNmO`Rnxql>BT-C);yLLt>N}AY$A`(Oo*(yF4brFFkQH63L&2ol0Nj zkIhs4U}-yVh7D)d4s9_)d@$=df36M53G@vncIu5u)Dd(>TP$?25|%jmuT0`-xjpvr z^JN8RB2|fGL_5|hD)}?z=t-_TXSdjcN^)|>e=b`3nuwZ8NM5GLha>eNTP}evExVEF zRM32vaE7Lcit>p?>Ye$&E}$hdoqfY6fzPTJ6(uwNA@!YO$Zqz(Vt@e0Pwwo3@{ro8I(h|j7PiODS{#Y-36Ocn zD9pJqI%n^TEEeZf3=A(0b`%%TI2O&e#TGT<6ed*Z_?LKAxN`+hoI85$LSdAUM?<+T>HM6(-SSk7T|)Hk*Um*Aj__GGvG_pBBp=!oxsVw1 zCFIbmsCU>8jf%Z^yj~S-lFEZLCUfAg@)d^l$w2_}m7?=YaoB1;+HziMK->4Nfc}@) zM3?+)E=R`4?@qp5`ljHuWZtvim$aUbnaJI79K^o z$cR|?{}Luq$sB7NV}cx-S6hi7EiQSYi^7+=QoOfa5|MWB$&>Esd0=4y`x{s7{O^An zSVqBt>9BLERW|g>3nRbpZ)4TSLmzqYq1$Q*k*anmWQT0@`@W#D)onm#G46z5}8kCk)cX%vhxkn9%zIP#p(sU1YRa$BEw}R5cDT zHTty7^tn8bkuax7TA&f&I|b+_Vx8u>^)g@-g0!0uyRhN37!+^jqHHPPLeb`TPAX%Ivi{xk^hFm%$k)6rn9hW0=kE|P9Ek489Z zW;KldgANTxNk5Pf6ASuN!_T_EFO@nm{K00?l911GXl$aqd(zRxjPs7SUoe+u)M3Uv zfj{U_R$nK9m~TC?x8plIWf>5E=cf}rhFC{$+-7KKFitWAI8(YjCN!PxLl$g^Z`ZN_ zhkFipdN-xXrKHI6cvxM5C%P;zu7FM`aM)~Ohu@h9JPMw5XQ*;Oiph*qGu>GqpSSn%d#x7QGxJ1 z%_+Q26km5euIw`$eEI9dM2mE9>ty72#x$sx@%J-A9An*Bb>pN-lLew!P&HTA`i|Gh zzAKolm;DO*!Ny^_pjZ&WKsA|`Pdbk>*)TzOxD#1M^Y=5KsdP050GtE#>x3IvUkq`_ zfhIa`#D8KXqFYwZoLB(#@?7v`@$qR?n#K5@^L4uGlb+^^W_N|dTWw>f6+Ql-B?@s# znB6*QtICZ{U2x+hV-XTKBW}%Nwt2hj%Ik7=;^RpEP;EppuMD#(d1qG9h)2W}TCTCp zM7gbYVz)(9DnW{Csxn1H;(di6r8I*8XN8#G^zK zC|*|ha3efGF)q2I9r!KB8qg@1ZY9!}KRE~v`SdH6=uVfNeq7C`myBR_2Z}i53qYM7 z{~74%?}8{d-tu|4HX<>g(enJeYmlPd^Sl+rRxC`0vC)Gg$y)yNI?%c)u9|-$mPqdA z7D`G$OT$Y8kFwQjkR$_kaDUIa7UCB9O$+qI3ZztzofnS*67~2JU4p@`9bD~ZaCJXD zAUmSbCHckIm)SxhAwS9nMa)CUo0cfZ`$SA8BI?B9xHP3*_;tAk4hAU2kcEv=W17)B z03?{8s$!<5Y#GM`^~btJ^1TY8@CgZ_h$USAta3sheHh(YyiG2(w;-OkQ;{}-!HX#s z`r)pc>6YlX}vFfMeP7XoEy_m zq!j*hux|i=Y3rh*E~^`JzC5ISR}nx?H;BipcqvG)h2JS0+ENO*skEk;o?uFBo?Z%I zIf}vMa%&B1Og<+(E8S6{Bj#e)_Q4^=6s>j<`_np~bz{!Vhswqflb=F0z%#A4+*n`} zB{ElIW(>P`sO528$X+Lz`7Kvo3TZSm>-14j_neyOBq901mz6S3yYPKm%;{@(Zv~yK z|ExK=@6`x!4M^zYnM(LJF^j$$0{7(T*1_`R>fFRsp3?115wsJmZ}g(>WXwb88g+nR zk>P6Y-AJzbQG4b1N)>AEnswPm>98QoZr2^x8e&knNHy@(`vb!8H)P~ zIMyC~p0gODXYrtc&W1(oCbN<(O-uu0f23rAlf26SIw`Y~yR(072)5_P|HDmyYBm0X znTxH-C8J5l`Onxz_Y9KsPUru$Y?F!e{1g`3GI2xCXXJKt(pCVX zTUcJH-GpGWG|a|F8FeTbF>nmwPot6%MVv(WML1bW8zVx*Fwe)ymj@E>MNQcb3`uIn zF1fqxf-dm;@sT^T)RF$B`FgOy+n(68HJccw1jn>_S;!=BMBise34*?hFu3VQbR)YZ zUX{TCJ8x2P$TiRGy;@DrdZ~Np@|Ruabt~k6`-Y68Wn-ZdkWlEhsoHM*N8l6MK-K=n zt|7@NpX_OIbC2RAng57lPVu?5Xm-IqjCc#1*;W77`5Wss^_|H&9Bw?m1=+EIOJd@4 zle<%juZi&Mu&-aeBZN85h))sjhP+FpOU&!NJhVOQ+blUT6<54(JTagc&)I@k00YN@ zwbp=aBHy`9d}3)Q(OQdSV4j~4+?1j$k{peC+PPJg0VNn6Gks1GWZ|+HMUkz>>7Zp$ z#kkz;2Y*v1(-=4Wcc{S(sym~eO6AEE!Bri`erFa+Ocn%5?V-)4OywF-=si&n;PZSK z={juf>3DpVs5N7o=9db`C>gvXm#5s!IZ}cxB=PKGP3FDYEnUJI3)X z65LPO`*plySG12cDA54!0Lzwv?feXKmsqr*3I|;)ZhREinY<)24i17U&d2oT?b{%^ z9dskhTbE5Q)0d139My5b4iCO2Jwis#}$KQBS5auT5(hW)Z#T6IxY#OijbAXD8 zf<@64jZ`7(YmwQ{^bkzUKy`F$_zwh!>yvApEsttwPwYljk1NpM1poWLSVm!;J%()v zhN+>Cwh5cG6dAos^>r^}Wad5n{btT3;{aX4pkrsYQoAFtQ4){@qrZc@pOKQw1A4Yw zJ$98mE;QR6NSA0CW#~E2?hchGBT-q7**@dyerRX#WG2xM(Ch#NkOCnct?^Eh)iSk0 zj6|k>Vb^$r{@T~|c%T3d$1wQ5yCk^;FM-%Cjf2sxsf`Wag=o|Y64_A^Y#El(L;h0S zP(VyLjFXW~VN8Z8y<3?C07x45z%?bnp{Z{go~@SWM=!eICz{8$MjT}$(XPz3{dkga zOrMw^XL#gJpACM;p?|wPV)XdcG=d5pB z^K7td75~YnwWo(SNy?J9gY%i%zvl~-)%fN(`WVV5#q=w?gBc~JUJ&p0M)Bm#TLk(G zoYdCJ&BrImNroD6o5*x7mR)u$U^R26nyM?~A>0NGgppTAc;Vo93@$7b(9z zIgz7la<34vgQ}Xr1V(Qvw)ON;wNR)6|OuNM`5_)`BRAKbHLBgRghm>{`Lxp15>~U!Jd|R5Eh&I%{_m1?ZXH{&$La|9GPntA6*}2qr7)e9n9fPGipcp1p$)uRWbnV&GYaqMm*NJkK zUhrIk1ZL_lS78xjOk&}SwaGRAHN}Z}htfnukPorR^<-h2R=P%PqeK$j;xsb5FRfWO zoQUgiV9q#?Ue1n))mS#&kF7C*()CN09rxsY9MBGvH6m<71t?iccO%zp*-8B~>vgdD z>IV^s=y^4?M}m4l7LAXxN=L9y%%u{|f`TeaF%oYhlb|c)?YLU9O7ZKUk243Iy$fP~ z>G+QO*eCM!v3=2-FT>F;)=iW-5}aQM?hhj-_PbZ;bN|VNk^A+aX$wrtoAFf1YoD{k zd~RQ#5phJvH zx{0&huDj@3pR3n&cU&Zmld0L(xG9~dK=_*0WP$j!-K10HqpcQC2JoFSHe~t+D{1zN zjSNnRbHnBfAVPkm{`-0hc<07SGZ8ANFgyAgn7obZVc3=6v1ilo^ci?n$msA8ksUD! zImKQ)PY4rhEP3{AfD`9q^x66C8$hzo0;X@5bX&2Cm%a`#rEdra&PqhBtK97{BTS#r zkt$^-33AbtC_mSZ22rsI%o`%O6Wq{`xry5LX_wbN-&};ng93daeH}7o(`nPij4wm#S?pzmm3OTHU%rEy1T6-u&whm;npe4> zH`K48a3&!6zr+9i&x=ykHL(${1Y6&;W4LQFx9KR)W-BBog}0=h?TK*@Yr4i#8`prc zv-$b@62u8jv5j#_x=rEWK%E3NR=cB=o+KOd5YzdOs>j9~$MD2zCokKuFc}irPI#g) zGKZT2d_L+IP*uc54M&>g2q)%*VUx83ppdAkc6Tb5P3`LUJxT~SOp7{`?^ea4qT1ti z?xs;huD)va4M%^4_vqrh$IQlKH)$G$eDiX^T0ma@W>%%FDUZJNbIuFxoPWrG1W~3y zQFXOzp3=>P$8eY5=XE7v`aoxEky}2pYkKcB{lk=8kEojT z?!*Br0zMZwZ&b`Xqke$^Z^FK!TaHWpEVFVzb@zG_@TOi5C z(l=-v^j>fS#6P1eX@r7f0xe$IB zNv1g^&fb2f?cNUvsPus*ZwUGazNK1OX`P7cgNHv^K(ZuxQd|%HPNw&vLL(%-!gjDi zib`;CMojVCJ2$~EhnQ^EZE(fC}P)J z!&K6arr4Q)9Gl%-^dBPpQqWLHL>!MB@m3v^FnPCen1ZdltZ6((Om(CZr!{!Kw=?5)@L0{SnhTMgMF5AOp!ehq>&XZ9`Dc9;Qqjf_1+bwxfbHgGM?Fx@M@@5ER* z7J7H@;)K2@J^+zfFD^%(5EjaKV#&jAZMnF zVg4R1*({+j2a{=+ZvvBhu>n+Y_;sU<6*7PGtc?|6j{H5s9MVj}IKB)^6cdFpW5dRd z+xf1Zho-+0XZkqwEJqD6BLY!DDQioD8$o{JT1leWK6AV@rUi_>vtpE^4pI86>SPVk z-~2B_Dl;%1*csG&6Si_rHJt`yYqe`bY6&Wl@4BPC3BYaYcF^ zv7u36u+qnLMjVa4Jp$~4)Sz9(jp??kmkhQtJ++b4w35)6*1 zU#fzAuwpnRAVe>6?m$Pr>WL1yy~nIx88cv*#DMQ}BlNs|QfXA|OEz0RnJ`wMLQT{c zY`lx1T`pp)*B+{wrY;dpWUaX##qru#F6K0uY)=47103q1P8`PDIEqm69i&7sb4qzuL&yHDZyS=kp zw{wM=Y?PfBo?7dQI~ZLS-edNs-2R0bZVV8IBZ0e-e&1m?bd5g;rZXdIVreI!A@GK3 z?%$8=lfTR@q6@^KeYbs<>JwE-LDByk^%J7xnbktUION_ggsit}@&YMZ1P{TUTr2Xi zYjW-c>?ws1o0dx^vhKA_Tvc7-I|%i1vVt z7}(IIM(8x+JsyFPDQ}l)q2NVLH|+%_hy(dnCDnSF+66E5>jZBwnfN8y4r zPI)pAlbtS-o{)*%>%fsfu3z@`=5utLUIQSrIz zud-os-Cd@{^;kSxB*8H(D^cifynGEDWaRjG(6<4z9y6=Dzk*;N8EV%Bru4$KOv6s$ zGy@;w7A6!^$xr;gJU{Lns=&InU5fvFRtp8JFDIOipJ1s%7nO4;xqeoDRz6y}ab?ZN zb9-~2Rdj2M>H~QKRjPmKJ8&d5vW5rKZ4eBv(bb)I@zlS?!648$@>(F^*==H)OSZ#h`xt7 z!whGRmuXcik#e|rqzVm^?n52o>{gNamcXo+GH2Ko`3XT}Jp4m-aL%N$zcFE?{gL;8 z<|l-4Jt3>=s+pXS0F0E*Woz5L9fWbMvA<~jW5}2B;$*S_v`9Uy{_>1y$Ag zi`;1l6X!3fYVe-d@njEcNVaGa<)_)7Y!9ho6K=-8*D>**&v_Z{$orv(E<+|2{*I}j zLCJuVdM3uKoq2Uk1GFrRCnPfX&;O5Q=RPwqWB~F0eJi~T*u$pa!m*0n=F8g$EW&T#Oa}K*Ra>wn%bl& z>nC{j_gKK7z=8eN!SmN+t>$avg8W$YtFM=y`|BJ1gNHN(KiQ4!Tn6#=&Y0d&2_+yU zo;Si8L)=f$rNqNOxaxZVgek>K&WhTg10b2^LsIq$UiED)(&45p-x55PO8A1rTFp)} zVA2>_k1^pVMkl~e4pH($TvPMuuC>7qfLG!@A+)jovE@PO{VS^?{ZauMW|a)eOk4%R zNIlR?1trln{yDipM3*MYXv|juWjXPgP9SL0D$7Kp7DrT;=O+{S{x@R`m@uHRnPX*E zU_%(J{0#p(Vsv4_;V*1J*!r&|jFQB?+-VnuyNK5RQg^vm(**Tpn=?P8n@shJev|Y0 z+5da}Z1&oI+{#~*j}CzHv1+o+VeF;U+q`Qh65hv=5?@&zpl8Avv8vVO1KHwDzAOSuh1h5>n4}h`{r>2 z#Q@_a%ahNAY8Rb%g)pzUyp_zMMG^w-d08RMg#mmU*o4c%aZEToPVURl(E;UmxEyl} z$Z|NKo9;Kx7U=sX`spr$vS4}D+&%AftiC7RaN0501ZHA_D>44W5{5qmGKEr-$SWd- zd}>9{OhcfO>N_44P9Q-wnWML02Kl^Glr3pe!N#ZNeS&zB7^Mtk3IICbc$`AKFq)KI zEAs0oIv<<61oI2gaSQMQT@WJhS!cd0na(2@VOY0A$IkRg7fHmPPe_)4yoC~IUkwm{ zp0I@jNG5jhCD^ilnVWD7XB&=hY*+ZnJg-9^U5;v0J2AXo|2yZgq&oYv2_#|#EqT0i z>rp(5#fNJtIeDAgcbw)=fcWjaR1uqIjJn&o_E@*^La2BFTa!{t>3(Z1$gg`BVNylj zoH*X^YRAf#iosKs^K~;ZndZ1#Ms}$~Kls})a+xrY|)kANd0nQOV*lK=egSZ>%RrIO_! zgi|NKe&KGbz{`F&Lo^8I=(yrxo)OO5WEajb9S)j{&PxM|Gr{67>7WwVPeK~a%Cwqi zhYLsFI9qt$Z8c8!*(q5Z^0%o`Tb1hIO{=-fH%Am~t%$mMG79;^Tbs!&k50q&M;7A< z8Ou)IvcxARW;_Q2>iW3LysXh>z4Jb!ksBHX4HgQTiEXwudiUBcOqWqep_4@2%AW1< zTp7}{3y8~xGZdt=P&iP1bVH`ia<=K=O z5B-?a3~d6$I2&(?N|I_cl7&V?F=(?6M0~1{^2aW*3wPcv6sW!AG&hn;ZH^Q5mo}%T zv?q-OuF1_jy8tsXLkmS@dRi?nhz9&_kXZPm*|XS(i(d1srOI>&G0XJ0FA`L#&6vsy zl0YA}nCP}exg%F6VD*T85HyqDH^h3gd%q||NvM9yy^i+t+86f{gM}0IHj}8f&-ZZc z03H@QKaz?p$dO%G>L;U2W*(1`NM9H4SvfLfa0jA=9Ndy8#~i(9-^)e~2G(EW5{W~t zgJl={OlFU_bE*LL>tf1FJZd=W=;cv>q z#~@h}Kylz(tUn=1Q#P@LgJO;#k}rEz%dNt;^7WY1WeVx=ut`M_&dz7b?J;NLtGWo2 zfZNd^`O`t)pma%KXNKme-EzC{2HdTQp>X+Ya&GgaQ4;M|{5>tJi@37d3K8HP*&z z^l>Jf)tSanZb}{KI#lMynUwBh_||B=ICLkPpv&yxtq7hkVjUvxS<+S6pk{J8{u`Bw zCjO~dKj))X-Uw0K-5=J#dD}ST*jVi0qJcTCE}I*#2G4f^BR?M{KLM;d;+azI7)`ox zs7Vrq=?XLs{myZX+Ec+6u%|1@*&=PSon`;Y(87 z0nzNQG+p$@rsDKFmo?TatRU6@O;bEguuO_uWuqnI`D2j@K<@M7Ljtm52vl1+&Bfzo z_7D-nG%fbOvq`smXQBp9@=g+UH)+YRYB)KB)+-w=jBdQt{M{%nhTiG^D<0AWYL>zF zuJHJYh>05a_-%E&Qttg7bq-F9yUSjU0;S(aqdJ~g?Vu3&thr%Il6kfZs7|$u^?o$Y zrw>WzC1Td|3t*-Us%Y zbhCtHk@lU*!OfvK8?GZcGQ`izexl^2k{%qL#xGqT!hIr9nt4ZgZn~l&t|YjN;40yf zcn`nb(mCaVGWkX~P@1p8gXUB_c}}D*5df_He0X=aU4~R0u|y<8304vuCk$iEfjK|D zRFvx+WLh*|Nmf@yG9Z;IFA#$GVdHY7+GsXEEBhIw^xkrvCRG@cmX_L8M*2qIC?u z^(3|5FN69zNN$k*LN7UOdO669L2{?wHZBv=HRB;Yoe6u(N4?Qiz%x zj@WFJ{R80IbrCmRhW#{Yn&+!w7+8!2&8$^~Em6!g;!hTIIZ{OaPu`o%?(qGhaTdc> zAks0VL@Tcz*)C-`y=Tmn%wcPn(hXz67bFV7*4Csu%dl;Ocd_MtF$b%~)C-NzC5o>S~l#bt6N zq-CWEWoVaAjs!%9$jZ*F5(&?h`wOeA|9O18SrejgLMl{<{#XhdNRV@@;PCVDYkVBH zaH}t3^nB-LRth|>oN;g*{E9g&9bvWUVD!3xO)JZd%ue;AjN&e}29G75Z$l_$A)E*F?bZVghVA&Tp_{nV5GTR_s_zN0!5N>X^!I!e7VdrNnrB z+LFL?p>iD0-#asO=VpIpoV$o65@}c5#io9l_kBy8Z701pN{=Cw9mwAK@9R>KJh9EZ zH`pi((csTIF0e&m;HH$QA%?%I^JXq%;*7Jek_@Zua_DXV*A$YkN&LPCh!<3|ni=8_e`SxPB~M~&P?Z?1GDgc%g7VM* zj%8_q+C)Y1Pwh#;6~2m_$Ob_Vio<5vqX8=Zfo?TCVd!hZrFIj-cShLa<~*6zMRktK z$I*{{!ORth+M|`i7qctDS!Er!%#gF#oS8v8?-2Nb(NZ&MIH#J;C~Wu+s+I%{Vi&96 zMMYotdYtN`Rmhl~vL=;`*Yy)Z0S_hpc{Y}C4kO0E6B1dF=W(Ce7s!55P(!KRMp<+#)n6+cas%0S-m2ZO=<%VWak! z00?!+{8*rntB&=>aY;!34;)clv(CPO2*#gBUj^CN=*BL*?Vb}Kuvd@cghU?yniRuS z37Wfvr#ikYv$q>x%{{qf#kh)qaYdB3lxdtiog7ha64LlPH`pXL1#oo=Vb4X9?<8It zoJ_3NZ#~fDM&K?j@<({>IAkOWdO#D}i0Ik@>bZ|}+)3fdx1Nt9lbxb2S48G0A1wp) z$&1>$gp>i%U1!c^)D=xrUmr|Q(7%!EokVW_?Ob6T4|5K>W(NIy4BdAJD14cV z)icFv#BmMIdjjDEjX%%#0FkbWQs)>Ba4s$vP77P(GCXz3zE=!K@hd0*IiA^qCe~># zl7s@_cBZcr|MsO!VmP`3-DC>h1^3`&4C3xDZd<|<+{VU$DP!qepF79cu_dy>EPELZ9Waa9crn`Ho2z3ay#lYG!;5wsAnkX4yFqHS!Pe{X5gew z+in~%?k7xhE(%VX7{Vr*iHwW`okZtV5kO-1N!yvy4s-r}nR9V%HZY}%YHB3f3C4&$ zx^L_Be$JjTOWDWL@w-GYC`%043LDP8*y;CVn#n=6Fb_3$viFO|D(dBx!-QD%K2l*x z4&o$YB`Q7ae+K#Z8o1+bt{4LTDqyeeYh+$0RdUWMqBFk_xAJvBvy3hfu&yBj3)pTTMzK(m?SGiJqXpA`k%-D{Qp>PJp>mAu>gv4U8LRayePg-?dqwn zXrUlIv%WAjie3YTXvYLIXTc=oSqYa^WPYwyQ==N+dwD_Sgz0{2gD^ zx(8OXWBU!-7lNo|pixYN%yM~s8N`T5P@ui0;;aE(0FpNQ(F!I#q)!cp?$6KQYjS(Z zQmvT^gH)u0QuAq)Z>=1yFd!h6aF_Ew(wI$b-=^WN5gen;MnaSxU zp&aNqN%&;rwNr>#gxLa=v-ZLgcP={^>9n|0fWk=QVpPMoD{Na*pdaXV7HUw(1Mf3j z#^Ie1On3DNb6*hT+dM?Jh?`L={o$6Ef|f-M<#vkAk`dVwdm%pNQ73j#cVpD#j$jM_ zjH^^MNgF$m?+lo%ej=;LoZfMwt8(?U-jv?HOZ+Q)$IZ}%FWT)6Ad@uJUdhUoWTVpc|_QC2W(wJIQZ#`3#^Rj{KLInUOKjj?(0}5L|GsywHK-ic6{bd=Nf2#>Kv7Zn>k z$3RH8K9O=J5!hW%=HuW#tH&o^!7j^g>XXLd0?v&th%&d7Xw9QVz_DFy1@fb)5;|GSn>!~1)H)fy5Oti0n>rKPEuA8D5&xw#W z^t{V1A}2meZ(?;`16I!n$=F>ZRBNm<1kWzDX!fCBNKYb`t?OkGgH9mmwU@ zFU@Pn*eXnrgua|c?q#4g*R;ddy}o}#UF#u=B;G7G2%KSzyDs^z4Ea|P5p0%=J-t8d zwt;#c_jR^D0Jtpe>WW%F8UJ-X>LxNuzC`WYB%GMLD*bs0o_XNIuQgG)|B*;a=S z4;$jbsAWdOM#5?h$EtRbwj?(^y$iN=9}v^Q4HorW%!uoAUmjA{Q6<861xz4t=mdl? zNdo@)-?7|dPrU2O9z6afH|uoRzw?_qbe-%Uq=Ftn*%2~{aY_Yxe3bcqnqG-$u{=wz zBKw<^DeLD-)7=<$`wH8wDx;8t7w;mDU6?_AUh3FP;$n#`W%xZ}T;*eH#wor+vkT>g zzS^zdM&rJ56iRCozyNr5=w?>|xBuGO_lXaD3y^T9ax~zJ8>+T}=+-0}=Sb{(igC3b z*2MQ_cL#V~XeY)1SOQcYuZhee+OJcFW#+X=l~f2VAx<{ILQd%187bOH+``StE zkwWT?>uDjEp#?5biCwR*jkptRmA$>Os?m#i3C?DfSCFh|rBm^Gi8jk=g)I$czM<^b zR3d>r89w5*5`t))bwEf;VscBzsP&I*vy)cbwr5`g*&IW{}|6B$u&3&Tr5>euMaWT zfWAHsw%gfzOl}jx?G);m>7r^tjTs91Mb~jpn0!2R z+r;s84)@iMEf7EI%Xd-5K-LrSPi3Vz#{WHTjSq9wBUi*<=-FzS_BC)=*@ml$MV^nq z$e;P|02seI_A%($4@4?fwsz*18u=Ox1^l@?)*zqLsk>wq-slPP#^X$W(abkLS$Vl^ z_Qak2X?0Lt>uqz!8H;@1A|`|U>9_$Djf(Iu0G?OEXTbgko&Oqo%oLQzxkjriWrUNy z)9hh>)Gu(4eXmfgxCJBAfrNf2eC$1X_78{Mgf~G{b2OK^eBjQzNn@R|+g`X!c05h1 zAiBxY>^b+Dqj?3?$ZklFdPU$w{CJ-|c%{5Zzw-290SX!G>sQvjfq-n$XhbJA85cDb zi{Bnu)zn0ulQW!W@*GgyzbRjrMJDiQx_wEEJ0HQ_mK{y;K0u71F08N_X^i!}Q+HKZ zQ}-htI`{rKX?*Dxr(_u5md_8@CDeZ##T`T0Ia06K7isN^x~65#ofN~K8)DfsgEvUj zJ`^kV;cO`^%BMWBgvjEL_*&BdwvA?AHGf>qH(D1$C2(=2J^Yywt|spK*zFyUuTDV7 zt)!(%T`_AVCU1hzF;wGA71=vTdH|eME(PJr$0@nf?Wv$NojV}hxgOuoWP(U05$LpzO8j%cybRJKipiQ0-3$BYGg^zqZh2$16*EdC zQBBgvk~)$12w1?hCf?1G&1^5L3utoL6FVAIhLMojIc1U~V%d~ENE`1ENDHBkS^Slz zI4>YZzz}E~I-WO$0d^t=MtjDiFq)|nQOer@H6|Nk)%S%US|D@WA|T)}70W0?<-#DP zWrD6BYfhG<^&ShHT`ML5=*lbpmz|BxE`cD6-x{a-9IDipr6bFQS4 zaSeyOYqSK1iLX~ehnhbNf@PR7rxKo_VmVqT#|4-=!heL6*n4pknMHYTI6V=(sod$T z(WK=9N0TYDjJPXYtgp3)eO>gI6Dmkq5Z5jh;-I4)w=}6?K+w4wCx6(^?4qKdzae7&@pEICOM15rkb33WNqfv04?d1$cn*;AD+~fb zyt4x%qjCvDc-{}e&`dE)g7exZ>c#5YkTwUY6TpNgSyuV@5r}t%Ra=AlXqRbYY1?0Y z+AK`Q7zWk+Vc`8^qCRFfAc36k_TV~Oob-tHI2ruj`MC}Xkn)9u9M^(|vCXx@nf}E~^9H#QEpGFwK0ebP}Sv zuUBB#w);oj$gmT;KC1)ha9`SV%*bdB?3#{aimPXT9vVE<2Hm)W)($+U%q?+DISE=V zUTfH*gc*uu<7}jMzB2*~V$81w7aLdoq!jAP{#O822)!5;{=atRn2KA+;tfg_a@c@vz zaF}9>7^(3z`6`RtvWhQrs4%ae_kp>NiqNlF+lF@T4Uky0d*Mo?#+bk_9b}sdtLZx( zcQ-&R4_hG_r?0LlAQqhvX$yffhe!elKzvABb?r>LO--m(e_3?|C%%Oh9b_b!VJkYg z#we3)Aix#*mFDFHT!f)M;z;_(85GgVK4@ZgT0}vBzrxTF7!~ zmCd9StpkflA)GU>du?&!XYTm^l)>5y^VjkvEz9YJ@L2e>5V4U?0?`Ay9;)I9K@0Kp zEwh}?z&Rh`n1a4@4l2|hFLrb0-c6J;(2VPFJ6IN{Jp_)@WFVXO=d6r~_4{mp)uUL6 z=?NSLyc}ZYW^`qvDq0cTWJ>eIR-prAlKx!Q(gkg?Cc|N7Tx`Ss6iEiN?)X$M-lwFj z?w8sB?*!;LtbF6$nk&>LsOn+Y)j*{8Z=Dev`wj|XtUJ8|5eXlai>sUA~ z1B|#qmMiArCy4{ZNeeNLmv?Q)D3N7RDJ2X6g(6;s(H(-=d|<<@uv3XY zE;fa6b5wu#;PW0l-z5_Op!M5g?uN-rI=>XnQD?gK=ggV7ZQH>yOW5>)3ew)5K6XEhzv+O+Om=l7yYePTlYlf36DwMad_`~(P82l%p2&{ z5E&2ih`9G(H#hZp6C_yTTvb)Y6HG@c$UPL>oDY7M@h^T2{tGcbW$8WVeymk~Sryb^XmTLXH)2wK=QvzkSA>XA*Nq7Z zD#uXGbe14B4#Fg_D=d_V8 z{bprkkqr~Ha#XrqYc1om5e7-q5z_KsvV22Y-u=0z@l$5hF`OyjA-qomavYYl9SW{U z5fNg@>6x8IPS>~4cfck!gaIF%&pfIb+hY04^`k(<2Me3(=-GdIIkga7;uSYR39x7I zEq?}s?_2s9j_QtF`oafUwOH&0@ZlXnv6sp168@ggeIF2(X8%}X#0qd@qW>?mB;qrj zckVWa?Fw&-qt#7Mkzos0T)+RQ}EPQZ{Ls8c@L+h!9ld|u~!ygGa5oTX{ zKgSQ?bBYEEiG~;F%gMYOvX_xI?n1k6FY1$jArW0+zp?||&DElko#|`&6S{r2y z_W(sey1$D=(69H5?*X&wT03iiJ|^iWxWRlnoT+M;1AelTH_u_Qq&8)C`5@ke5O4j8 zXRm8x+1!Cd57kU0uc>z)PX;5xR)g;6Dj_#x+Bgm{y0LTdP~S*>sqyu()q~`&?7}DE z7zydKtYX&(wYNK;5H*i|HNPv0 zU$dX9)g%WIgdL})G0+tO!67Z6UcMp7$?6BHXu|wLKQ9&He5H(S$!JHzdlWYf;ffJN9X5ok~MuOL97I6NSu+_k%4yPocw0urDlxG z=)Mj#cZQuVj3P^J*6wPT+%_K3pDN<C+#vd@c5wONLM=tWFmV6$JE3(2QZ0?k`R|5<46x;ys%SJ=ta%b%d#klo>$ z{PPm%)o|~^s|$3j`x>?4zf8dr#Eu|**k?Uu@R?fgP6aK)#sZzZ@Fag5wD$gam?jl#>S)X8;yfhB#0o_x^e)c_)&4|M(uH zt9%uMU8G1bwZYwQBu`lBA&+m%KHKz4V$;{li9UKCmRHUd%kWN&S(AFTC?y&@-2SVj zoZBj9SGH{Oa?Cns;y96Ouyq5OTH>WWXbUXGgvK>Ay2|-ay*>HTSe1M&RM%?;j)Oy3 z3oix?yNHI*sV#}J zoU;vDBvFWOyf0dM<&gHy9w7I+R-F~UlYsX;Xn`tP@D&1YZjU-@!=)&e2-lD1(b%c* zA0qt+6RQ#NeHlsti3Io~eltv>k^>cc=izr0o@Zf;Au?OD;bZ(&(L}5AZdbF`QZa%0 zrtvuk8b8J}>!og*s`kk^h%Y51|x3{;R~qBE-N zM4>FuCyj}#p81eftz+|N4P%s?XIx2;+sq86I_@i@m>vCZYS>bLpZl6I7>J zW~a`@GqV;5fSMEo$uZke2=V5OAHxy*gqq0)`BI(%ozc{O{WL%uHRrRvvS;J1#3Ju* z<{W2hz;Bx<3ZvN}BPK1NzWnyM4UFzCyJ#ZNiJ3?W4?D<(wZ!=6ylRIDj;oxHreGMqyp;Q}z64z}~R_7Ca`d zpf7X5*RxJC^^vc@1?L7=r7M*Q;iVevB{(meJmjYYX(FK6S>q#7_27YFoyToI_ znT$|o1x5sRZBf-0@40pC%y4J42x3i^W6J0V9c6nMH(JM749|PvP+UALN0%frPF9-> za#J=7?xozj3Ky4nICr;~byY|q6Tjpsz6H0AU{(q^+L$}7LaEnHi2+UZ`=!(Cow)cD zF3DH}e}Yw&y*aitF>>Q6AblCec>S!mx8pQ*#WK^*`z<>9oEzi17szw%gV4eDBryGS zTd@(YI01YEy`^|hG?r0+$Jz>AokZ_Ay6r5J+K0lf6Wu{geabSRW<#q*d48YQj&xIX z;l^*2iUA~m(pU5-&=k0)COWs%zL#ZIw6#{98Z*Xx(v|sMhFq4WAG{gyU%QfpDEt-b zr0a(M^*X7=LuPVlwq4hCqsv-X`#+!!#U1?Oe#W{S^{XBF^mHIa-bcctDB*70`>+~1 zPdnii{=gd)UPjusZNN_)S}%hvz*qB~xBA+$YX@Hj=x^0lQM$v9AnEje9p)=ufcr^W{7s-E zn2ydF<+wKa_I>&W-_!f?o?FRDZ;FpZ z#*8P`C$qHJ0*C@1MPd5ndYs{eV5y@iZp)S8M4IRHE5C^Gt9ki9zq& zALo`-VC_iLHUA}teb%z-sYp1It~z3J4USM?_%jSpcQ>nOj|yf2{Z_EEWfcx#<7a(6 zQhWu|$!{)i;&&GimM6p|Z~U`&903A&bXFD49o4X8GUy)n!j=R7;Ho+jShRc|$om7c zNIpbo*mZok7#(N;CjQ$%o`{qj6bM}(!o+wNxD0 zI`Lu;X8#28*{wkF8C&vVh*P(jG9M(~?SBT|R=KEOYa}!J-*XH4ozvUMzy##0qW97q z%MWoD6bvop)UVzX=OxvJGmzhI%YtDOxx#Q0nxF4w2q*8964 zIr5!r4wsqeeAb-oaThSc6p$1ZOOT3@e90(6L3J@q%TnC$qAZo8;ZMrOaRYa}4zy`q zp;zhOD63P!a~pO%Ng7tZd1fv;X{hmYy}0zl%Gl(xYW0*=%ROOM*f2>yD>+XW8Gh~v zTE=hS=zhVkDinIcYC~=2=7ClCda1A_9&<_@cxjzAIx95H6Q_7`Fn;_ z!}TRUsS$*2STj~Vc~T58547>f*^I_Qf+|v3b`VS$uLl{X2T`Bhq*hG$k+S#FF45mt z609Qr0IFsz6fU0S->sGIR*?Qg6k54)bOZ3HfCd3L&`lBDpzO-}ZmNER*{4tRreCUN zi*0!$3A)eiics3vH9b3x5!~Qyd%%sfZOhw52F_ypt>i?!NpXmw!Q*q=Lj74ZUDrj6Rh2TntN za~m=P_1B3xR~em-eLxfy-=#im%)i|xc^FBq z5JsA(LxI!fz#Neeg)rrJ&V|h6>d)7reeyMC`XhyQf=k>^In>0gHM#Mic{r?+pBSAP zSy4UDak~ZtB&3U>P)EdjcmYy|?9^>UI#cgCq64mwx)k7~c4PZ`Y3)PqIIdh`)Dh!~ zv2Oo_F{lbP{=l#!>-myGR+C`i4{@uup4}5`Yu(*TL1dy6*Syedm|y zcvyMnY{_-zJX_mISrb#w9{z%SR&B5fbSB>Z6+AYDbpK0gGJJ0zSDV}bBoR)@O?jIB z1ff?kk%e%^4eK<^AwhPJz1LKMJwt@8}NQzdNX2TnB_Y- zMUcVY4~%E9y-aze!|QnN7w93zJ1Zl4JJC)4SgZasE|ymS0VM{?Av=vzk~jV_MMtFA zev_Lu<~~rh{hIO`zUny1$r5&t&#nYNfxp1<^c!e{g30Hc?oXE6?k6u!cEW?l6*(NQ zR|zNxe!Hqs1~NqX?lts=E%#tiGE|ct)T6R{h)WEBo&scs1y6^aoM}&T0uSWJy>lt~ zGpB3d`|iC1{9M7`E36U78sfDxzyJO3Sek@Y1H^jA8T0CpdUU3{Zh>!6%EQUlCygJT z;q=T5RNZ*2d>M#vj?9nq0MMpzC)71N|Q3W6vg~K@o)zBS=X_u?4%RJ;hAp+ zGr?Ejt4==}O6=DwsE~AINODRCgs93IpSOYGrCKi zSy%P0dR`VyU|b!mQ84M&q!e-ZF}k{Dv^wxOc-W;GIj(ju>t^;@-PAox zlLUp5b4fhe;z5AkR~C(>I$C7L^l?@()up-s(tKxoL!yPZD@rrHT0d7ocz2P6c$-z z{2-?7qF`SWIPR^z)OX>84|(jZ1ED?1Im>AcW5_&mlk~PrQIz4zC1}p%SWwtMey&Fu zY$D+2C}(pMvpSSe~`@G?^Gjv;P0FzRh^nMM6FB}|+8q~vS7dpu`% z?6_}B=Jq-%A*)=hs6xKppCq(sr!sPP*8s7v1N>CC*Cx-)?Df(pt#_ZeF{r10QJEV> z+=atsy2fgeKCRTpE}|5Yn9ViLoI(&ez^_3wP229m4BM=#nw?WK*mxh@ zEdrT7Aq^!bjyKtM&N%h(NY1Q@Zrq{=5YqDO7e&Y0O@hBi^DBXWD}WRMnKBUc$3Z6i zg)$---h0jszBxN|E2DA!8#)qhdV`@#ybSJ31j<&fvCT<$?4pFKonSwj9{cIDZ9qGV zWF1Jf3j!SsrgOdLme0xf^@!&BM_%lZ*}f^hXflnHW-fjR=!sCkZw50edqufp^jPeZ zc7kMiTDb`ln7^1WjLvaj31;%O{%J=`&HbA(=MLd`+?)A1|HejkyRV<9=w!rq_le2@ z)9{v?*#3o-p2@38N@_k8cC;Nz8jM|3c@&;r3is)fEKr!Vn<>e}2lKdb@Gip}icJh( z#1ygj`{JYv0($Ea)XcR5u~7bFw*4&MNBu+Sq@Uih41b*G$eV0>?D*f}>;o6b>r}Xu z3z|LYl-R=sa)#1wi+jN=P^eo*YaI4in2#wkS>zxnGItM1IG{MzL4fTr4xEzy2p%g$ zA#|)B&*ty*+{*FF=D5!oU{KfoRO4VXP+0Ub_#3;=o1}RGY5hgRigxg89wI@por>5I zB2$de_cR5u=itT7nE~FfaEq@^OO%PZh~S`6iyFtzeIInDs&Gta*0xGxUJs=8-m&5=cSs{XcGOL=rejlbQhH?(qcYY(JD>)H!*6RUMus^IG^z=PJJfRUKp|~h zML-;m+@gFDgA=Y=>U2Jjakcgpl@XjQjK0ATOy-?fpA5f!Z>=b>qi0ED(dO*P6eMS*75^Nb{;c)4^&syiou zUniU5?dt4Y%d*o?uQgbP$h^+^i36G*cyhX&1bUI+qPBVl*C|_A=9c0l;y!DvXgSwR zS%#rSlBnQ51rQ;tL$yMlwENbO^8id0^QV9s7}a-?{eiS56on`$pTz zq^PuCWYS0NP=W^?zWf$&%u0ujOUz^8SOJ_l1{crYM9{Z}Umi&gEJJ&dOI)R8_uNG5 zdGO1+jL-zfpfEB$qf+r>T^ttb8^Af(-}H)E?7_D>&yvY@@H&mYF9{4H9t-RdFnED< zA`o@*WuRCxPsGo9=Q5g@xy1Ew2E@sup=OyaUpKM~iPSj|E=%ar7^UpVGk-3o5#_ym zof<=XQ~W+Zc9=D?UMnOi#V7x zC3u!kb3Bx3+ubO-nFW1*XNe7B6oC@t{)xGNXHII3Z(V!;kFGaLl4Q4;X5VG@?FHQb z=B`P9!`+cJcQmKFDw70(2oJum8o7NM^cppsdDgv&JQAfFGdymRaC=EMtcRQ$dk(9(0 zZ}55@)S)ngG1g&KM^!qoe-)%jtih3Y7G~7bkG%cL9Mk669Vn|Rd@3+BCdH3lLm;@m zC}D}kb_?joi!MTDDO;X%-njD7)=?CA!a+7sX8WGo+rrSjjia-!j3k3FMRc+jU^b4~ za8xh|T3>%(nSLRE& zudYJv2<_x5d5x`$Hs=}XLE#>Vy_76jr6H5r=EdW$hXhVyuPe+T)9TClB0}ZBTg^0c zgI$GIZeD7Y@51jlx~-sc89MIov>7eHl~(h(fv~^QO~<;Lfy8$GAU{Hgw*V87J{Dy# zGKl^W@nm`v#!|A9xlhzwMq4kZ=63iVW8t~mDLF6iu{OnP6C#FY=(LOd9Ol^d$(<|& zB$%BXgb)F@j-d;L9B{V*lKc7xZa*|Yl=z6(HQ2Kpai7Cw?u#aHIG>tkXEnKPtxyd@ z02(+)FV!*-_DviUi0CrsbJ|M24j0O^+9=j3o5Yh z%X2rJ=KrJs^u^(GNraDxvjw32bg_deVM*?dVPgtee2@Lqp{2)ADQ=Z;D9Xp^#C-K* zelz?KhADr0?lkr~9Z!^!DxG*#Q@@Xhj}p%f+z&Vl+NbAmeJ=+X3e!v+{_-Q|cxEC@ zR6=12qy9en@BfeGi9qE*#oPhcmn4js!|BU8Pqh-AoBcT}ovR1GR8Lf(W2<{tK!Dk9 zd?xQrUwRu4VZ?_5p9>;fXl?jZMX;=TyPbui$mL>U_NmwlEndvG>*}+ugUJttIlfLp zemJ%7qYh(0j<3B4-T_CRsb6$?lr91z#K!Ags6COxg(De_^O{qS6*lvTB<7_%(}*Ev z*Kw*!54z~%?8%u;DwumarDo$R>94Rr4c*d3=l`6Kik)(^FtfAd^VU zRyRzhE(RmaDPp9wRJp@FA602#sr2?DIK{S%tqfDk0J$5gS! z2h1hnG!YtXRaPq~eNS{S)qXSxsDz`o{2SwRe=Y=(1Jw`C^XVB|mkeyV0+kuh7)Fk# z!TKC0ym*n}&%?l$fj>a#7c%4=gS=DmL=#N}iwvNO9SyNDo@cn-qWG_Uwlkp$sh0%= z*D}jm&iM*ih70JrS{jn*NgvnlPwa=2C)-r}0AT;o4!>`;qb-8Uv{`KDB_eJI8YIwy z$w)ZaXujBl5|oJ?QJH3QDz7mm+e@mTR7%N+M2QBB#C&^SktkNt2$SH_$WAT$1`!>{ zb_-P zSLHl`*))Fkz4U=Q4%Ug&`L=q$$m=&u%l9dkFj_A(?ZQk^O!$iIB)h|x3vNlfM zf`E!dAD&O=7T3wajCi0{0ex}!lv7TJ#jMrhQKH!+4QA+b`q(djURGanLSSNr5n-kQ zdnr4on2q)EW&mw%POwUOCXPXA$spC^@gaF`)Y8B>O=k(DnO1_HXKCPxm(HK(+b8Jv zkYuRSP51kuuWMv8b_+^p`N>P8Y?8uDhDzM;`beHYcRsI6);wu=^>U~|3& zc_s=4+fn3wnUhl{$Nh%+uwpJhRYOruj^2At+DH+@{b*ycZ3H!#T60RgE^4gQOc|Ji zLyxK-#FpGM!>2uE)zQyb>7vIaaS`aC@yA$_VK|%|3|nE~sb={4Tmc_{+gD_2eq#7mW4iTZJs|z4SR(qvTur8e z_$w(pb3#&Dei(8~ArT)JiI*z7O|lztrZ~dV%SlK>mb9$=3}XQ29LM1{5Iqs!eEEu? z2z%0Te~H8g?AJpz$(DcGg8KubPzUizMXg>TQP87ENx*?O0Q*jrSr=4YSI9vj0l5^C ztW)51$c%0%PAcSiccVqKhnZ?Bt6nqs&uV4+@5;abAIozeAYy}Q9%Ne-E>^U#bv@8A z{Q~F-HgKe(<|J|`L(njqFyTrD$`iyR2*whQm^cU6Q4hNk#wGae{7M?QN)GUl*h3Uq zyV2zw4ZJ5R9+~2kQ*IYEg=1U+a<7$>ND1<;@;^%G1=yj-T*4pdedT* zVLk%`%sFRmN!uLH5E~S8cKVCKVUut&1MxOTN4#CN2v;z5Brd`#8~dySsUirka3re6 zhl_WXkqVTx>Fur8;z0o0*4wpnGO*!I$dsS9&OsustUIMHau4V(ZB^oJ-O0!Rt{V;% zGEv8;H&zdiAIXp^y$bT6n za4f*|syLF;OW|};DfO+{Iroerpl^drL%np`bYl7my>U4>ifLOE2jy``*A+%YlDbJ} zU42uJs-6nF*oVch51y~(yM7r58QP%u_Ow#qR@`}~m)&wr?cJ~~t_^Pc-Yt#Omj5BN zwjD1@cy0l7j4FHPeZ;4bnob^-4lf0HCw~r`ZMm>OOSw2Y!fcyKKps**)@szWxI=uh zmtZqF^{_4dbwcfWXJ&m9$V^~ocOHXFMzf4CCOCaccH`}q2)E-Aevj42ePOkbUGjqD zu;Wrg&k(9?D3XN&^$FDDPcU*kh!Hvvi_rhb_wM5i@NLj^lQS46Emp|3m*(?h+7*(B zO^5<=KE2NpGat1Yfc7!YVCUO>k2%P48iYrucbC8wfm`Q^R_=(gUw+h|w!24|94Nf!2qWHU^RRf=!cjcjp2j4um*5#O;eK9|6jllOAc*kt6I zANoI1pwB(RD`Ag=?crA^SSOp8$-Hr!#M=5~%%Zg2av5X{zk63mam|!~&nWAO6p~hg5DQ4THAsa3?3a3KGm!__+Hi=61q8DTW=R!; z_eDviPe!eL1{Tclse?Nd+SIhL{13h!{dgznBb|+B9O*3K<#1mdgVYOCZXW@W>jYRq z52H70pj5LhsA=h39*@^HZ||#h$6s;VuE3{%&}>XUV>S<;6#p!JSrk~@9Ly?lYvu?e zR`mN6)rCuct|@k5NOwMcd=#v0sUv^Zo0h1|4Z!i>q>eX!(V%NuBeSeUzc;ovX>paO z{at*Xjx*Dtd~vv(G{Z&7W@W1(r@WgU3N_I`tofI0}h8c_rL$f zl1Ux<=-LpT#79tFMR46(f19;!=D1?m)bLq*wK`em#Be$s&Y9|D1i>Hy2@C?3kn;FU z*$}*tK9%6Pkgh(gq0^k{a?sX$%5~V2FWKHgCuKOHdS*oNcWP{*)MIrrIuXId=rJ)y zh=kbZ;;EAQD$LkR^uPu{`s$t1IaRZdk6 zJJ57f%-Jg~VxRGo*hJI}`5}NU_zhV8S^eToqal_-BD9Or^E9{!n8i7Rywl){hGwK~ zwFK5lLl~P3mm+rMcTN74zs^q@GsKVDX>aJl6l3z0)j~0CeVfmCT3iwI zi^~W0$-FK_)8{lO2hU%oUwR89ic#`#AiP@vTSI1nY**S*Sx_Ou3-j1ufyY64_|W~u z%dA{oFfC4?o)!$h~ZE4lTqgOmo|Q&~JJ)-3w?q)L2gS`>&C-VhXA+V7XeN8+3>!%v18O#w3SS7z{`IdZ-K6}h zdBbvar6BYnSMy#@7wD=HPq5}F@eE|T_BMzKkyi5o$8tSgtN@zMk9+SsHn<#7j2ZJ$ zswY<9%D!bRobTl3ZNwBXjo1V*g#2#H4iE zv8Y8upVf&Eg2&kpDOpkWKQ?vhK`xx0m)*~Kbm5Fxxi>bDOigIzMmRRa#_GtyMkMKK z-fF8EzO?0nIPmYg>QQFr3=opMZA!@|>%_Ci1R|NI0@KM-QNhruD#m{WBPco=#Gf%u zmb?INq4*JvtF15<{_U6*XSK8)E1bPjY`yvXVvVU-A<8K*of%@7z8jX9ylLb44;R{P z*Q|IgKsU5Ip0Z!K7SdGIS;iC)h4VZo&K(v5zH0D@3EyYXH*F{5e61p-@#RUBA1=Rw~ zk(BAvNiG^Haumys6Os-)9~w+z)B|$Wn0EB?X4PPNwIF2sk{B=}5^lTEXMZ)fkJg4$ zDSAI>`;iOKe*$!X%ejZMTpk5J!Z696t-t2T7vk?Z``=jZvIb_`6M}jzEc|q$GGNd1 z)2~z)>36?m*l`48I13qhfqSl2;R{?@fV;?maZnW$1oC=w@h6$nnJ)pscEk2MhcB=9 zXGDIg9IxMbjvvGN&kS^tRTx!^k@M~ix(;?%I;oAd` z68|60P1N>f1lIB#dgt~u!CP{68OLDLIFUoq%85qKTVU3Mbk900~QAMW>%tPw&pa;xUq&I>^qJm8;7SY zqML>wL0QBVCf)!+GGG$pZN{*2B(qps3+vN$n+`MU#^cP(Aj|dhV4~ur$crGY9!y_* z{fADi6P%>}^Z`<2Fh;`6>T^B*lDCEapmlzPrOTJ&Ic<(E>jKo7@@dyWlvS^*a{{^D zM0P~si00^$VKkL|MV`fM1yE9t@%K;>GdY3$cyxsYDO27eWbNBpHH0~v9zGQ2;*ijh^<(k4D3Ts zw#MVqpd2RM@aNIvltE6isl8PjlE?0YSAj_v>Q1pd@y3}v#728N)sNX+3{g2@0R8lO z7A7De)>TX33fT-k_RI5Fl85_gOKHMI8{sR!bT*2FMdKVuBErks;+b}9q9(sCr;wIu z2dyD_a@QVgS@yQGJ`HUzZ`Mo_P;8O>OCGPf6`XWuLA@)M?6^9}HKmd^=p?@uYR}_Cg3hfJ|KX90oLEhsN|3WjV;yL2L)`QSX*h zbW(A0Kw8n}$;$JL4)2VqE@_yg^lL|x4tv}4qZ#=)oK}7Uw?;(Q*V5z4NEUk5Dh}Gg zG;~k!tJO{^#=yK3-U5lrbw|O=Sk0r32GM=(?R2UNQ@1ft{-Waj^U&O$BJtX%Putr* z@M|b-?4q6FScJD7gSn0!qLZ(i2Lx`PDU<-%hb}+2IEY3BkrSPOlLQIkbLV8}52gw8 zW2EO9A45A-`PwS~{ckK&Evh>=UA5)5nHjtoAM1ZwIOdtL)K~@_xE1*sp|MOR`k>r^ z+bJU)+OF^sho{G;_^$XE=1fNcFkp^eVQFSXJh19UZi*xOxj{}T!=6xgTHU1IxRSZ% zb?!t!hGsP2IW!tP8Y*H4_OA>e>L<^z;$Ts6?q;SrLuvp*rlWJu?J#>%;EPQ!?j7)192|%dW`e zJ5v;1#YzGbRrjc^hNJsiO;t0Q<*;b|a-gr_?b+TKy*7U{M|x-wfdqcnRW*}zv#yKB z5~FL3CsO1lVNw9dpsBBCQ$gnExRAM`Ct}$-v^3|bTf4U*Te0k1@*AE5>8hPp`~sVg zlQn-<#pf>OeJ(Q|eM7r+v=bdjZ3O|aLkBZrdD|Wdy#1A00&gEZS}xNk=@q%7`yP=N z-r@Y9Wky#P9$hS0{Nh9!ML|$`Ir(|E^$eOhod~99x#oT-cYt1ox&%w6?x>w8PX1`R zWMp*Q`Nx^tX*?M=c(EigYPMDTaPn)R1DeR>!0Q*KPJ=5)xw~F`)Q!o=X@k!4@=>O2 zmC-kH=HVpuz4UxqXw7_*M`t6Rb9GVq28)u(<#R$(q{9ixCTh=7(|X=?gJ-d?^lX`) zYOYUI7-nu+K|TONcI-4BSj%%|cRtOV?1}y|7&Jv320T|rch0oGA9u~mF$;V;xv(Z{ z>oqboaTx-qWHxTqibUek8dm}%+!e^!&4iVu**$q(ay?5EK>aBGgRvQ6v1#T=Ojj?% zrHK)>Y5~$)y%8x!hoykf7(E5TgkS-cG-ntceLFkkI-4Fj;>pu`YLSKkwKO+F0Z!(S zshBOYJ3L2RUkJ_G%)EBla4CA=JMT{nWWlLUADoqV-#F1ka=j-7old(9I^ld;?5B6y zewjFk_q*foBN$CsfGW)NP_YUO#v|f;Mbvp=8=8JO70iw%x-US3CU|F#&2Ip`wF1-* z+zVk{h$9C~ksZ}stna)1Hs^9AoqM<} z7k#Lw?GGivOPVqXA?UE;L~E$4tu6h|w$d#k)3s$w_zF2&f7YPX$=6b0@(i|qWHMdG zkri^R^U}(80DbtCdhTHPbiSWV;-%u_*xX&z#dzdy9nWqij>`H$&r$=_aEaUux&4ZE zR5JvAO2x^E&3z(JC*Pb&*LN~IJw1KUZ2C;XpdwANJjh263;==?$A*J6B}LnY7Gmi$ zzbn)!W`w3)w#Lw=M{{ZLv4&n~V_4^+8Lo}xOkdQc11n)0nDdncP#QD1Y*v3Rk#J38 z(Kaf7`3gOrkZ@m-CFqt81)f-Pyf0YKjcM4Y0mwlPSFc5=gEi(AqO}dTW z9<+n*&bwR{E(G~btHpYqa=^7$ZS6pC>80OSh#t-O#ttLDMsC55|c~rlkAz+ z(_DlaYBOa#H+M|)(lo9Id1y3FPOIM9hx!d;lZ!8VLoneg)}Uo(j>m)l{{L8-FD24t zWl4w=L%?oN75|$b(ClOP2q%-yX??rm)W}1mqf2U4;l?*Nh{ug%Nch!V$Vi9}#eECS+hs~ey&?x~Rv@~vUQJu`II zUW7jZ{}`)7<5{8<5#M~z#hhTO1Sp=PpbKIG!eoBI=2{3^A`wZqf1Qhz9IX^07gAyJ z#Ct2o_y$nrs#Spf$j_M1!TLLP&(C*Q*O9`x>L|{dIh_shgrB@YrCxPNCi}3%iubyB zPv5>KW3r`zQ%7G;QC~rrJp{!Bo+BGOib#&t|zo zj(jXlyz)Z8>0SvZ@X0che(sZIG^TQlYF%ceHTV!D8X^~@%VbDg@)%3A57IbHwaq1J zIzW=;vc+5rPY@o1rm@=ELo#cV<|vx^dirL|3_PYL!)nI>wf3t7K^c1%Sscw_#HoR? zjicXQA4K3oIoVO?sHBDIASi&J;dXS}vy=IbaD&*Sif^=6)n8anF)ic8*h5?o8EH_a zV9WyG-gp5|oracZbRjTKO)sqJF1N#o-5f)Y!`|uyx{)nG0 zz$sG=AN_F7Pqx^Rga*R(paSV=aQDJM_Y_6J-WnieXU$SEMbGWkwrvK#I?l5?5wwvc z)9RBY1Qi;AEdIbi;$tF&p%2qsV>Z=KFOW^QzmEeyF2l<3dhE8%?l+nCBY|vGOISx| zfky*9itgv4qd#NoO#hvQRvxPEv85rA{*YdXzn4{&ob<5}?62c2vkfCrJ~-K}*Tr)H zvD~dc&~?_gz%m-5ZY#Uw?G9%E_1-m~oO{$egPX`#rHU;kA@>fu8obkh56qI)|XFeCV852bvvo?z6Zg`8qS_%hmd_-8`X?{{Jg~ zbb-&*5P}1PCcZSqbTCFH&(J3!U8~F(yA4-#4fSrgsAaZBK43I)7VQyALo~kR(A~JE z{n)Bj2SDjg5E>IVC3r>0#W@#bnXhO)liQ^2F&{f7{TYuO^KE>b8mo&D3^2aO8+i_S zDII#UnRC|Lv9U{2LUzx7?spG{OLypHs$IdMJsp8gD?*-oLA{a{PXU4xj6i#i?<>F0 zVqIJ3%IN4PPuCg1nePed@cCxNSiT~E;h<;UdjSNr!0{Lzp|dH6@7yF*XkZe-w@1xs zsH9L*!k+l;LAj+I#h7^1!GwK?&J3SbbGi{JOfZG)4C~$;AtHD_W~Tey;klSSbhv&e zpUcvb^%|+;-LAwZ=frIi>4P_d&`8(jy-^jZ;4{{e+Vt5~)W|!W2HB zUuALSv7^VF`PP@M^yn%ff?pF0!vFjH-~Yz)ol=Gijjt@@pz#eI@Gl6i%oWuE&@jLS z{8f;0FW*)|VM!<^N3XiEnatiOoRQAq^XXK0Z1afevaO7^b>w}T`!N7qc=n|+Yk<(> zKtOSsBneKTO-49^)(@_sqG1^tZyT9PPDUw^N;1w#4a}$k z){l?-)C=bpxv_f;Z{3^jh5+Ytjco7W^NrqxeLUiI0d3{2;_=u}D#Zs-H(5qrcRFD4 zyz;4gs>plKq&1RMR!iczE@L2xrUyfiFcaz-g>4@1BL8(uAdFwDXNnh@67ca{xdM$$ zr1C%GLpnL=`DZ@V5tf6dmHa1q#lR)1*hnUEi}L0+k1Ya;2I?LYUhs(|b$TUwEEzk? zv^#!rXmJIJO$!#E<7h>P>dAEh_qxBiIG!+&;a*W%dyx`rkbL>DeGpD3+GfTLH;75? zUL##UuQTY7M8((?xr%jy_dC4^d2&LxVOKn3dKr1Ab3(X-x;_$$9ZEBqW&uYQGy#rz zM;HHS&MTu9GBqNL4pV3J?!Q@r#MQ-&SLW^IaWp1l(3j)ss+j)T`Hc`hy}b6__%gwA z{NnD6>Zr<@GfZKyabuO%Hf!;UwuGK6%9Vp-tGXk@`*xb}GIH7r$lG6&6_i4tn1gsC z!B=7*-$K(eaP9}w;>gcl;DSuT=y4Z8&56bD^i`S!S>22#;X0XPPqse9q}b9%P!6A}cjkoIkn92s!u>P+#ZH=V>t!B=KlIJ_q|Oq$6+8V& zN||XK$_Q$Q%_C!6;%vNXIRMchgkr0QbL5F@nP=|on4EdrfSM#ukkg=KHfec|bD1tj zE`mJ6+=RXBhekDU+;GH-tFef&MDE)tlV)MJdsd9+c)@!^!YV!)L|G_5BhIQfwk z4-fAXS-;u;!ulRR&~rQ} z%`7yZoOtXz>eSmfCs;;ZGwEPB)7+7&;WV6~+@$6+9A~L{SU~4|=m>ZmJJPY=Yx5hM zR)UvO2B8*3IGQ_nNy@ZOMsB*L;APanc@HYoL&s`JiZ11W6S|_KVmwUWqdW3DFCSA% zdGi>%&Di6UJcJvAeV95+oO?A}pnudjqcj00qI148EX`Z;v*z^`ZN%&2{{coLq#x4? zd!$OW$C;u$UG&-kBJTh(3-HcI#OJqaIHoAfdwsP9H#uTE=fyDlyRBZq)bXWy1GOcS zpx8=$_0CEiv&8(IDvX;71TacLUqc-9RFva{gV048@kh(}X*7+Ht{}weJHY>(o#?kH zwtU*B0*zzQaY-__(labkn+~Jz`P00xF1t)^hYuX7yrXX>r^{9cWBb2<$8xe*Q|!4Ja?#hJwAlogehAH%=jiVgBqFS>oDciH!Yi_HWVji>!bktf!OxLHc@#wD*0Vj z94#Np>zdx; zj!{D=#p%X0Ei#L$onF2H*jd!$1VQGIuf#1A2=n=vbGL$gue`O>q+~54z0BGQQ9hiQ zLwKGvfqjjJxa-ujE*;V$9@zWhur2%hv) zHhyz5{ipBNXn~vlu%C?Lfb{*cJ+d$g-*zEq-Yh(h7?+%Bqc05X#}V3i_9*b}O4&Y( z1!R3NVJk+CQhPc*1k5;1!gL(KxHM_T2_znPy`Td*Q!9HB6 z886k^a+F+*8{Yh~FyiEn`o)2ZA^X{(Q5<%XSJN?nGyle3Nk_9$ea#druhoafpcI$W z|D)N13F9HdP&E0{bzTNEVpA;L}%4IHBM$88ZjfuKWSYP68bCA5F-`25hcl^#xje9{2_fFf}q z0o$F_(Fp@)fA0*}lzly%_R0A8N|=VO8U0y}HV$+m(QXkkJj1;RwUs7rU0CU%+;346>GC4|^1dbz79)s<(=|6a zRkh|{q~Zc287}K;;N&C%Q066{xPr~yxm#DzAhheTK7BTpXV;FJTSDdcT>>`mc{0nA znAIh*H?)x>t2n8tdG^4-Z<`9g2{3~+hO9)^vFV1v^(noP8Nc7jJ9Hu*z9$Emx`uiM z@kPPhslW;I6NrEZIw9e8K#NRzUR>i~B`J1C0ro{n=RS^` z#G66(N4b+Yu#Lx*+*p$>Nb$D$qcaGqz`85oYlh*B~mNWt%F{Nk2Fg8<0athm5 zLeA0HG6(zOaLB$wM!v&t!T2UhE}{XbnH%@g>MB?pcT-MoIja(>hh|a1Ne}*$s>_J_ z^WA<0^Rx5p4rK-}Z&4G~L{NOURlU%j@+wq^bXJ=Wt^MRNM@z`$)$7j>0ZlOPg_I-p zV&|3);&j89;{pxeX+Fxr0TshY=jLKfk0Oqx8X#0ppeI!}>r0*De3p1v zsF|0|C&6xSQsW?KHXFax#M2XpwNd%jws_}pW<(()9CJi2OvqFfVMimbkQBnqOoK_d z6g-nWpRXyU_O;zaMls6^LVMc({pTUifpa}dP%?3Pe(g>PwCks<*OyUQ2Tm;Fq64^l zk=V$T-lLaI2&tZGoSKU?Zhn;11LlWoB9^ge>;yc(%bnJJtxV#KqKC%(FU>Ta_M$k^ znC_mOb<^bM2*J;Y>IV|E!=DNz(QFE~vpVvy4rm&vmGa7W^i5SmUTl$RRRyhf9<$SU z;%Ci3w@NiU<9t#kDwE~I{7r7Wb{)3u=ELIOsraHu$r(wqh4-&^lw^NN=*u{C@LpSQ z{(fh43p#s3JbGQR+Y(KyTxSH%D4IWs)z!7+@y3Rg4uzTTU#;j8|k5pD!E3VB;`_QBL^2(}DWqkneN_JtT6JeFPZ!`n+y$dnBlgebmQ2 z2VX1G8RJ%oEu`m)>2xbqQMkV~gYT-p?=|k;6~}qHum#%Q`5L=Rf%U^3`O&SkQWS4M z$0?vG$1pGt65AbiJ6kg8&f~Ex9O|Y`G{A8%2V1s)%G+W_odetn^+zrgL zqT;-B*+@_#K6duG3&237S)nCAD=+OJqQ+DJy}GmeTPrOd=hIgF!ZL1zrY<3|L+geN zf0gMbbsZijfvS#R8Zw2hT-%dE^LcIp8)?HrpoxxO*$Hn$Q#P90EM(eRXaq{&Ng?0{ z^vZN*o@~@tjse%>j`rDr4mG74Qm=>4x`XmW?gYt(=cy!b3Q6ZlCnqF{FDl(&5n(|*Bg znHyVAW_IuK6`YgYBm~P0)QOPawl{E9szQAS(XTUJmU`q#(GF|_J`&IjZvr}6;>6Dq zvV-l6+y7GenZOPfE76n%fIE2w`;#)HYtvO=DP#QsF3EP)o;%$xqRG#PGs$!|tnQ~m za#0enM(rR?Pav_1wBv&#L0}47IVyj6Laebt)~t2__Lzb0etPoAT|l)*(p>9~kXqMg zMIlhgON8V&fUROg=#xD~d%uI7aEZu=uH%bPtNb2!sbiQmCT?sk?~Fysr~)n>In2f& zS=o1=jFEu?QT>E(98t;|2!v5WGU}#DmHqKNj#Zx!eDb&=K%G=k7X|Ds3=Zd@kT(xW zNQhVa?Oi3}+Fy-P8V|$*X>$*e%r(+jk`X8^=411o}`)I^g` zDzPw4${^PS@_z<9r|@EtZDQ~xZSQ2}7#`PLIE^nZGG(&5zGsGtD9aT+;XRVV_ZKdu z1IuQ&ubKO=+VAb~KJsiOnPWi3pkKPRDHT#jqgBGYCHTynA_7??yY%izam z=p@E{IvfP1$IZ`@ppm0wI8s-ccGNZ)`s#AUDwrjzIgP5V&A3C82Y z-@jvdjxKJ8lT_e9kIgeGynL*(Huu4u$BjJfYe5*<2c${b&r6&>!Nql@414nRS8R<< zff&NehJDfz!+1B~i^4zWN)S4AJhU%atIpgY=>eTFJ)Nk}V^_)@7eqPf8Jc8(n9--^ zDzB`huf*2`IZPC9vOglP^?ppkIifP0eiNk-0PBnDJzqDK$PB}B_u-!9nh)Sn{HVzP6Ex5;$Yz!LjA#aKafskxZ94V zjh4QE5*m8E{F_-gPxJ_g6V0fQ+y{$<(bhwxTPne$@SK=_3qjin8s%v9 z3iiY2m2S6%PZeC9l3*iS(sO?2J+`c=Dd%<|tDbae&cq94wjWv~cL73Fn*<}ER03oU zUg}`pJKY|odDLbbh@2KA71UF0I)>l~6>XB+P&y3$4GDORu_5M^U@`S)sZp zu|lNmy3q?EEICFeG;l{AWIwjK^zbp=V(ff(^f$ux8-;S5)6eED{(r@lQ4LxUAZZemoZ{xV<6KDIRtmwlKu~Lu8Jh6J^ z1|ky3C6Jy2)hCpNQE#@V4+728SLeicS`TWRSjj!G*4_3kmIT7aXE~YlazL;q=sd|PLVv+o@U_ZI`E0vHAE`P3~ou7IAS47 zG`7c%lwXr>qun|6o$k^aLmsL>Q%$>VwE{a`W&g58eIpwZpB?jNZ-BxGWu8R)b6)b$ z)Tl9yYX~6J5IQ~}MZ@FSrOhm&Yn)^r7>@R|L2r*1c#noBcy)9;NG4`(>*4XIbbGVUueeeLIcnmQBqjLwkzCL+X5VsPVj z@&v4tj!jtCr=iib+Ov2C~Prv(;siuoZ@hs0GPL+qoKPphma*S)f)t*#G_-)O77 z-}>uYkkn$l@SqF9a#|YBPee; zj#BTGR*h(#9puss-YaStEWjr4A$r+}zX-QVlFIE<42yS>nDkd{=kfPDNGite#x1&P z;twhx(O1U^gy49Xw>(H-i@r<+_Mbtuz39zLS)f=;w z>w1}Gr)Drb!D$Sd?oEkpdV@%^JzR7ZnJSdtiPo`62QBRJ0nP^2aX*vBGL_6P$ALYT z2ZuNci|?#!dy9neMPKJl8fqSrt0hRW9^Q_LdVlNK32{q4PsPL_*}0sb&kUstCPpc6 z*1hpTx_02h<2J+j!Qz;7sW4_5KvID*N#9+1HlM!Q==qVfxT$ONPK5q}$W$)U&{fPG zkM3!)EUY+xGpB+Gl*?&l&!Rgp#$NJtiU4kd*kkL4Ys}WeR6l%X8Dij zwfHCmNIL@&JS%lb^N`KNzt0HR9a_%iM5TQ(?v7cU_gM3MDnT5_cukxGOwMxUOSNb! zMn!g8k&)Ost(De`Qs6}LGQ@a@% zuPAW7IK~p`t4Yz}RhBc=q}lbK=GTu1S)OR+rS=Dy__^XI7qkja*5f+(X)&?(L)8+! z-YSdKY3ZF^yo-=Yf_URqwYsP5eQ^ZIedFWYKpA?Yk~Y`>4eNrsVRqnc7#Bg^7I{;O z8R%IuZiWd4YzlR7S0w@TKHE18DbX40tkh+=IGfWr4QScXEZLk4StZZz-YNEf1U+>j zOx|Al5ZU;wv!)=w4uYoHPL*{R+P4DEDfCjWoqjks4KEWE2YfI{<$m4CsHDD2M^QlE#2{Bp4Rsl!NYs}t6YEabm?mgRweVZ^dN8BLH~6Dv?Qa(;H8I8iyu7|@>~MGy}Cb|uWGBt&43EcMJ>-)qsK9m zlcR)TNEVOSo|N}1#m+!_@6H8+pAr_sjIP;#(_Wvo@rN1YaoK=RNHFiy&$OR|(>SG} z22sbBCLM~Lv6US4AZCJeUSpc#bu6g)^*raC1XYQKs=&M^n&R%MmyjAw)45 z_LIF)I37lG*`Re}a@95wH}gr^rGPwgf|(*)Av?6u+okN?=R431*^(0+i~a*5rBCGP z>G*0c$Swm|n`k@=7>s54M6o^Z5m=!rbEJEg?mA42f_267VSxT>)PXjAiAudpp3wfK z<6VB<{)zbCf5&pw(U6{|<9mCA^$*a7MBMnYH8OJ}_cpAiBvXdurBMy5@VgH}IvZ~S zS&d?iwr%aS>AUP8wOyk!b24TQ)x{Of8MEHLg7gVsNhdy%z4Uz$dMVKvGXp{+Zx%}f zXLAP~jpD1J>o0~pmjUBmdS*x504h&}eeO>-@h*fOM>JuRgo)k_IvX1aa`UU;TWNCa z*?{1Ng-zOp;>S@gA}k!Ag5vnzU}V64V|JtTCI?Qpn2WWb87MX4e(IbMI9`y=)Jz;t zzP*d^p-PP_Spo;RtC(T(i80x!ca9CiF(WyaM#ea@i^SPkT@nn^6 z(vgtq;F)(rp0E)oVflpcFu6x)=U<`6p^qktmMp75op)WjAUGR222Z8 zK6?e!eUk%mMD)l(0%u;n@nGNpIk&ZEKU54mbH9WJlz$y)Ekn4>N!E{tRdt^h{D?*x zYp}VV)?3WBo_!zck{2gT%*aGD+<FG~DVr^QLB46R;eD zo)OV_dm1zspWv>=7U_dO^46Yw_R-<_Duk=$&ow@1mFHhD z1pMZ)G1HAJdor-GU&%;Wd@f*kCC(bsyCfkwBBz%l$O$F^YIfqR`;Lg9re_HYcx+DO z(;iA_PY$wXaEpx3i5I;`Yc7iuj+62DG@Do8O{%$yCXF#Krx6jl8(ZYOWR0-vh_&^( zrkhOz;tVi%WY(^%7xeAaBU(vwGNV-Qbyr4(6}x3P0&^nF9~ zWk24t@#Ujn)ODeA+ArdEQ)0sEXP>a{gkf8 zBcgET1m4W}IS%EqbAwSz72bPbn~f>O33(Hn9Bn8EvJd#5?1sqYaJM#6n(nTXMy)-1 zH?QzolaO=ep=l92b6T+w@%6${m}sj~%<#(Jk{6S;aowYUk4~m4x98+AdQBKk$2SrJ znEsM6O@GrdC2y#j9Gw)W)-rdJABX7Rlkt;_CQR!VETucl|M%aqT-$>anoxevaP9!f z>cr1=yArIl-9LEsSZDwrN2oAjqZ3E1WXmayIZ7fEAYU89`LUId7QUqA6zOUW1w)o1 zuZ_90=A-xUY}<=o$WmdU@}4}cdq%0o`=71isWUzPoo7QKqm`2T43>{&&rUj708e=1 z&ylFX5IhdX4Xj=L!Tx}TS}K;JaeO?e5xGFbpd7+-fvwWdx>2aAY(_fxIKF}KdePs> z#Bnp-e&$A{*C#yNc8+!1JqvgZxT47%_voPX?nJA4aX8^2xw%#JcT(CU=QHLdyQ~T! zEsm#}vzoGzCU~1_5-FXTT)tTncsEfF+^E)S!N#Q(rBQP}LXXe5ox49t8SZjYe#zaO|vD+hEt1C6Gil<@7|rcWHr6HlQi}%Gme`E#(+{!eF+ZxQxYf z@T0%pA~$}*huJT+G=FRD44Kwzpml|*bKjOO`fr1y&W=Y)>gXsa-drSce+1v2= zim1>Z8f)2yq7~ah7BedGTY%lk%#Sx56smLB^ z)$(wT7s;x{v|ji10!U0tqq8k;du>MN$wI!S%E^EnW{{RC;TC*31FZsmXnduGIu#+bKA603-AvA&dRD>GOEC`#4~bSEUo)*}7EZ>Qo_#gO z*q0$>+`Ax3H?*2kkwfkFzvDiRDWsvjl>9`EEJOn3rM;pS3QSdD5XG zz&Vzp>_C%|57WnP5D75P0RP{A9w+4Rb0z_Ow6p5yv^x^OOOwvQQn)9iZl2UWbAzl# z9wjouC(1!72beL)%fVN{hujQ_M=k}J_1V5E?6CL zT-0VVaP`y*lYOD$BxBAdYrCVX##dPZJlFxuglITaG{vva|qDE3L_2j}PBpGzU5p++v0eqm04zBw|$V9G^+ zoQ^*>bYydf__D7%nQk~GnOY%24Mfk}x?Tm|66AeQDNHCAu}Fi@56;gs3y$X_{x-1kJRFH}3R^qJ52uYXC9TluO zj!^v%w9Hq|k_l;oz=km1klB_oc%qQx9627P$Qw?gnI6-=zpUdR1CD4EdB15CGUCq#yJdqYV5V33)pVXKgWVL|qokxs02aJ3wb_xh@g=~6mto$> z;MLjTYTec*T%=iMkqVTHK$qT0xuQoCfIp1z>^d>{DvJPr>l5pJ8F&PKqUgaR`B%`b z9YoUa@ty$Zq;6CARwhWFy6>|gR0a$s<7~oCe5FOEFHTg7gDEj*o3}-5ZYs6SgwZ6C zQxiI{-#L?0qe&f7%C_wOrH|n-A(K%)Yv6IS{5pfF%4yv zGK}6%9X|3ThiL{hDW06|F-RTG6!&oDfoPEICISx6Ol?zLEhsIHJNZ44TRl0MlX`UautL_)+_e5U9)a#y7b@aSbsT(Du+oX^^Migod$UKo z*hwHOa_{g9W|C%`0aWySm@1wXU%6)$pC zXlzn9ImP8AS4`en6);ml2fZRhWAfq9s|d)O+20u_T&)KT4P`s*?w@mNm>myZ)saAX z-fi-vx~Ja|C39NEp694xO4-WT34s&C!(@@z1-fV(Wv*-|19lKS!eJHshvgr8)boEO z|L;HcE%=IvQXfJ4{#kkQ_Sp+=VH-?sHD|bhO@R?T^0tJTHwOTDkGhI{vD%lPq zwv*1G8}s(-_Qq@|VGLgfLfNd(Y4O~TnduYcViUfOhshE%^tTl0YDx4hE65P-0soO8 zu-=q?xjU{9L?V>Q#C9g9-9+N1SJB>444~>4gI(^BriD{XEq}JO_8dQJMQm(UkBZ&N zmq(62-szQz_L<MBtv#x(9vNDFJ`mz$ej!9aa;Gkv`q$wy_d>YW0V*_o-W8OM z2_KK2HOwL!HO`;vHoRIX{GrCAamX_qK(&`-Z8z=ECobL!$6Rj#qIvozrYuNEl0^rV>gC3SQ$_WQzO>~S`HKYO zm*jj_HAX###YoD;wfC5o93zbowr82WSR+1WAg2j1*@@?4_aqk^lTOM$PASwGVe(!B z3$~EH4rRM`q1{mD43NEjH?*=kXTvrrGvzJxJ8HHRcWQ>cL>izW2!dCFk8O`?%?jv^ z-MI$uJua7(07uBgKU=UY>>H6g5 z;&bzAF}X*;tfryX`P?8o`MOLF#(vZ}`g`_chrh2S!lbH3_ZSH?WFUIQsym{s*P(Mt zaUhM)TZS9s+IFNfev|GZ;_Je6eZ>CT|G)oLSQ6tEBBc(IcUI=KgiQK!eK3|s8L(u1 z|N8oBOD~KQY|K)OS#g6A>c=7}U__I--}bdV;Ax$^l$?0Pc7yRU*ue}rvVJ{Q6uJYz z9Plg;ogYT7>O11aPgEH+bH(+r?}fFBdo$$NJKl1n-kAxl#;hv3b8E|TmTrMGis06F zXxQCeO!!(Egq~|jRic1`2SF`?jMDDx_HSBys_Ba>s^c>4V5*lR+IL-1P4#pJsa7IP ziB`QZNaykXi+%`k6eH$#;**&Cu#${S8xj}>`g^!FBbM-dhUNIVyh2%O}(<)?hWCw-5!dKxxiBX~b ztfSNvYeTlqgEztinmzdFc?1he&}ScQT!xILn4tQBYADOp!ui^qX;{2JbT#1Jl~HAS zn^Vh*mJwI_OpzrPNX(|K^SI5`#1mR4-Vy9OzU0M9DrqE)5no3deg-j0tq>77ITpcu z4am%Q+6+?rf<|FNVaxDJg7jnoS(7Fv6~{=&gWMVb$4tZwZo+_oKAV1-W5Hs^H*-5d zffLL2C79Fj490F8F*XIZUyQn_jT=ZU-QyU0t@+X|G??cA3Hc-?hPmypqMx|ZKo4Qaa6~7u zAfR<|hT%rl`3@B0dz81%9zmD%l_`Vb*033%H{67_iWvh1o*+r#ch`qn0N zP$Q-d(;2rT9$PtX}ZBd{c!gt zlc7K|8od|7o1`5jy%GtLiVdFtBPg`uQ!M_+e9;_;jL^&YHg7BX4%1?(rD>e`MDzTmStVgGdGrbhstG2=B2YW~h#3Nlz={%6KY(z3Opa~O zL+=FAv5GZSqWK}5(>4yy4qad;ewpUk)RKEtr+rQc+Nz7$5cAEDrcZB*F9EjyHl7+~ zI2t2^G4v6C)ZudTDHrx9!y42G+kjkvVh24)sIfh`|L_c*Yd{>`k!(FG|M_$d%KjaJl&pg>y|wK?K@Zp4m#`3p^rJiI3v8#?+C*O;)P5BR=GFU;%Ep z9KVO0zdZ^8@r9IHOR>xT3FS}4(}dH6EIaw?B4g1P&YlyGU6pas*V>}~($Y(l>pN2l zK5Te31jW_<%%LJ+b!HcUtr!=8YIZtRjs%UUx zqzwqB>j%|Xt$FT#Gw<~BwaRZzM{k7^S{^QRG$2{a3a6z!>eD-&)>Pq~ln>$Q({A4wGA@!$xrlnmfxNhB&RZM|Hc!~v< zywl=}&YEh~hh> zJBBKeOl+j!Tp~tm9d@SZ$0g9=lUeK2NyvpCbmTPf8Q07id{1OZ`dq{Ip%k-B;TG#O zqalF1bTx!S6~o$yC^2o)is<#rZO8a_@ExPlhwiY9A!*TQ&}U;3p*o=i2b;ihRW+63dwn;6&d`-6{)Ch=1+#q$T zeRS&mL7@KzIwkkn4v@>jw&7KZ5a}jBJ3mO=t+_PBGM<+3Q|YCfD^9ZZ)8BKEFR$3_ z_$1(y8JdP<`J-=g!;RzqbH`*kc@teh%ZsBA&76`r?*I)HA}&4*?_Hxew0{Pa5V_=- z%pKkJoh1q`BKML}%0>)`|4iTmihRNx&3-(_UxPcT{kFZsLS@}nGQVY7jU=A=CEz0B z`~hvb^{-U0g_m40>l5E4#Jo3+2RH;EgyB>J7%pxfE_@Z@wv!*p9dsLV)*trgQ(Pl% zyk1&e{BG7AZz-w?qO~<%b}e+FH0Aa=s+~vZs6@G6>RrC?#2$b{`T4pxG|U;*!^RdLEp@m_U*s@+Lg61w z@R4%}fYGrHGkgtRVew{J-{~dVjRXaB9mM0N13U`m5>a`2RmzW5lW#kf41$|&h<|k2 zEFN&dKVekgEtatvEhjnUI!8M$&JVJj#MHP=ft17#GkoUW;9%qDCYd=JHNyliX@R_2 zkW;tiJw0e6%uz;{4j}IKdI@o3Kd0GM@ibT%K9@(eZ62?#AB5?O-j$Ox&*>j;`q~a7 zq8^mwOt@?$=`}22S+gt=X|(Dyr>{bY0l|uo2@!Os5c=dTl$Z0Xey4p%x?y3Wm7f?5 zC(qG?J}EhNVb31@slHB6kBQc+fOdWwT?5HeH_g|dWc)G0biBxw_6-{|L^x#PB(udQ zUOjG)4TETlb(3TA7I`GHtAHEw&8!JZ37SV%0UsOUAyo{eEH{g?8H1R_8)DLqR{M0D zsS{A!c%1E*t%{eXLvy=(O0|iC3EYdO9I)Pej&=*G9cW-bDm2885&JD1)8?NK@p!q& zOd_xCe42$bDag(r#e#S&8XWc#IE+;e24QHeu^lD8+j|25z2}Hr@?~)NB+o;s!(qaK z8*k2dAJ@8wFm$ql_0Gx@;LT6MrrUdl0hd7sW$LzRoYW)hCV!K?oaeI-#s%FJ#9n!= zhK6dfBYnfOBmKwA;9+u&dNL}w9M|qpv;ngG;8704ZhEd@n zW=)ol9TQ&PoPVVEDTJBeS3-fjLd6g^P%ESh-!!{vO@ufvMKcMa<KbRM`Cz_8g~{0#p_ zo+BHVv3VZXw8P6ugkZ4)b$~EZ+^F0M>Gn1vN_!9Bd14R)!_WyvybI9)83)XcpP ze@>2_aUjZcLRasIQqz!=x?{shj4qLzTn1pxDKR|T(pPhb;)D<-d1HgVg11;JI@v`x`Odw;p5_eNWgXG_swHy41jVD;|QI!tzma`iI zT3$Ort(mmM>miR0Wl@w5xmb&tTN2zU%<-o(jSBtyU0BPDDo_N@=R(h>wU^B>y0^nV z^hGQ#4}@kXWCi{&^J2E_-Gw<&?>7TYc5S_8PmkM)W^HGomrtya3~`~nCmCq_PTQGz z?%^WbxG{Q#!DeYXQ59t&4z6P%ZjiC5q|U4v7uTGn(e4DzSx!1d36nnnsbSq-$CNG) z&VuQ4WH|w49Ru}bJ5X)P^$g82yT&Hgg~TQ`K2{)un$V?XRUvNqm^D50od$rH*$>4j zaVAy$NE$+dVz_ms#&A=#R**PxOLx#93;r@n44L0X`eh()3khd(vje0VP-~(2eX4E& zz8~qM^XDll|77O3&!e3h^%AO*@W`gH&RYtYt(9=%`JTiQSN-m3<@)`}=Z4+-ILY^e2#9*d}p4UU6wr~J* zJ76DrP*fiqQ)02{hXA*%JiZobQ|5rX>{$P7UQG{D`LTVEBNhAL*}9KC>4f2%2TK1l zB!?%>oio&Sb!=yz?cs8B!g)2a>21~CUlcfDYCzH+INU6h$fmV%;^-Wx`^QpH09x7p zPVqbnf#=gQ8s}W?-L);vshrr#8-qjbNixEC4wJ56RgpH6VXOnfGjDDuWm(IT- zG}Wu9m~QCfqy$rRJBi@@hgXz!pckCSWhqF;-joOYSF6US!*%R>t?d#wWW}u zR|4}oa5}yoaSXI8587SEfE^@*LBlDCzD+fBJUV6IGqF-V%i8DW&x}QI|xZ&|3womn2Y% z)t9ChJTs1X88npznx@&{?ECSAh}-*xN!YSI>sWXQu$ipP?5QS{gF@gwjct2s7{lu$ zRWFOA#khe5{`2MolGwIO9HK$Yaaw2>*vFrUkSG73t7{D1{Csr#bZB1Mdynd-+&Vr( z!tbP+V2)mTQV&1e4hk{Ju6aF*&)Kb(Lf(k-j-I+Rbz@=_TnFb6A^VQ9u?kkuX=j_a?2aL$Cu8CD<**xuv}Xq5JDm|X{$(MEhdXe&l6zeRDyI+8 z(4Zeb1oHy1;@A%3$pIMO5c0ytHHX80Ry+;?q9u%|Jil2ZGKC4pvWG{<7xLZ3kt8fh za-kPU!4@tPAd^es`5GZTypSb^Bx+uIx?%DT5CwXw3P;R+XFM{of^FWFe0=3s@o8awTGA=xSGRI=>QM6U;f5MR1noD?9#ZICyQmv zq^|?+1vvTQnve{Wb%vFt7kO~ESHL%R8$H^xz?VwCX>KGGMrW>E2deEk+qDDmmR8a! zPU6Lo9B43L14q-yPo?L9TlQ0KKpgx=r*B@WPHk46wc4ac#Mun6TN(iIm%n zL9d`jq)pOmWy`6fR{;6}%Szce*9eAU---TJEaJ!zh(zjL1WYb7|Ld%%5MEQTVsSOF zRyynD8yf=Sj!D`-Ju|R}XF%XI$KvGrcg}crZxe9u%%7B0$R=P}Plhx#Kp{JbFKYuJ%D&&E~mol7YNouwhZissNsUZ+e@IV*PlRclb)5P z9TAzLggL!1W8z8n8KUDGLf%(1EM^+93To_zFECqdy$_xbsD1jnAyA!KFqX25`*$Hb zZA1g@JEHVCdG*wa5XL{}SX{dT0ES=xg&KDNSF$D(m-miER*AE! zg&6M-L9nBGGC!@64ugWbFWs5#6T!1c5NA%y$I#;pBvbwS;Uwi8a^a@O{X~MuRW&|S zNTR{opJ5(>j^tNwo9I+0fh$I{L^3|Ql8hTwm=TA>@6MJ?T>Q18`lb0GZ31XurxX25 ze43YOUQ5LFJXUa$ZJQf7rEAe3Z#Iia&6n~W)syCi>e-#W_by2Mj;AF;h~`jrWqqG> zz-E0>t%8nXpcvV$y=shq9+iD5N=e$A2($H4%nxc1BkJ;W4ir69K(Uv_N=De^g0aIJ zC}4syj4DdYp=Ko`IRut5Xh^)bh6HU{w;bjQj18MULzuHFD?RO8Kk3Bv zq{NHh+$1`mc2758L?5bzB$ykHv%h2v5Aqi63A6hrq%fj4F!ble-P8nLY?RM*_szGWlGe@8_@}VTY z!Ctj_r|D^jQO4L|M><=8OgS1j!$S7#iI)L3=k3=(<&YTu!8R&9iyt_aE@T8ZJ$&f~ z#5wBN5NSkR&4eU)!t-RDC~@{9ibx=K6?=6ld%JGdZIde0Gu@B z0=P8oDIYgI`?!G&>(-G#GCI~QRZO;1g&RFRGH==f6yam0?K?T4)J~ZYAl_Pg+@18c z?VZjewSzI9PI}6DAFfU%4c|PTJUi=goxtXlu>wK%I?$}cSrk^EUARd*Sr3G1CK7#G z3{1y8axdaK647_-##q$E2ch({K!sr|dARR-O)%_@EV{aI&yDLeOC$F2FJextI+)G< zSe@ms0y}%y4uEqe@$m`i3G+d_iO1WE^zI_h(J%A$%#}F{Uphu_UAf(Rkdk=1<2Ao6 zDqFIr#^aH^5+y%GlgEV4?EdJO=~g@B3dwCQ87dBNn6E%|Lc#N6Gx;EeG}j`^Wj4?2 z;-@`oc;fQEf5&p2rwjBt-Ht6aaL?AGL&Ux4BObAog2Hz_S;A4?i9o#p_PPO1kQ0Qr zlZ=J$P4q0lo*~w9yQA#vwj44(-}(Se=Qho$lJ#s{Vup%i7l*1F!EwOV#Xx+@n5dM_ zzU)v)hA`U3&rCv_L4Btg9sYFbVDN7M6S-YcMv6)pfF%L2W!$K^+y$q*9s9NQHErlD zlN@xvwjBsQxg%L8h?_g1Xt#z-JDN(AgfzoYMCN#s4k|#MaqdC7*?eXBHK+L~;PQG^9o2Hy@T*aiPZnS#`G$fHuA>P?zds;cd@;-$kt`59g z6y2PQ1v`17pf^gskLMHtm=8fjL>&!foKewQ70R3{LBuiiDqq!_gh6mZDtnv|&EK@I6biaCL`Cvx|=xz z>unUoYF_e{*qp>jX1IKrOmdSp1RkejsJ@I1G*Mmn>OjrUIrWfs*lMTx!rq<`Nk~Jh zr6EiB(Ay%1T9p>ou$RS(nb9(8viE}#%Mg`@ZM(l;IPW2vt0Dd#$hF)RAKD~ zk3;6lvC??I94oCQ&7AcZorx)F^72H8lH%ge*5!v`L6f&b@^Q{PLC2Jz~VskQWlVNM^|4?hqLCtNvLo~;j z)KDh$v7q{@z??%CY2e>!VAc#z>YmuyvLlKX=FlO)s1rE7juJZTJGoo?=(+qz+l^lG z_^gK?c~YmdeczG5ejPtw2M?cpkc2-~I!Q{zkZyNHzc3zFGLK;}6`SS{oL1RyHAf*ajPp`EU@Kq(w=G=vwiwR$C?ov3eoMn!ADws|q;O-M9j1#EAd(rVh{NX% z;a2t6`OUX%3VoSxxYp97hFx)P*<>;tt|1!+bFGPaM0Wzu`Qx}?rW#EURG{-sRDyV= z!%`>oE#g0hS!YBmQi#Eqe4}(-jPU&Db%gyh={WJ-=yY;C@qjd`ZP7>Q|39|QC`ppt zR+j%VyL$omzqx19Yq&eIrq7(|s!WmqB0Tsblk_Z`ImIuC4DDt#19ln=mRUq5asM3m z%~jhtSHl6}zAyv_#2Eg+U;KA0i4r`~0n8b$E%~~#u(bns#>@~DWN8 z=@3^hr}}UVkr$v3i67kX;ZZ$Ogx^uS6CM*L3yjvZ9cfZg8I()uW4Y}`aI0l38KSXO z(n0U>TXRR{kb~w*lR=%oQ=xsrBRla$6MR#XbAQk#njXkkG96TNeg{Ax!QtJwQOQYq zSTp74R^u69zsj`dPk--djoueX+xM?=>zs#ksy9YEqczsNp$EGvW+(TJ4AhMewbSoS z-!iynQrz}tsf~gV#>a71SlaHad&05FLOsqDAjgef1xU{xXU>A!>FhQ|2DwH; zcZHRnM$C32b$UAtq|3zajv#OnyD@7VX00i(iS>qz z_iiAuJ{u5lA_QCiy+Bx|PJ2|+qxw-!JqTe2s60`>TWOvh>EkF7#E;IKLeE_$I5XHZ z;7<|$j;hNxmZrneO&y=-rI|de!*TEZ9DlTY3iWp=(8r$~x-Db5`}fVq_qejpw2kQT zeCd68)BwHb!~pOpH22LUG%Qj6v%H+BlKGD!CR?{7>_z9y#S2(wyA7EH!-cwpP*r)l zs9OC!3sw zIS59_JditNhr#?`|t2S_$t09Fr9H|i7ry0U@>lcY`kY4Os8TPVV%$9 zySQvN>nqqME(_PwYW&T|Egcg?K0t9b==d>T-d7;>h%#dOTpxSNXj`-=X+lMgmKn7Q z@h_5N)N9+#->;V_|JiG{RX(B}o{mK&=@VdlUHF-x_B@llpYp-*!h>U>2D41A5$$f-#lik8@Fi=;b0bnZ{h(lA{{ABxiLj67a5Is5rZj5ho<}A>`qk(=|>Um5c?CZ;Ni!jMgYDQB-dZ{>bnTpHflzR=_# zycxQFBKsK2*Vo&;mZ_E!dyMgh0bmS+dlI9^BYieo#WYFKS3|IEbqKu;f80`GhvU&V zV}w?cE)pkQQKe5}$X^FLL4=5U9b~6T-C%5!t-Mt1sUL~fS;U;PDu_$&G>UrqLSXcZ zSeGyufcULD*{ze!47Gc?WaM34m~NBGb|MuyI}MU+a4aw=!KuP-lceX5iEA0SF1uiGnbiib@k7r6;eBV?vhs#_i6A2lk@ zsxY4YZojz)kW-j6cNdi4(?*bY!ac$|vG?qguEtI!=TvTN$e0jHBEXsFXk@HQtorZd z7_p*-pgJ)5Ie?_;BipD=E;GF-F9T+ zW~UQ8abt<=p6_A5VLCOMl^7zO%vUlrY_phaBQMQ5++T^!u3vHp!K{so&?B2(7n4`< zb!BSX8E7ZMG1^0cff`5mkgjPG* zr<3|nb1Lz%pA6U*t{E^KY=G!k?xgqG{Ga#&Q$!ao_~+1<#>6&E<>le(V-|1*YuFz| zxi8xmgIZrYLgsT+cYP8@$X?sc%g?|n@?(z=m0gb*=_?58eqFY0>aXiPSap*iPQ*=96qhE(a$s0)yoOJpl<<^eeX|DP1 z2uR=ju1=ppeVU>bClO_3ZU7a^K_{q4(=-Ox$)>>Y4N-bBOw7ipf(@jN!=rleAc9Of z*unFC*|GFc3;02-s{oGR57WJzt_}yrO%iAZhooTSKpck- zU)rqh8aVG9Eh4ti(Cwc2PKoaJ@zSo3>nNeG81kRAapr21@?V0h?aRa8s8pQ5+HJ=Z zm0^cxj9Fb2dB=%25alm83!SSsJ=derl`*$-x;)7(2 z=q;fXXIGL=9->Oht&=vAAS@#2hs8brlLZYdbElC6g=)vs;BF3QpM*G4-P1T|g!SAa2vEoKdW7 z8G@brQ}U!B5zhP$XV%zybUZz}=v3R)VSSJy<``L5IQ%DW`&W!hd;o51oK>;ssxA~@ zlOsFZX+X-kAEJ>F1n*~Cq6)X+K|xL~T*goUSgP0QcIeFG^sb+?GN08ENB8L-<`~Cn zLJ`Nd)4^I}m`i~f4rtAh?I$T2@aE)y{~gP)f59gSwLU6sTvvkDXx3C5!J!Qtdg9O@ zy*+z~O$f4D9a&pM`0uv_v--;K;QDr8juXx|j)0!jG8gwMplAsr)!i3L(rto;HHl-O zT=h>MS`WF8hYsHqefvKtGnI{qO^-9BqC`$-S9qHyUBY&8P19Mp>9~P@)22_GrI)7X z42!g_$9bk8Aph95M7qBh!Lu(ZDAHhvpQpdjM~F`2K$o-JPy=+~5UXpe)AoAYB#Tn+ zTkj9fpg-uP>CHALa~Hf6?C^nGZvyg6-~NmMqWX73xk8XnS<;XWt>d&UAUC1{afGK< zDbtdpMTjv@uOp^i_GK&65d`A|!Arvh~9PDEYs2@32_mk~? zu;Lw7iY5B&(u>|F6@*DtnmQ(mywSHT+Cxy1@(f{Gj!QI|fOBye?nEqm%wr@n$7`x7 z+Ty_`z0*AvRkci22}y#JBJ=3z(!zOUzAcr4-UJeK5?Z`7?+P_esJo;=DBH{t5tVb^ ziA6wN|Cw0YH;DOIG$uu5!lPCnj0ld95-h`7{i-HJiekLyki>4zKl|%Ib5eDXU^R^h zA`AfwyJ#;Qyh+WEX7y>(IUp)oMK}=*l6ox6F+{=EO`)Ur7_ps3L|SQUTq!I{9lN2J zl8{91o`dI>Fmh}zR%1Cq1`KbCCL2`WS#I~>XT-ok%4)dHGn)p#G}D9(o6mJ}RQ4!3 zC6yvs#WbRC#S_1Vg~auxGj$Kk_c{Tv4_KoTjm(@46qN1*WqrULr$BI?waW{yb6hh*AsWUHYf`w63pvn2We)~=~eForUZ;j{;;Y>ZyEVYK=iiB2C z;crlLDy6v#LgyXqei5~CsGE>;;-MJ5(ee-=6d}q}f|sg|Bp-#ZcI8f>Y;B z$|pIx8pq$(Z{xIVrNSgSdpKRH`*7H}wqT5BybM7f%ytbUA*&s9E9jgfNX{4(`;+GJ zthIQ##P+LD6)Taz^f<7>X-4J%s_hbDglze>FOH`r^dDOi(kfEYsVu>0*aKo-kZE#^ zrH*e?-X;zD$$Sd0js&eYQPP?VfKxs~G|;St7^hLQ&S`o>vCWoRf6Y-LRUkfqbD9Ni z2kloJgXL$Es2x0$0|f&`qquqIpb$EWO^{U94=)96Rg6~F>QS%2YsI$!NdaCMR+hQj zPwztS>E%)c6Pcf8kmr+BfRCqUwCLc>fn;?F-CkX=qHFJ?$Q^#|;Y=KR>3GW}t&uE- zyFcsY#v>0QjO&tPTol&KAY4p#!AV(46V?w$^BGZ@j<&YTDG-m_k%LA$bPW67f5%eS zwyyc}*jes&LQ`$4alo9Z1#m8U*Y&+#YE=b9zBzS`3cJ}v_b=<;CRJM<<~x*)Vy`K1 zbPF~_+o%<;Nn2fxR%qG)1xz0gxLJ4PRM~~x9dM>c{a_)k20_>T`8?QIb}@+FdPA0x%nD(>>c~-aKa{JJ3g>D_3Tn6j zp-xab6Beg?4a_-ctoi7U1ejNMn-~M{(fKXQ35ym(&i16GA-s03{3h|lskss?aK>bU z68)s@#A=yvsvt1M}{@TLx5Z;Lx|A{}LV0qMr`@9=w&Uvo~(`_;a9owv8wN~@^j?;NXh48LAMpXs4rBn{=tbLN@{NCNYa7XQusX{QmJUc4kK5*#o&wz$oXOo=OzPY&cd7klixdGrw*oBc9IB%4#`ELl(Th3VM{d~ByvS@>}`CvJn_1Ae0U(DC)1S?XBxkSmmEcebK^`( z3jD_Oo|*u?o)6i-XXYEyCKxt~w2m)+xanqCH0{kGGpf;N4}of2qmS8HufhS$OuY;h zk2&`ZA?sWqg2H6*P1imor#I3V zq+PLbjj@f4yho3%t!pb@0726t7sEdAz5YkZVL9uOLsBh1!9%$3jJL1EnWA`vw2g{TpMQAAqK52+=Nm>{{$QAdC_ zY}91g!^9&e5))}6`VC^~%YNPKEVLMO@b-1!ll+vg$Irikhs3K{ra+GER#6j@=R=&` z+Q#I3N^I0e%0+_Ux&ttl8R%cRH#ECwJiV0-9%=`-A0gMvN~97HH}gFbk`7TQpK_Vj zes3`2(@t$uK2Z}|wQORiPAQQs3s2>0&^0LPrW1 zL?}>l_avzl`Nw^Lm??T7#GCYM5{pV+LesIgX+oz^+LVSmfm80FkjbttEb@#@zdquR z^@9Cphgppb=FpJ`c{Z^4dPSvn`;Zt;Ycvmw;InNcM*+wTeQTWle0cDftbOT6Ftc^p zlk#WVaf6ZT$fT7Uu-7wF^lo|cChH|}Q(;;S&-i0Yx429Mo^|v$6|}zKUp9Ovc)W(W zmA9F?sR{X=IY(t8GkT&*(}($|R$DrGOqx379<*({l}4x@z?R@5D2t5UayP{8#Et|Y z$nS{6u%gRjF^(V5j4G{pa{7x+Mk)>~fg|b%p*k^1-{y}oPwd4!JEv7W!oCV?u&5j3 zUKWI!Z_>8JCN8yQZW|7yWC^FMDr@O-*er`Ga}s-&ymLq#`D=Zibs9M`6(d#*w5XYM zO%}pr!Y9vqx#Gzwq0HnluHGK2p~_Hh%Ln$_iU#rgSZjbzZj#mQ@qi*D(JP+aC|zo) zw0{>4qrE?S+PH# zmB@fS^vqR3q*kz_!LmLtr6M6r1)R^a;|X;#Ta@P~2BP+?)vKdN<}m6_3)KwS6lzoP z!*rt4G4`@3u(4q=JyhJ4 zUCznz7YaC77nST>5AuAD-scJDHykCT(P}=PEg#&rhVD3VL4dFd;Wc2Y8lHoX_F!^G zgmB4He6+1L$&KfMpP@*=&c5bf717O3KSA)m3O>SK?CnYR0??;DgpO{R;$w7z@=G*< z!^F~Y!(m+Vs?0*TCBn!qz?4us{(I!>U(-2a2XicyydS&wo9~g+Dod}7UhwXMA{M?8 zCOxe$2IT$yCzdD4XR71KRY#OQ3C#_0F9JbHyg5$yi}l}vu}^{7Nr?!&!r9F|%il)J zrXudSdtRDdk1=*3K!etL+`Xm~gV`@J+08&^vml){eEBC#~Ce!+ivLipR86 zc^=T@*6b^i_u0eJ5AZQf^+fQ8f_ufO?aQp6Fi2cM&{Bl2;cA@mbj$SM{QI zUwNi;lZf=J-k)^N%Rir-(MEhX117={>{MUES8J=hGy93lILD6bx7-T_O=WhhjCoQG zlwHs2twGChL^rZS&odpiUo>?e?UU5(MC?9pRCYK{BYUEO7fg*gA2>2MM%~i|{9<5Y z{qgvHX8=aTGKwL5)AG3v1i;|kv5l0M%1Kgul)i*V;)=a)h2EfNw+%>ch}ZFicy-w9HV% zCM?9jFYGVtY+Q=$sveje-lbhZ5X|GH3n$a2(94uZa=INFh>u^V^a4?g>}GW{a1$Dx zDq}oJ0?64(AhYFN91W0s#}9$K5_Slo zuEvA%(XeEknBVD^!j*3eFc{HC_Cc-KM8g)P7sv0z?7#f67hu2N9m+f%jd7| zG_=k(*zppsWNLlb-h3-;1X0rK(s5HKpj)`% zkY#$Pu*)yPi3#@b$K6M+6!NiCqUBCq>d!)grjjA&*-gDjqIcL>JEZ2=k;cn08ZhIU z5(7(8b|^D7p}+eX+laIqDXZwdo)U($RRFzXYY?f2gq54rgonyWKd3 zyQ^_*3HC&K>Gy^1I(LS4IAqT$oibY2q+ADyads7K4~2+mAG%pn4C#q7K8$`ZbQvqu znjB;vjAw#?ghP8P7S1M2=(6g3_Dn0qm=%m8H*@9CJHo7@V?r(Ir&M+LaBd?3a&i)p7Jbq#sU6oSXO?-VrBJZZ zJGOj-+^S&K$klB^*<*FO<3x!9on-NGd&7z?K|O=@K2=XFP${I5$lfPf8*!@KIYpwj z^&vM~TuL~r^Ew#DeJ6wUTpAn2I&H9DMEJ-RKKEBv)aY$KP|jI$VockWepyPmPB?!s zZ1ga8XoNAC3z(iO;-TI3J|UNcWj?F&()?ht0YH;jrYwN0V^F_J9-GKYD!pls0Y|Ts zYok`KQ-FaMok#?I1oVw1;#JHu1~2L`1|7>2tEX#K7}=IKL0A+KlV)RVlL!{ngNgu@ zQbn;q)k>9&Qi&>Tc59+;BpQNdq7aey$dalxIKC}~wA*+bq719m6IXV{M08{6LidYbuK;T#)1B5rhBHw~UQDLiPo~*Y z(^FB737BEJwD3pqOu(THc+z}EAj{vtT?#{|zxe60f}T8_dc4q$B=K_H+ze+x=41!X zEdd2rbIwF_OSZ5whiUa}Q{oyu6kU7dk?|y&YMp(z9!PE^Kib<)*D13RaeVZ?T1XK$oJ&blHl~4yfigwmIeuwG1;hp^F1@6)F&laN*0zRww18>=Cq4Pt&vlON;aeiI>q5 z&>f7f0pcW|Kr-ZG6S( z@r3K5^ZbHw&NKH=(}clSQ3L#@UsNBSa;VB_PL%@j{bYD3X zaRTW)f>|~WaC@bqtXwM)Fax>GuI<2gL;2_}nQZ5C#hH9w!!LJ&YNLGwD-pxRN8~O#maJd74`u=}kuZE&wb=UPJVDgc=}Ti48J47??IjXEq{}jB)I6j_cDeKou0#t**Cl& zP&8k>PV@@eD$H5KxnFS-59jM_Z@QT~>)Ec;Q_Q!4_+A#%AGwL@q8a~p%{Es*GvEo` z;in2Y|J?1OE5I8q?IDS2VdW7k(blCT+EF%!J5}aAwGGGQl=J)9LAeo&11pQ3?b3Zv zW^ev4wTEhmX|?u8MvIsW3V3}2$td$W^^MA3-N(QkDE zd5TF6b+DH|>m)cZ?_xMM0hLj1k2Q9rjA9 zP*yndvHBjz)Fv$S%mw8(C)4t7-;gB_ zK`J>7^hnO`m)_R{TrJ}-g{h~A0>53J{>2#4R3-Cw63$ass#^AV|1uWQe@gP#iJk?< z*CrB-ljEBkH;(Hf?oJr?!x6VZZ-o|*0GszLD6ofjYB*F(xgQg;2Eqss$*pfXOVfu)Cy4J7PqBSw<+*c`&0o;fu;;n*4r~ zuni=7X{*B+`kP{Lk@R>I6w=3|C}~Qx_glkR7szuJ0-Rk!BC6 z;@OgG<2iRcJuKSwQP+rfxj>57rs!l8SA3#OdD?!GGsNDktU3M~4IH z3D@*v)|~5L+Em^|VNJMQzE-sxdq?w=f^acCZ%0`<(^)HkTRD3jas7raU2!h>!{DT< z;q(LLj$q&`3{s^T4V&B2sz<*v5QXc_BqyJbm39M!BfmQZfb@Su8@&eWA*%f7Z;dZ04GLgbO@ED zOmpxw3&Yq=q`33q945l;;Ugi z@Hw;C01lOzaXMPemsBrd+Oj`G26M~;}n zJ%B(6k!>=?3e#ivub2L#mDf(#2)w(xZ>C*CCVeG}<(QOcdk%~>&t>BVgFGzqHaRh} z$9zx-xu6AODYJx!dhmJlp%c-e@(t|ke3^dP2~QbNG{G=QsMA5Cc&Jgl8m2TJ*Rt2~ zPv#TY)reXNj0OVp`EodRW5V+s5falR*lSfom;_?S>HT%_UvtI;laipV_t0Z|KrTQQ zp?=pd>9+Pijt0EP9Hm47Z#@<5J>aAL?6T={LTWa_L(58Jj6Yfyx+u7dqPYih6!=SN zPe{cZ4m^GyS=8{fcSN{?S9aQZ+TW%ndS_Bt0%@$1*y|-B@*Hq@2Cxl9+0THA`dB#` zupFM~)J;UGTXPykk(c?C#%HfW9fxbH4?~4o{~pO{jnWGB@@GYBL7}iEkOTPFQHpr! zj@g3yROUHD>0UM@0{SL`6xdGHo`ZDE+;_J7Qg9Cv`kg~v)LzU`+QT#u#VT>tNnb|! z1cTXYoP3maNLJJ=Ntmm)3Z;y9Z{=%WF!oSyx4|aU)phU%|-K-^*O;ie@WS# zXSy9=PH)H+?8^{DF*PoA1gFGVj#3b2Ou8hLzF2OKhC@HuUn9Sjq^a5Q>>m4ERQ?u0 zEUiNLo%B`G*~`gWGKL=}VN(AY|ezZ%}eCVw2a1Da7d zI(J2!5+xT2#D%(d3znVSS$H_=5MWC$f=XLJKglPu!P+tQzywGVPorXQvx%G>X=_84 zK<-icMn(?J0l!gCwl*tbwzH+@69@v3EcN_!3(H}uGlwxkU-~-CoJH-rrV~B=d;j;JSbmf<3zM(g**@5N>!*)|Di-E`h-$DKdX)w#8<%h+4X{8Pi+g&| zCt{W4QjZqe+=f;NV?a(54%$Uo0;n;^&{!yroy1=D2JkW{BT3by_-hSsh&DGKpuRG$ z_lNpb%(?m8M2GlrIcJbANy1Fsk7^Cb`;4`7k}egZQ5=6ST{nt*;!^`7h`&qA9-6+U zeHnRq7o*ooht8wHHLbZO9Dz2SzuWwVLU1iQbQUhoq7zdHwoXhSJU2w>yE1Z#jEq?tH9Ps~_t-{h z4fSZm%s{qtV58TiYlnV0$D4sL8%WL7c;oqLlOSoChhg|@tAYBWCjvJIUH~GnVbV-~ zJ3x4iiy*HMd*<_)nibOB&!N8Y3OM(C(OcGKm_G)wk1A)1ZAZEOvBG@5`tOK~J{ zbklVyEVhAVhYd+$CHOKM1(udHBf*NNLk7VJ#y4V&w`MfczO!=QA#X66({RRyz%yfr zGnjD}q64yITpN?5AI>m8KpUOhBhO*6cs>n>X+!f71k@Pt+u36n(bK}PW)zeF3gH3p@F=dPL*+dsf;XQwa zPR>7i7&fUy#?1=7(LQ!fA-eS2LyybD;!{(7F0MhC1t@YN*Lgek!o2D5w(no*K<5YuE9k}sbFT?&B(bGXt6TMry88vjR8x3<<;J9Qf6I2n; zq?iLjgUnH;9J{l5@Lc=8qp#+3#*DbYvWtxvtZs94Byls~-=_jnWQouo%cfiX-U&>J zuCX~8qUmwrni5(Oc!^MB7D6K(?f&g;J1@}qh(p-sJTSpaI zh6+Cs{9m(!-88OZ`94 z-twPtoLq%SIZZAQGwJI2XOQjdC^kiqFZSUThR1s1mLhEr655)N1+QekWp|2nUoxpS48WZ4*H z?BxIn(-)yh$c96dA;bYH*>ZFZ>cOjt0mSe-)Bv2F zve(rmR*ol<(91GSm3EYM7}pW2=j}OW-o%)Y<9QVMD+2Gw&CjGLYoz}B@BjUWR8C&w zS&%t!F}=p(QI1>W3vj%?Mf%KC?Lg?a4tGhhruAS$*kWt($os=dPYu;49obwKK8Gb- z=T=zpTGIrC<|4^{QU;jBevg^^84>`2)8@Vcha{X)tZd`mPXDanF1 z@_yuzt=+N{n!;Qfv6|EuuB1p=^ptQ4D%w5z3j#9dRvJx4CPR)>dJZv^>yB5)cS(jA zzo#GL9M2LI`c2@exr~pe@f8BK&mze`rVz|EF8SO{dpMK{dO9LQAx-_FO`zJz#U-=n85z>I1Mnh})hC>=+P!1gQ5k10HFkdpm zbfbe`Vs>4%-)3UQQ{i_%T_C6rsxc)tM`oHtDsK*`IRWKm|wV~EjtkaVhfzfLN zvX^z&Ja=6npC=tkGwbT4o3*l_t{N<7F_Ae6+l+H^UFRj868PT= z{h9HP=DF;Y+JleDHb%NIhvnwSh;OV)@WE0p_Y0xLnh&$$-PU`c+~8gYZh@y_E790; zXo*@;0vKTQe1CaV(^gfr;YcJD_6)o(?d#J9oPNZz;z4i0Wv^S*HDRKW*W&W1c}dcz+XSG3GfI)fOK>rArL4|U?Sc_FLykvkIZ#+AEi&H*0F6o?*+x7{9_%)9#zPIN@C zL*kTbHhpdk?lBh_;liLW7!AC%X`-Wz{_V$gh5$vXfSHaqQPAkQc~ve>EnMwbCm>9& zKKlc=rxzVbPU!sg6avEfWd{gP|A2Xt@g~2Mi1dyO9+jG3&{hi^-{?>&u13Q~YQ{SM zU=2^5@We>k*B@^M1LVI(H zm{SJqOwiFeiI%7UuhXO>p<6LcmI#6GH^m!;u>1TJWJ*?|N@A{j;}Q_8ESM9(ZwzQ9 z?}O7d9OVf+bBB^`J+WYZVc1q;9fy0@@H}MLi&iY189Hq^DF(|#Af+5uChprCm%__@ zNv;mj$4RMfOTKCNGpsSN3%w5F>8q&aaE~+qC&ZI>u2ZL~xkRDklv8cT1amz6bgI9m z^i<*1hBjnBTKg1X@cA~wwL!E0{ZB0KScnB~m2wSghjIFVpqsfTHa;Xs9Wwq8zb2DPi)OM!N34mbnKtIVHtUph-h}_H-{Y%=)5D;7c|7R6yPb(W#zCfZX#Vmlu^bN0=3y&K~IASEn!%IOF=)gkk;!>-mk?&B^09R6BXs#&KhHQ z$VnOOGwQl$%nHHIs>XRisl;EHzg~)KqNc)u{4jEQMY`ep#;ESFBVqXn8HI^n!W_|vw@Z( zL~@H&ADt|Su(0NQ`5$)xrx4pW?n{r6JFrjVAf`+1t};89Bo(HFyNTEl`d8G__#C83 zSh=!7{^eKQ5(-}L_RKput=9KaXu6W2W0nUt-1dTkG-2-NQ&Sz(XJABxx5r&)7in7e-3R2a|1V-_PmqW#Gi>_}^dSaYq10Awhk|mu+I( zqVOhB>&MsG_7{`scuCcKpkP;$($XhFt1cK1t$<&%0y-e4wHf0%fqo$a&o?jWvtgTd z$&&=3m%>+O(Nfn(JI2W@?93((JDFESNbPnMRz^>L?T*DwHmpWE%stO3Y2YC{dVY`Y zN;YJwqy9;xj`{MqfftF|!K=`!N*#XVjJ4rd7R-%HEI&3nl;b3k`|b4<3ydutLVNaK3=3=ZT>El75lqo_HA}-jGm( zgzE7qEb;u^x5-PR*p-x0nMMNWFcR99p_Mdxo62gi>I6w8 zP*$|{q+?&PGauhisXYUjj0$f1ckL^FEHXFCRLm$twt`~d%fw2fh%YkCJ!6v+h}N0S zRkXQ^mIamR$pi%seS;j-5ts*75(B}A3H%##@VEL2frNmBR-RLNJ2PWBe&Y4iX6 z|FIk=j(VHxPeAc3=~<|EB%+QBbUyiE%X&x}sn3xNYDlkSx1HA+9<^<~swm5Qc82n4 zXR6_Q-$8JydzVh zk<)1LWw(u$B4BvnwMInr9Z%zcQcQCaGo2kTaenYPfEUyL`0J&Gbykc{$q9eM0seGh_w0 z$rxve3Iz?*W|yW&*CYn%UK-g}pEH!l&p0bg($c#F!FCz5 z`E2(mRf(YOkex)v1iV}AP3Cu=JllSEPOgqO_hF2Z9CwHCto=hCIlZ`a*O4J;$*sH+ zR;zPOfP18`94mHPiVuvNrUEqBr4`GTikfJ{ilc8L-1$hD^RCnjp#&serK^HUYRD-0 zzQwNeKY9M#%)>Bp`k?5Zes^P!mxF+$r=1}TNepN1EX`@d019T=aH#NN_fmw+87ZM^ zI3uu|-+imcbBh~eAPtx1B^Iva^F9l$D#{sc1xRGKL*FC1ulz&4e&|@PJ0G*)Xurhv z6M#^=F~MQyPD)io!_BO1twj)^wPB4DXBP9C;zL9@4o7=_m>AHqsw(#d!l ze?3Oj`IJT#Eu|l4qmYfjxl?7y6U}P8CN>!7K9HTAyMu}feH{G4wzIx&*+VcW?ek8l z=1dl=Y2d^8&IaIyMM>V7qG1A+i0p@#v*hME2$(}6>eI;Sx9(Md6Zw!1^4nU7}UM{T3mTiB5CLFYNrfR@d=BD+1dOUZ< z%xM>sy$Yg!(@ltWz@}(fo|Xx+#PtxOW>C_Q=<0#Bv;y8nV!H#=nNHJ*cSBm^Ni(q~ znklrJGvWHPvma@{b^i{Fgx|*ux>%@$%kFXAdLBuxF0;t8?b7d=~Hc z+8IqK%irsxgT^|SWvEv5KRuYintv)2G?+ioT7^)2CsSMKYDV5RW<0d}>`G3zXV_<= zWim~witY9aNJ{~eiJ_vG$K7R?=8UH9-UN>Ud6w2v0Xa;)2)``auQhl)CSU1S;U;yC zh1a6vmribj}yO zIJ^eFK{@0f9M?y^N_vlljtm=X6xsgZe0?KT{`zP1U;i->wEGZ6NmnrG34ltJ;JfUI z!0Zi@UW+}7lrwX@tttd0(c^qtER2b>9>;~xwZS22R|@)z_XbV~$@Ku_^< zktT3ICxt~E=xt!a4!CVdDal}zHsesF9jQ0#%w4(PgbZLt{CIC zkK(>M!9_8YXa+lOPR8TxO@JStHV-}Rpn8D~4R$hNn9zOTo7E+Sf@(E{pZ$a+Am;xfCCt zei9#mjaWm9%0&QReYb0y$t`jrTgi# zHUti-?E{aMu~l}rA`*s`j?YYO$RZX%&=XBe`phR2)5wybD!X;Z|35W5ivMqGG ziep606FSn;G4C|e1~Q)kpDul#d6H$!73FfHHCowgKw;$jUjr&$S*i3YXpdXyZR^wV zG&g}G&Q-L@SrRwaV_&vt1}dCiF~E+50S-BL?1MbgMf&)6(_Rb#vRbv5__v2A(BP1> zsV`I2Ji)l3M-aK)r#cZdlHX_1*P2IVQCJExH|#T@4r~uNr-AupMjJT?35MXeb`vj6 z;mIMoMM>+sr4YIu^ZLP_yS!7h@2o! z4s``tdK`_vreMh_OmF)e_Zf=g+ zrC*e0|iQrZ%sReOQXckspjtj^QSoC=4 zH4bvxdGCDwV6jbXxq$c)HPbX-C1$5ly-*42jM$WNimQ=9Z@$SP3JhT{kky4Bn@>T+ zi5Q2|oe5F!+AGC)ECdlBxA#>rdp0;dXIB|$=f6*$wMym<(z;Tb6yni6O+#0Pxe+en zNza*N4uBj<8y&_VQI^N2&P$)yNRM{z$->6M$ZBO}CxAya(|QbhOqviiI$On4p(=o) zYnutgf$E<5L8NpUWsQi644TG$(KpXGL~R*MVjKl}(WNm@D)*2|#8$wAQ&lQ)nz`tO zTlAx%tL?h9!5mdjv)>R!@epmZ>-Gn)<|V;&3Uxe0bSkzdX50G73JYxWaE94!xdm4$fxiD#DlV< zx@2$Dxm;v@M^MjCMnu)03jgi^R3aSAuvbPqLxMB?Rw3)Qc;~0goM&Y-IeIKP1Az&R zzP3j>6Y)A}c}y~WFfWrO5MVNAzB#>zE?u)K=N}GK^ASv&(bHrq#A5VA zL)g1m#dTX-HK$w3P9>@&bT=O0H4xpGqYFY)U_69Qa5*Dn33%|8f%I8$evtT#avXFW zoGo>GT(n63=MIPDnOj57G_KscV>&p$&0ZSztr=P{Oh&0cI8NAOCPpT8LGy3JrfJTI z;r6gH)LF}e4)hS2&Lt(2hT+%zoYyHhX}v*kI-zi~SfVGdrvfEhoz*9)D~N9VO6@N> z4%b>pHEQ+{1T{ZTx_1gSC?sz$zph7*;{wc?1Z7sfL3VQK@&#ZjLZ zGpt&>DzZWSqdc56RO6PEogQsAjw&-5R-19Y(yKS9ZJ*EHi2;|^oShmF9j^tPZ(Oyt zKx}(v#f2v{s-NJwn1>mckd#a|bu=9Pdb(Os7(9=hP|6&8plCT8du6E_xq*L!A0Pa6LYIl16< z(8(1MQ7{@1NR{-zR*=qoQ9yc(c8Btz@7?1ZZG;)A^iV~Hd8iPlAluwP&x%=i;4n_zROa`iS_Zn!1GOSrHd^6OeC|Y_RO4IP zPL!_k=Wb!PN|6~k#&&t@!pIswB3Yt(q?zv85%)}D)|((fVU%&FIX~Gs@XA>7dNupP zsZEo?)l55FkREMxy)YW{+J`~WzM9l&3s2{0Nn*4Gher}C+3yT(L$|Y6LDt}124uU` zc&w&g0AVb|6)=^6DkCm+=65`A6$XHUxm#jZbxfrAT3uj)J^-Fvk}zqZh=?lGHgQ9^ znKkG;`+xs`ER}G3rkiFMF_MJb3?JUiXc@+xL>I9S7+1a6zLTNGDwVX6PN5toTI}>( z*9^q-mmCBVy+F@1#oQV(sJ!HFBk0NWdYDWM4$PuD=M+O4YLg?u0hIy~Bh28c5Ww)R zi;W;YlF2A{ms1Ad)=mQgU>&ZPNFEvi(Fa1t-(`+gGogmtXOZu`zr79Z zmyD#1?!dJsC3k(4dHkldiP;9{*LbN++A?~h8yp%Ju7mxxZIBsn9iN>FpJIj%+mjTn=LC44XM-psE=z_0Zg20@X(xej2`LK{1 z8v!iQ8Mkv3`787{r8`?KVH0Wa{`no`PmDuN*4ipt!F(HNVi*Ma+TEJWdmY*L<+f{G+;*(Hpxhbg-Ez;SU^!7&L(cj1r9c z2ZcD!3=KjFFvVam1RdP)k!ef~>?kO0b0=yLZvad{v%i+xH5tq~VF zL*%3Rw0+Q$JX;JgiNsPkyg9#<>^c*;LE_v--^mpQ?)}Bpo?;2^X#1{ABxK^ zL>=;MnI=qZlrExE1(*Wx-gHz4N}%cgCi8^zWMg`Kn4qE&;M>^Ak{r@#Sjmq}3KjW| zTIDRsS_&gLrw6bctHXk~&dG5A*>{gBraX^P2rS5_P{U|Mb8i4Th7%PX{_$BKFy>g{ z;(&dI`Vy9zVsD=m&@6*6Tt&5B>R?g!}Q?mBXs%W*}(i=t}ZIjX;o3 zQuntGTh%;i3xbu4Xzt>GO5((39UM19@-En-y$h1>&l!<+|9>oNq?A!8psvLkb%(I6 zi~vSyTI4?#zV?ulc8~>}aZi}FclDh)6Oi=6l#__87lL_2cZX#m=7Yix+r*HsLJm~S zI5`r7o5)K1$@a?zG59B(QK0g_>^cm+JJ9=1{z8?*e0(=tpVZbTk z8hAj3ZXWw0Pxhq|3D3OI^1z&Rqo&D#3MKB%)_#M5;1xd%-%bDu^CCz6-hMrnvop6d zgD#ln$~j#1MtReJ{4<`W-4ed1bn^A*gqx>r5?}gz$BVKrs<^ak+ zaqGqbbo>D}ijk25$LMg@5v)57=&6f)_`%todq*Qz=ni5e;GOgEGskdGWkdb0W{pR4 zI(AcY6EZ=wN50?Yw=SO+8Uu7;dYNN~A*mLa`BsdOq7ZCuOD3%5p(aH1vN*5$(D0}Q zMO9ulX`w1?9meA1ZT{$+S7pLHdGs6+U;8)0y^mG}&&x>QpmG`Lq5(AyXcc+-C>xc4 zrjUf7t<|-~=M(+-o<@_p2H>OxLnKS&XgX7CimBm75kUuu7|nRGK3&9?BgWd#^bx=o z=V&>RAzdXh@T->5=PAVI8J%>Zfj|Krsc!Wo6EnnB@}=?!W@PxRAi)Nx+RwSa_|t)7@e6Q(xL^8d9X_CRjj|74_tk zY6_<|v`@E{f&gX-D|gM6dNf6>)t?<&jOw2lLn;O$@Qe6`@D+{j~NKR2$)g_K&(jkqu-v} zQ;tPRg2ql7r=2&ShL)4pazPvxRV-+?H9P@~@&x}UhG94K*W)7eD9w0w%kc!q+@Qz6 z)Eb5RhAc87k_As3;k~2ljjd(HQKe_5(ZidWAl9VgozcHM3ht@=ygXvo2b%yLq_Mt1 zh;#UqRPShwlGv%B`96cc)=wa*&!;G~4NTh@@cr%0IBcWkVSFt4*=$xWlRDRTrRd11 z!e#OVgDjdV_1V(xQ#*vJv0s=>A*V#@x9&zkXT>1T-RG41rUAf)>z7d$-5K_K1+ zgY(3x4hd4fqBZN0oVM(dVusIvzu!{!s5YeYUKcAs(t2$a(_95PPofMNcGl$KfLY^o ztGOB5GIxY>8&QfRW73(to}Ar!Kxc3JI9k27{***)P8!%4*d;i80%rHjL<|Px)ypmp z@nAFw(o0BWMa-2<6;AW<|ECatKIsaN_Y>h;g)#aQjHsi9=4F4XPNJhc`|1Nc=RQW< zD&W7psGgB)SjeFE3+}n{LIh*KbhL{WY|5@&_J~A{1Jp2R_4CwENyY5023ebq(aFM^ z7=HK5O>N7_GBVHq{yUavypGOkX@#L91l~PE^R7>9?JQ|-Xk`?KG^ft@Hh391!I{2* zjF%aNdis^9eY4WHon_P9&G?W@Vk zp8YRlesW@{NCfsIaLK371n|J1o(6EvMCSj|#}PI;4jRU5ZpG31iOTf3sUtfZlgJU@ z#vOA`;Ibia<#rJ)*0UmNNgX`#*r)l9DJ2E;=f+8xT&0+qD8aeL{BK~(oP#?WbKtzB$txG75*F6NE+#quwj zCMWb18CcohIdLgFTEF(a#D39G7ssmEEJat&xGk8ylE{fCOHCbLMZ{Re_v`mnGtJAI=_!af1mraP1K(t&cq6bSP7Yr`(sq*=Dwk^1 zjbQMdko-9(y^RQ4!@QgbExm7FJNtcI?2&RCT0d1Y@#Or-hsNrB>fR2C4HMfv9l4aXYvjFOPe?5Ng-wUd-6F6&>deS9wrt_Bc4962Ih{7$`3fV)9d?p zCR3HU2$+|Eav!I+-%NbM7uqlsT8#)^*t_GL$GI9}X}bsty=M+eC}&(D#T+B}lj7Ac z`RgR2Tp&Oe1w@WbjQ4M=ujrk9#RmVF?OK}rip(4XU+jxwnmfy-@Lx-Ep;mNrbUfRA& z_DQ;E{!9lNyPDE?pnW zK5|P&O9toji5x_P>y|Viz+JmQtRc3EJ+N-ra$3xTDms}WY6-?t;b$3hP8K}Yss%yhdtI|r5tJe4X& z--~;XTbaMSux{*7LD#V!aLgkFTGA=6B9o8rjGsix=N-yp|K9%hzhg<6s~{*zcM~q+ z0zG%rLggJIaTbg}b~d~bup>^=Xjm9|>_)v3!gs36*x2>gBKtmIJ{urEasS%+Ik4u|?Z>Wu@Y7m)*+Yqs&Vgx<=-07`z7%$RI z0GXUS2a+16$d9J{+!hYv+f7s0mZ*f~@8dyV+WTZ+`37SM`=YxuKrN9ngD*#B&2f@o zCvnaawBL~+XA9R8Tdc@S-mBv4IChK^ZPL-+?Z7>bM)d|v1;Rw#Htr{jR72xGoqu5k zh%lpslLqqnAhSGm;I1T9)=TVZ%v*t{=|@3V34C?ozkXoQvRH1K%Zc5r*V+g#xEH;$)^pK_ASW)G6shb5ltO;nbV))F`43+* zmV7obNAgTv2U<0+4w{L(2k?A8*zN{SyXA)3@!F^Np%jy-F^Jv zVLC3TzDo$bc_81x;Nem!xPj96l^_&?5%YP+X*_hv5w@boQ)*wD*cLWkszEEpY%t(^;%A&P0{i5!HG$C#lhG(})+8VaRA7pkxycw#-YRxr^es$3zBtBaTZY zINhA2+0zCXx3B%X^cah>!n?UqEdQl!?v za?jjzboV=d66kiFbYJA)DoC1N3VWU_W3{S+Fev0`=6|U2hL)p?Yg6>(Olp={QGcqz znQB9Sw7 zP@{ug|MwqT+u-O6|Jpj~SuMY<;Yl;k5IC~)Mh+gz-%mO{V%++hDusLJZ?BicyWEo@ zg%yuz&>2^_#zX_dn31j0k!FkVbxTKclnHkYq6Rs!se`J?+V|C#NH$c}V@HG;W;kp> z5n`Oa;r7%2oYDqY85Dj`Yf#JI%a?Jsv*+bClXbNz()dd!?iE$dyrBvA={H!N&@h>y zH@_R*=P3|cQI%O-iJ%``scb3q;j0vf`a>jT5K;{%lQSUlQB*3JyiGI1MUXcGe&H%i z-akS0Bz38XyxIQ)wUm06H01m|-1b@sr4;%d7{NMeE?wJJsR>3@%_{6$WlLKCo@g>T zDVIcR0x(Ib%O`y#T81%)J|aEXT=cTtcU@Ws!_2$mK#w=c{Vj!M12J$ z1uH10Z_V$VCxM=ngjX{r_?{WDSb>``V1?i;z9*L-=d&BSi7Ob2QxrbiOa@A#649A# zW}ovp&pgYWPS8XNzmu{5r6x5o&Wis6HLz* zZsreAMf*_yTw##Euj*|0z2KNC*f%yB737?}MoG=2q#``$v0;^+D?moe(PBeT57YpR zlY4e{YOH(2@9R7;%(v(osF}}M`s=2v_V?j7ondhc-PfaRXodzQ9B~-#WxUcdNRD`@ zb_?Q5gXQi}`!WEE8n%!1+wr8XWbcHIFZ&Y#)H6y14!kI!&8S2$)O50)JX~;Ed=MSG zE^xj}K!?2IdQ)e6s|h~k3{0kIBUoKtijrAsqKu+|(Nj?26B^_2d;0b?-O=E)6PCqh?`w=Un4*CW|y>GkqTYPR0;I z$F6``^kNU1EJc0sGDwif6~M8=zK+k;Vc(rjo8Q%wkHgnYe7(tFhZ#xt#O=pQC%cfV zJPy936K_v%_xdW&S$~>B#McKadCw`!W!GFp-L~pjJ7)lozGL~cwJdiv?vN(gUh>x7 zpOIkQ{u@|QM!2PmT+vQAz$R5UrP8+UPu3Gqn%iXuWO$yoo`8kY>9+^U`6w2#_|a}a zNtDt_c{I0Q)XeGUER{?`J#$=PI_lXl(P53cj=HfmYWmpxt(b!Ftr<+KNmqL!#cYbx z?}|vVt1o=7Goda$nSH+9oMOxCiv&gs*hRKJY^*$x9NFokCda@uKwUos`Kpdl_4y{o z^ddsq;S6{;V=+(JR|od(lQr!JOcSehTmua~(Mm)}WF$I+bZ#APphUcG@lR<3h42p- z~OC2zMO8h~up4cAB45{o~Ta?D^OqZ46&te;7(Jr~QY5#3y}+y`KnY!1i=i zC^_HxV^K_^)e}6@kH#ra2MR}jbnCI2R`m^+_rcBRnzOCYdFBXQ_ewzbFNhwS zB@r=x6rf5)tc(e*C3ER@2mSDmXSP;$<%f~RE-Z7vw%I-HbvUGjh-LOTt|ITHp^y{- zYcT?QV3%B3b~OAT2(oQ2B9LZJ*$<2G=lvl`sSxsUGj~9tZx-13aX772dlFy6(Aiso z+a{efEQBU{k{3Mn+u0404&U z**rScu?E-8kSr%kZZN&mcD*}cw?~KeJ?v#V6&qW{A2()L57svZnr?s& zrcZ_Fgo0U7W^Ki8R-NQj36}1>nfkvG)Qq--Z<-BnpGnJs%B`ToRB4}$?pd7 zjEZ(pd?`u&WVwOA(D#5vJ(=s@>J=@_T+U*${UIp`zZD6lQ8rbTsjR>AJjl+AG@&E2CaE_$#CP45D6^+5JuyUE=afp=Pjw;yg!(zvJ323Ob*# z9x+QzvM1d!>I>HEjMY8J96-r&m)}&j>!XKt0K%wMyi8-6Q>yTbo;opBQw@vH#oCw4 z;pJU^1H$iX&H*aRZBc>T2e+M|O^`l2lB(7jf-WQ1;CQznqi5`_Ii`4h6`>L~X{!J# z@|*`R{k@z*rIUa7zWj<$d%{d#I_vd(V(6fYu?+NU=#Rwx~`F+Qnk3aM-wtz;M(<9i8;zF=PSVvZ}?Ibc7iz)-^WFS*V60p{-)9)}WIu(;3qecEATYn@z8{=W$aS$nRph*E;|bJZ zc0hJ*vb6qLucIP<8sTZ?5H(CES%~ka(w5F+K@2G{?~DcB)1g+U5B;B5H;kbnp^3op z@Uok&!jrj6?@J$gA($`cU{CSxa|4|;C*5xuCg*0|_&U+aoKy=zM%=TzAS3m_twA#f z+z&00Deg30iT-h!LWz?M5inCK)t#pySkQ){8}`xJ^rVf@ z^o2lYVmLXO97;{zGpo5#bA+us8CvM0-U(5uQ>tAFlp|$2>}t}RL6JsZGnbwo#}n#H zTdXdAxw5q9w~Avndv>S3PaHMIkrFY&wYd5Zl1iWNjn@-cySop~t&?_gZ?J)_V_c$kgVj7zB_`(+`w zkG9h_#_HoPi5i#ABo3swt~c+j9V24lsT%Rb(|3TYcv?*F6e26wlmHIX8P$q-BlkXc z5`rY`dvrQ3o@ogS?4$~YVXbhjJa@uE99|>o1QIvWJ4FcVz&PvyJ{57<7E6edrDxD_2+T5D-ab4(clfzCgp3|%yHa5T9VCg^q zufm=bE}H%*>o4mh7zyS#rg@Z;9>ZqCz^aYXbFlbdC!Pfcm9`*}*Yo0>L^5XH2c~GB z+Z4X^-mfPo!X)83Jqy?bg9)9oaPmA>N1gHZTsreJSA>^miLb) z9X=RK{$aQVh#JfWyGXTrYBr-iw_mh6EHqUcnMA4$fZf1|c&87EsESO)0$)&RLVIQu z$HVa7RYWO3DQsrWXtYyhqGt(0teK@!*iOV>)?8%Ba#v8OdY1geGE;`!p&>?O!@KV; z8Z#~*0JL)~$O<4z9_0ckv)r5-hln$}L5c<^TKQp?*hQaGT&$Xmrs^*2tU~BKx_L&>ln5y}?}l!aFRyb6FRNW+`b;>3YifMc_j*qd!U==@?sQN} zrMv+cy?e)u?fSBj2B5`}_t&WBh;ZQiI=FltVU0+*0I5S~-Vkpww=F+Yx>Qr6^HV%e48O2L_UQtI?lz6NzukRF~|6(?G8YGCcz6d^vyZ|J! zuN@yVWqWU(1SN-RMkh!3hY3sM3aIKYtDJ6bq`U>|opz6clVKvd`_UAn*K zw9q_@sUNQsq1So_+$)%#YR_kUj(iBi+Ey;$Gj9ye@RP%t{`ug`ub0!tWyf|Z=5!dw z3>s#V1nrW%Nt#5&fg8hN7-@mmY+#buSxa5|eSQxev(r06q7T>m8BM@)*avJs=vilZP|V($Ci`RO9;7_mlRODocgoE6ZZj)u)=3I;)Dt3aYj1?Bx@fDhpuCt@gz>11Ar?`>FDu|P%`=1uJdA?uL{D}&>ML+ z?bftZF*E!6>*Y9MJ@#fGzh&qHi?PguyEH-JM0gbBqi^0+~`CYhWpd_Z%)8$TPS zwaDrc248ZT`W5JPelM&v`PF!#Lv42YGF4~{!+u+h!Vg}A%5`%6qCip@^bT_;Uhb{# zHIby=>`Qc{>&ql{KieG1oM;(M3@c7!w~!zQBf8P~io1#u_kAdV9Kw@yS- z$3VTwFFb&j`>kQ^4qfqL?(&r4|%zUB5m2%BuN zxs4P@w!M#jIr%bHjwzw(*v5+s=|S;E_H`)GSVnh48m#~38zP#e8r(GO=#*L;o9fJC zjKST$AORRRaX>A^(`S~ z`dlxOHZmsqY-V4cB?!C}8pmwP?9*ujd*(O&@h_M>RyjDen<ev(Sh{@q;*(Xg~{7w zv3Z?La<6*6F^Ze{J~WcG21|?hs@v5sX(v7hwP7wc46a`+gSOzjETS^@Yvtk&kFz1& zMMX#kjj#(c{INDljt$nXydK20ARH?cWR>9ILm>pOcnTfdU+XugaC72t;1+3=aVWE3 zEDV|5$YSCsrHO*Ch#Nx3jA*P_;H0I#hiwBJhd=2K$Dg$A&!d_i;$PrGIc3tm&}4dA z0R7~0k(YJwj*2XK-Wu;L`7vHQw}TYJa!4n9aw-q|(s*v#d^CyY!jAv->&C)3_XtML zT|EitB!ZB$>&XG!o-22Zh)Z!X3K&Y(d%CM!qE|zN_+RtK`f*v>M%85P!VdDU#FU zqID_8sj*tNsA;NnVbsp#COHrbj>�Bmoh55AV2hFUa%>nntH7fL4&scsCFfF;$^V zn3sz@BS%bqJBO7>iaN!GUO73<3`GQqR3;A4I}D-L*&z4^5*SJLY83)>HgA#O1{5QBcGYq4j?lYJTQ8T$3jxT&X45kk6SUuklYutD;aW z)0KqVFwq#<&?5&(S#L0nW@n>D0PK}`J=qp&NNhON2F&X57VygCdwN zc$2vU#NVoa{%@#V^I&V>KhvZ zv&l6E+2dd+#PfW}7@r%)yWy101_F`nlfVtzeUBdKK`~e(R-@}JYfl7=f zQ_q36$3|~*rI}B1cpk+r>A>{O9V0pU&0pIG^h80i$fq{hi^M22mL4y$hvvZ=m=6)5 zVUa$wC#BBGJm;2?v7ruTXy;|1aUe!AK4_S^b?67VSjq&G;orRq0<3HVjeGoNQ~iGZ zyd+j_19&u0#V@^fV`>~2*JPbOHIr_8)-e$oCVT5;&^zzNmZxrNIT3W;JDH5q8N?4!e#xF$dz#}mBl`0nC;Z&_t4ZtFDk>A zPpaYbd}^#B62jLTvKz$kskPks^F-ed>key_;$}Gz=1D^0>TeCO7J2!+LYy(pPx|{3 zkcAt%j|7RLCLHR`f-( zEJ#G?sJTO57@i|v{>Uwlp*xe6w+5Oe1Yk8ZD!?0+T2TB>9~7!= zJKD)42=xQf;8ET&9^9R=BP`FE+_8B^xg*vwpBKPb&4i&gJa_h(wA#VeK8c*ZvktO} zx};opoKv{=twlD5l4lgwEP3DZ=Z_EQQCdr1Qj&el^(icI&98&3R*96iC8HLwx_Z+f zqW`e@gX%8072fbkf7HVr9QpMFm`?|L%*r5#xcSz7G!D0n5U_X*DHG&9SU^5O%4mVw z3JDP^K0?`gRXTp}!Tcn1?;vLe5KV7yqS#t?l3H~bA7D>e31=vk<~c(c@mT!BH{X*FQF&F=37K9X=tP`8{Ay~|NJ=qH zlp6`?o;y%bzr$XR0vbv_pMTd*UktCjS$zwQ$F3TaC+T&8{;ODMu*6s}pucqX?bELq z=A<%_paePN!lJde%(8~ej38$p_Ey3VHbS%e67F1RYR=e|88l4^y{WZzZQ0C48AG6V zlE-hSN~CZJ!TC0G+GjR5vb2dZ?4MJ9<@>xYuiRMu z-X!aNZJ1$S4(HM#&>a>0nw!{O`q~^YeR{FEG$w{g&dVq!;8I1B@HC7KrK@io=0JS* zP4YAT0?$&@FXQ77kXA3FSN&}P)|Hww&NTVn6oa88@!WjdzQiM2MpOt7YAh96?I zWzBPzcoA&3C|}NyA#o-82k=gto^l>+IgaGl8-evyxR*U4XEul$LA$b%j59H z)pDIE`nMRC4_&5$#p7L8^vo4vqqoj<>Spx_zPkG)=*Kk=T+VQ-(NdWLmm5Jzx#NET z*k#CP&~6MryWmU`$pUzC-YW6hVD+^`A`96{^$qW`o%fJPB`$?)9O(e>Lpy#)8)v$& zh+m$nMzuX9O##f^n-(Bk@IA&*4)i7jvsMpKPUV8i*KEG2nln^>IPiYcSkj62G z9ff=CZo;vIINWKkOl4JTmy(K)2NvDOlrf%e9qXOu&Lb?1CmHl#GRg|MPG%Q5!8mcs zD`36OZ~A-v7sJMotemiu^D-pXB-x=;CKJI#3E_Oo2qKsJ*@WOOVeBRqA>gvXy)UtU z{mpFZ7SqrOBA(-Jwg#kwat?GFTaoIt4K(CPAq{`n55I|F;=>mVTw$U`AtYwCKk8q$ z1@(-d8t;hHgh6r8+O>;rX_F84{OF=b3wftN6^6l#TKU2IWrziMOJy1DTgk#rAds;+ zb#1N%VMf=I1lc*JFI1wU^CBr7tL7;?omlg~>Lf^ptS^qOO28R7kDSOB#t#*+YWPA) z3=VqzFW5E4+g}0>!WS3di`^A`%kxO^MW~F8UPt>!aBc>h%8ibOnTsTGM_KLE`c#9K z^N9x(>{(5;-0!8A{EY1>7cUIz@hKCR=1&shv_msm_R~}TBgErd49maqF}R2Bagxa6u%%DefA?6RxF2jI0JF>zmP zUidyZ1{A6qpGz!oMph8=i=p395{q@sP4P^71q@aauTVoSVd;>)0!O74k~bQeSONA_QL=E zPvhbo%z=>srhW66C&CTA-Cp|~JWneIW-SdXl*g_eW~E>7-=4oa%Vh|2`v%cT}I_}+1`cL?dOc|AtSOh97R7-EkrD*4=D9z`gFRd z@!B(C)W5*vpX$q?)9&bojU!&8s3-}!@w zH9YK`Bxg_5%5Ye9L2Hc8<+R&M#hIGX@6 zT4QL&(+7U?IBAxsQSNn*uz?_|87htdV8qD50eEA{#`f?|AR2)WmhViJSUnyjSlaxJ z+1?0=Ja$rH6q<5W|0Y$ybOaZM`F100-_Glvs&2D-b1BoHxlLnRew{=+hw>$IhXez$ zN^A#s(w-dNrjz5LTXOa60o=-<@W%>#3?^e0 zSEI${zj<5d8Uj`n;1un%Wbm@NT~Z?>%lTv$6l^S`eu0a+Vfgt~UQP~@7(JJ_n~@bR zAw4|2cZ$B;>$17je5_b=AKORY;R2(HE6$tek+ibIeP{K=wyfSh)R>a;ON0p{L=0kmlcnjEKDa zYH51${rG_YB6yVE$)p_3vci65uj+iNb~Rn>B(=BmGs$bS+dCmXX-lDk6S+0HZML~1 zqP9C7B2|i98Mc4)kPN&LX?g=^`1E;?*eXb&lxxBS*7rctRvPNM^ySgOfw=CV+>waS z*d1{YJ2MN0{y9;X_@(mh<;Z6I%nQarMFvowcs@6HKJ31hYzSqPIZl(Bo{_w&^5XM& zF(e|P>|^W?fk!VqbtfNe^mc=z95j-sEd9}Ia>wx*VKQnXi_;CtoA$=>+|H<{O5#^f z2VWJOw2rNuq@@2rS z4YzEXFX+gE0f+!{YG;-4)`iB#tX# zNGMSb(%sEvrsVTa2Q<&`H6M$b%Eoi8p0;tSj@*yUo|(k6m)Z`QPHZfn4G?1F6%g60 zYQoWIk0+yBP_{r()=8;+KZ6Mpo2%3crKtq_vQ4;lz}Im*KZ1sC{Xptf(Wy`7%axIF z9K{rh&e66l!rX^YcD@G-w-)!lbnGjO`}^<`!gWAh87E`iE8J~ar9qgAAwJFATfzMkeXc79gBzwx<}Q#MqYLRWixrlP6CE;qtiI+#|(~*SM)Tg zKpvq0*A0#a9oV*IgG_S7gZQZ-ZS%1rnsA1!CKfFUCm?_owif<(4)5rsa#ap1rR%(8 ze%>$jN>#Y$Bf()W_-9-WAd^vT3?A^ZGsK@Mm@kt}zQB5*u;7<@k%4!8AEst;m%#-~ zji3Wvm&IB{(@;oc0%GmDncGyJTmq96mBx#DD85b>l zvGD?kVl{Xje$2crMf}S}JqsTd(mW+xN81E9104ytqq&NG3|@(lX}`Y>X779x#rW;J ze~Pu@Rt62-nnHOf?`_+1|1(0~5NFJ-bGv2qj#T9Lpc5pW-=h{nr%M(SjIRpBIR|32 zdIZHY6d-)#728$)n^l|^f?O_;S-}oOC6e$@jpX7XTaM zx%Osg{KqZ5@sP9;ql;^=66K{g|O5&q;XCNUlXTiOhW1+SAIoDbDe)-+T zrjatH(`B!gY@T}|Q#*W(H1Ig0NptEN@~zjJZ+jWPP(>oq{+$h<^M(W6fMe$;z*TCEZY`PfA4(&I9u!pp>$ z67@{o?F=|Bd7@QMtT+xkmz5pl_S{Axm`M}W#=l`*v}5II)(3x%v(zU55~O@sF+H9_ zk3Z%$ZIk2WKWy=6Ys7NU&xRI{UxI)Yk>qkASv+xGQ`E>3VZICPvoYxJ9IN-)GGZ;1 z=^ZkYySqG&{429LxjM?iLi+_p4YEeygZMJ^*f+4BZNRH(2g(zkp-aO&&bvb~5X;JX z+;P(Qb4X_?+C}S86gaHoj`%u{MEy}xZlRlLaMAmd z_NbBUxLSZ*`ojXc|Jbhmz<;1~Km*zAaH)zvKQBTU_}~AHB~cRXM`5;2%#F#klL1}S z?)-939E0>W;zsa$=iV2k#B|jT4OfK&!gRuCjZ1fPLQ>=FF!`d;>{LR0d=+Xd>bF#O zrq>@QNOU~m*)0%zm`>E9tAIMSVEJNtooU;yr)P_W0Agyjb{$im(m;~(z+vIHeX^GEAl-uAr-C3K? zFIz9kTj-&~3AGl!)A?)b2^DHA<;7oSO_Q7NvXk`6`QY_0uHt8 zPttbWZDio75CJ0FCp)0E&60Pl53{;l?^_+XqX;Mxhdm4rUg1HdlH@s!c@`GI@4A&C;(NrH&$_)^ z8}Gu~P-YfNl6heg2_v2;HH>CYu|K+{(9$z{e?%;PP=Bo4dHWjTdAq6TVe|OlvHhbw zK_o;-TY48EUH5fxhHF4JvaYJ?(+N>3 zbAHwjF7LRo7LxzK-#3v=|C`&Fo{YaAS5z8qTBUMZxN_*izQ<_7=$l>caZ z?K=P+W=WBJyxnW~bCyc%j&FVDWmVq@&$HrJ404j%h8Krlc_VY^7EPcp4BY$~sn`1l z%-lL=tLi6b=Oq$jvt)Ua!0RVD3T*M(h@baH22p{J#mU$WPb5^tz39{^h1uJ8y$bY+ zC6_i(+3&s(wwptSG|FC1j1shYWC81h7DOyv&@W}x)rkT54xyLkjix_RdEegwwbkN4B9 zY&&TTY67wN~YF!EO4wA>EcGB1f8db?}g*yd63Sz!^x ztj`YD-y~fMGJLcknPj!l9iINWv^(YLy>pFfN?u1^h1cDyUUMW9nM6~yWVTYwx-?)^ z<-`W(sw0OzVGT%xb1&~a`CGB{L7^rZ{Ma2b6?rkktKV?0_wd@&DHl?Ej8OxVV<*}B zqwwOzmTP$b`(G??ql7Z&D#KVXlV!q|ivILrb2mCfA4^IckQ~R3|H%KmQ2&U3_4frb z-C{cS+d|trEbJV+N2JprecQ|iowroio=^5b$>r_}zNPlU%4cf$kw;D~_|KzHlsEEg zxoIZ^S8&bI$FuntIXA3aNzbFFdO6p0_u+G)2SeKILW!$<>;y?LNi zYSH^--}r3XL*^%Z)Iyv6rIyj@Rk_>6)Gr>qGFT%L zOMXb379>4v%#*|2$!<4Vu{Rl$9Op@ZCN+IW=oV?-4!$&Y!rvh8SaWX)v$FQJFli9w zCX;Q|wToe$hKdD83Iv&BQ9SwKT|l&X1tfF-hP=%rdC~d(FpUxV&_M9YffhA^LWM025s`@-_h1StQk&R77 zjCo5DOY6a&ooH(CRB9!PDqLy(e8xGm>egs|@^fGHx1v`{l}DxzQ2}_|4Yjs77i(;&j-i1LhL$M+fDbJf^=^L`u4S z1ca$Q+RUjYSmg=Qr zFsTNPy?PegSHwF@2)>(dmCO;37`V$2iIWH!)WW12fjcRNqEAxGeo2D4kYtgDz3%>U zT(ww@JifFN6-3XMRX1ZVZIimYDr`Q+&G?+a+T?BhYMcN>FT@i0viK$ge?IS@VV_kF z@hx$Xj4#K#3>s7$th{Q-4;&%tXVX4xn&)v8Odl6nWs~t^OuLq@+$}svHTGFG1MjnH z$i2K{0Y0*&#NnFhCr`+;EUK>y>s(z?@9TqL{F>rIQl7&QsXjB{o$zv1%EQ;#A zpo47eIP4eE6Wq0P*OzkR?qB=K^{1*Y3}h`EMPX0J{K)#luE8EBS=|I_FC;0E%&7P5 z$=S7VBfrm=ouudxXEG}VCQRDI_T@v3>vS`iG`*M2*`)x&g6g6U@pa79JWGxzpnZKp zZdCued&GUcrpITv6?W5yao$^3Vr(|o{#*q2mJa6rSx$f?7aIaJ`YzN3Ip~I|X$A-yzkj^DIOiI(pOMiO`jEJe2wNahL z18S*LV*(bs3rf8g2DTI2ria>w&~4dI$9CT!U?9$eI~5|E6?!H#KT!gJZ627T(snWV z+Oi}Z)=A$H=o_0oMvOm!xpw8WC?plR`)cy7Q&RHGF({f|r0xF6(l@(g_<*;Sc!Mb~ z!O-_%!D>|P^(SeHtq=tu=cOV?Nh-RTAb#_bxVB|JBSh$N!021q#RR&krtpH;-1Bg;kCiz}A$ z&$I8>Vd(zgb@iUl%CePAP&nvwC23*eVJ$ivy}SXIBPySeWPL+dAqrFfiPufZd=BCs ztuW2d#Fn)Vhn~xJlM@BeSUZfys<*DRGCP#e@TC`kBWNjV&}|zsbZWsnIn-6cD(}P(>}+ z7@{j_9NOa4H z9FW~FQ@SLZgAT#yfIkzj9%lX7oj~3WyJfh3y%?boBA+4&fmx{PQs6=BlMI1Bq43+D zcsy#K#%d`s4QtACabF6d0G>9F$hniP1N$kt4Q-EmfOpheT^V{cP@Y{^%Wpc4liRMc z)AWq){t9tV&#lStkDi6j0Z+V#5_w}R-wEO2E9TztFjoLZxI`~zhnSb=Kad;BZ171< zqzp@_IbKPDm=^`M<#Z%%@vtg zM+tRsejc8?njs04AI{3%*D-mo;m0R_C8aL|Yj#N89U(VkY$Ei~kgZlNg<5DM%GG`{Y@z4a2LCgTUb%9$It*+0dr{#O zS_591#D8Ws=WQQOonm$<-O}|}5msD}I1baFCWqvY6`HC3gfRl;x#NXEG}ngmBM#8T z*{rLs6tNO-rp(PCSM&1{upVNY3gzLcdD$R|c3q|(>YD9&mWZ%4+vr$(o5kB>P5-Us zJ`>*$5ixMw@TpTMTV&*QGiwYE`}zuI`?KYAZfk}#-vx~(mVHPy7V7wZ#x-OiFV-i} z;fq~uwJQ5ao2}Zr)Ia)030jIyh7P*Wz<$$H8A{#1WTgm(WeK*3BsUZ%CA(gt6-;Hs zD@EOD#UOI7R^0bAbN*E@Y^sU7K9_y2C_K!R@7>6;-MD~F+Zh~BKWlEI%)Q4cQsQ1l zJ50oFo@1uYcCy&m17f11qCTB6j_oWc)yWhCClgP7Evd_`!4^1PGERFd=(??b-U*U& zQ75w>aAn>=s2zBYbN5X#mSJg4WynW!Zv@J>K^XHCUl9<-g1^uC_k*x*@`}K@6R0F5 z3&9U(vgYh`hFEE~;!ERA+Oc}F*lGD};E_bOV_H|?t38$$M+Q1{A1_zQm)c;kgNY$f zhN_?%E4N%rPexg#c9!YrDRv+&jY1ZE_V4m@Q z7wFFymD+`G!5yk%I(IlYcnTbn`bkVOB#s_dthrXO%}{2G1|39Ldm2PJ)Ev`i*3}=WMHcX@dYovXMwY&N7bey^%wxdIV-$L*3f+sFiZHS!sgS(KaulC*!YFSmRN%c0 zQ~d^}8czmCkdE>;BZ(M!NM;iEn;eZ|rJ3G|As4rQ1k_O*m53rN%UvY=P-I$eATj*T z8^n^>Gu!nIO`AmT7MdXn6g;2SCv@B)RJ@V8E_gPuv#Yj+uy~f3vGi5+uOFhDF*lKu zNet!9-<#*4Q98K|NW4+zWkyXsMf89WhM@2#g~3hX}irneu&aQ(NT=fyipee%PQrqc_ z$%{DQRfjdC$tmW2i`>*dK57;7CjDjzLSx!ys2hjLo7A& ziMQ=~kg*e}`>J5)eFpmXsb0S`hyxQgLJUd+_oZk|eA5C-oMgyG$UC)!M;#Fz(M(;q2uBB$c}<~M*kjo4r}m$eVr2#lagFx=d)kny(FaN8AQcQOrmzbtRZ|j zIo9_B_vTfOyeYjt)-^VG)#lwkz^wwQ{+TUGg`7vc)9zzP=ou(%mF)0l=hwPM|tNJQo;H z9v3drE*1T9j7yAUJR`Ycacb8J^nUK z=nIa*cC>DsLay8Ws+B!;iU68$Jj~kip~aN2jVee(0CPO?bEZRL!(k&~2})jPh2=c4 zApHUTDA3~1!>L@2)XLn)wXY|p>ba6L;zE?oQ*rt$uP-9W5cLHv_0I^9#M`DS>3Vo^ zMlDJNfDZ@}2aB^&7b;}D9SF<2^>yTB1&u$+O>pD)K9DdKQ(Fn{J}FkFT95Z}_&{~O z>Zh#q?8|~fBgPFPmG!YWwsY$1;EPy~0cF1_-TeVy9k6Jx7m^%rsbh(01X)#Kj~M#Y zqGl(NA2>E)_%K;NeRinBF8pFN;8%W|)Cuv%tF7@o^ITaWIC`suYy%> z$**5d=7ZWzYf8#lXgJ;FIESu_C&yh|8P69^`Ff~cQ6yoQGj-F0$0zA4gg=rUEA1Hc zy1?{pfZW5e4zGV276Er%zusU^CSU3WG0i6uatyL~TnSk5-z?Ppl87y z(;1ah;60eUtutx0{pxI{Y>+f{A_xk3NNdWfBz)Kfn50!1@SOOtNhGb0dvl|A)ZF{o z8kr6SSPkYF%7s-RLM>PE#>JS5pgcq3JEQ!?w)N8*+Y8>aMW~$4i#020-7qXZocu*r z`E!mFIOo)lf_iF{O($U?!LZP4Ki4G8fpv$`Me3I_Omq!95h;QKTOP0wQvsEMa-1l+ zLmC{O!1xT6e3%lU04+7ccpRG4Im0S#)K#LJ^x){*0U~3pIan3dG4w~gP6&2dCnUS? z0q&~2Fr~AIPR0jIK?vp1G7*fKp~Vh?gBg8rLs%QL_>PtYot>Jign{v6^1Gd5E zsMu^`_dk@7iCyYwXV&%pkswXl${6O1q}QzN`R8AR&Bqh;IcMAIv(I@;AY{TXE;sRQ zm?Eig)Vr%hO~-)J9R``cqGK?KH5+-rF+f(+cws1hOx$G}l8`A-iB~WpweX2#xF*8e zQg(MlF|F-UTUl0PnL#)wv!1+uOT^7>{(M0AS#LfV&J}FWb0>yw|9VDj zUVBF@aUFYP%8=eS$UD%lu-h5q;Jp9t`_q>7E zmP3~TlKDUvGtwfj4`R|X{OdaJjtVJ+ptCP-d+VC%CBxk`#GvPu{q&5KSnM5b(|<$@ zAoHt$37D+>SrU3rgY?$8orpW%ln|rIMOi$6s<0b0WeKD#kc*eFX7@5D0ipCc%w$Mc z#)Smv$~8uRoc8%mFjyeGa;PtX&znHlPE4LdcqP>UTK|)T)vMhM&Pl?5xBvHluGTOh z(t!`_z^s(!LaZcN*JX5Ib1p~X>8h}GLJ|{sAn2_HP!zqwk7?hpA*ILAS9G@iXKiY> zPTn8b>nf@$`4;FC+v9`fqfVyEzSBjhB{#uqMoB)a-DF^^zHUK?%t8Fbp=Ij0a%fW! zu9@jYhdM!c*sfxj*mnjiZ^bHB+WeiPt4e8RJ|^)#t7ERExZrA9?C4q{`6wpRNR9gj ztnJwn4VL;K5wEJeO4D9P?7F)J?Xnr#0&gh=NuWy(HH*N6kag`@4< zA;WC;q$Cl-7KMxlUlY$0ijQ4Q?vv@{<-K-hpu<$s>oih(CpCxlu?bZYY7!;_*zyIR02^yTHA&8HAv#r#mnP_w2}BUCAo}PD$_9)l%Vo1H5|ihl#fGHV zCHCOVEnNtSudEyS;3$}`aFh*;RVC3o577l7D_L8EQyD!uBLZ5hI1zTGnwK? zECx(~Gk*Ha-CdCqq`&=m(x+ZFVI;EQ!9=3STwKA#ldX~&o{6I%zHUwRd;U1veE$V! z^ltZ_w9vYPqb(r%Pu(WtLMi+Enf?56_AvKXx#_Bb%-zA2nP(`EiOoaT@55)I1}AN{n2* z!%f{rx&`;mS(P8s!IOqsEjGQ?RTtwE`Dh;;tP#GHCL4A{Ul~<8io8=NlTG$?ZD?Jm z6s5U&3{}9N!}eOhmdYgL?CxI>4XZ4l%lOcgy%Z#((?yb|B|E3tfRf*o$*P%Hdrf@y zD@zVEXNFtr^+n*Pq=KYQyn+j73KgYI<%|_I!3Nz$t*gk%j&kQ{eBodx!hDD*UVz9u;DZ{u zY(X3i{gEy~FqbR!i7IS&&P@@`D8jU6UeHyD+@BSxKMA%86v19LpM{LPJg_r7x@;(Dem-u(nq|2E=gTGB|Oc04hE@O#dVcHQ0eTy0G zDC*Q%Waqoi>rx=vKy<%s-9se!qhu3G=C$!zX~hzZEifyj*mtAvG~w2!xVPlO!dl%x zUZd4`_ir%279_UKi`uppK|~c7ozu}7Z*;jP`Fj|MT+a*7&4N2||9Ba%C-n7UEFDZ0 z;0R#G;!I-r?(*)Rik5@cgzlom{pdjx`B>E6Zzsx?LhaWD%{;UfE)vOeiQG?6$1~DF z@!!Y-hU>-L8!gI zcQ{xv158xa3sS<5=Rr8C8*YAAGEn&x_qyZ1P~Y$bFf`5h5MHH_aREFJCVbjKTSjYG zGcmL!4~ciNMaB%UuOJ?2!f=Y&V&pE1(HEN}(@1~3K+5T_qiu$!otY(gNsq}nn`vTR z9i{HxgtO_Wc*kmro2h;FaBIy845n^jqpq6mg9=<=rwCB3$>@cZt9yXck@s=*6PG3M?}62S?wiI0?6LX> z<*V+^$>S-}sLHvGmX{7`56KJQliZL@4?j#F82>>8bb=Nn&u2wpQ z&^y2R#;=a9ekgOofyI0FDZo>vf=i>U zQF^l1bY@))9U{V`3Dk*Q=p$u;boG{v#BH)gIA1BG)?tN}UAE+QTg8AIN!E{^Jc*1> z%z45F)gOqCKnpoSf<(~zNsMtH1~o(8yaWWmsJ1Kf)Czo-88-^fOCaW(ilVW5$>?XA z)##;2G>Ax>)(?J(!wm-KDGmysNC)0E`?}b9Qk~6T3T96OvOd#ecN4t4cy2adyPv7f zK~u8r!Sz7|x!t*_Rn}UcsPep~%c)g_D znTp?63@6^KM6u8AWJuVof`#X^xu}W9C`ViqShR`dfmCd5B_Bp6B^sK=OEr$Z{W8BK zdkepKCm>?hVG;~a)5O*FU2+ebGl9#sl^Sz6axh#O^6_X0 z)ug8Fr_m1fdK}BDP3HK8Z0pRqNW>mHjvw}PyogA#F!eSe8S-WvQQxG@;YMha<&&^m zWIQaWDFs4%b%dTXtsu<4E>7DkwZy#4;?p~$4`iAY z=s6_@bJHentd=03+AqCe{-a{_;ORTW`7Rts%xb(-F2ABCj&e!5Sxpy#nCc8Ku)DPh z)N4j5T;RV68A~AdZbkaOyCR~)?T0o{6Rk8jlgF0l*9FV4f;~zmmU@G=sp&qEq$RV= zCM^~m-^(W7wOAIBgT{;i2C5My*kjsUC(8ULU^0LbAvJnseCmor=k1)KXkBY0llj$c zTqRpOAwsgjdg(xy@n8gp#vvU{VGvu5yo3jQTl-9I?F6r^|I7^sLYKjmZvhMkKzmS}*7Hk^w>Q)B* zzDBFl+FSXIhjAjEf}t0>gV5Z4sSut%VcG-xpB2J-p52i-ymF9PbkRJ~K)RJ@&Niiu zVy|VQ&51E8go6)Zm@kJeuoqLvTT&mE^f}ptxm`qAw6AZdyR_6yc1~HZKr_~!Hv@hJ zSOh9ZW%O>SUOpFT~XMJ5ZlTV zb))8-KDo2y*X!`8nf8o3GQI8!v<649L|tJorh#MUx#}yB?*K5th|0BUyR~$FV)4$2 zyeyKF3<^q7MTBBD53L5y?5n|cJAGr{Xp`p!F&Z_KhBEYrDW5Z;ovD-2M+=xwpo!mp z*~o-Y<(4EA;m~|%PB(LM1!+vorPB1NuNqYb~t8GiF;#CGA{BX6;ygnv!no?E>Aqw1a z%4Ba;Ju8-%v`z*Nu?--?LYsECEP%PT3du5;(kW@0PLR3oY7UC#U{g3dm~{-p35&2S0|g_o3^wJLHmw8lpJ#p@%*Dx1;&iEuob8hE4LLln?{oCxFR;UOSFIy;sl=-wX!2mz1u*=k@ z$-LXl)0do%`a1hbx8LyOcFAPtd`45jACK8FhXUOWm-j&9Ot8XOu8(t@tj`WG3e!h$ zq&t=3C05Rk1gUlErGMh$Z&opl$DZ-Al4^R)`ibdM?u`?JoobMdD+_t>z%b4|i=)D> z?gWbtNaB)3v*xEFgftweZ~lLEG7@IuSgAh!5ABRW)GPj54Qh-)=HJBw0pPAsdOueF zJa-d&F<$1(72-Yjy9hw-Agn7O3owX>FQkV6?JsP<15j#mlrS&7K;noxrZxzlK- z_!21sr;xgyx4?AHAJZaJ{B!!&PmIYXTtAO8H0EUZ99|O=oM`(pMA(lORuN)e1(_q> z;fepnuscI#zU7C58Q0V3Gii1R+&!A#v!W4^lYr(vgmHhsS(@O-nU#zzQwcsycw=xJNvnbV~?o z(_wkn3ZIIfX;@!PK)rG&3@K;BwS@MY#!onv29Wdkh5SsFRCYt4k+B%9a>6hfj?Fn3 zof51epwTBT24#|`ChiGu^}3K>{sCzZ$gzY1Z)>CI--<|Tb&pi2^VE9(Q{#&WELuM(dt$fU3Ffzf>?4-e%ZDq z+3{?gCouhGoKLU-X{5UE0j0ZCpOQaR44w)>byB0%em|%rX-^Ul$M193NP^OV_I6X` z=LGOx@E@gIdwVGNovVC3t|t_}8O|9Wt9e*(Bh(ny+Q@4ht}=!~CIe>3SeEi^HRBo8 z-LKP{B4OG^|2$+fBEz%suthd!EJc~IOfJNsn`Qbsu$&@ooGI=Z|6|5GQ|`r2tO7$q z-ch~#QoOyk*<(56&9tv4hsynXFxrB?JI_O3@y`Ow>4uY-PM$#-54mFW*$C_a=aBdv zXG2XUX(noC>3H@a?nq*+5sMWoS13vv;pk;Xjm<_UuudV5daR~l_6*MWiK5TEObC%B zyFWPm5F_-VU;~}qq(Tm#z3q}Annv`D76`OY{SX=-?~-q6aR=*>hv_;+oMIqn8bSMi z{|B`vB=0U5=t!folS@ZQc#;mt7(e)}C;)8&BYSH`gnA5?DEU@QRS@{QmARqx9sQFr ztCM)AlAx{YOui0Yo|)Wg-X;ynLoyce6S7OknL??=Awe69A77m_Fr3$exS{B?L&+ax z+#4?yg!H^Q(ELqioAX8elS!jB-PK*1=p*Weh*OLaAox_j@Ij$O=O}K`1hZqSLOWLr z^(D9jmB-YeG`OPPtpr1u@NrG#1okBn$#&lc+rVL1Fp9vkZNMTMy?fvFl%UPBO4Yw5 z*j$0mgJN~U!Kys&j>gz9+&L?#v%GUsSG=g)yX&+!a=VT10*JQ&cInbeu?+9C5Z_3{ zV0~_N#O%h&NF5D-K|bjsi4itm-g$O)W4I$QlPTTc7cF>NlT3EfWPpWRFN0FE;HAid zbXycuSR~n9CK!lE+&@aY#!-K1LsSGPH?PyL1UtbVPOg(Tg~PNnW7f+n;GBKuAunT6 zmfGD)6$95Up0n>F4u@1UqXbEWejQ%}o8GZTKw4{ynp+M6R9oiZtUwcUOuk}=?3OB+O6jy-a+5o4EF+k zGjZ{3Ul7$8HhbPsd4XKPoaH@B951s-t%Y?6 zX5!fKsCV@TP#gnVg9D~<03?FTdj4ERfhG-|e0n?KI6<;JE?;Hj+2{4UNWQzFQkv4g zyXW)lZo^%7m-#)oKk5nZgM-K?dr{{zlJtecm7~NT7K32&DL7%_0vHsYUyMw&Cf5Lm#_=>z!y~R0->WTYFvyRS)`6!c5CmwBn2X_0?tAS>oU9yzH62g=c9Wj_UQc*^ zX?*aVZ;6}N;nC=&On3RjllTR;AFNYnP)>iPlhTfym_{`}M<-OVfYwYVKGG^;tq`1N zcbezb(~yiC{jL5*C2}4~@bca9d|A}=<4I)5`Zsrz`9=}OhWq*5rIhD-XKZ#yGxA)K z3l6Yurn>2TOo)NJTHg2eWGW;|)V9R}{o^Pbt_EmENS%dq@`owPx593Q(xXH_meYDW z`r)ntSms7C#tH#oGV&MwVTurfhu^lG*6+QrRa7^b*ol=)>bzcr#6}H=9hdle>MfCg z+~}fe8iYt>P24wCE0Wxp{bnfW;GC9+Z)d1u=jcCfw)Z7PS#$8j@OvjLz4b13>!dzn z&tj0^Wt-RWcpI#Y-{>$*oKwIC={Pa>bY416eYi<@ub09RCw)3wRrR9USTmQyJszC9 zIwX+FVXT=AM#xBmNIET5A`r-M4->}!G?Prnr4 zyaf7Vo+ZNxd}%$4>`0%{%nJ&J{VQ&*(19w2(XVHeZU1~pBbs40E)?tLZQ@1(wxl_A z(*_jNaxBG~hUvmuN3-wp{h^AOE*%lKBp8HMMuqs}o4}U>%N#e-r?e_&R|ShuDGw{X zLdN4*^_($m=lJ%BW=8HCi%ZAi+n60G-l?L6NRxmNjm+uytZ+uWK<-rEs#r6OK8${% z10gP^{mIuya`~tSWG@hZLt$_70Oz-{Kmr`WskGm(8i`NI&RkZ2jZQuewV_&L3 z=3ri-Qh`p+?B}y#NObOql-_m9&Et>}N7D4>CPSm7sxH)iW{Al!vFi*>*FdeSFU1g+~DZk4DQrmnA`Fx$b;WfSix zt9&$^Gw$nH`%rv1fPejcZk0yNzgLXc+@f2f8byNwxOYk?&hHUKJ3#;gq?X7I;MgYx zdI`DNLEn-H4e_h70i2I(jFba{jaGp%>zzac1uLB)-+UId_&#yd-~+rT6y{)c6NSf8 z+j^SkY0sV+UkiJ)Q-_Voct7^aa;e#tb6dBs2}OrIiS$Nz(Rx{I2Vd1Bbux8qyV*$= zo$F_Y5>wI&&$Bh zeEeN~qEVQu+aIAzEwyfxP}m*T4`+f_I5l;<6^u2AlNO^;phz*G4v=IZ7{zN-bCYK= z{B?^2H>QZv)OzL1cgiqA5~|M5CENcaOk@&NI?eu}1F=Auga%0sthihTu8W~zuIC>gj9$e0M5f7@ z+%p=KF?)x=ZjjeQ^&3(j@4y+v5m-4B+6)yvRg(m~ zKmY$&8kIy=#Qb^mjuJk5lQs5hHOJn?-`SusQ&vbSa3lh7J4?y?+S3?dv^`e;55c>=w&pXg15_s5$h?mjpq=fDq>tBNZ?!1!2wr9oTx60n} z6)pizp~4&CF2JC;Ssg(PqpQVRQyzP5F>mq`_^T00wTc$-$}kIlV0Hl6cCYQ?p9jvG znhJJ!lZHnrfU~ju}+XP3PnB^sTy|@)Anch%k5Blb=l|9P0XWf}4_s0t=<#`E=H?Id7Rhv*w3;|Dbhbb;c@K7ZMJNl>jIFOo>jjS0SHg z;Q`6xxkhik8|~c_;}gj898kvw&JPmrt~yzU3#7?{OAHF>*b4T}PHfcDnbsnPaI({Q z<}u_IHK}qqA^qo0SJP()+FesOwcEC8ozo#5-5_JZfrMikBZjCLx*q&IooHsLp?Iy^ zxp?JSJ@6e5J$sUY)(zX3zF~!xt}vSWIJ-A4%gH4y8FL(j#EH26OGlPa8V)R-wzS%rJBhydTPrS9AL}l9`U8>g@ zEPk#hTw*OrcDG8AGp6@O+%>y<68Trw1<*0VCGI|FXX4#{JQ)wwFqAc!lgo2T;lol~ zk!6NF@vc}#wvmtcp$jh^!X=#UK0GUf0yF?&eiIqOwZp(5;af1jmHT_M?lRBGd|oT$kI4idH8@&-J|OTxe2fe{U=|y zYyJVmMN%CeZ6WkPs<h)o#{5q?P?8$TA11yzn@U+UCkGx47I8FokZs%uH;4NPQJH?t#S>wr_l6rE} zyfD!rCc33V8lb=Oa{1+gMX<0OC&YOxBuDZ?ls;LKt_k{@x>E!^c8I6#t&}pccSYw} zm?t>k+5vypuu=k$2tDp)%u)dqDFK$Au~u% z5}$Fb@pC{SP+h4g!`sG9NZQwfcy%gVxg)0HrG-Q!e-BtAL%^+CfxwLG5LlC|=WxOS5;(-%eG{{9K2D$Wl(U2th&1C#m0jFxr%b=i zi6;7#W2o^QMNSF{ z`!>-aWlN$%8RAH2=S8t58fBwzoZM)I(?(>+BktFM&FqC)&{O7<%mb9v)cY_`t(O;1 z#G7^4Ct^~RzuHrheEg$lvn}gFSJD+j18%aEcs2T4lp{xsWysK!dJqozp&afn41^&4 zkM$CAz+04uj6MFr3DuRMtbSHgkA5mYi52BcwU``9oF;exNyMnG`ui0(aGXp=B*IeG z47*g@E-5^!1dj99%AMgR>#^ul20SOd#aZhFbLnSeSr1sJ#AnhS;f#w;aAQ1N*|$Su zh&Czrw+1-iQ=!Uw!0Cs@nM`E#yaK3xt{z)Bb85qJ%3gZc`r#tN(^_I4LXKZ{+r*Kh zF#cL0{Gw#AoJ{r3fN)U5VxU(H*=JuZe$E69Cko_SK+hQCw1BPilZPGGs?mZ*o|l_< zc6+D-%R+;Ebv|OeVOn$8c(VL{X!x|;k|Mjz2pj~U`N{l@8!O-Ixq8Yu3aob2MsZ5+ zNYP5g68-Q_^`G1@C50MV7)&zf+|zXEgG8Du=Epk3OfwIn`pb&QmMF!Ylw_%VUO44JfMO>1x{Ip+j0Be_?cE6pw&TU#;Yt7NpQS!DpV~$oPdshV6SRfy| zkZ$J2_Np5~l)1hwB8B{N&3-MNt8S5$Tvd25Rv3raO%aWn)AdMJDUjs-V=j}o*3`k5 zYm)&^7V23d`}i>yQuMg8yZ^@G5NT1i&8%U95EF9V3HKdhe3Opl@>ybOmz{Uk5Yi%I z9;pAaat&&5(lrV7)VZ~Su23=4-S1+W$KzMVuNb;>4Qr-w>o*LS&z1hjSupTXml7U= zU|3h$7>@^^2qYeFjRdsDu(;MSp$|-%1llvd3U2AEBOPw;&eDu|AsB1nkkJ_@>rUq0 zEulICqZm{L_x-do>Qi)9WPI4sPHGhE#_G+TC-~r^uBWI_vvWK{kzSF;;!ZIch`r-r z?qg7NLm06}`P5yo*ZtNPg-f>t5~B8@>w-~Yx5z#fg_xvPKA#^)HOyy;NAvb{Hurd) z(X?n@-yKKi{_M`4K2c^(!L*{jZhJLpM)qE)Y~l!>s8hv9$L?n6IjI$bdj^g`4zVk9 z%{lkSeUf@vXuk7le*mlZk`!DvXXGsmc8oh#>Yg@l(%`XzS_&a#@EV2O*n=0irIwkK zo&VhW@BhXUZDP{~wn0;jLhWA0+fYB|%=|zQ=A`{0eaKyvlEc2V7UlVri^uSEAik06 zyC@M{9Uhy)Nt9Y!OrA-n1z3=HVCYv zFSV7EO=Fe!!xW$8;p?*_HPZbhYKI7dt;qKn5m}<`OVxUrG&Y)z!eh2_V(ebD$l}5)W13AB!1W1cKj@kQ_`_$D z_5O7v$@1%hTL85c&l@oFwSqc*^FeA5QrIYZ27jl5d8yDQ^>@(9r>}F*hG_`&fW|1I zU2H}u!iD>~#=;Z~URB&#FZw2Z?U>hES|%m*%U6Vqx3Ij32z;M0HZDs5{Gq(BDunIF z@M7>@E}N|b`cAo@l1ir%BsHdgL^U?hx?Ax3rQn?L4IZ1`EF3$s@LoL<6btjPXf`Qb zVDBuTCC*}j@``h>9~~`Nsf3eIW}C@e`#o2vo$5kz9d8g}v z!$puDXR)d2Jt_tn>Cj2$Ng5KgGA#vtm@$NdlpZDBReWf#n9n?*fC$*#rNC;^e?%zIu9 z+w-uyPMm5^gI&G=bl+Hh{(4ATGLu7|7;p9inVTyu8Y0x9Koe1a_kbN=x91r|jqWFW z(nSw>-O~qWQ5RWsbLm34h;o&6n~24wQ!wId4^y!e`S1-K7q_(%e2^YA${?$?d8_qi z3^qtXc6Ze0sK*u+nj_8meRfwQMWoaFP+hJ-Ms#d1Nk|g+%@Q=0^cyttXR$1TOWI&G zWW}32Gw<8AIP4Mr3!GHtC33Hd>^Lta5VDD#9Ry1z z+oG!8#EFBR>x8z5K^7c&*C!Ks?)5L^s7Ugxi>avGoRfH=f2ZMvKvNZu>o<>Np~h5Q z1h5iX2eHEUauw2wdqszx({wN8@GuBQpy0VCcEREGM^L(v#dL|jd7X}-^U_vXEvEP} zRs>dC?c-JB^1H4)_q9>CkGA%p-upiKR3odb;q^C$I}EKPQB2l|9pb_%l!=xxF7hR` zd$B;BOI_zf&L6@aOC=Yqz9<;Ha^ANK|5iD(0D4RriMP-p(Q8roISgC9DBwCK0mjTj z@Np{T$)D&vZXqbiU6KNV9UYY;t(U&}hX6AqNO``qSN5zx*-f1a+$?rg43DJlw3Mu0 zFf9uED`MYJ9(It&5q}soK3sisnx!=IxFX^hxR?VYMtEE{>983249?iR17xo0Tqix^ zKK|mRkT<~Hq>m$xC`_jnWs}0Qshxs2X(W{hR>+|(O-ObKBngzPD^6kkT#D>iuv*vZ z%@1v0N~un4k3N%e8QY)J_-^cyDTiU2JUVw`eVh#ZlbhAod~aL+eQ7@^Ivb}fD8BU^1kPTR;^a%KvW!+Bf76W)x+k`$OiGEItz0Xx5t_;o zxRE%qdFYCpFFjT#?Kbi_*I@7#*dml(HrXRs&$*dWE7k$k0YEIDqUkN((&}|WMrk2La+?!#}m!T)D2|avP{sbYSRu4yt^c;V-tu;Y>--m<@IauJN0FRqYu+p zZ06+z=;26a#DT>SS^)y3pgnK0+x%LG@W4AhLC%sk69(ihg3v0mgWgjb}Y zrdjvzy@x5&eUR;O)Bz3DI}d(}I7ao=Lt!Ruda+{PxEa)m1uw-`LMidEfNx; z@+A=jcu=wg;Jgh!65N`K@QWM*lIPm3#8n)vqW7$UPQB{Yf>EGFWT!JFhmR%7FjFl7 z^En!R3h}hCl^z9t-8yd-F0pa}U@#e8hwvaTie5S5Fnt{VIUq^{Tl325n%P0X_00(dFl2zMgYdP0ikm( z4)rk<;-4|>DqAwU&sPe~YWjqQ9VjM4eSes0c`E)V1A|2Nv*U%pm7;PR?)Yo`eVI`1 z!~Rmvi{vKLP6CoTiUs2fZ$%|Em0$$K19MO$hSt*&Pvtn{yi=`_HDf{$#usAL>=pVqmjAIoR&A7AAws zy5N62G))f$WFgcAXpKv*JvNJ2k7n1tXW5x|1`4usFEY%q9Q;nlwPh<9G)tQ{R9|Fo3{DD} z_ir5biKP`)<(HBDIBWS0U;`7X3Rb5AE`xX%Oa@SCD+DnlMi-oFnXJE05HH8kw9t5n zf72=GzBh|spdcTT9F4S7UNt2cw~mEx8t*ii2L_iJAY2VQrX(l}lIrd5xc+8vfL?yk z9W8+(xO&g6KFl5};uVF!`8fK0a1f7eLRm82fVpn= z&(Eu&9GIOEx=bh*yClq*y099Oq9>th(>&S9@2*4TLR7kLJkIS-U_6{fgDb9_!5GUY zI#_nBKL7t%`edq9+znseP&3&(?i#SiY|8WFilRR6?^9>*8XMD7^PPG0`bawTK563P z%y$LvevD4X>kp$wZRxcG7QbcV`#~jQa`*2h%6*^_guA-PhAOkHF(p zs|NEYS{V--KJC4lbWUcU40>&B@Kka$x>?HV5a)usAIM$b#>e%pjOR$8+q#MMx*8OJ zT@diCSRL8Z02<`8YFI>BT5p(O<hgNn|C}$}r$wD`l zmAi2u%?Z)?G^G(fREzZ`A319wODEV(n?U72`9c+`(f65R;+cU$<~Um{{0I)6oh0}Qs3wtO}M zw7H-Kq?O^bY+J1C3QvMV_ivRsrQtu>J-N+mL1`j^qw9z75hx+*{$4r6DZYV#=hKiw zr0#B2wqDK=zRUdUPytG$!uS5!ASqNjY#ka;_9~lqN}c950aq;>?zG`V7ME zhG$7ye8T&rSrB`9mg`=-0)o8S@=lP#U3cwg1ZQYBGn8zH=BA(6xK>DFLeYCAE}e;JrwGa#dU8Ha(5+((m_rd?_0}LEaON{fslZCmP$h%M{-%0AFUuBl=`3RCWK$K7=BLWpGJE?d9;EKLOa@d> zAH5H$pMRW|CG=^9GY^to_RfKJQB2ng@5xv9@QDfUqOPTl&HT3CU!njFU%I01bG4m3 zD1sk^Cpa&~(*%Ozb}e=M8p*yPavv}hWH_Od}G2y%`0=yu6Li){!;p)&9Vt;8_>!p(MaWw?U(WK`er~Cj? zK&`*4G2$k2NI275r7_EI%>06^f?ZFEQj*EVs9z%$CQP@49 zx$7?*FFPH^gq0?Q_n0vDQd;^Z9T6acHHI9ysYbi$tmEuC-sYxEw)$0yL|=prPTLMk z#+>wFS1B;qje^ln?Aq;HI|t7haw`v610z{+dSGj?Fqsue1Y*0VPz)#IMY5GABZ|;B zip@&IjPfCH^&_}FmL&P;RffdT!>q9xix`bVWk#M9(nJe9PQP@puSwgjUQX%$Z<>G2 zuL21Y=4|eO5qo5XS3+0Fn_x>_fVr47y-p%*$>!eM6(5h!0&RB1$tmkr3^_^+0Mq7=I0y0F`JELv_2-Vp2DUw&eU*g}NOB)t%|wwc5e z#W%G(;BHCwsBDoh1O-C!V46(o|P3|15Dm~r@Qg>F#e`q&6=di%BUo$n`zrlGK zjcyGeCVxWk+V43&u(sD{#-lOkH&Mpr`GZeCnaMKc=XD6M@VtSMqa-z&)UR{~H1E%si`spGq-B1Bgqbm+s0^q6e(srJ6_&3ksdn-w7-BYEs z4em(Tkh8v4kON13!1K%W*`c4&7guwepQLz1!G)ez{h z-o=yR31xg*#Z6w)zZ-OnVCn%gT`C(Qq%0wyZ4U1aO%TSKm7)<4qinUahqO62Bvi&j zV7j0N?8?b)J*VZGViJdch@e|W2&qS`v1)BD`^UAztHaH!GJH-ETy1EY9GM*lUR?@2 z!P&)Xb;L8E8Nthm%g;3XyMyg?A@4CQVSocBVgY(%x-p8a?RQd9(!~Xt=&;`n;NhyW zG{%921L3t>0e&t@hbTDKp8g>7`zGK8z~lHu$%N|~#HNR=<-R7ruAw;+D|<2Ug88`x zz1DSJZRD(?DU8j}OQmk`R*3@T?el$2R>SbLrr;(p$w(YY3W{ja8j6zyFUPj$vUevB z@;iPqoUzKMl$;Fz=G`Z@%u{z;L&v}haMWo;C%a;n=#6$!uVMoDKPUwBj{Yq)iq1OX9<${s*40Rl0&v0=p_lvGwhXzz<5zcw?ZhNz;5c z$s%4e^1P6Ai@=+$9q;%Y=yn-A+zQ$ikYxDUc>*klj}suv#u1v9%yB3?;G1fbx#Re5;fAgupS*T_v~{sEr|moEu9}>h3mOT6fOp!I zvt_^kn5Iu8$RhdtE#~o6AkvZ;c%wj^?cl|0XUjnH%j{yYD-d}{T-N{jzY1GeN=Mqp z0q7b9FdV%W&t7KH(Ir7C$FH^bIbh5rTi(KvIn9=rz72Mr6Pd#_1e*kbW{eBiG5lcr zI-+@IS2v3Ij_->JVSz>A*ZJ{!qzA-ZiYv(rvvg_pl*=47hLu3!CS!n~zAKfa0AfOm zR)yrb6?`UVc({L^$|jGqt0f|_L3SPffgJzJyQ1z@LWEkdW6c6jyFX|00&p4Qhs%@I z;sc5LsFM@3<~@duR4n}Hgj=QbGl0c3p>;Be#gnRZ%LogklJb>Ifd9}ntgO|uU zqXD#(+Ps{z<-5Ztcp>#CW9f8k){+NLWlOLU(MAebI&^b`uQXWH6VbZyWtOvtAIXHV z@QQWQqfCh%=+ea8cfkpzGWxSRJc`ZjUQS*nQz1q^e80?kL%lx<6#FP}jm&JlysNNi zGQHX_%SZm@s4q79G!h7IaW|k>mfMz0L{qlkT@Y`wG>+XW$Sl3>+#{?jUmCN1?oq~8 zWKV39b*2{T@XnQ5eXYcuCFPEZjIV_cO5h=jVYnC8?JxUz9mGIi2#3&MX#MbXHdg#+ zeK?E9gll17)Um)hAiIr3DU>Ug1hQe-3>Bm1+5!@6mG7&4n?4}=wlQZH3(QiHlvr!)-diY7yH~7T zE3|NeTKp|0#E_<)G;?hx-q{Pd$YBr-o7OjzanGIOYR9r3PNZ%w<3Pa#jku+sau=bG zjw18SLGtq|bE446xf%Trec37OrkGo7z`B?CWRNdv-XOfbH~`C_@(+SS09)~w-lHD* zwhKF~Qe8!=R^wJ&)i}0`@@9}8wU5mqD7ge7ptvYW%i(l9VgB(6?7Gjk*p_wUdo)u2T7ag=katJAg3(8AkV1_H%Treyml9UpN?j^!s&^5%I!B&1rexH9D z2*yVB_#1s$-+ZsMW-~wx)_)+sG<|0 z1DvNwc62oqH%E~VE=_BtC@u)tv&a$VmHn>L0oz)q(z4jBHp=$S=j}qm7Nm65u~iE+ z3(T>djq)E^uN9}arBM7X1N=zeS!rM>m868?MS3TEe(;VRhU)SWc8 zsX%EpLZA!%q`d6-;pA59ESn0{wM=3uT0utj7v*&}qT@|WfU za)@9R#WiHxql=wz-JHl9<0Ed;eK$7)H8(roQu&3)%e>2PZ%6TYww&0Z!ir1T-B*!#27K-5#Qa+Q2 z*k`moR~OUBQuy4=pJr8b3{1A)A~`y@QYZsD`t)> z6etcXIP#`=68CLJum+e;u9A#jq1k@ z5sjur12QLjl{j*N5xe7`;be1psK1>EU?SPv zDeBDGmjyqTgoX4XZ(lR!Ze}&4>ubj>1d#XIZ?Zsld^+Zg94sEs-bO}yLZzCZ2vNf; z-j8kGZMxNMnQpvf4{}_gJw1x)C)}HEsoM)X%YFXTLYS80CGq9d?3oinZJp`)LiT`p zC+mw5#|swge7S$#U_E1UV(&Z+vwRhT(d)r=x48oy8@N(??)(=;R+eS`JxM-g#;Eec}KW>@zO z!8vDQ)nNb90Q5&Cbkyn$JS`iPL#~N`N)M`dlZ>l(Fp9L%&F$oo2luK#*mj4(+ZzY7 zPksu)*$9`GsC3!C01Ic!7A*xQaoMWrGWi>S=2^siUYU}sW;gE^!W^#>9zwsKY+H9!&Xc1?;qgc2!=r`-cvflmR#r%U4mg?I-dV)V z9e4fP`AW?3HII|HZPMW~e*?(g%f*Q?b=UbQSV+VGM_9hHn{B-eP@YN7gT*E9gB?nijs=MW z=7;y-wiTjn8!n0p0Bw^Ya{Q$odAlqn1bdpdz^=p;2*1tthJ^kgZ)il-pCO#|BNnd% z2mLHUAt+^(PIbvA`V;pkv3!8yPWt5$yhLd1F?gv%;L!iMn9p`JOWn zX9Tc_!BS2bM2ZpDJWan?Pi2v30V9y8Ce}G)!oktKJS+Kofgt)b8taEF@O9d7?($)j zmq!Ik=s)IBE%wT?kor3K$y6rrb)d@Ix=H4o_iuY8f%7~^8hOYF1~1%eVdo*|D4V`D z+vEig;HO*`za)Ixuml*m3P{B<)ZnWz zV6BqJ2$>y9{B>t?$h-ULRP0e5=2TrCMt49$L5Wehu7zjalL5r&vU#C%ie|D zBngGlu)u;DQ&(*8-3c;@3np$(nd6-_o$m;>{g!re^w?Nuv@Ha7YWb>Kw?lWQEjtAo zzLNrj&v-`RMnr~X`gOu0a+EKK#TWS!H0E;RHMGFXlL^9>j2$DzR0m!ps6>*in7?k3 z`49D3_4xxrM`3zzJzfSSlC#!|HUKlXe~=8E)ygw-MoYxBkeyo3$y`vWOBf~}-Y}se zTrA>;3M{@m-&T|zJU(6+9?o@zF<~V-Ig+L?xsyHn;s{b5sm`>s-5==hT^2N1l%32G z+fl~R@a3>f4_PpgWSr>2Ti1<<=L{{szBbcgOb<;Nl zg1Bj=s5L+NJk3rH8^+J`U@QMBCd)8mj+bEK{TxS?lAZ`2`-G$g;c)dpsRZya=DsIq zBojm{hDtfUCEGVEm*Y?+Ea4CJ8QH6=*(phkYGzej2Lo!M*H; z_-d^C#}M{hPjV7`SEd`%(x>uhAaq3Dd}Rzxm{Z2ozI$~E$@qf%JF{smq}m~tSOXPW z_^8Rt!3@f4;0w&C>GZHwP?urPcfEp8{8dlMmKv4xiWByhC`snuY9va-gSigLZeklCWY(H#_gq3?wqR86i?R zbbWb$*{*Dy60Q}`*TWS2_rrhxvrmY95z#Fgku9-q5_li%rU6kn_(Vn}P)`ioU(*ph zfVb=&dtc?5TZ*Tb1U))VkcJR@1lR61ZH!d!@WzkyzV=QxWUFLjV;My|zW`y)iK2Lr z_hZsYgtW%Y6SF!0Wh%AU9h8Be8{t)-_1qr`pyMa(tR>8C#TRZR%-Ef{7LG-E%YU=R z^Q=orVzUWT_w_OmF)io{0DGC7BmRXV$-E4Z-5irdzj>(`+(3tcfzg}qp8#ZxBM50UeGK;1 zq$9hWkqdGAwF=ilZG))A=hv)MoN3AAQx?PBwvA5sVsQh%pOKmN3E!U5Xb+=71jO%0 z*M?&axb4)M)WqM(vH_x$RL?sCNhudx4U%i?UYm}dc5%iB+nP0uLQW(2#ad1jQOxB? zuSF@$pH*BT0rRa9&vE6HSM+_Tizr(R555iEp-RoZ={vb8WsxYQi4xI3DCGr@7Z=B& zj6f7ne!ICIX6H#Ks(Z10667iV*R*31wdqd71tE9eqeXx+XKw|%XY^xs} zs-t&L?#0H)9Aok%3C4}pUbGU<`()#NvlY&(q1y*z#alT!E2}rdfx;`(+D+5RZW5l% zfC)qfiOas$utq|(_6PoIs`0D$+!SBmc7%jKGXnvhDBa5MD2MVU{WJO=v_=ya_1{_U zb^C##&pToqh#wrhF&DjC8(#6zXmoI3?9ILgOs&bMfn|hRR9b& zMvKHPbIH?=FnzjS*Jtp17F4XUiB_B~w#W!xu|9**0k&rc`!j=JKcsj$5fwfvNV2kKpRI<48vhB3EZYq}@E=@I;aIb;lhSkke5KI0@2aoBJft7_)gIocRA>)yp_p7%xk?+ap_P?h^ezq1%ZCJ58qj{sZ;i1#5Xe*16GM`Fsb1#Nei`(pKy~e zn^0O<0ZA1tNRdV6=!UUys5g#WpBScC5S`8Beq*!A<8!6Lm35BaK{xq2CcHWEmu99f zu-+LHlm>XOotK9NmB^O?Y};>a8bgf;U5xX25nMkezXl4-^Hei{T1WgKwqL4Fat!b) zr@?hbqQH`D_;RQm$I-6(+BC7kB{qH;ZEceL*B`^+*u*r(;ux#9oBJjQyOeh;MSjZl zf~+H1s+21mCnVV10T%3ZIk-b~G(^9h2;D-V4;4%aJ@<|jqqo6T3e2I--NgyRmej__v^TDpHRABJWfncTB;l~hWqv9E}rl(>76)k z9pMsg9@pbt<){$%kv(X#J&AJi1Gm~}%M6Xh=jd`=+QV~3d(IrK$cvcVhzkZ7YB&ENv#r*W;%uB~tbLY9;41>)y=B;-8 z{j%BNXELpv9$4d1*f^DI;d)pnwlUu~IN^QH=X*k65;E3a;0m4G@BPKu6v6I{KbmQ{ zQ_+au6;;x%HJX1DgtNGzOREEIHeZcH$)PzD)=EG!<;W5)xHvBr8&&4$0Z$k{ab&Y^ zFt__mHyzJGsB2vcg0MJ;rp=u6yPGQSl9D5@!goTaXbnyVLW1MIGV_wbSIv_%<&I1E z$bsr_#YD$n``vO!^*s%xfEJ86e<(C(i3kGhdVE3P9k;B;rHsjru2+f=T!_5Pr!BeJ zk+eSh)*43+NPrCWZ--oZ1-Z%A03!sLua6NTe*?Sp`BShpxGUN+${`1Zf3n5$h zA_A(bPsscm_M$9^wg(WcIaHmWvrLx$& zQ>ng=g#VH}-%+X;=Ku3QvE1EH9{OfDWFs8Jjs+TJN3P$o+$E6m$}CsXUBM9G^!?-! zG!$bv+BZl{rZcYX9EbZDgHdO?&p^zPw+V?f2Q`@4!$vJXRH-weJ@zHgpK7SGK2Ik) zfWylIZdAES$e^z$K)|yoAU%fO$EnN1;t@rCdlm(ZOkjS~_Z2g0w(h--cIK68De$;N)j5T~HI+HGh3i!g7e-vZx}9GB_w^!DM+>>DNj#ZE*&#)fPGCZY!;4{>?=uFEoVGa}x_or+i+{ehU8kX0& zU!n>z`o1d6%bY)tg=N5`JVu&y)WI zH$tKVP?2H*_^~CSEhzhMh=%*dF$rO`NMM<)?aKZ_LO(I##8VQK^I;Z{hAml2=DP@^ z5T6^U6gE50-`0jO$q4c0tdKnDc6sdOW~^amZ+M*u25z9WVav`IMf1RVaa0>D@}NK;${R_;L8g zZx^G+vA5U4L`QsSM-9k4=}aKtzfKn!W3oK-FT~3~94VfwJoV+DtnikggNUe&fXOZ*a;L4b%M3i=-k2P9COAlI4*?F$$JX# zaH00|BqIKB?$u-fWqmm;Y`bFVaD@H&_m$!I>0~cL`5K{JsbBjVo`@O_7p>@<{J&4L zcbs?i-LMchEZ#~)_8yhShA#~{jRkz)p07yhhd(dhVS?FqI`g^P=fv<7dghKF;o?C{8`WyK2rkgBF<^g7dOC>u$vJ zT5-SoBGF-rpsy4}2IEUBcP6qn-DQe^kvovQtC3b>(!wDtCMjXFf2cTgvFHDP{Qv)s zCAVHyaq?O~XbbmZ--&cMSTSczA=J)=?Fa0aGgsDq6Rfcz?sa7YGNEWuvxI6658dMP ze%O;t7PNBMU<%ngpNwOq@^?FZ89RGD0+@3!HM_WPkgF-CDzAzh_xbII-UNe^n!;3i zLHYtAw+O-xp9ML)`s9em-Fx0_}CDuP812citLoJf;CF!c7Zh1nLR4T?dB6*!m=k)TKAHvV;gINg` z?MYc8u-9u8yknE%&En7#@EFRV(<(du$szAwW_UI>Zi8jA_KH`yTb^*eqF=zPXk<}9cv};SZe_B zNpr9%IOap2RP}XEoC;0*Bso4U5C98LI^lEa7Oaz#;i)PS&#LMGp(=bGg|?bmJEGVr z88qoK7@epi1OlEBSjv}BbY+#~$~7Jf7?Gnw%B=$H#4$0U^5-+DOHdWw;*+2yEYuBZ zv7vJ?c(vSVaQ=-0jt}F>Rq-%1hE99XcGoZ|LWJy%sy7ykfnPg57lw!u&ch9Z?*@#Z z$SGiAusu3AOV8a@aN;8c#`Ab+Uc&XRoWk#>Hc z1Ifo8*ad#_?R3%Jsl+(E-Prt?y1lW$67KJuThdKbRDgT>zHrublOf%rZ%$`>kZiX> z8mA5^`oH5g*f%YZy@G7jXSH@S+{b6~yRe$FDsUw}O+lB<^Yd14-{&b0$ppj(BZ= z7rLZne?Dok4+lByUM8!4oE%>Pci^h`P)T$dV5Jr*UqqB$s(|n&s5Ys`5Dy+75 z<#+4)(hyqJdEBbrrvL3f-BeH9Isd59G7ETHG&JLsJjp z#oRQ;Y`ti^F00t~k+#yufkucu z*?Fw7{$n1Y?bQFfHYtYNL3vvyZ%-SCVQkT=ch*&c4}B+KyqHW?+EUBylC(y_XHiYlw>^ZyY0?P7w0_j{!PxRf!Pk9?naJvqPL|rn+Hv$LWRvW!(YPNU5K%~P$dl?#J#mLMf+Wml!dctCCn=D#wu8^{aeAs4&l-J zR>|8SZ-l237+b^-eHG@pWy3x03M2J!os>YQ>YQgGqjj^Z^=fGf0*~Ti5Yi{wuYZ1$0T9c9GdzDy2F8ibOHN?0!b59& zEFI@MSxSHDF@;wBNPnIiEi~>1?tp~@2GX|!=z7WN0H!|zHXFNU3^p_d?`0~Vq_$eA zv-cK!A8iVu_9gg7X+ zyDWis!DwS`vK?R58T_w;z6RVlc{8Z*b|bte6XfxF+zS5yv?Dk( z6KuIu{O6zl{-;rFQc{SycG1;&4=w#VTC}M+2@j$!awO7q@+sK7GfIy5zEI|Hpk~^i zMFAJ-wwG)c<{BCP6grgehhx9^gs<@9A@9cgOpJyHZ{G(SCL{{#u&}f6Ix(ZWf}$#R zWH)U`nl;if-!YQ*?@VM6_xJ(fqYFD894MOgv2Q0mI#KJmnc%H&Oy?^i^7uBu#siqw zGih_UpHn^i8m;39?+r-jEj0N6cnrQdBa_# zfEJnA#)cY%F1{apf5h9NVX2a^iMQB#V?%qpSK3ltgSb zLHq=Q{GW|oQc75XaPXJv%Q1 zBfi0V&X(+-DIsZ`_PI;q7Ug_UTOS|e5}}g*Q)Z9Gyg0(tjOreUf@>k~c|P+&n&q`T z0~w^PI&jEJq$?t^k-1Guvi=FkcuT}Y0KyaLc%$jcElb2=9f~cXR*!S5#vMTBd}?;= zu7)46E8WMGLtebSbXYs?1fFrMyL{>4lgD3~1JE{JN&{TpC+1NE82Zbrfv^$;>^Ikl+X!?* z*qEZeDu_o?7EFl@Y_M~oi4`VXx^r)-xbs63yo?*1>?t#qpiCxXZW0~cTY;>uEXGL@ zz;G?JP^)DGf*}`tTRjciir0hd13~;is-}l}>#$CsXg`+=!ZcF~vCjrCGlR-W01w{l zu$O6Z0~LjPIsRM#b})I}Kaw=AOKq+^XAr{N?D%8RSh^miyQJ+V?fW`Zw7I7E>s>D? zih2%ccgi>f5);8YIY#&gZ1TQ4x{tj zFX0D{$$*N7yzraCN0ktaq^$>^Fgt8OMo zRzcIfvn50z>q>EcG}bfxmW;0~8@_#R4f8x`qB$t2 zFUFPX!WM_leldl%l@$EB!p7&|hvx&XdEAk6zo>AFzC{K%Syg#AAPBANDhqO&i#H3S zyhssGe$3ZA%7_Y+B@awA6mIlDKFO03*%9LmGU;XOT>fU0<9mfa5_w^r_M83{I+?ka zome3NbiSXX+1h2J3-5#cDBRc5JC7t;ejZSLBH~f23a}(xZnWkwn8B3f*jzO}ozDXljQQLdWdg z@uZ}$hvxu_$)XLFHk1bTLx{(aCx7%&T7q$p#8wUEa`s!3(H3-vxf9B_2Ob~8{L5*4 z*)o!nJd%f~PY7pc>}aoRO|~M-2lxP~stqSKzb1z4sFE`NhrOPpCIXo4^M&Dx1`2V; z$w}jhNj6WC`8oMP>TiwmPqGd$<(Cu%wt|QMxj1J!^*$&OrwZ5dv1r^OL}cKuuaG<| zhNdx&5*RE9Z1qva7Nx%dex@wCiK`Bf=i%8n#47OokZ6W(mUHzGomU0UrR}Omv@`v5 z5yT8T0hNUcY+PBDFN}K!4g(4?u8>X9c2dYbsh3H_*Y6CT5k6s$w(M~i-(^2h_ympU z`6gI(U5)LVyWkolU5RQ|Ev6Edlr*O#!ql5u!P!6kdx2<}_s1huKM^Z;5!zJBXo`cx zh_Phd4s3ihL~x;KV75VVXJo}~JZ&`ThvQ$V3JPHT`L;3=y%Oj zdHTnd$KT_ljmf#Y9*1bhAaKe4%ZmZF9h)cjoGd`VwcAC;qITaw&JrCw4+v8Ze7+z5 z8~ddaZAdbIVw^gP%d_?P%TDN!xXG+Z`(KiABW+g5Fi85r0s*o_2>7Y8u+lfbIcFFl z>H*ksDq)|~?Dkc&wH~?g0k#oJk<$zj=yL&4(mIA{u|EMDD>+ZH0RauOn18qy4L2o} zCnfdWU1Fp^8N*DwZ6j-ycr$`Qu zv{eIY)%Z-bQs03IpmEAB$pvaAiE6cKqo{xYHhZH7_c||T62c1aZ)8xsrt?RaHPEMQ zyux``_r}6UK>du1LXvDTp56E7y>QtL#W|LQOoo+Iw97i(G?^Tpa+q zV7SMt87m(Icci~_Xh@t?RK_^$B{mMmH!LdNFlG35`E)xue3>ZZm}GD5V)#gsCVw|E zs)nuXbqYsz;-NC$wD~UZ%g~K4wFIK6byPR{$a~z9o!^uuswAuk)`ID`#4@O1Epa0r z(PEb~rJFNdw9fBP!mVI&4Z%qNbk zs}7&h9zA8Aq)AgcRG&lxLwBs>3P~uF+jwP7v-PsQoa#jlaIsVAA%wc~`iZF3nx|y= zrc>^R0j8p;CLfOjK6av(m6ph8z<+!^hFt(NuK>^{cPpBFVOm)~}J5XVp5qbU9 zFrdR@89bA%QqJz)6M~i72qqZAQb~xJ%G)5^%J9NS+~RP4;qQ4}S~ZQpI_9OcEd6SW zy!!bvzAa%cy_Qzv(>-JYhKb0_NFf22aLYt&K~3p)g#hR7kfrsI@LG?ClyeX0eN1w?OVu2&b_~k*hpF?6oV)?-eWRlWL;5vqU&PC>_ zBsK*&lX?>VEltJ>Xa+)EG8+E4*njz{h@Y$GVz()vuI03{^Recks6R)f{PD%9@Dzqu ziPE$SA1!LbF7siX5Ct>=<)t7hnIA#do0!~yf#)u^5u)&l9O%gc=PS@VCk(19_q(ac z8z2ZWOHxCVYXcdkcjb!H=gvt~mTr$9W)g#gzJ@DJp)(iK^a%%0@6K4e-R4Xu(0ap3 z=>QVK!I0}qz)Ft4k%=?FW$4^WRzt`8{A~+-an7ilIJ!>)7^wN%`!1S{$}2JtizJcT z<)}ob=WfR8dKXH`SrnuB>mcPZXFpdkac6PpFA}@(F;*%Ow3;)&PJB{orAR29J+bX^ zsIUoYCbCBHBI2wPNq0!}w<*)u#}T*`wl{7f6OU#t zio9E5n!sR22tC52$zQ|g-tpHdOfH-3pSD+-CCoTD(Q7HmaB^CL-`t)%*I!+jUC>p1 z?ng^+bQ6_Ooavu+Rg{#6;16@jAv>{X{zSW7HPH;c;MBB1hbeXHJvqcWO9p|MSt6^| zk#P}uju<)DQ>PS?{S%-Ir>`8I^2RU)X(MzeEqPUhaiN-A$IcL%#$lDVkg3}|p46Go zzdC_|%aMO36CWMYPnxJ|TnseHY6eIJp9bx*v~bP$o4TyKJLoXu zN?5v(!!5zqLGv#E-FN-H@eIq2pW0UvULS+^`ZVL)5 zF<0PBR_(ta-69yvp3Dz;wMhtHI>=ur$z~cZBq{8g8S99o02*xof%>&8Zb?0Lo5R>{ zo_GE|mK&FC79k_HJxnCQ$C3u#nNOq->2D}#$!u~)2y23StdQkw9wLf=_OypddzmLI zUY(#hUmBc>cRc*^8U0{8UcEeKT@OX)hFTgfnGlc@$gZUaalX8#=3@lA)mBa}3+S zQF!DP@v^N`?D!#{NS8XdFUv@N{Ev&|pqP*jc?ikR2N)XUgxDA!^@p z@hS-PL}mM&{<)T1Hs7q^<#!c18V9n|@^543w$f&g&m~_nF;pH>o1dD#c;K9fUi^M$+tU2)2*aJp5b@~1_6gaaB|)YI{gCN4 z@O*IG^IDOYycM__x9?{8sYAb1(L^Y*QCI+3m)oE4$aB*bOuq9RGR4zh=l0%)Iw{|X6GP(G(^iO94#Eh7UEB;r2epd z#nB$5wIUUQ+mfOWkH1SWFvvYya6SqbSFETF>@0LEcF;(L8;)P$@*?=F99#(qZmTqT zO{8J0*cPNQ@Q^y#7^msm03RGIKN%`+vYNSif_M0j)SKDWxU`F`ezAnE6$E^C&icAH^Kxi-{!(Z|e%@fq^j8+>?@)w@)=UJLsF9V?!x;3`JtRd_x z;aTs{8eF$o`PaKRuv%xF!?He44kWXyT4q2UVPp36K6MhUdM6y0Ca%GON}32%_In6? zS)wb(r;rAX1R-w>p-+V3h;)a_j^v0-*a=&pFpOU7krSze@kAMgrQom)j3K!uUHv}* z8-o2JWz!|zS@ACJrV|pU(=mz6!Wr0&#b3UPqewO(q{q%$th49d9wP)=eSa%Ad^;I3RFgYjQp9cPlPuH?|FI&n z=(7P65IyC`7dW9gbC9NYdU`Qr`8L6;xE`(*HeGW$;Tyv<+EE87^@jd)< ziFv?j7zuL>P*Lr&Hx~gn)~s6yULB8MyJInc%_G=8S~G}Yv%dP@yzRCI#SEfk)OkCU z%SYomvufml*yU(n=wD{i)AjN$6_m73M*)3!1&G+9TLEA`uM6^1&OR>#(S4K-Hl2U6 zLIbswqI2E>{<2$tQCt~cx~)mcE0jTNU-L z(oGGKtsJi7|K|MU^syn?dbvJb*AYkr?PCDdGC}<2O; zClDe2xFz8!k*;@iHkb@DDGIKcst5E-?Z9B@#P9tp%*R%pXbyqhY`^nywW|M9k#1<5 z8HY(vZA&DY#tlT%gt>HaLsnG7NEd_N*^0tXIjaG&1I=<4m45ahGbB2jC?&EaqyfD3 z*kBurSXY1+4U59BRQ0>^a z!LrX)z`K0q3nNmYsHpZ%#sW`xx-aWe_t0_7N3mff6c*I9l1j8YqQ&UxN@4H0krx)` z@@3Q;Kt0as42;voh9Rg)1!gCHA&tfPeNuCanOyU_BXm#U1B%pe@YSX=CG^*2VaE({b$JGI@w@#yvz}K59Lq)8@47b& z*FxDXD7XZz{Fj7Gx3c~kE>F#C+O=+%I%!#ulDgzjx0OuB{rpMlfpPiK;@#$0&m69L zTI5hUPB?BH(nv??i-*A)q(eeaqLdlzBJ~H zP;~_e^IvC~wv~&=+WE}(39#3#0WN_byo3DBZN{5cpKhm2o_hIv?o5Z!L$`aF_hL-F zBHFC+AbbUQF*?>W;d!bcN50YafQi;ks(+T7TugE=Z98{DXEZi))l<@6rb3uQ;0eCc zL7oxle3pj~Kfl{EtutVF+CS^xq~`A!yd(l{ty7qfK6n_p&jM?x2f^pr-Z3I;#(jCO zBrFh2lTSLA7TjTf&3H$G7#jPSLtg_83h%|uuc)s;69sPKqtfoI_GuTd^M;67wG3bt zNSYP8lD}JxIkP3UjtZo&a#ri3y_}%wWT67Q4?;=hqR5B4aD0pi{a}1{IGesy2z_Uv z=aye@K9asP5tA=@#Q^Otk#nDZF#`jp2(#8yW>W7_2c0ug(zdKcKWM@VT-y&W^2XE2 z!~Z}3|NoDrQOM53@%%_th)k%p7lbm_$^1JCoUx96rZTy+vtZITiGvf*T>;(C;-?1y zIoUS3*-#ah+rho})JrbV<;0?RCzz z9}v4n($r&7!P+TS(SaC~BjX)jM>5!#(QM53rt>*xCiXKTs`5tUBx3;;0Bv}!PWYKL z&R?aIhVGvtH$qs4loSyt+F$b_x4G6#vvJ^5|dYlH-XIu_}O|Vt*FHF&1;i zzj*D{oy%w#=g7}LTP1lSmHN2DH7brmt=)+{$(_PKaw; znb$<1i0K%^?O+f+NWNGoK&g}ybK|R_PpnHC}WIi22(@n{oA68Hveroo`u*-L_ zb}*K5p1o@%x)SJwCRxlwVi9@NZSq4W6y6T@Mejub<+fzPN1gW>ba%9M-z1F26v6V7 zU$MFQ9f!FAg~uqckI^Fext-h{2fv{;P533IW3N&&Sz%K4t8Ypf>w~fGLytN@)LSJJ zBO0FfMVumzvo63jC$kqT#NekQiDky?KSA$Wo1Bn&Ch5OPoz}5=VXUutL)6WzaNiO! zXxS^jB&I9nRU(tL+2e^PH8NZS_8B-lH#OQOF2y)WFC-Y)-KYFi>mty2Z9ar1=Dy5R zL^H-E-gH8>ChdSy|C9>C|;hXhX4!?S=A3=^r!6jz&{5!ycmb3xm|DY$!AB_o*+P+lZCd)%R&YqS`m^()_cCFq z5|a~>z}2H$C7Q(x86OZvzJLG!SR!hhJGz1_%bN^|i`fnPXM5#qO%y3{^Uh`1Es4WE z{EA7Cr0lPGbLi)E(;@QeN(7Ugt>;ZXGh3oU1^<4-f8K|E-T+BOY*_*Q)#0z~*|^}m zQ@5IKh(5e236DJcCGQaRa$y*`!THRXMLA67_Kz!r7^`pRk8HEf{V*8T{92tj>yn-k z#KSp}dj{`@F)Lj)Dt_9Mr}riu=V$TByyOXN`oajlQFAO3OBs4;D>-G?8j;|;MQ$!DkS>2~T3D2dkUrxL)F*T=JA9LyAe=TlSH8* zR)Za@ze5O|YRBjMYdhWq?Tn5`hEEQ{^Jyv4T*!?A45 zHj_dtO2?htLmeTAI-!D76zG5}(R<91ks3ssC?|i(OpxB+8R{~KC!JrGlJOn!2#wRU zJs$mJj*auGK=kwAcqiGR03Q9K5o^=x_!6rUZf39j-~2?mB#{?c`f+trGcOx2vjF;C8-0GKXB^t&DLEQqL#zw56PNAbt@B;V~NlW zRz*MlI^}i;yMQh)3|g!3V%7abH1xR7agINa-zGQXElpim#y(%8Ib#vpnvhjZtHCFS zES_QBFov~O<$&EG&j2D%uoxyi08aAZYH}Ap#~-w{`xKlj+O|yPY!1!xQyERm^RFy+ z%Iodnj995&e&=0d*hp`fLseKy!a~es4Pwb`lN*Q6WMIQ7*wI1KOvw9OVa$(ZjF7k7 z%e?1hL#S3STye_t?s=cVXc4IO@54?c_SNvt^aq5^$X+<7^Qq=kWY+I5D(XOu2cR4L zd=~N@Kv_j+!$BrvKhGLMlk`DPs$-9rcO(Q$Jb7be0qF#5%?DO~@Qo4%+yN`Hz1E?eS`7K_oApw*vChJ$xbH z;a8$5%f^%AF{eHU_}5=n@|rJEi}x#MK82HOy5huW^2TEgBScQ46ea+GYz z0P@z&m%*~bM4oY`)9Nv3Y&d&lZ^Puxw^&Nl@-Yzr%XN$UE93k4o!rU>A_M?)k=cRm zd1n>rN*Sr__w@5V)1KVyIwdLs^7v&V^MG^sl#EF=yM&vFV*&u0BiJRcvlemttqLKG zpCkNzMJPo=Hk7A-qUG*#vF=1V+M3%P#M-eBcefIhe7IkCczYu>w85CqVTRG!BkecDw{0=J37u>Gya z=6H0K9n4SbQv1>-C`BovpdHL1!CTdu1k#yjCA09e2)&7P;6j_D9JgM2E#QSmT%U{3 z``=Ul{9lFL3l2bepn;D@ln_1DNm85e7a>mh+LVxh$p?Sb+LV4KQL4$75ZW>-fyhY{ zRuEOWxRc7A;>ajK;)PM~9+A!&J^mHcyzn(Ru7>X58shUlgHN728y0LyootA*k%Ax8 zE~L*%ZysMnD2=gnC2)Yp8pxnnq-^+nCgmUP$+oJezpG8T`WZBS<%>vn@*u{ViC_$O7bloja%`Ri zqNW`Mve%q#_3x;^My~ry(cxG1FfuajU|cY^(;6>Ld-0F5aqEi4Dyyd%J{La!8F0J6tTguX_=5H2i>DicD9bjn;U#v6Y7GJlW-7<|Ur8 z+;P15!V%a>x+h{d^n$lm<~?xMPZ$i5(j^j+AZRmmUm!bTC_XPC%|*o0iGWgak?5vE za?S&{@!6Bl9T(G{nHo$zXm zaHRU7G>%2@{Ker+R~gjPki~0PIg2}a-UX}Yo?=?U&IWPQHvvI^(RC-CbYT`3A`aOm zb;A$8#;Lnj(_lY#E9lgkuDDJNwWdEp1bQm}OD@`tp8j(qu#CHl%;AW4-cKWkg!t^4 z%JJi4c-{8Jz>Ng}|K8(Djbpn_0Mfnl!^@CL2Qh|HrK8lPGSQW>$sK36HpR2sp*EVt zm4oo0gVaZ55K!h<$lT#agUsr|bUj%)Bl3BtffOfAEVDDLtYs*Cz~o^nz29}?(geUK!julL2c}ZV#U$cma%1cdh4F}wa|rz9em5m$UFJO7-f*~zn$pDhfD$c# z0-6s=U-3tHYGXN-ILO=pZjNdF(y~A0s<8W0H{X`jH@2M9MdkAMG$;hk%h&FjizXb} z1oxKr6RTYi5$0pnt9rtmkfC~2u6EJxcL*)^@n<5*_c(r7=+VWKgl7(mDy zo5!}V`>)v)EYsi z{9a_VfR%kf!2{Ews(Qp#fx8=()g+ey#Wux_{yEtt*Z9XiNKB zutaX7oE`A^NR@b%zifTOfO?Vl&+73ba7AEO1efQc`2{B|y`=epvpKZljGtlG3B32A zC+l6ncRcl+Q|m%QAASo%HT;u-i1p7O|NW2l{Fz{Fh1h=jZX=VtM}p2!ycu#yvlGfD zI)D{wEE$cIodXUzpU-aajmml#5f`DV-QvgigOkGv>?bwkct0#FV5>~$odWkn$#|R( z`wod{;gRMab+e80eb}6|No`h6d|cD_MF3~$&3eMYj+EIax!>!;a59MMfya&{dELsH zz{2Pl(*#IC1S-;bRlrKJ8;lUorRkI`ufscXWh-K7OFphvknsMS=!hv z#yKsdUNJ(qgw2sn7wc&bULbQR3;NI3^|s63Dgj$7&|{iKb00ZUj%kSEgdqsc+;vpm zvw}LU>*iRwlxd_HW0c{9FA8Kl{s@jN&{Mibt!Ra)h1(>HvRK(kZaGOX~;VSEs*e| z_vDW0UReS4T+Q4;nDtVgfC`Z;B=(kjuD*M8^>5I2$z5?xm~OEmVb-3=Jdlz#zt$89 z#S7(ujbG<1VSG*~%OlucM#zsZl09;yPT}~rh2OgaMJZiK=+G;`JNM}o$+k-9B&XLy z@*qIZO~XL8Sh=2qZmc0VU$&(xcbkmchz7~0{^J%G6zNQT?W694DH|nfi0Z(YZFSOM z5oL4Uvm3HGh9gf(7QgcNtv;>L>EZr^&EJBBHg^uRV_1d3z?UJqo0_1Kp=7z%Xp0ru z339~n-9SM--tA_^oLvQOIwtsgRbn**I9>e1nr)vmaBDy#3~x*h4Vt?xrGyV2TQ; zoj=}RitjafAn(+IWs-U_Hw?2!6p%BfF1!gt7W`SRg!=-x zTxw89$LJelZySx>qPC$@W0GXTIy@|0TYk8ZrToolhb~=oIU?=l^L9>zq{mvib2S!k zEypxFllhL?i%OkyjJ+XUM~Ic5`@` zQx-z5@<+v<3GmnBPaYxl6OSxaQEb`BhtDhX%OCR;hDg&LK4S%yUxOm*G&_+z@N3Ku z>{VQbcdtv7q7x%Q&Bwz&xtlwDd+e|U5Na5Ex!Ln479XPTFN<_Yb1JI$Sd!f^J;%|G z@Fg`PeSbcw-NBR)Iikx`5nT`4q`h3nvW8TW)?-SShXV@rhQX%i$Z%vEboc+ zhuV(^+kb7FK4RD%fn#cFOzmbKHoD=7?E!Alz0dY?r&WpX^l>)fh_WCFB;zWRQ8&c4+Ybo*lNyQ7J?%bQ zz0SEM@90GqQkK;@OQ7h;7kMRI;p=>Gv;A{##CpifZN*CBr?TQ zm{BbUGBRe_&u{GXq4hh*l0Ba)k3pg}=EwQYm=a8QlC&-9Dz45OD3iXTj;6bEiWksI zvTz|<6Pd$kBA*a|Yi=sp%w-%w7n#15tF-1eD&$^`ip=w0gE3tvGnPK;XUC7cnD_{98U$V1_*KRJ(WTk3 zHey5t>-!?qh?*~jpPK|EE-Agcr>h8=v$N&@R zv6i>_9x_S<;&5qSqL*v^N8K}yPz+~GhC(kbFVjJT*u2j~r(TG1)68Mu&xjS$-|@8W zIJg}^BAYuLf}6)1y+R>cYeWLKzo2_4CTytD%$2ney7fZ4Fj@_Uor(YiYCvyj#OkUY zs?C*xM~~N|urj^kE8(o4^oGhxy%j1_IK;9r5(OvEcw117=Cy zGBjC5Al&ytNH;_I^j^+CLxv`QNeRyC`)0x0|MxyI6{YS#>?;(Fx;o>9Um= z=vO&dKpzA6Hs~OH;==c?A1=u;yMQFYzeoRrtdxfd!{dPw(;<(#mpY*g%`Zcu$dQERs|@@q(9k$uifDT4f%dZ^lL8kMZ_ zJzLdCTz*_oL#h?n&o8~_C-9}(>3_@oe>cI84)Smvx#(IR#n&djvq zaJu07{`^+NI&7q?EoxMfH@Q0w5l91z@rAbCJDW+R2X~q+#qDvUsSe%ikbRQ3ZkM3% zcH40w0p70D>p$!X2;?c{S&hXX;a-7gD4_RKIW?BL>z zXYLSMn(vn#wLD2~nAkrHSz8g#8Ra&e{^-j>eRsn>$36-enadAJJGtG>SBp3R@fT5N z$5&=P6)D0hH-HJuc}o}?Siv`3&E8U-Dp-=V{y^$g(?jHUA%sRYuv%MFZTdtf*ot(lKe?cHRR6*n`eg=J5D z-Flv<-Oe`oG;@v^wU>iws~mvD(C(`&3HOc0%PshvJHy2XF{*EjaHRIi#^-S_%vdVl zZkjXbB0I`VI=aeJOx|3gz<`8*#O9%!Xo)f_QP$VhOOzb@wHYjzt zE%g>St>SmpbPJxPO!|HEwfhQ5>5}zTEI+@${W-0mG)Wo;pD-ThtXVlJLkuDawjCtE zU12=mK$64S&1kdBquT%IdY2?gk|arX-vE6Vmiu4sy{dLbL{^K5%nWxk72yvNl5PfS zdd@CK%AfEzM{v6}6LPuEg2ZnqyvxE?{0u~Zg3zxkwSR=4&Q{>olUz~a)rBt4s=3r~ zgX9Sf5-z|i*Xgps8z<7xq2^|OFUH((_x)(sQD!^f$KN^8s=t>`2tyH;YhDXF7FyojI?GFM38{ZEj{GU>cD zlYNQuwi}T_=2!t>=EJ}l1?Q#{16=VU5tzRuH9m2C^+`}ayXANZj{exQu2=ID!{=cG zLcGz@m6G)JG6Jw~^3}P=ZBEuZRT4+hG~88*kRHS%{(27iG(}z}Bb;a`>c`eq>Wo}z zTdy|DyRFw3V)`*~7q9I}Q3o=|&35X6hOg8zms@Kl9^S`E=vt&NU435OcrF zlLqEOtz6=K_cLUic^TI)*3p9EkY&O!oVUlY;`L*<_TgAT7G9d>py1y~HbpJB!^GjW;N5ce zHCw6bVAuyD5c3d6M*^Zrl<=*R^!2h1IFYl;v}qvR78D@=OMoWNyW0CXnrsi-F&HY{LG|bhieQ zlZ9#N{c)*y9r9=s)mN-ewPqYny4r(m99!j`;Vw@l#Pb`& zrF%Ew`X@M|X?_!J4cUAJ2chyDt)Bg0I!U_bH-?e^L6M@;B^0e_}~9Kmi40yR$__->Eo;cbhjvdobEe{tci58 ze`3~2)7n4t^u&krne9tNMY;?JP#}~Kky2P^Sv0KLfl$a#xZv97Te)BW`U-0 zNebByO#m#xbaSUK=5fFs?<8LY^A|)<2GNz=W6e;@Hz#s)2B2hy3(N{2mU(uf=ILlR z{6X{myn0iLZ!j2&#+ItKXU&Yi2dBz?^5O^wG9Z#E_YX>eldQUtX?VH96nmfCuVyD4 zTy>ffq&8PZepk7?s95>&XI=}!3&J$Kkbv`z$8;Y|xOj3aW~aXl&1AN63hxS(Nl$js z=!9^(79uoH?C`<$D|s15`yw+Ug8(8D~bA+wTOh-mRIy{-`KH$xq4L z(E(8z8wr;QyaBb02Y;Ob?|Y3LOn)nNTC`#o`p@q z%L;e!Dk#iQ7~A@W5K0D*RDmZ^tIy;&Xy-Edl8b|85UrH!S){u{o(y)^Bh#KtrX0n~ zpEp4|EAh(&rUZlz7Sq~p833MlK5o^P@d&SmNm+3*+)5YONqV^2k(vmjVu}xrXVUD- zb`V(Q59vtCDv6u{$@0?0HqH-+foSVk{!B?P#pVQLEAYmLugd`g(AiqmxRevb3J@!$ zhY%1pYShRTG^=Ui*af-dIE4M4wHGZa4zV+G2rq? z-s|!8TTwDdD2|UmL%zngU93askIBw%i-%GO;H*<-Fu{!jOhqiiTVT9}xB^vkP zDoHNSlYjB&>||;hh9qHsKL_UHH%}#oU%S71@A9d!mbpeZ;)MaQ$4gx}*8nFQ?^`0o zI7txuOq8r7@B2#|ge60odQ43hAm5s5?^2C-Q;Ms>$^o~*c|}-Y6(Inj$GZFEKmT_u z6*So-1{Rj~gIm(`F;1*w&tIdmq;#&B^Se}YeLbC*J(YRrEwM!h>e%MI5S~Rkfzrh6 zXM>YK+z6Yb-Q59_3IdAp`DvZtWYEQSEsRYbW(P^|t6a}c zEv(Cq`n(d!x&#RovGqjo?~?WJ^0FOIn0O;>Y^d>-9s?pewhU|CPc9`Gk8jd}RqQ|3 zIcd>)=tivD@a20#*)~dUV47`pTb@7i`c{~i(T5I6(i za4;A*b)NbyfC{7{N<1DD5okKE0fw=KVY;;r7ePO4@k-dxB#C6?ZNH&zo^+USg*uM0 zuZIj!-G#pTAJDgSpV8HFXQ3OPK9;Esa6K9>crKB;k9rKO zG|3ojzn-6zK9FRn zbc-cGy$7Oa3VLJh`QAGolcV+vWh+jMj1S8>@*cBpbV?>8o1x&?6f;zs!XToY6Dxr< z*0r{RJNMHIp`{Df0e1&EuaKF})`Lx5xKJH+d(UYz9V1UFvJchp#LhI+?vGzU+FaMT z1JKy7Q>O!N0n{2xNnz+%FO$vrp@9@>@dS}$JM4|%c{^yWReXtrogh!q$wY<4vne*2 zMSUHh3LfO_o6y#xhD18D+4ilwEA@w=eReYOUS!FRxQ>|Pg#7i561SU;N&T*WY+6@W zeGKBG$mwCGG*vCkg#10}aW(gCQ%E~ZdoeT%e3T7lmn$`U6ypO4el9_%5i}<7w6U4| zo7X^+I(LvjnCNmJ5|`((o*DGgo_A5C3IY45&X+scEuh8f!(wbZNi2ATKzRuhHjH2T z9(d}ODaQG$Z}Bi{`89LY_Z2vq)3M{=%Bw_oKgQMQcKd7|Z19aM(eEEW?Yy^1%sZP) z#W>lej&f#=rIATym=r*REXK22T7F&t;Cw=nfb({Fx!K=P;NYkFMDNOLD)0GV1Ql8VvfTvqna8K?S6^SclZ{%b;g$eGl}fc6=HyG-3FZVI)Y$ zkn`cTnZQv|+4M7=f_;CYCsXHwXLfxUgfp5L-NB?3COi7LkOXT5N)* z1tj^S$T@^JN_(gx8nr$Tj%4rrcfs9$vypx+a%Mc{b2Rbw?k5f+_*=HAnoO7(;CwOy zU@tR9!_alxXpj&&N&q@}I&Xpfx(L3p?)LIU@m;ub;e3{Pd>x+8BdEQeM+>L820?nm z^?}a+PW=)Y9~kfTsMwwNKweH;%e*C_NmS>60bWyQCl~08VLC(kA=^Uefe`$}cZt&T zo#N#x(b~3eOUmbDLiLkaB`XVM+OYlKbpQK54NUebpm~2d=#HU(U#KQyhJ8}A8@I8y zR;3y}UV>Q-5c_~w)s_V`?blfxU_|tsy(4_gdg<`^=6b3d9kzR9#OCbID@X_w;D$$5 zVSGbRJou5UfB9)L>K);8OdxTJ?S)E-LIt1W{LYewCY6|@$m-`T{*qbUJh=gFLrBBb zS8C^UR)BA84<~y-V*37Ip7}f#kt7vgvMQa9(fmyM_goR<$mDFl3M?za*2-?s$duwz z!A-f$XuirJ_P$ZxId(;*_=gU8I}^k+AJ$?Jsc6R2;hd2nt`Hl(Y!@6;?MliDELA7f zf>f+s>sI)5pm$~>dyk=sZPw7ABkJ|VMykiFV6c)|qzyO?0Tp&oVRq77SeN0AObwQH|#mwend=brVhIFZ2)|l1_Nf zQ%m~$Eab^q!}I#s$lm**00UmWzoVQ-l4`?-=Djaz7_0`a###sMSX{4n2Y{DLu{vU`(wt9vc9htV zjK-#axW5+@93J_3UYhhRK{)XAF$j8%eaa#qLciyAb`OB-bC5|hKMwOpqZ9!le+tis zY}&2VC!Pm_zIJrF*Fq%{{v;C_E1(FwsO(QVUwA@G5~Ikc?KtXvzX?oY6Kpm!GA1$) z$=f9BhX<)7c8>*y>U7>*4ZkGOd{~J3Cb>8WWTaNLT%cOxg8m6;W)39~T5i0lLGIct z5Bu$D#ykMz!t@fAF?x4A?}=55`LpgpdtIX02kV!qDa|0hHq7+9e+tz3?+JHjp)+rRj;g*48aLJ65<}s}W&1f)bm!d> z(@`1!JMyE0VxWJgkJ=)(lpIN9nk+%%{>=^-l9xKWYuF8F2q=&t(3o{HE+%@feCy5tSPt=mWn4Afi z&=57_NQ{>_n5B3Wubw4C$B`=ndll}jj@U-jM1>c&fBD)yR)ZsNVlwo#?5NhB3T!$& zT-J1^ir%oH{}l?Lb9|9(&)lJ)0V}(aFfyF9p>P5GRPUR?to5DH#h@DeZ@ra_6dIp- zcZb48R3~j~Q>rLSQZBBhhCH|NV-x;*Y_tc5JxvA%omoR-I|i#%Wyt7%UIU>M*^?_0 zOf%L`FteREL-EeWCFNm<0Cq*j=M7JD@X5J@meSk_Rz&J!5+O2KhP_*7uEi805&$jy z5yo&2-@66PpS5>i_x|Mcxv})H>{Kkx$@9;-m{43B7AlyLOghvcg#eq^Po@tF_CN21 z{ox#WN$C6*825otc-(V6BFj6)-08{ByTeZYCQ!#ML&=0QY0Pa_!0mJ>bIewodA^D8uIFWbqB**5R?=m_(&hMBJKabEz3B)0h z)=6IrF+ATEAhcLR>5=HrtJZbVIr4;Ll)tYDR)Dg}PS1^idAtXOTShb29ttA-UQ2G+ zo2^XSOVe+FGve-Rv~lsqA3gV5FEDZ)i-JC)!AmD%G=2Os^P=T(p0IXORG9R+u>_#( z;4ZnWl2^w*5Dl~DukX`OrB-D1)z{(&GZ7=WSD=KYCP7SPq+NOCP4FE6buq_A7{DrL z;okh9Z>lS@bKYnr(rCDk1=&HGpfFNIwRqM`W>>IdWr7KBTkxbNOySfW{Rl7&eGE|@ zs5nVKaV_+R$><@c4D^2c8Kh4$&XKyNYw{{iCr!ieaZMC%%h z<)9`4%6ylS5s|Gkjo4{`i;No%3jtv%}5TCB{8FNi}* zUL#$BQat(S$82A9^Yu|mBhUG%e|HcFM<8#BK!w&nB!a;z3;^v3B9dL~F*654DI zzs>JVBs1O)|M9~LNLeJj^QR|tB+gS1r+x$5OO&Z)w6~hcE;n z?7Az$LII1~^fs0&o-zph`e22gjouNfszFCy3y&^!B(*7I_)ZQQTrhm8$KI$NA$&D# zU_dn1u6cfaA(#&F0Le>9qJ(tAFgwfZ`J@}>FnYhEQ|2^Rh{<4e=|I|%FX~OeVP-`Q zT<`Og-&xtM@_RCwP&FtwV^z+i=wlQj7P!|rL*E8Cw7Z>UT(a=p6Sv8u?9e7 zG;e?mq#9xhLu}Sv@8ie2O}NWG;Z?l_j3y4h6M7c+K02eZ2P)!trQ{|0grNLl>zrOW zMpLKY0O%~duAe?a!tSfU=K87;ykW{=ziA2L71=;_7J)_P1T$iNr`*Gcd#$B>=CF;{^XoX{%Farn z`OG^yzeqwWx~>bL_L zK$WibkejhC*|@QUPbM>FK&oaO%{>$gJPO#*gnx|ZEs!4EInfHjN%#ce zw2fob{>h;bv#3c*;G#q*-`!R?m5->KqKk_Eey0`fMiy zjS<$(>*KRZtJDETkih%wR#L~n4Xa6nD7s?=wW$3X(PN&&%knUS6bHC?!LIU_yalXd z_uR?0TA@r}6=J?$X#y0TKanF!!Nk#;uR8wODW^5G7!VJw4z9;DA$o4a)Q`MrGB~kZ zjMza2(yhHmvfI&H%2#L(mw?-8*?I2#zB?spBA`_7j5pow5sx4v7eRj1BdlgWV(=z) zvH`tEP8U)$H8C(m1VqaiM zR3aIH<8bOUKs&wuh@99)Q#FUVv)76kfH9V;yW~Fg9WmoRP>|~Cy8_nRm%@>3YrW65 z$zXt^Xn!90j{bZ5Sw8NeLf~1m6!)s8I;nH^dqCq%QYYFx77@K9Wb0@`2{$ zH(ecr%Pe2XU2PpT$Z8P@4l39e6W+TMv5$9|nxoKs$h|Lwqr{3wcz|x9=nEj*mPw~J zKn+Xtq(xF%aIl65PqM2o-2b9*^%g46WztJ_-XNX9!t z^)6&G6Z;-P9Zzlm=JRFdV}9r~(T>OCWgjokup$4WvV5q-H7?7q{Yw8B#c(=)ygJkA z3aq`Kf8!P;P(14lVvJHBpl`8Aer1&p18h^K*G}y zw1ZuKGfwD^1~JmYzcT5w3Hal6v`p7~z!))>t{FbYvH~(@k1jzbHL{O=It9lc5P%#kNtO;zd zY}Aq<7xf%}*)`ljY-k&of)e>{$Ka&Vm5JZOAFJU17CTUk; z^2UyMuOX0yqY4n!64D#7@Z2iSc9MA@6p+{ve77hesea4Go%Wq^*T2uEi-8@@(OUhJ z*!ZnN@i!v9Gb68w@QgRiox#|a{qax{+zrj`^VPRR7TS43cBBjxXEgJ3CeUm}? z@{`U|zYTTT2xJg6)9nhKK5i>q!c-@+`P@fI;feD593S(j0IXNw@=7Qd&(g8zWzFP~ z&w%eYKl;9Z>^E1k&>VwE7?vbJvuCXo@5!@eR!b_3Hf}ymr`Hx(WR>Bu%w;47%)ZwJIJe2|JHzH>LKfq(cqC5&kZiqF*N&G9+W#XBDgOIj8O#2BYl3*Zy!KByLaquK~vr7xo7kf=1j$PRxwZf4P zNnW?F*@_D0s-Jno!&3>iinxh#E;v3WHd z9_pY>keWRd83N6LYEydcvT{r{oO>kS)+}V?O|eQxrod)i#Pe)HgD9h!7?*_!V~qP) zq*%zQ6kCY}WR|qS{27XMzb$gHbQ+)J@zAydyxTYsflXtwr(^C;>Nb~#4@@hmx}$Z{ zQ_(ZQLUJw24RajKGn%ma(s_4@ESE)MbDep8nk3|I%)>Mc3*-T2?ummz(T@tUSo%Pg z9^p=Gus7C{(gXXt?-=ZF{B-~3by!I$B`Ab%S2-z*F@-kg-xY05I=urHO?!ZWt(7hrdy{?YBASX#wtiCAt9 zVfI*QDG2K~{b$yfFKGfhuPxu{_;%~*X3Hrt{@R#oODWl&@%o|dfGn#?B$}+gM#V^O zw`T6Qj}b_Ulq1?2P^jKwn(`=_+0!psNP=sOCM=y5)*wBA)30X`0WZMJYn?gs;{{;Y z;0L@M4C=4L>{7_OTQDacO5F#yxA3l9ZX&C=6@Ax}eMhXhu{JM@9c!uN%g=b*BCm`{ zr=tc_$Ee(tZiVM&Md=^3XU`3qMo=yC65(DJK`h#Pg0(}!lC;Hzt*Zay&@HpwwfVV% zzDddjNqm!ONX%T!L~cGgk>IEyDTK3vT-1c&rJFPS-IF;aPXIWE1N;9gY_-?_uyCR^ zR^`{%)(8j+>^H@AA^eJ z4L@zze*Y(mI|(pWn1$<Jpd&zo$tQr;Zv(+XlhXcn~Ka5-6ic_<*-;YnNmy0rpK8Z4;W|)-}F-7oW zR~8EXF*3Hs@(ou?!}?mJcdi&DHkzC2O~6-#=S`yL=R>VO`0t&`X>0W{VrDnA3^@$gh>M z88}4N4vOqvZgL&8LZ-87p!lXtur^ALMPwU9=Kt@!?J4nF$ zAoj3lSb`FG*xY%bOY3h5!hDEw7TYN53LEP)-Fl2~TZ@(1ixgz1`5hs!zC2siy?EEb z-$WH@P<|Xqc@sN9+lyTKWZWTX^9G2q!T;TKNx5|g%}Y>UA5&ZecnrH?%^ z=Vj)gREsG2?8f-JP%ueEO*{``uC1RdXEp5K$u-EA!isN>_uFFg>6GOqZ-W|) z`d1Ru0!X0?zsA|ep;CYsOOh2B2sN-8QJ&IJ!@YY_8Y);MsXHmnz(SuFf_{B7tsgIA zf7cbpF#DOv&Wq4cA!m|f)12HM1?=f?g^pW+wLr-)PC(9_`&emu5B$TiXNxmbST!=M zfygFKr6WwRq1pVV_$+gxr|&Mks>UspLj51s$L~m19ewPA)IvYbI$lFvM8wMNo?4kN zvD>{?tJ;4C+j%wOCQuSyhlCAXi+)m|-Kj`W`_4)KjqE}51$p6pZ0kDPO1qMsB+;g` z%;F2R68Ns^V-w~oc*l*MY;Q23yt_q1#(~%6XFAizGq&Pmwk6&c6;=S)SR=va^rg5ADAlU23xcR z!<1@qc>mxPhfpa^9dkN#gxZ?_|Ih#a{|c+PU!>!pPVdoSL&xAVaEp{#Zz$wJ4PsfO zHLbiLU?y_cPW&up=kmYvqRIRQPN)#)8)8+AEbM32#55hgZ-83({~)8%|2IVEkQ({I|p{j!V^pRC+gEG zIvgQWBHHt7CWRY#x296q?1ImbZs%t}uz$00_4%xI!^YeRE+7k1OC zNqz|6`#wP2lUkj7InfAArpZJ&bYi5!x{q5s$)Wc1W+4YQUrWtd+8{+j(LEyG&A6Tj z_WpI1jFZ_b8S^zD36o6%&}1;KKtfD66NnX!)ec;$QO_yxYV+Z>;fv}|EtXb&-Cv>@ zG>nSydzpayjHS(SP6Wni*bZlxzH(lJa{Jyj5z|b81MlB;2_H z+-|AB=(mIxsiP@39ju(t8qW)% zm6OS2KB&Ij5HiOlF`(}#M=MldzU2?!&QQZW)foMtv%Bv=P>~>=1mmaJC9+=%&CDre z0K?xq)0TTZ`~>QJJcKTD{4}1a&jS`qwpe6lq@#q3OeS z@>y3Bwpj191+G~Q+v7&G#L2Y^JTh>RQTp^x{ehuQyl>y4Iz6%17>< z`$%7~kRQ%!`-h)Ig8e67$MPN8e&v=`8`T<3zI2m`f9LD&C{@*)#LjN-?lw0Yf*x)1 zu^;G-F}n{{f8I8qkZ-5})k%xsg;rn#fS45?lrOh0O>e{=5tB{Q4X-R-wI35ZN_`69mAj2|#N6{{0JoPp`TCs4!U3g_UmaSc-p73;23s@z zm}5OD8oTo3i%-OmJ+c>l8ArPGs<~nowCJ}rM zW%tm3{x_D}uUQI@Tj-r!@nu8_=|$&ugI}F@E{NBe7YEO*o7! z#4L)<8EiV6JLAOuEA(2sV}f$%_TBS29?~@;?v%X8I!4zJ1$m_9JGqlCs2>LerxU$c zW&=Wie7}3eksw_+xX*N2?~q3yQPrn$!=UrnhTqC$ab0@k#bi+H3J9ORZk{84+{?`4 z+!>UGKhDZG9+|8rp^}&ja7yFd!Mu528=Tv%vV+6~1&QARqDcF3CyVVC`sG|vF6vxABn=4eP96BiWjygZb| z7Yxye;}n%%CRnHN&uqr|?-hW^&_ak^!&7_U_`4sj-+h|(l_SKRfi{k2_rmx@Lnpqx zU^AIYYHR#^xr0Fj5lIPC?WNGR(Tqw7Qz#X&y!q&QCx4r$LM{F=9b!~8gP||BpvFlN zZkwM|K7mC&GXKfbFAFczzgFs==k>)Pc$AV=zjD-()o+ z3Ibd_@W0nx!pG#qXT(EFDTOWJb4Ei0z2>a;)!zX!8} z?qx}$Xl#y}&Af}06&lz-v|t6Pg%OpgYiy(qM1r_jG)KzA?X^KqcQ%c7k#ucM0@ct< zh`Oh>GYGK(5~pw_d5f(Y*DQZ6JT~2I8pMlHL^btIyftbc z!ef$Y4}PCk2~^ZL4f2p-@UEwh@nZ`nnCy-1fEgwd&KUedwaz+0cDCF#kwx|jvz|2? zep5#lgp2+JuzMvvkr-OpVY}fUUu1*}r?dQ|&17M7IGFuA7A~qfjrq$Gyi5w*`1Dkm zE1khOJ64<1jS5Z(dU2(>c&CN)!SX&I7iz}Ex&VINp3J!qi7eV@{$y?(u>2x7vYv1? zF&l4f|Ae(dEQdFuoOZjdla`;nC}#Zm1hP1=uTdca zZ1)k}+0MJ5=QuRM_dJ09(5X5!%jWaBgx&9)C2?G>z<0Z165Jwb*h{VKjl~F}YX>SO zICpM7ZxyE;7E>v)&**0%@E7%bw{G1sf>U#oQo;M%g=u&5r2R%NaSJ4?L3F&GM5)T2 zF@s|cDC40`WLmR7LPOaMYSaD_eTRLai+Cq zADmfK0S!!mJ}k_z=rMuX$+aU!*S57Ig4?hvWC+{yd(>h4ahT2d7Mjm}Rku?Q?0${u zcn(L3EiVgTLkG*x=kmCTqHJfa-%Zb8H8=>O_=gnQ8@p;9Xq7t`R2+jpUf1Cy`q)T3 z+sMWEm8p)ULbKbfL8bZdzfy3H)y&OJ`=boG2;4~qf-~n4io`}R3o@=_9-ftP19zxr z>4w3~t*a)(t^rUCGGIBJe2V18VA+}2^-iyPy#Bx24n>c!0ht_XID4SlTM;zNj-OBzM^H?5a*SG9gk?y;LYoq5<68?Qp#BD0~G)>fa0`J@g~^nX0_7KMXJVmr_VCw4v$w?44O& zcR9H{2@3{a`a|;FfK8y}PZVpY<$1YWdJYRI!zt?o6~|3xcK)T(;j%SSXwOW>Ws9ul zUK@mJLw*E=r-c)iwq%wnWf_p60;-xE*BJ^;8kB=0SI*c#nN$!NJDfKHv#GqiUcPp3 zcK&4LxRaW=zY?X4C@l#4TGQePcc-p{@+ULt)Vw0!b&Qt&mX zN<4nLGhl?}odK-;Nsc3wbNYhFE{qZ8a)ME~8GL&v zGa{G2$?q|lUoSVtVr6&LhZ2VPWW3LJkdl=G13^UD3^?Y_fl%1i!uK4_$+(pfm z@Y1Yp^ExL2n33W@nzq~l&$za8s~vA06VfUymhkodYVpEQ$%)W)moW<0^Iy$&TemzU zvdF%C{w!gbU4@Zc@j1bcy}d0}Vk^FlDgL={`F`3mi1|_h;1t@t!(6_>!YWmQO6(|D zfIP0$YyfP(w8bs<7BWNlcO+Tz(Pzn3C0KpPTn)8S?M=)X>U^=Wx|OP|v3&#z+(b^3 zS2ldE8%Tv2W$*7);O;Z|6U}pR$H)G-PiPD~Q9w53!(oO(0 zWfb5DUagO5&t)dFrpTWR6WR;_rTP0fE{k=YNSxFVgxBp<>IyZdZuvj2JFPDnn?KT= zu@aluz(+H4w86Z?{Z-LKqt;4oXw!@#_jly~MA}f;1Cro?A(B*rHF;|Dlj)a|a}EO# zaX6~HH2Me$d^O}{??z%W0+~2(3$*+uW$`+=?jaB|8wx}ed;@4LzV&cyIRwPSmU?!r zvw2Yvxun7b$*`lhea*3xU;#kpulwnVE^9tKR+2cZq)Fn-rHF@Y6CLQ|JnL{(c@Yb-q7< z^Z%Ot@BhRA)`Im$U?GcSH34aeURN`F+bhpNnmyFpJ7H5`9Q+DBS#rGY7IdD^H zj?8FNE0dSQRjs;gWR$aKg(9Ax-dYdcG2XB14Y_b%j*_aM$qHj{?6D3) z9Efgk;U#gwQ?M(-pr3DpFaxRKkb@~uM79;{e6@1zENmWkKQso7$%gFT5NMHF{yx_T zH<5Fx+GJ=}5GEc@fQagFCS=1Lq*jgtVjJ^!AGW-0bsEal^+J6(7oZny{ z7Svhvm^jfZ)KO{s@B-;Z%_&_{zZqU04-hOFTEU_Yx6rjcgMr;sylfkM?sP&$QmwBK=rGUI&4AVPEs=1 z+=$Jz4t1@v?;AFgNFu`gXT1%p+kb*-0;$+H2GhO$GiSEl1y0sk2KxK-?s~a@wxS-W z7usA$mQkJK;YsU{I2VY6M6mCH>00ct{aK=8F$9?kbX5Rvtl=^kR@y=k+XTuTtT2vi zod$J#|8+vdtc$hgnaUzVk-zpoSOnrHkkkH3PaXEg4;Ov<%gnL=!ebgJ{RugXexj8q z`kslVv*c7^$nZLwsX6E!akQ00u|M}pB?D&J_2m}J2$O;R+Bb#STvggJNl?8SLb;f2 zGL6f*AL?SU%lZnr=r(M0IsP0!QEl@9iZZR4GGvn2QxmoL7~f+`Y?_@}*O1t96H#RL zWSP_j9QLK(1ywH_@8ei(iloi&K{>fHtzc}v;yZD>)88;>P+Frvu=GY(^MSjUu zK^l_U(Am3a(=#?bC5?@p%~5R|Io4y3a94#9~pRuKwGj z>(tcKnBbk9A`Y1f3X|W`{UEla{w?vJ|BdBpQG}e2IpQjxky^Ihn3I3Ml%@a_+C2K5 zMRGN;dgOG?HSC$@#8{en6lmukrw*EZb2N9*kwEE?-XmU)2P}{M)zJY;H=PRyFM+jE z&(0X(oakHrC!A)@aP9m=EWcxp4ljH-X{<|iMznu>$ia9`6}M^U_;|4vW;Jrhx7{%y zyMXwG3L&VJLPQcxFl&c9YAQ~MF~nIuyT6~&G#zcc2=tpz1$*o@q&M(Ser-2;GkX2b z-txZL9TQOvcZ-*jV*BQd*bu$V#+CN*3?EV3)PUrP(4>v7)fPR?{eAnD!QQ zpK)P^=Lo8+_hj-uHv+P?b1V#iy)kXnHqN_iQgJ83=)M!Me#g7OXzCUZ>*QmXx!fep zevTE-lYw}NPxL-WJ7}nMx90C+VIm9*V?LC^%1Xr$5Q(_McTud-!lhAPtT8Ks z(ci%Et8QI3r;(jdZ~-olcc&^+&+GzYa$WUlv)c7OJ`k(<^PWB9y-;dr!^$2 z?THn`oD{&Rq8{tYE+1p|_6&8D8TWbY^|~7ub}G|08C$NWTh)!o*08cq%zQnzaRKu~ zt0N82)TXl*nYYCE%7Og)=dmoZ-$tdw5n*Qo7*yKtfkWtFrqpisjyd!@$xeuq2oao) zlJ@9iZk&}}tK+cJSC z%7_pkw8@MwhemqL(w>@+`Bb6?Gg4F4u`?-wLnA|z>_sQ)HoI+$*c$(l0_(mhVd-!Q z@1}!gw5P&5AQyL?aifKZY%oz`i1BXn0pl+!NrVB(3aBrwpx_(h?A+<;YDizMh8O!) zqq8+r)ZMF!H6oI4jjS&ScjlFHEW?sMXYlw1RFh)|?>w1Io#EN-!qmU9)Cf4D9RKhC zV7<^c`QoF=yc~4r@Unj&mCn3|CqgrI`tELeGj{gOaRj%R8iBWEhgd_j(oSFMh!bV^ zaV-un@&BElFN@UHD&fdqg8Xq_2`@K$&tnEKF^A5nAgD8d+c!-iNkzTEoMDi^8h;u-7gSH zzgOb~LBHqDeDZv18=^CtZV6VRl#y4{6{Ci>$T(ZDS$ivI@D1}Pk0-3#92btH_ocIH z*oqND&bk4~A#8&xNk^MWN11%gQZmL#XTyMNcF`DAJ654XBVaUM@9w5){9IGqHgh0+ z@{08`x5{FWcyg9Sk{ib{a^EO1XduQ8l{C4}RpE%yv*i0u6mjQn@*yKxD9Q07J}aP@ zu9T7yqRq+?Fh{3>=gu*7A3>>t&3#J4?r{iBQV9b73O!OGjtZseQP)J}RR9sh^M(_# zFW(rxsqKRB58Mq5yEvMdR2BR;)H*rmk=TSuW4ob@v{`hL{MAQADJvJQuu^2ND_UD1 z@(DH{`Bu1mhT#nxOmZe~3q$6*FMn z7rnyI>)vPnv)}MQ2Z#t~FkZ<68&Qhh2k#v_o5bE&q_gn#Tu-YwE$4x%MF;`tx8%0r z%P;xbl#(t?Q|vZ?&wYSC`D+q_TSi`+w)g&{e+W^9#w$-{ph9Q?kmb}4@f>akkEBNO zwGE@bLjZVf+v%Etx1i1)yt)8wNE4&!T4z_og|W3K@0YW;#56I8HHIuu9u{=#vg%?) z!L*baKt2c{_AhJfl#vUVDxojmxrG&=eS4y=QXH}-z4mE5Zu++(17?R^{*3D^5sS-e zunufPnZfQcz8+eU#R)i$Tc&d8wkXA}4Qct|N647|IPSch(J|3DvC#)7Pc(M3s++bT zuy%AXQlVI8T=xyC)z8{z=F>HS6|d)nM&sv2uvFm+`mG$5DP|uO^D448T`J|r=sSM| zJs*-iRh&I@H$B5M$4@xT;M_&v?n7mwff`-HZ5@HnnubYyO@=_NCa0BG?H%4;7ozqi z>8RAG?$XI~v9qmr!six|u8nsxx!49hk?In6-5RiAaz& zRORs%_c;RD3|E3Q+3kv7VM93wVqtUh!Njq{{}4%rHyn8cET#fd3KKxU1JeD{V9BNhV21uA^u@ zJmJR&WRO;c#e|owcAUe4jdfLFn@pSi=fMB{Z!G)p(1sih<+^x)3lzzF^nUrR-Xs}X z0aGp%$ucENi@G2&9}|O)1;8?ay3SpcUz5eklNooI$s^qCiv(AtbQgZvJ}4Cfgp`Y+ zenKE16(%$UG~F;-ktP0Q7k-ox9Y7)dU>o>PoX&eeIykta3b+9skBoKZmMoXV?mD|m z&Y3}8`8pvum^GnVySInmwyQxpJq2V@qiUg=IJa3{4J@#$?`*P27(&VCeD z)ZuJR+%f(H9^Mo#gFS~ss-Rqg(>y#UP7yW}Uho%8?3w-Zo3foDEegf!O7JD(!rR-h zJFkt|__d0AG!NbK8;S@v-4m`3xE@qNILtFwJ%(+?7e!9>#EzU$2)zTne?B(=a_^WOEl{kO3GK=K0nUVG zm(=M5DNKZSjzOuTLsB~HNX%4I<$PyGS9~^2Q1aQVYXS5y9h{5rooWj$U>~T)9fKLd zy>@kc{l+*TGAp*SK-o#u&!TECRv{&rqd@q&Txk_Ah~l@EiB<#7Oi&#e?|Z4injTw2 zI!7ivN!}zxi%yZ{W!*P|N~9Y;F4SjRanb=VdGj&X4FJWSlQ^J^>~L*yMSLmaFRvYm z#|BkFGG%82SXO-*!ReBRn8TewpB3V=f2pi1{TSDrqjHxf1mh@)w1fWRShnvH5lsLV zD+V|__UizH67jd4W`}448ELzj86K7D>(=&8WLx# zMdp~Zkx$5Ec$F`ME){vZ+=A1oPW-};53z}1cPythJFc9_?G_>5QJrajQ^Sha6s_T+ zjE{8{nqsUj9XYD+?(XzA<%yx8-n~9#G6dT@$z~!~=&6`UO7K3>)(UI`d;%}1%C<`_ z>U7|FSm(?s|Cw8!bN$NNuw=Ir+YI64;J)h`=Wl@G1(!rX7dkn^tk4Sh z(&z~4MhpD4c)R5B>x3@x*5JGtZa7y^bZkhFZM(IvUWs#3lhHb2iUuhes!Xndq92hO zJlr4hqgrONM3wsdtrlb92$hS|G57}fm%pPyT0~)>cgGqlt)ae7oHRFVBqI_d^@fAJ z4x`Z(RM+RkZ^Ndiap<|B5+O=(>ya;7u-@&&OZNBg&N$z*iNH?7%Yhycen`}pmF_2p z5%lk$|NWl^X>T*awXlktm%0=AR2IU{{kOTf+6Mlv*_w7*(nS~zm&iC2;h3LaolA%I)!WQO+rE0$%nC<Ug&pw?cekJ=K(J1}Y{*Q$98&YOxB6ue73^*ia?X(T^rkK>qcOxZZF zJ8uSlcFO1wU6X@1dA8^r+JiYzGw_;N=FIHg-ZQ%?qh$RIXSST&VEhZp95~%pw8s>A zLl}|ijPV@@5Gz#=hwPT59Rj$8nA&NEK=ng>-cU}lYORx z!fRMW*a6bp^dk3 z+H@VCYD}m{;f`%+6Ey&8Yy#d&7`_H=80c_KQ!Vo^#$-le2DpX?$t1+(PX70+ITtYL zpz$%#dLg_)vDnLu2^&bm+lmW9I?a6hd`Ua+guQ=`O$rxx^iv2ot#m2N=M`taNPiGb zr(NMBRB#hf9gydr5S(4(?)Kt>0o6Z$5qq}n3PM&?=@m_uxsyEy0%zY8ZI~oJi)QxF z2ud#_h^=B7?j-!>87Yi7StwY_pa@Jq-jKdbazk|7K?Fi^!3+MTVka5fWOP#nKLzXN z!Z>F0*yn2`Xy={LHvqK|_g`=GX-b4nMKObXphK>d1(?Pwp%J56&BxvaFBXo^BUACApq{Zy zJPw8n;+)Y=KqV;?qKM3FLkK!J-U-f|1N(UBz+=xeBRuH%e-Horzp>O1T3~yEi6#1? zJO`D-&M^FE&BKlCAn9M5-7mX+m*lm_50NyOvZJDy!JJ1wOb4O}5C^35!^g)oO?ZrL0O+=p9+_5suUNS(GUl9(xR~*=5sl?l zf~ug73(<21XWvziHG5{}9KARZJv<*b2wRIvc2Gk`ShvX}mdX1mDuOU81Ndt~*S;78 zBTB>NM9ZZEV*=p7q3S0_Yjf!g>j7f&T@+!{`+6v-jq@Ap2qA%iWJ$8db8IS@8wJ>r zc{OAVfpgnwjgb7>{-uC8tTcu&oSW~GIc=OK@CWn)16qqVN^?NAg0emH&aY`j#hIGN;)KMv$s zaB&`I(yqKwOrfrvJSkQyY2LPr7sytU52n6r`p#k3z`uVm`=(Bu&=qTod7d_z0Y(VQ z(|dPTow%l8DdQY+JXyA$a^QJHENc}KXXDjP^w}?FZG*CB^^e)Xd>AW_9ny`rZDX}% zLuMq;Hy-|EWWK+K!?enXF!#Iz7D&HVtESp*7@wn@)K0rUPnjb~d|8z@z#@d^g0z5; z7^xWR7j0cN(@ahgpJyENr#ANBAA8t(+)$hE!hRXj^CCz~ATzm*>Q0p$ojGLcu*V6*jD5%jH zxXBCNgxLX;gaoJ`e|V-X{^IPS8YRDj~X3lKVKX1&3t$WT@!qUm>Bw?rwGL8%{;(<=@L1mM~dEYMl6+ zrn6udQkb0~{-2miu?r=HM?|bd(3gy6&U*V;?`T_Hv(023l#`IAHXeDzZ(U$%$uP;`_VnC z$W>I;UY^Y<%mR5)+ZPu{3T*FaL;cRc3PYso&jrX9o5d5nAWPgENE0C4S72* zT1^k zn~h8#U?F;m*hSX^<>uzc?;8(QXsV8;zBRBSjMz61P7FAG&>9YOvZl5nLe$i3+m}rW z=pL9eirTMAxE0~~T|7Yor}c=ojUYNCBnO-gwQ1lMw`&LghB`sWN=+h5oiylP*m3k; zN}@CEQ8?;PtESWIa#ygRjbLVF^@e8|8F~VO`c`6CGrl)0#dFS3(?W6N^BvNS6WlaT z7Hhu5{8fOn?XhQmn(^>uw7)XVDPoFRZ-#Aie*g}Mlfz5lCsU%55Pl}ub;di0Mq%Yl ziqVdHH(8az2+u$EAz{0a1j$z7v)h7Uq{4;2Zsy7MjW0y2n6>fU%gPJ_dW| zbRwxSBir?QIQ_uPl0~t%f^T~xZi2G~7|KQbvqo2CI0N=N@1doW)$C(a9emDCn#Qd{ znzV`f`aZc}J`pB2vAw&*E4B{9!Mx0N{iYzKpC_ZtJWCYmdUrOM}T= z3CW>+BE(+Z$4+mycK@TkZ>7Gao);Q0be^`#9J~Rv=5@1ocDkU4vsY2h8^KXtW}Eco zQ+Ph*Tk+I3Uv}E>P=;V})Y>m!H;K;<`=nuCHTyD%K!=P9R!H8rP^B!A3MQpymv@7( z?L#LzuMg9}UBBPV=}&OJ-cXM<)DukC2INCS>9xI{2fp(PI8h;bQ4ewUL5$iU`QJf- zXk?uxlzDQQXJ8XwnZS)qjzQGb&w^*wWtt=71Ae}o|BRZzV;n!pM98l{a;)*99y!-> z#K{hKip|K2P-czje6Sc3SsapP_odso;kj{?0@&A`j}ysbZkqGD#`u8g$-rR893$ zh;1^B4*?BP_RaEc;r*J5yf6ZSk8FOfF(Ew~CO>2?UrIkThB}daoXcM&3ndpz#RSO{ ziVq!KosC~^dEjL>7pK$#HAYjnRIhgHnavuie~ew;FeR8?kW1x>fc2j}wsjUDA&sgG z?_y}u(2|@2sUqg9Yb*!NFXUK>&znbn{mr8ai3r2p-<2SNh$B8lxd7wT*X{rO-?5Y+ zN;VBz`LaTIhlV(97I;Ib;i>X`Z#d%KxG@j8#`8UAQxTpH_kP&CkZk{q8B7>20m@40 zBbO|De0VvfR6~bPyOe;NT*viVe0&-w>pK7ovvv?ZaD%Kx(p%Uzle{xd1~e@6{MD=c z9@ds&DlXOlRYYgGwVY`vL*YHIaxm0%9XXA z-PqBUcGEbiQPAK{n$1FWPIa7#l_ksZ@~6VC2Cx#0jO-{$LMM92op7h$VTq1GK%X7u9ZVffx4 zS@J?y>0H|37b|z?g#SH%LY%1LL=nU?@vRQohHs6kG2uRPW*Tf2rt}roy$hM|+||aF zAU1~|DQ&>n zBVwa3U@r9Y+9jz(-iYuxkC?mMIs&$%PX z3Q&siKVT+l^q$8oIq}QpXUV(+j`=zj%l|fsidzu!4f@>_+Zsn~q9au-(@I!M(7^vY zZ2@V&mEf{3$#=2^(@GPFluZ0A*Q-xubkX$q@}MF7GWtuP@3uM{BfP3P%j9&35T zhXx@t^!NZP<0&vcAyIHZCV0CL0Sb&=6bW_%nMruiyf6W5gEKk10z${wNpg4LMwvkN z(D7W!2!=jN#_>2PqVjph{}%ed8V_*GwePu zvqM(-hT_&;MaC04>Iv|Tm2)N*i-NE)1hc}p2PHk|AaHo77`hH><+;FjZ|^3N%(ETL zVNg9BbG5OXGk?G9RueMW`K)q^3Xq4AP2+^#{njs^rT8`0j|GD8G+l?djG_3zvO7k! zV#xObw3dH`alHTbROAI|{T#fHNfT9?@ylI9R~mC#z&Bgaw4Cu1GI= zi9@~88W65}h2ZwsduSI8`tQlep*Z#b^ZzR>E?=$^UldJ`N!dVJHn;fD*DEsV@4DQsiz!b)><)V&R|3;{24so z2=)1^qP{XexqK3?@0oYzUJj;0Po%p#!DfR6*M-wR^Taxk1M^#*l9B%B*PCY}iqyOT z=A~-08;KP>oKpv4zPmR*=(RtZL%-~V;FPVNyRIim-Zv4eA$e-6mn(W~%EVFR$J$s3 z#3y(!Xvti2z5Jwp4Hh~>EXy#Tq@2VAfb3cap${|=4iJ08vJ z!O=u&?82S*nehNM9jF9jje+g9%b$>NIXDhwmh5F>EFia-nh3n{;x-TtugfOIn>4p^ zUw<5S6B#g|+5T;K16d?Zo7hQMzJ9m?yM0i~7q{HBEdj`Sv2(9KG*c`z(_aF5w%H-M zeN*v$rAdvr?(w*M&|wtb9NA?YXRJ#otd`CnGV0cDD3;^uS8H$L5lr)4UkS$rtlL@8 zHz}@Ags7Ok@Apc_gK?b6M1>mFchy9* z-yICs&7MxMrEr6~+OL?rJZN8xR+~6XGA($tg`uWoq5#CKDQBx6)xib%>lC<(6 z1>Nq5IQ<^;`w7_-hGh}M9*xB?a=z@&!T0lDMaZ;f=c8auh3d&jP5Sw`asoG=dXayW zHZV_z%u9k<8LsvMB2Gg}o1O5I7MMEl+AK54;3lZC5ot#=`n1@)4_6LXekz1>`aCu2T0c~_n9+aORNpDLQz^|s{`vc}cO@G6k7{bQi! z6guMUllsxID^&amsuGm#=2SdcN&Y#cXZPCxTh;I*ll z{3u{!$BQxDVA51ZD_vd-U@zmRu*ql^j{pmQZO;L+A}r=CfhLHn3n4kHFe3u?dcxL- ze+*1i7W2v;Frr1T^ab!`GJ2nC5=*DTWde9pm@?^0LQx9O>?e8oh&qRdwT zaV!czBb;)SC?~w0xg$;1Im^CIe6lP4CsSct`%b=_6v#L^)ax!#&%(BjOE%uCvP7?R zD^wZT*&n}!9QHsjjwgSwT{@_Mx)yAd{=}5g#mPW8p4af~fNl^KTOD%l#Jb>PoaFzQ zXjmKXpBVc-$uu$t-A-}k>>4|hR-! z{(!nCU7F(xw2zUPI36>EVZ}@8LB>>qmYdSw6p1neo*1xF#tg>fCT4)0vOvXk&bhdH6bZbn7---%FheI6m%+i{(-h8uF?EQE{~6m$|o72kCD$z)#rN8%I0tXGq|Go zQ9nR#&+XbTMGSrSuh+gu-wF~NWp-)7ulIg;bl0TDy}4<8Wvug?WjSGU)yQhN%<#w< zs8i9XZd*d|B$(n(l64UIb*kp{v+&OZYDjQ9)Uy^lbd&mV z@`h;6cfulM=6*WYo?#VFtOq;h=hZQ1;Hw=1YfE!VRJD0&G$slWYPRYT5i(HvojM|f zqy6u7OzTwV1oz00STg)ZKvH&F*vKtXM0Dq)rlhM?2t4*R?lHckr$jkxRsy4wGQAW> zib1)(%rM42Xy@9AQ)EPpR8hrDyAlacDN)M+&8vX?wdZ*`FuTdwk3mL?=R0cU+%Z=i zBf6lum|^#XZYt3JcSP8oKEL2)1$K?eT|1ZJ@DO{i6pdVvbCQp}opzII3T^O1C4|eR2Q(F4{D>n zR=rREcSjON2u7}xxdi-8=2wu_)5OPvHSsxe+@m~$RVHm?(UXV<;wUB(JJop+d@OYM zS_s!xg9y?c+p_A)$yOM+vl|xYGif`o@+K)l-BDPZ9|kTVtVY!?me%maAr4t0DNZ#g z)St&@4pelj4^wk5#vL3$wNYp!+9d8RRIdxZ$<^ZSfeO9|IV{f3dEi#fPNLepa{9e! z#oEBM(n3veG#_4io?N~n-8F)Q;Pg(nO%l_U8SQRpv#%cKMZlaSM}rMD7i7JIOIyax z6v*t@#!aOaT@z27(;uA!hVO#nsPn<#F#So$KD!sZXY(2*nQFzp@fC%hV}EEEiB$Pc z>`r%aHZkKr(Og+^a5{NW68CgCXd-@VMDF3&EUny07A>tm=^;RY5lsL{K)1h@k9R?+ z1Ir-#(z}cV4*qRPDVZZi9-RWo`;kb~4s<)yuZhhOtFsf=2veemLOCYBlv$W&E30YL zvZSQWv~o9YWEkE)+bVfiZa)DIYu(TbtL#LGC6H_iXUEBE`ZVRO~^NW|#uM!1p$ZprD1WGfH5y;Rv8A!C#d z1kWK&7{yIrE6U57b$2yx>C$GP`!gDCFpOpyDKcloPxKjAAQjv=EzZG5 z8nK8s37S@y17J$Hz!DeAIOd1aea{Haolr4T0=ioyw$E=h%yqKw#bY&@$?bExZ0@WV%`Yrb2-maU z(V76AkCKJZFKe#5D?U5a-VCyELHeOqkCz6+T^k?+&)--=rMIywKT0nDDa?E)yUQd? ztf2H<1oV1uC&6j6#?5BLT$d^%qEDBy`03;|CZX@gp|m^`Bb1Q5%pJ%=3Z#GNFs&-J zOJGtGWt4(w%J4aoXSd_T**s9n7j!9p;uk^R=lTlqs)2NGx47=1U7j#~-U3i}vaUPK z#_c;`=4*0E+1Ts$}y0#KO|ZVyor7XMl5S^Z5# zegIZS=L=dJ5Vq%pyb9d9M)${4%u<3TtpC0i;gUtSAH}&KqhJ%BUC!?{H z5`AW31(fE#;VLVJgf6$eDUfA$(8Eq@_Np6(DmJ6+Rj+3y08U9hFYALIGpWFkR&PGf zxq1)Uz?fz}Qs&Me&iB3YL&qCWX1UH~j(XPd4zSY1n*d?h`ZDP`kXe%wl!#~NUrVH* zlzPUAQWoUa@oJDM%gdXbzh}Y7vB&p7W@CCyX;IUw=G*SQe#ynh8T_XtT0ZxxHB1R< z9}*6>MmqBx5F6(+h9wZV-TkS;35!eYMAf#^PW?O~re7XX3@^HF=AvZ$1C5}^(KzL8 z9oSE>ws(1XW+;FY$;P#BgO+J`xyPgm!kgc7Odo{CHS4Qn(yN7Tlh~39#04+RNxh(y z!1KoNkkAUJ&+9Q(v&+f84$_co*PNsBe%K}N^JA^|PtLN&m$hYkUB;VpZ3=~o=jdtQ z4VM;a&0xdp$&C(vUObDVK~7Frd?yni+f>cR{6KxB1a3;QsV*FW-2UBm)`>Rk)MdU} z`>h}5{F4Aa9(39>Zu%5N9-8+Yew>%aWOfm0eH)RYL-9t#pLN=n#dL%c*QsB#&UIP{ z0?EnJcrip};C4#d4yV#{-YRN=?3YkKeql@BAh#6o1Zg3!!&-WO>L*A2Kez$ zMw1j!Ew?)Xr1SdFT5!KwQZB^cUotqWaaKo0r@j*=(2cPxzgSHK!~m1$)BXmwvBvm+ znE0^OD(yrEpo7ii&{4<7VhxtkN*rE8qs z3aUT7;Rp_QL?{yO;AXcl{bhc)+9yak1aU;1dkj$-d?v!+CP(u+c!b42CF)(|AIPoh zzBewO!AugZL}9zqt&9TQho4Vs|=2U2D;~x=uCr=bsd{CfbP}MkGLMP zhp%_LIe|tDb59TOsm>MR*Sq&BN~NE}!j5&f*xf{ghfRRAhA$FYn9^^wOo#O%3Yjmh z;d8yeEP^R1cc+H5QHr-FlR4h!*|%y9pH?E>Wq~;*dyWyzN3ZOOOKT&e#^d^1Z5}o``U{C!T$mAH)F7%$V^lE^8d{7QIJ}=u8SJbsFO*BzxKJOm7 zy{W1C`?iX|jx!m=V|2Al$j`@lka_p~Kf>2JtKG73-_cvlHmuOC>q?xt#_C62N z%y$lrs5mg(wNyyWMYhE$u;!C?%StS_Age(?8Y_PjQEKbRP%o}~Jv_;D^EGL5 zsX&DDybuKNNiv9}}th9-dg~ z%+f+edvC*ZsARRV`kjxK&0S*p6V=resHd|u{pWA1etp0EPDL|~{=Ld%nC5lZ&J8QM zoe7?l@<4yG*Qu7ZXe1OBZjNzD22@E%NfRUhdB>GY$;(ZrT<4E%Z6s&RRL&~vEe#|= z-v%y;{pMIxEW`2&GA+kX+Dn{~m!_X2y$W#~X77N6L)>*Fd&=6eq7xU)MvP77*T!Xn z5+`7r0Lh8;7Xv)|w0j~pryePvD`FqZ0`jePR8cs3m>ZjK z_abOE7 zb49uf@nbWV@h^QvVx=45DVtT3j@tEs>v-#X;E7{r84Wmbd2bCXQZJBmV8T`3WNL(K z;lKa?SO#%U$ZKN-H8R0?cf399RH7eKbk0qEB><(zNG%6yj$?s7h1zj5=Sjp?^6 zRBTIm@Bj2aLlcum<_*!SH%IhVx?-3H0BaejSFy(d?nUW=Ea@(!46$M$o1-U8xbt5Y{yp!-y^ zu_VEhBF0K^$eElkB&|y{b^$gmQDsaMFe|SH!%0J@XJn|j1{Y$Okw2gzcO0S_f=4hw zlIHDrT4JG_Ra*IS=Bb?Blf;YWzAt1Z=yO*CCw9gi;}!|%gmZ1^@U56UN3V~sH%-mqkPHDV`g z@&#GH+?pDkav^A~|Ip1eq0IvJvc7Y2l%RZZOE4zBx5b{X@jG1lF`aE4LH#{;Kbw@Z zM||ms{HtkFipA79^DP&ryR&3!w; zoi@hJ{Jkf<++>t;X5Z3pJf9GFDmq^~;3me%a9BuB4h0KY_4a;vUzz(~(0B*r0}^t4 zT}U4-c!+)DtO$Tus(OEoOEsThK1&Rb>9;7;v*99saPD3XHe7$=PXIR6`F4L04!cS1 z9d)ag3=rlgZG8@d(T$Bpc)~~RRPl=it!``#3;DT8Z!deFU!5+%tY#CA1X5Av*qc~> zOBcjYW`ga|CZSJfN~qPwqO*l_0jHLgIlhrsS-SO<<$IyQV}FMG)LKzYa)g`;7USt{f)KwjJQH6EZkLb|>R|CjA*c=e z4`80(7G>j)8YCP~9jp1^41i@{2;h>_J;t5>*F!1PN1}a&0^LxZSct;JvFF#Z1bHum z%$;hF6_#_{L^;13E*ek$Uyd=_q8P*o>Vvzs2&@8@gO_g$&w12OsRbS%wy9-DdcDB8 znIAs(7nATg2ibVJ361M?Jb?M+l(_6|IIu660xKxVsI7pVXX7?U+Yv!wzEN}jj`BQj zy=Cq0q_;^Zm=WGoRwL46atMxl7&}A^m5r+9Nqo$lHW=tTHyxk4M(&S}Q$TJ#c5EgT z^zrO>3g+8&SaZxzfzw0_9eS(@@x}o>sYiBQ=-1c|2&adWzkTz*128O@mF5QSFG1Z- z+Mw6FwfMlzJVyPZ&>|^%j;aosy6jSr34s58{^$QHY_Jfx$M^4@B_=oM4A2)aXwZ3Y z+ETS1X2&Au>k(eyQvfht)`cc`F`%8WsF)}pgT)&kJuJi9JkA!gr==8>?`-0JzJ*IM zN=<-JH<)2XYT`)wR^f>H@sX?EM}2sIYDhd%(P8Sjs7TafBR!IULycpK)UC4UADcq3 zkdl#x*e#PCRFuZ~PASd#T>R~N)PWQozSf-4T2z9`_hwnYYcK0BO~TX(2v}~9%WV%E zFWsrw9(6vdPzXO$JMgjX$U2442l0GuK$h>Y=@-Ow zET4O5Xavasmu|_=`O=)AB%Yc5+^zKDl-Z=QG?!z6dxPtF50E`nr}MV8Suk*~Djs>* zs!ayjG-;q|&JmxsUg7I<$_S8&EN-?b4XeN)kB;V4sP@g!T+)g-!ZbCnE>;hZy62)I z3i%F2Dn!s0ib`{fqLP?2fl;B!>o5(mo<1zaB> z8=@?|AEg;Sv>wt&w(`nJ*Aj5Wes1w<=L=$8W6pGSV$BSn)0ixVdqIz}5xV!E@+P{L zD%rK1=XhJa`z0lxgYo!zoX)!M#c3Z`Eg#lC9YM&KR}~PQLQfxZaH|l{w<$Actks2L zsoeL?ZSgJ5^r9dv@@*YB+~4`?G=Rv&@hNPRwX~bDR)KX%JFtbK^|tBJf!MTq5VG^4 zdG-#BaNQvBP3C@xH$`xbhY;j?T6Y34#@mHL?2LOPOgMWYxr7DgIQXJTz&PiSGXDC` zaCp|HoXP->b-~egb#^!>d(~Sz!&@3XDDC4IA$HRFM|x$8qOv0szlWUOdThu~HmMyV>yX6nFJ zougWxR@6hErs8&Du7Zs%*F0BpNK5Q&bAJ8IH|Jw5VA~<_lsaGPQo4Nn>^{r57N<)T z(sWPN4t(AYdKjC#0|vMK6vKZpV6Osju05^Kz&6Trtzyql6PfXmYb*k_Vn>5Nkh0=x z=3R5eBQ$tw_&29fk+83Ftf78Dw14OwWrU5vQSB1+f9T<`wLDaQN+BO!GVutP z>vfL2?UTLJYOK@9Ohe{ez%!9Gq+!kzef*QbAiZ92ximpljQ5~K;z404UbJo+87n>v z{qygC|Fd^cGQG4NL8{?!^szbUhWXND1&DAx5vy#$E?IRXtafF<&|L6FJNE3naQd?1 zw5opVqd+jtWY@&3Fb;B5;%BDb95mb-e}3*5E{iYY#>oKJofTjKBSvpRwp%zq2@vCw zS{xdkS@+VM{WHUk{y3&{DT?3iP|zo}fxhULUC)etK;O+?`EHb$Dd`hh2S* z#GLmL+G@UcCrV2!cjI-OLtSN>LkwdWr2(?J-;+Wc6ie4Tv-=Q#i2O@YqhA){-zL*4 zo!e|Rv#$00{(8NX*N*^XSrGB@+dJlC@3Pz*rdGWqAQ5}#$E5e8sAjJyQ1ofsyzPuP z)WmP+YSh}>9=P1K+#pg6RzC3%gn>GeV|uva#?|uv7USNWb9qfcQAlUJs|eb7h;u zjq=!;Y=~}uDY*IF=mltARdPw(T&kHxaA?@ve=F1OPCh9}Ij6=B5u#(^sr+o~PsEKxSQ>nY%#2&SqPGzAP4LNP zXWtNpKTMVZkcTTzcKIhuIp(AWWXD&Qt`E-8Y|nhHHc5b&(W9Wvei>$!e-G@|Oyy5o zvaXVCNV$2cFRCVDKPRPN2ey+k)^Y5u!+3hkrt%$=IW>zV?z6hryi>o%#E5%g3RF+G z`NQv_9l}!&{1CtzT574DjPn=}uFTvsWE_A1lq#P9IcGxmhjFEiv53m4MX=$S^Ou6*AI4p)`nWZykUc2IJ#J4S;_vR*)sxLYBSb=Dx}SH3 zADLiJWH!qRTu9rr)AlgsDF;WGcB@yrQcr$FF)mSKrQ88&)8x0GFi+g1){*nN=qynq zQ$j{^z7870ZQREr>8s~2v*%nb5XM}5k#=)XL$)b!kUoUL<7k73#bRu^{^ZsRLK*AH z`r62Y%v|D~f@pfi^qMcgm+JSF9kB~oID!;z^{?l0?%Qu`&9@&f`zK0QIO-<%hQ)yX zTou?F;W+E+g?2y+QF@W9<`DAveltlfo0q*f0p(ifJ8W30{*hlsSytX%?X{9wl|Y>c z8GAWc7sa}zdS{6Y)}8p|WB^^myfq~!v+N5!c@#fT@A3K8_N26*SI4>&mtMvbKj3{C z!Fk5-V!KCdHX>wvFn9f%jbbOnQ+KpTWj*cMRpWt6$`>K~iKnWg7IoPPI$z7zNyAPrf#DM?(-&jg_-U0e^;6$+0mnYLlbUJi~c$~HBKv&n#0XRWtve|+SW=L)|N#EuF81<3e zJ5AYkQUI7!gqJ19Q1P~DQV#$eX{BCQK0ozxTEqtBy5{Jck76#gCqIbwtZeYyJs7g1463hNof>jk=Lk*24&QO))IsmTINzP5V{y!z7L-1&)N7)CB_X;5tDr#VS9sO;}DLe4?Du0-9+HzxhG z8iU^D{BX7m#it|EWWOfwYa|Qh=e*8dZe~?pAs;9~$v^9&uxyNZmmTU4mCu>tLOA$v zww5Hv1M9Ud!%eP;N;Y_(4Ziox3>AmwZkQ;cRbb`$ak3Z zftCy_*(a@r;Ut55Y1cC@%4ke^ha@X&A`-j~`U*9`M^5?Or)KS*;c3W`8A`@xyid< zrlv1)jUVf&0`p>0B@{N(!23R`?&~Z9XsH5|?4GTH13%xb{1#ghEdFVM7Y95vEFVq? z#Lr*G4da&VcemM1bWtOzTUjw1x6_-{E-pcd-;X

AHFx$D2>>&wJo3Fw*?u$BmyN z;qrNT1ScnMf9uIGbb=hc>#m*Dno0Y-+!eI@uAy=k=Ulz#O&vTr;_uezVCI?6WfGH8 zR6T*lddX@_IY&8v%XJ^B!|{0O+y_Ug@^Veo`*TYB)#K+g`3RnLS3N-`fgZD zr6BFmjYV|6b!%2HS4IXReCh3({Y|hk>Y$x`0x)x%G8TLcYV-^e!jam3hM9XF>gU|c zQ9l*4(9g{rS@=l)l=AeFfp*f?)e90ziMjeE#KR4SY|YObDE&$1c9?c9QJg#XxZfm| z6BC?aF*^Ued}oH%Y&>8GeTpJ`AC3xI82or_U39(Fn9@TDMKZ8J0kss$2mvB=gZ^&CW!la^L^t0$qgG8hmaymwojKh&c);7()(fnQ@m3>URoy&hq#Q0xaHjXv`ai>h9 zw3NaYIodYu?27`{){!;P_nsVtCzq^71mc<)^tqf;A*qk2-zDc*z|g|EXVeDAR=?!R z{c*i~Y&uBcnSODC_D^no^)$d#5YhlHNk+iT0qogs-dI8IYz zq3H1Up%fc-IR#F|s3{_X&xLWiOIFF+vW))ZR?&j^SkN(Jt=f)N-pBg!pp3|6PRI4Y z_o{p`Os=*N^foFRCz^mP1K8Su78G9t8k4(Ix92;7y_~3n9BopxC0jB;mI+Q-eSHG_ zuto@=Rj6(eQu1ntlA_*5jk0|`NL|AC)VJ6jeWN38>({d;!lcb|;f;i;g3v+cG-sby zoAZUtXvBMH)a!29G*uiSzAD=Bj-sn37FN91jSE8y@`6SYyl!NhkG1aFq)E}3*9x&4 z?#U`{Nm!~)jZ^ROPAZ#~mVNbpy`@~Aw*pt+dfrnrO|Cp*oF$tmTB~FNdY0IaSPvuc z;c4bMcT4JWLbi099=3mn6Gjd&0a*$%u%(Dgtx)vDd(CHia6XI%&^-^VrUNlf<{4GA z{HWOM=_ku9Tn%#L3HF^2ImEjVvZ3hnZ;k@+Trdr6GQxh^D||PM8#Cn@cs|l5&GmHR zovJkYEXiJD+HX%`{X$c)F-@Q>l8_7Et16v-IsTIrL(9ti%vrvL8dLXoD1{C%o|jeW zV95NmGQYDB1L2Mu4ohw3dSs~2{WPZ7%y{qah|uGf!H|5fLB37Az24TOGdbtPmx={F z>{?2cv~vY?fayUejf9oHUkZw?7oYfOoc6J}=7necj4X&Z-N`~UZ8*Y+TC2S9HV&$^ z-hknL8xNA5$pJSk&|)V~zozJP)od^Ws1xfie@SfegHEqUxg=Gkc zdXi}6uP=8(@rIDHsWr(*Xl>(u_m~3d!G_*I*hX8F0DsFs@5s6p4QV?(wQGo7ln-g& z;l{~X;b?U+kgw4_MDL8&hJJDxRGHZcmYo=F9q7l})DY4}ncb6;&hy4Xt`!fd>NWm% z*xE0{AMqpf%!tm!`#v@;CojJd89uGQM|3))dtnRNweRH#Y5L6CMuf(3@8>I+4@Gf$ zC8Qkauww~B{FOXMd8z`e`4am+rrUdl47`?X7XlbvqG_0by=`Vfzpa$*$sxMg^-9h# z#a}=kB*c6Ij6(7ToioP!j8LWUM8`C18N(W)A@D+RUKE0f^k!T0y$ZMFLAq7}ANv{1hH(fhS zT)%7z=f0!Y*FdtsH6Bfl_1W!caKYHyEy~0IgZ}YzezCF1LLI@&G~ef}%pFSWYOB~6 z1ai66dIin+5eUtMZEh?C!5U2|WP~q*kf0;0FtMfzYf(yy~__9VUQWAU zgpa*EdS|UAV@8`q$ZWKQ#s@6Q;{5Lr_>(2Kj#hxb&qR!{^J636sdS3@B`Mu*2BBn+ zf7?MRf7hSA(BJf2*yp43ae0TLArP${B^jwAIp?fZkM5LEFP4kbm<+hec}--qnAbui zE?#K3Jq76on9CcO(=@b(k!NrBaObnNJUVXxzY>7SVKnZusY`Vd;@XpN(7Zn1svWz7 z`>XhNIW?A!;h6Nt9BuL{8bt&LO?_?aYSDay+Ud?<76~(Nu_uRFNE7)K^=MxSX>E%) zc@)~eiGNBpD1f8Mpt`)7>|#gSQCs@=`JI{TOUvgsATM!Gbx|KE!)>TLEITfn&RI;I zgL21YV$gozV)6G5p|tohW``Zm;{ryA?0sM&f>%DCRlE_~?=%uUj*@$aFC=Qbj+UFk z(R3I@d0W7DV0w!8>{`zG;SeX23*ox4{nadGrF*;S%x`?}&MKZE?{%L1i78FwXlgdw z&M$Cl|2UCohb*)7-O;#??W;fi-WP-udfoe6`7Hx;IKoNsMfL6g@RFCds;iA$kyzyF z&P_l>)rO>tDZ0b%HMh84@x>6*cWQ6h-MTxU*#i$$+RfKrPU#v-+%UW^RWC>HeW8?x zDM>XOMbI3jc+;HCOu@KNmM84{l(bje0+=D0j|1aLK8wQ2u(1`rL{8)s{$tlc-!G^X z763%c>`RYXGv_K;waj^=4kRc2Ad`=~J2`6lL2J-YJx}y0!sfDq1#eGWvQ|HBc^wvo zL2d0x{Wm;jo_w`qYqi$C9R25iV_B5iaqc}p8Y~xdh}5;Wap|e#>C|z!W)h;myz?}M zL@!cRZnZ1|2dCEVnJqRNA zIi|%#0`ZW3ED-jTqJ!^Q)L{5>@zY($v&%0E<_hD)Q*$a7H9P=NyiQI-(;)5Xw-u}F5PYbVOFET7e+9Fy~%qml_dU{xBSHwXo zdcuR4sE_&muD_Hwk_Jfo&AvoC;R?z^&bt?-8@4d!WX2Rz75n~qnNmhvfm`YH3^${|RtKWmO$QVXgGO6zv@A7Y%32=lG+KMu z_0#q^#}RY)sYB^Res=ML*_7T8zpn89CJa%|R+AfB`_8F_jWo^$hJv~Uk&2q@1*u2}koA>Iej$fQQ$KFe zc}iL)a)2l(sWsYFI=+J*8ZkP$bPWtrky9Dg<5aCm=)^+qR@4^(w<OwtH0SLQ6c1$;%@3-=d!S?Axt(4(qnf(RTq{*qk#g_Y}U!0kv6|cffr>+fq z6cZ#y2HG16l82BmZo50z7#p>viUD0`7?@i0BJFj)1&kTl6N0;|zYW&a3hJ6)Bh#eQ z5&&Xr?D(_{1Tugx1Y02~1Sz|?a$0;Wj%)kTny&*^A=qryXhK+j4wufa?Vm}{h%qi* z+c9>6*>;ir9U`1lj#fX+w>NX7q%j~mR9=fA*QTb5cWW(Nl5@(iK6*8fjhS`w zqtpDHwL)3IpMnEg_C18ef)sMBQ5_B32DV1$Qi$Y1WYpmBM_?a`{wG25KY4T;7*`Ce zrJ;Id62PJ6xIFM@ES>g%nF}=`j*EyVndIxO^1(1kJ6;J~(c1}Ii-ULcOk@QvZqewC z^fAiL$Il8n%_{?s6hDN7Jy!dD0P7u3#f2D=$btpQeHFjl6yxpW$Nd|}?JP_Pef@w0si4AqnH2ZbZao-n!&hpLiEQauFr;`PI=mslk_qIha2nj zA5Od7zK;`BED9yD>h!>#abp_2hO2%ud<*Byj7X0Ci;}-HC@tSW!iv?|OWzsuAa~2Z zmKw5>aHi-pzm2+F5jb~aG|iIgr9#TP@APlZgTTFbkO19IJO2Is-~WFs#rJPe#3hcr z(K7j*E2-IYj+FD%+6vCDR%!wizGyS?hSWwaE;Ob|h>~Ygwem$J(!T}5w9>MDus9J{ zv3Ogc6J^XdfJ9n0X<%tKliFb|GJm+hu##^DRcBMWFiY5&n8Vh&nGnp-`Uype^g(_= zMcQ@hs{Jkf?VI^J({)TzYM8OT=$hwekocoatFsPGXw|oU2(kfad*C&nv!#qiMShdM z?c+X9jSeKH|9XLEDQ&;}V}pRu#Fxq5`zRT`{(|xRldd^|)G_tT^l*g`#H`f3E5as7 zIDw#JXL}eL@y0~p7P8_;+Ue*xBWt#VKz^*|-Z)zcv=FE(-xzZVn)D~?2n)5K`uEp6?4|ynM z&v7J@^U&&@uZbXhY?7|$<8E7oR5%={d3h0piBlze_+AFEC}#aBls&x!)x&kBq=Ct+ zsK6U;QgsT@cDkOBscaN+-1Yl2D1o#3M0YCaL0{AMz_5O5$Ccp}VfHdmO`JC4*CXsB zUJ?CvK?-hSno5_t|DDrfK$yMdtdAE@Y$uc&6gGZBXG(Eeo8x1lSXXp2R2``}*F0IC zR5{MWlPJ3n#gykZWQFonXj}x78n2ychY_$Q{_ ze(7r-8G{z4Gcis!7%PvCVG>w&(wQ6>zuR5Y8gI+7vBT{76BqUh^vlX-vG!0a!x5X? zD{?h<>UdB@KT{pcK6E|e*TZxo_1XtKn$A8v6ZnovA@1p5aUEGV-t)Pe@ltIP z=CB;J(%$E?*u^xuv|ckH6RifSaaysOQ7T8aOgG^-9OJNjy)?3qGpj9C-0^|xr+#;s z40Tm)35_Lbdk`ot(TAE#^6O!g4c=}YVz_pUaAZQlD?CIsPRA|7Ik zf?0YoR$CK7C5}BO?ae^OXWRI-FNo4;jkg7_<0Mf>;oMU;^pv0_I)2p*+)a^^mfGiB z!Z^M$a!n~e{os~?)*~VP(4}8j*BMO^uRA!P&=V(|vjUFyNoCmOK0U;{kH-wZlgWFX z1HcS5{ry$Y-h0+Qp1&^fT|qpBE%~=!uPeKjOY7;i$SkWa|;l5|gS{m1koq~(0Mz~xy1pDop%+KARk zO!Cd^?7hF`;!!aT>&UH|L?w0SHJ%v9cr&)Yy1=t@H1~$6A}7HKE!Yop5&{i6Gv_%q zOtn6vPQT7sKNdM>gv8wVb9SU7aRjz^Ms2w3Qj2v~W-VxqMGrW{UG!%pMVQL2p)jf9 zWqm_DK~n(#`Q)SWI8bj-^=k@MU1zX;HR$)-Q@e zq7*%uHI1xb6qbYuI%c0@da>d6QU7K7%j5J5LO9Jv&HHKsZ{5l-MXf% zqujJHfuFhVsuI6R7aryBE&K@F6K?nrtC?9`{F*^N!>rzf3HrT=B_ZE7kS{24gq}|i zzt**~f%+V~r;!mF20}ReOMJu3`-RqkZXIL4OysqI=QuZ?V?{JTKwviO6Wt2b$Hwzk zaQ_+NQzhOVCh}>~cOi-2Yx2`zUS^Ij>BlK8ElFlsL1WSjiE)oDInD>?&0H*qH8Y6C z#JTe{FM`fRCyY~!J3?Iw$b7F+_GvSsg1xUTVq3=gWHUT$CHATo07@+=k2ZnT*IgP) z%~^c$%ElJWfmaPamCseu8rr(;BeOw$=h~==c`WUTzdF1#`Su$e43KZ+?i<7?~mp#x{*TG~L`M&i&5M z9XX?@1|8f@jQGmGdrcY^VW}+;DsT^JvWF2$wBEK09+eMVq#@aqDgaQ5z&GEovMxBr zK;9KM2P`_?hcQOcR`KzR)$2&vO;)>}u_xO0(gbR}f`YY@tt8KAv^mU(0KQcVtcvo4 z^2oYl+o2-ms_h9NAyOt!KU|-Z1-ti|J1qUQB*REdtkQQTnS2AQhxW-*r6qSrGV^i{ zw6`#?b5I!^|J)z;nVcoNalFg?Rsxo)J$6%8167(cjq)Uuh6uTD1hd)*LzSjCE~2r;vX_ zYmWrQSHk{TXZEBOraG^q9p_%8n_k!#E{D)|vNbQufo+nYj$dxrYXv;y_yA8-km=EP zntB>`0HL-u3nbb$uuY2$TkS+c1xQ=3C1)x??VrN75zF;Ee!nwKC>CZ6vb)#{=AAhP z-`k4kw{Dp5MPz0EnAeUiOn)ziRuuhMR;_kza_;;}-y4nm4paQHc0A+b!Wwxepfirk z6EQ+t^o;**ZdHCd8@jvo79t*ps=x6OPTuE(md)hz0%v0F$EXsQoRc$%*z(jZqfN0a z#erENnvhYo&;(x=J3^cn=pU|z%?=_to9RFQFP7S#N}=9sZt7s*Yoa#MD?#{PZcyX% zq|=;$^L_qWQ`J0Y=pEwJdcQ#)V~672W8*_EY@1OYx`bQNR{+NUb|2>c)Q2s;I&L%N z4n<<_%;57l)aQdGks(0|L+fPvQvucO)Y_jR&G7Y-xGBNX|qj{@E@M->fNY zv6hEN7<`OdaO*>~-o`rUYR9jX?J3x%WsJt%yeQaX%C*-+BPg_jrjoEG)stJ+`i-e3 zqcunV$aGW4I9{{AyEK!FJ{2@fH3x^C+@cF0)=8~>OrMKj`8p(F{$9T2^nqfxrDcSz>~Z}YcXW$*b7>oGV<o;JNy=_T3-DaOvo}!;|EGpTpPjv1EFOFN}y0iX9q@UVhKDz;Zfx6j8g;145^G zpNdd>#!6!21zS~??-TEVA)BHZ?_Q~#z_w+^$2VDfrrA4`9}<&97{0Br84W|T>YyEF z%Uzr|k2yAon_7b5Z#(tg+{Y1TboQpFm$UQtLle||ZqL21pzP1JbHbQx~L86n!Vihk!pt1(*94+R;-0a!=tZG4Ce%$#7B)uC6NmXBU|H z0$GKYa?{d)f*+kpv#8tRG}ErW^Wm!nOJEio0@^1&Xc>QiUWyrGUjD*Ayd$zC$#)ACpxgi!%vmU1*9Jbrvk@ti|I#ymSxK?>3Y)8J1z z)klaag@&;YtpDshO*J23|So_wO%PWNuSGCH>o>^Y>>o1KnInfca(R3t)a> zCf%fciR5q{ZYNvr*Dc%i`i#EuDIm3y4&NmCcJI0^0sf@rcK_l8>y@zjvJl5^<*O8i z8{^DzCr>G>6rgC6P=t@{;XQM*cY|$Har!Q$nRp4kl9iWF>mt3%T3yej)JV|gOr!{f zIf(P@_*gSPXDy*0L}=7sA_F00YQ!Rcs;>eS*`TAB6a6@jJSE6iMvbEE;!L8sK>CH* zRxnRWSgrgzo8F8{AGY*R4^T}W0(`F&&qW|fx7Kzl}^G39TkJ}sMGVn zh<{FYs7-3omjrCmM?36jfnd4l0{}R#Jv#45j?QP_3X4xn+gpq(hG}#2+M+g-|3ise3rhj5x3a}MN7Qgz1;OW%$Lo3 z{yBncUQQ7y1;<}qg_TV@Y^Nyt4M@^A?B`bWe$CyJ~CRS@bk#TXkwDmX=XE5@OEyTA>|kk|8w zUE;G`(=^r}$)-o*BCyOJh|KJJMOu@Z^s9?ew2hO67w((fkYz0}sD@d?H!H9Myw>rg z1~QvSY?jHtZTFH>PSoQ%H(mAti?&)OJs;PISWBJyOcsVzVCl~J%<^)Lx{0rN@|k-N z$a47d4NXpoKV;Or<6Ahc(hP&N6aVl8NAT0PijW8|Zv$hSXif)0OGv<}mN(mO7*Y75 z&OlKx?7D-D_u%~}wbKd@HLsV4t1At4+vEvLRo?;#{p1{rbgwDgK>C^)El@Wp8ju9D z8}IGMYUyJ~?SMLTC>&;g;{eCjnKM}_@zFBN(u?<^k~cyLk>Ho}cmJN+h77~AS`6`o z+4ej_OHdKN^;*+&>lqhnxb>uFCk&=O3tzp;n8*DCNFa&ZF%x~+w`sbSQ5(%Rw?^Xh zRHH8fZf4_=^%;clXmY!s_3$01Pd{qv-bQFh4pi5cr|=%{L6=_|k4XH9`R85WK%D!c z&^U!b_SW03u3^3d+T0>Fkp+zJBT4ZpK^abZk$PS%F+tI{#ze437bjd#bbgJU&5JHm zo1iH!g4S0TKJrfS+%;MBTf>(lQ~tFCYJVuR&kXWjr&@yF;@DJ#bB%{t2m55e%yX_? zw~nnG!6|88vMBRhI-+~}|E?x3_14KHHGLhxs0c}SgwJc1xcS)}w;%9_BxXo#c4m&W zI+AqzK6!lb;bYRqw@26s2H3<~8{YxC=L^JaC3=#EP9)A&z#{P)X`7qmQ#6-bz6+Q& zh3_Po442G6MyFqof@TU@7fUCTtbkk6&-QIQuL(NCh&^V5xnbWT#<9r(2X|)y#$hKj zT*Pa{N0-jeIQaWS#uesP$z>FDlCn|W$L|&0yZxWjbk3IsV@_g)ZAZ{g0tJA zJvp@`BLmEA5xNoa2_+r{`&q?;BYcn*QZnRP*2ZBiu1(j>8QpiqzgPb6|0*o>*(zr^ zW*ZDosUU%Mzjegqy#o(zWC+|(Evx8{aotS894a_Yvn-t8o>zc>57(`dME=vvOxTBQ zc2l;f6X6|nJ=d_z@7p8FMDRnL$U9VOy8Sw;-hH(sB(6xF(}OKaU{dTTcWYl_7iey! zjQE45w54^~(C|V)(wm5t=>w4X?7$qIg&4-cQlq=J@UbrgVghIdIG>O(kwWkcJ)gdP!V8P+yW}dr zH8)#_ewjp3Rg@ORaqW0VDc-U~Sr#bm&?d|4)@I9J(}PJVZwUX;G=AWtJND!B?>)Ze zLvCEifB3c4YRV9daCgd7ha;>*6&A;160*Av)TANg%kTasI(=QFGb)mp zy`=Ah^;~{E^j#f=(~NW$V`#V+S;OL&qO*EaTX@>I-nqaa@SGE>-^PzO=rYa6+o8>X z*aUDZ1X4=ni~QYbMZtH}mHth1GJ;MLH!V&FM7D!k7}UjH6ATW^r~?+S*E@MJB<0r` zV`eUB;wdxxqv7in(}iP?fl9uTKp+8~gu0KaE65(1Q*3_uPiK9(_{{K5)h<-KAW2LF zuQm4B2zm6PE@Y&Ad`4&kcBmEP_!W_j({F)y`Wr)v(Rg7`yrfBpEx3fXPL6zo*jx!l zKl!jXqiPt+X}}_(69si?Gwljv?7`!6qdMz7Wlv}8%bj&`1N~XPf{9DNvtF*WCXpm zF13Qc*EyWNlqjJfwllqgcFt3n@00gAkg#Y6cJ0p3>mekcCSg%V%X2G6GxV=Fu9k-< z*SPJeGW{}lENxIou;5{F)KIeJ*AyxsNGK)_wp?Umbg_8Mvf8c4M4UcjkY-0IYq571$O&B&=0>2^#at2CbPxsarTj)hIzc@(K?avza@_=r<&OpquZt?36%$oevo@4B=I`US`I`JHN zxfX*R@BrSf%I2{eEKUVUkGu13uqyjGxb^^n&x;`!dus725TmjgG>JBrbCmjsH6X%) zacn!jlJ7Db1@b%n_=MnB+s{|%JzO9Z*8ln6Sni=6O)QM_d1zst3=?aN<0(MDr(>lt zYoq0Aj3H+9CVle;dY!ABA`Snxx1GEoC!6$uX@9-;Dr#{#hvtc}w3a*V@MoA|j~thz zL$mY*JS0qJDo`TDQ9KgIn_e*4b9iqY-mO(S@SHP;JE-0&?JswZyV{AJP%?o2h)PlT zVGWj*=rAwxf1OEILUD^>B6kwvvbb$j7kvEEtdizmmxrBB{Egrv&Ptp#Y#q4SjNP7; z`^~9*Fl)*;HxZ8w`;1Y9;~?Z%*tyNOb~&z)eagkR?d)g{#-$Cuww}*W8=OQT9ZK_n z@#_Ta!60NeOgZ4qWaxmpDG4>_q$hWmWa&q3Wc}1L&cjz|b41|}%xn~ha*1DK+3XDigvwW6%Ex>4Lcf%VZiU z?|CI0rwxvn&OxV?k%l-RNw?1DlLPEb=GB|Tr2oS?tK;2C*N;$k&R-Szk@j^yaw3s{ zohr?lgyBHwK3*$eUaq`9Z7`=yVim_!E;5z-)<~4d`^Lxi&CPAfj+D)h|1BRhg{hu0zrBAbcw-s&luB0;ydj}Y8>w!*cBuW=-*%CPmb2(+=Tzpm>BC7T zL_NmV>rt8cyo`yg@XKY|K%eE<4!{16tWfY-qHi%+x=i3Wv7_V9PEY&w>Rl-y6}vy? zS|IQMuNj5G45;0XF-p4HC*(8x2kYtKDmleVqXl}$dsH?}!E+6^f8OZ;KP>y}Hy|&$ zO{Lv=8)VO^!BZ1ccz=2t>ND}D)X+8ZM;do-9#jUmFg{L<`swTQDFssMtxD>! zMBGXqtqnZ@PgH*xuXTKGf+x7AwC9unPQQ+<$)PUjSCjRNnOTdNJGBGqcQ&`FtX}7> z@cjE2V%-EbeWCiy%LwSY{afQdgHmAM1zZ;^Ia1+mSZbL1)2R`KSE@*Dd6a;lXg*<)mA@B~Wf4OOrZfM_O7+4T=n=al{?bp zD-CJzHMPhRoqRG_B#<>&NExb+C=2wtApq{6p)pf1gkU*pBN>5R7Iz97*VV2DY5U-+r8ut(1p-AI0&0@sQpw1Sat$X{8Z_EoZ#2} z=5J?#N5DvP-u(AJnMknyEIP%z!%f^OsJjeO~- z*;N+>>wKxJh3u18g#i?L!i99_vdex;K_Qb)>T<8a$JClbIF<@ya?T{Sxx-1qV3l*q z*Cv