diff --git a/.DS_Store b/.DS_Store
index 66734db..0421874 100644
Binary files a/.DS_Store and b/.DS_Store differ
diff --git a/.vscode/settings.json b/.vscode/settings.json
new file mode 100644
index 0000000..352e893
--- /dev/null
+++ b/.vscode/settings.json
@@ -0,0 +1,9 @@
+{
+ "files.associations": {
+ "device.h": "c",
+ "ahrs.h": "c",
+ "string.h": "c",
+ "user_math.h": "c",
+ "__locale": "c"
+ }
+}
\ No newline at end of file
diff --git a/Core/Inc/stm32h7xx_it.h b/Core/Inc/stm32h7xx_it.h
index 3cb491b..424deab 100644
--- a/Core/Inc/stm32h7xx_it.h
+++ b/Core/Inc/stm32h7xx_it.h
@@ -71,6 +71,9 @@ void EXTI15_10_IRQHandler(void);
void DMA1_Stream7_IRQHandler(void);
void UART5_IRQHandler(void);
void DMA2_Stream0_IRQHandler(void);
+void DMA2_Stream1_IRQHandler(void);
+void DMA2_Stream2_IRQHandler(void);
+void DMA2_Stream3_IRQHandler(void);
void OTG_HS_IRQHandler(void);
void UART7_IRQHandler(void);
void USART10_IRQHandler(void);
diff --git a/Core/Src/dma.c b/Core/Src/dma.c
index b0e0806..753a344 100644
--- a/Core/Src/dma.c
+++ b/Core/Src/dma.c
@@ -71,6 +71,15 @@ void MX_DMA_Init(void)
/* DMA2_Stream0_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn);
+ /* DMA2_Stream1_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn);
+ /* DMA2_Stream2_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn);
+ /* DMA2_Stream3_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA2_Stream3_IRQn, 5, 0);
+ HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn);
}
diff --git a/Core/Src/spi.c b/Core/Src/spi.c
index 69a4a88..8a912fc 100644
--- a/Core/Src/spi.c
+++ b/Core/Src/spi.c
@@ -89,7 +89,7 @@ void MX_SPI2_Init(void)
hspi2.Init.CLKPolarity = SPI_POLARITY_HIGH;
hspi2.Init.CLKPhase = SPI_PHASE_2EDGE;
hspi2.Init.NSS = SPI_NSS_SOFT;
- hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
+ hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
@@ -210,7 +210,7 @@ void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
hdma_spi2_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_spi2_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_spi2_rx.Init.Mode = DMA_NORMAL;
- hdma_spi2_rx.Init.Priority = DMA_PRIORITY_LOW;
+ hdma_spi2_rx.Init.Priority = DMA_PRIORITY_VERY_HIGH;
hdma_spi2_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_spi2_rx) != HAL_OK)
{
@@ -228,7 +228,7 @@ void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
hdma_spi2_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_spi2_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_spi2_tx.Init.Mode = DMA_NORMAL;
- hdma_spi2_tx.Init.Priority = DMA_PRIORITY_LOW;
+ hdma_spi2_tx.Init.Priority = DMA_PRIORITY_VERY_HIGH;
hdma_spi2_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_spi2_tx) != HAL_OK)
{
diff --git a/Core/Src/stm32h7xx_it.c b/Core/Src/stm32h7xx_it.c
index f5bc4bc..cfb34e0 100644
--- a/Core/Src/stm32h7xx_it.c
+++ b/Core/Src/stm32h7xx_it.c
@@ -65,11 +65,14 @@ extern DMA_HandleTypeDef hdma_spi2_rx;
extern DMA_HandleTypeDef hdma_spi2_tx;
extern SPI_HandleTypeDef hspi2;
extern DMA_HandleTypeDef hdma_uart5_rx;
+extern DMA_HandleTypeDef hdma_uart7_rx;
+extern DMA_HandleTypeDef hdma_uart7_tx;
extern DMA_HandleTypeDef hdma_usart2_rx;
extern DMA_HandleTypeDef hdma_usart2_tx;
extern DMA_HandleTypeDef hdma_usart3_rx;
extern DMA_HandleTypeDef hdma_usart3_tx;
extern DMA_HandleTypeDef hdma_usart10_tx;
+extern DMA_HandleTypeDef hdma_usart10_rx;
extern UART_HandleTypeDef huart5;
extern UART_HandleTypeDef huart7;
extern UART_HandleTypeDef huart1;
@@ -358,7 +361,7 @@ void USART1_IRQHandler(void)
/* USER CODE END USART1_IRQn 0 */
HAL_UART_IRQHandler(&huart1);
/* USER CODE BEGIN USART1_IRQn 1 */
-
+ BSP_UART_IRQHandler(&huart1);
/* USER CODE END USART1_IRQn 1 */
}
@@ -430,7 +433,7 @@ void UART5_IRQHandler(void)
/* USER CODE END UART5_IRQn 0 */
HAL_UART_IRQHandler(&huart5);
/* USER CODE BEGIN UART5_IRQn 1 */
-
+ BSP_UART_IRQHandler(&huart5);
/* USER CODE END UART5_IRQn 1 */
}
@@ -448,6 +451,48 @@ void DMA2_Stream0_IRQHandler(void)
/* USER CODE END DMA2_Stream0_IRQn 1 */
}
+/**
+ * @brief This function handles DMA2 stream1 global interrupt.
+ */
+void DMA2_Stream1_IRQHandler(void)
+{
+ /* USER CODE BEGIN DMA2_Stream1_IRQn 0 */
+
+ /* USER CODE END DMA2_Stream1_IRQn 0 */
+ HAL_DMA_IRQHandler(&hdma_uart7_rx);
+ /* USER CODE BEGIN DMA2_Stream1_IRQn 1 */
+
+ /* USER CODE END DMA2_Stream1_IRQn 1 */
+}
+
+/**
+ * @brief This function handles DMA2 stream2 global interrupt.
+ */
+void DMA2_Stream2_IRQHandler(void)
+{
+ /* USER CODE BEGIN DMA2_Stream2_IRQn 0 */
+
+ /* USER CODE END DMA2_Stream2_IRQn 0 */
+ HAL_DMA_IRQHandler(&hdma_uart7_tx);
+ /* USER CODE BEGIN DMA2_Stream2_IRQn 1 */
+
+ /* USER CODE END DMA2_Stream2_IRQn 1 */
+}
+
+/**
+ * @brief This function handles DMA2 stream3 global interrupt.
+ */
+void DMA2_Stream3_IRQHandler(void)
+{
+ /* USER CODE BEGIN DMA2_Stream3_IRQn 0 */
+
+ /* USER CODE END DMA2_Stream3_IRQn 0 */
+ HAL_DMA_IRQHandler(&hdma_usart10_rx);
+ /* USER CODE BEGIN DMA2_Stream3_IRQn 1 */
+
+ /* USER CODE END DMA2_Stream3_IRQn 1 */
+}
+
/**
* @brief This function handles USB On The Go HS global interrupt.
*/
@@ -472,7 +517,7 @@ void UART7_IRQHandler(void)
/* USER CODE END UART7_IRQn 0 */
HAL_UART_IRQHandler(&huart7);
/* USER CODE BEGIN UART7_IRQn 1 */
-
+ BSP_UART_IRQHandler(&huart7);
/* USER CODE END UART7_IRQn 1 */
}
@@ -486,7 +531,7 @@ void USART10_IRQHandler(void)
/* USER CODE END USART10_IRQn 0 */
HAL_UART_IRQHandler(&huart10);
/* USER CODE BEGIN USART10_IRQn 1 */
-
+ BSP_UART_IRQHandler(&huart10);
/* USER CODE END USART10_IRQn 1 */
}
diff --git a/Core/Src/usart.c b/Core/Src/usart.c
index e29e13f..2cb8fa4 100644
--- a/Core/Src/usart.c
+++ b/Core/Src/usart.c
@@ -31,11 +31,14 @@ UART_HandleTypeDef huart2;
UART_HandleTypeDef huart3;
UART_HandleTypeDef huart10;
DMA_HandleTypeDef hdma_uart5_rx;
+DMA_HandleTypeDef hdma_uart7_rx;
+DMA_HandleTypeDef hdma_uart7_tx;
DMA_HandleTypeDef hdma_usart2_rx;
DMA_HandleTypeDef hdma_usart2_tx;
DMA_HandleTypeDef hdma_usart3_rx;
DMA_HandleTypeDef hdma_usart3_tx;
DMA_HandleTypeDef hdma_usart10_tx;
+DMA_HandleTypeDef hdma_usart10_rx;
/* UART5 init function */
void MX_UART5_Init(void)
@@ -268,7 +271,7 @@ void MX_USART10_UART_Init(void)
/* USER CODE END USART10_Init 1 */
huart10.Instance = USART10;
- huart10.Init.BaudRate = 115200;
+ huart10.Init.BaudRate = 921600;
huart10.Init.WordLength = UART_WORDLENGTH_8B;
huart10.Init.StopBits = UART_STOPBITS_1;
huart10.Init.Parity = UART_PARITY_NONE;
@@ -399,6 +402,43 @@ void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
GPIO_InitStruct.Alternate = GPIO_AF7_UART7;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
+ /* UART7 DMA Init */
+ /* UART7_RX Init */
+ hdma_uart7_rx.Instance = DMA2_Stream1;
+ hdma_uart7_rx.Init.Request = DMA_REQUEST_UART7_RX;
+ hdma_uart7_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
+ hdma_uart7_rx.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_uart7_rx.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_uart7_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
+ hdma_uart7_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
+ hdma_uart7_rx.Init.Mode = DMA_NORMAL;
+ hdma_uart7_rx.Init.Priority = DMA_PRIORITY_MEDIUM;
+ hdma_uart7_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ if (HAL_DMA_Init(&hdma_uart7_rx) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(uartHandle,hdmarx,hdma_uart7_rx);
+
+ /* UART7_TX Init */
+ hdma_uart7_tx.Instance = DMA2_Stream2;
+ hdma_uart7_tx.Init.Request = DMA_REQUEST_UART7_TX;
+ hdma_uart7_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
+ hdma_uart7_tx.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_uart7_tx.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_uart7_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
+ hdma_uart7_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
+ hdma_uart7_tx.Init.Mode = DMA_NORMAL;
+ hdma_uart7_tx.Init.Priority = DMA_PRIORITY_MEDIUM;
+ hdma_uart7_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ if (HAL_DMA_Init(&hdma_uart7_tx) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(uartHandle,hdmatx,hdma_uart7_tx);
+
/* UART7 interrupt Init */
HAL_NVIC_SetPriority(UART7_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(UART7_IRQn);
@@ -648,7 +688,7 @@ void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
hdma_usart10_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_usart10_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_usart10_tx.Init.Mode = DMA_NORMAL;
- hdma_usart10_tx.Init.Priority = DMA_PRIORITY_LOW;
+ hdma_usart10_tx.Init.Priority = DMA_PRIORITY_VERY_HIGH;
hdma_usart10_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_usart10_tx) != HAL_OK)
{
@@ -657,6 +697,24 @@ void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
__HAL_LINKDMA(uartHandle,hdmatx,hdma_usart10_tx);
+ /* USART10_RX Init */
+ hdma_usart10_rx.Instance = DMA2_Stream3;
+ hdma_usart10_rx.Init.Request = DMA_REQUEST_USART10_RX;
+ hdma_usart10_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
+ hdma_usart10_rx.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_usart10_rx.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_usart10_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
+ hdma_usart10_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
+ hdma_usart10_rx.Init.Mode = DMA_NORMAL;
+ hdma_usart10_rx.Init.Priority = DMA_PRIORITY_VERY_HIGH;
+ hdma_usart10_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
+ if (HAL_DMA_Init(&hdma_usart10_rx) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(uartHandle,hdmarx,hdma_usart10_rx);
+
/* USART10 interrupt Init */
HAL_NVIC_SetPriority(USART10_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(USART10_IRQn);
@@ -708,6 +766,10 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
*/
HAL_GPIO_DeInit(GPIOE, GPIO_PIN_7|GPIO_PIN_8);
+ /* UART7 DMA DeInit */
+ HAL_DMA_DeInit(uartHandle->hdmarx);
+ HAL_DMA_DeInit(uartHandle->hdmatx);
+
/* UART7 interrupt Deinit */
HAL_NVIC_DisableIRQ(UART7_IRQn);
/* USER CODE BEGIN UART7_MspDeInit 1 */
@@ -802,6 +864,7 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
/* USART10 DMA DeInit */
HAL_DMA_DeInit(uartHandle->hdmatx);
+ HAL_DMA_DeInit(uartHandle->hdmarx);
/* USART10 interrupt Deinit */
HAL_NVIC_DisableIRQ(USART10_IRQn);
diff --git a/CtrBoard-H7_ALL.ioc b/CtrBoard-H7_ALL.ioc
index aeb0481..c5af9d2 100644
--- a/CtrBoard-H7_ALL.ioc
+++ b/CtrBoard-H7_ALL.ioc
@@ -44,6 +44,8 @@ Dma.ADC1.0.SyncRequestNumber=1
Dma.ADC1.0.SyncSignalID=NONE
Dma.Request0=ADC1
Dma.Request1=UART5_RX
+Dma.Request10=UART7_TX
+Dma.Request11=USART10_RX
Dma.Request2=SPI2_RX
Dma.Request3=SPI2_TX
Dma.Request4=USART3_RX
@@ -51,7 +53,8 @@ Dma.Request5=USART3_TX
Dma.Request6=USART2_RX
Dma.Request7=USART2_TX
Dma.Request8=USART10_TX
-Dma.RequestsNb=9
+Dma.Request9=UART7_RX
+Dma.RequestsNb=12
Dma.SPI2_RX.2.Direction=DMA_PERIPH_TO_MEMORY
Dma.SPI2_RX.2.EventEnable=DISABLE
Dma.SPI2_RX.2.FIFOMode=DMA_FIFOMODE_DISABLE
@@ -62,7 +65,7 @@ Dma.SPI2_RX.2.Mode=DMA_NORMAL
Dma.SPI2_RX.2.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.SPI2_RX.2.PeriphInc=DMA_PINC_DISABLE
Dma.SPI2_RX.2.Polarity=HAL_DMAMUX_REQ_GEN_RISING
-Dma.SPI2_RX.2.Priority=DMA_PRIORITY_LOW
+Dma.SPI2_RX.2.Priority=DMA_PRIORITY_VERY_HIGH
Dma.SPI2_RX.2.RequestNumber=1
Dma.SPI2_RX.2.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
Dma.SPI2_RX.2.SignalID=NONE
@@ -80,7 +83,7 @@ Dma.SPI2_TX.3.Mode=DMA_NORMAL
Dma.SPI2_TX.3.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.SPI2_TX.3.PeriphInc=DMA_PINC_DISABLE
Dma.SPI2_TX.3.Polarity=HAL_DMAMUX_REQ_GEN_RISING
-Dma.SPI2_TX.3.Priority=DMA_PRIORITY_LOW
+Dma.SPI2_TX.3.Priority=DMA_PRIORITY_VERY_HIGH
Dma.SPI2_TX.3.RequestNumber=1
Dma.SPI2_TX.3.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
Dma.SPI2_TX.3.SignalID=NONE
@@ -106,6 +109,60 @@ Dma.UART5_RX.1.SyncEnable=DISABLE
Dma.UART5_RX.1.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
Dma.UART5_RX.1.SyncRequestNumber=1
Dma.UART5_RX.1.SyncSignalID=NONE
+Dma.UART7_RX.9.Direction=DMA_PERIPH_TO_MEMORY
+Dma.UART7_RX.9.EventEnable=DISABLE
+Dma.UART7_RX.9.FIFOMode=DMA_FIFOMODE_DISABLE
+Dma.UART7_RX.9.Instance=DMA2_Stream1
+Dma.UART7_RX.9.MemDataAlignment=DMA_MDATAALIGN_BYTE
+Dma.UART7_RX.9.MemInc=DMA_MINC_ENABLE
+Dma.UART7_RX.9.Mode=DMA_NORMAL
+Dma.UART7_RX.9.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
+Dma.UART7_RX.9.PeriphInc=DMA_PINC_DISABLE
+Dma.UART7_RX.9.Polarity=HAL_DMAMUX_REQ_GEN_RISING
+Dma.UART7_RX.9.Priority=DMA_PRIORITY_MEDIUM
+Dma.UART7_RX.9.RequestNumber=1
+Dma.UART7_RX.9.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
+Dma.UART7_RX.9.SignalID=NONE
+Dma.UART7_RX.9.SyncEnable=DISABLE
+Dma.UART7_RX.9.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
+Dma.UART7_RX.9.SyncRequestNumber=1
+Dma.UART7_RX.9.SyncSignalID=NONE
+Dma.UART7_TX.10.Direction=DMA_MEMORY_TO_PERIPH
+Dma.UART7_TX.10.EventEnable=DISABLE
+Dma.UART7_TX.10.FIFOMode=DMA_FIFOMODE_DISABLE
+Dma.UART7_TX.10.Instance=DMA2_Stream2
+Dma.UART7_TX.10.MemDataAlignment=DMA_MDATAALIGN_BYTE
+Dma.UART7_TX.10.MemInc=DMA_MINC_ENABLE
+Dma.UART7_TX.10.Mode=DMA_NORMAL
+Dma.UART7_TX.10.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
+Dma.UART7_TX.10.PeriphInc=DMA_PINC_DISABLE
+Dma.UART7_TX.10.Polarity=HAL_DMAMUX_REQ_GEN_RISING
+Dma.UART7_TX.10.Priority=DMA_PRIORITY_MEDIUM
+Dma.UART7_TX.10.RequestNumber=1
+Dma.UART7_TX.10.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
+Dma.UART7_TX.10.SignalID=NONE
+Dma.UART7_TX.10.SyncEnable=DISABLE
+Dma.UART7_TX.10.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
+Dma.UART7_TX.10.SyncRequestNumber=1
+Dma.UART7_TX.10.SyncSignalID=NONE
+Dma.USART10_RX.11.Direction=DMA_PERIPH_TO_MEMORY
+Dma.USART10_RX.11.EventEnable=DISABLE
+Dma.USART10_RX.11.FIFOMode=DMA_FIFOMODE_DISABLE
+Dma.USART10_RX.11.Instance=DMA2_Stream3
+Dma.USART10_RX.11.MemDataAlignment=DMA_MDATAALIGN_BYTE
+Dma.USART10_RX.11.MemInc=DMA_MINC_ENABLE
+Dma.USART10_RX.11.Mode=DMA_NORMAL
+Dma.USART10_RX.11.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
+Dma.USART10_RX.11.PeriphInc=DMA_PINC_DISABLE
+Dma.USART10_RX.11.Polarity=HAL_DMAMUX_REQ_GEN_RISING
+Dma.USART10_RX.11.Priority=DMA_PRIORITY_VERY_HIGH
+Dma.USART10_RX.11.RequestNumber=1
+Dma.USART10_RX.11.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
+Dma.USART10_RX.11.SignalID=NONE
+Dma.USART10_RX.11.SyncEnable=DISABLE
+Dma.USART10_RX.11.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
+Dma.USART10_RX.11.SyncRequestNumber=1
+Dma.USART10_RX.11.SyncSignalID=NONE
Dma.USART10_TX.8.Direction=DMA_MEMORY_TO_PERIPH
Dma.USART10_TX.8.EventEnable=DISABLE
Dma.USART10_TX.8.FIFOMode=DMA_FIFOMODE_DISABLE
@@ -116,7 +173,7 @@ Dma.USART10_TX.8.Mode=DMA_NORMAL
Dma.USART10_TX.8.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.USART10_TX.8.PeriphInc=DMA_PINC_DISABLE
Dma.USART10_TX.8.Polarity=HAL_DMAMUX_REQ_GEN_RISING
-Dma.USART10_TX.8.Priority=DMA_PRIORITY_LOW
+Dma.USART10_TX.8.Priority=DMA_PRIORITY_VERY_HIGH
Dma.USART10_TX.8.RequestNumber=1
Dma.USART10_TX.8.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
Dma.USART10_TX.8.SignalID=NONE
@@ -395,6 +452,9 @@ NVIC.DMA1_Stream5_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
NVIC.DMA1_Stream6_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
NVIC.DMA1_Stream7_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
NVIC.DMA2_Stream0_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
+NVIC.DMA2_Stream1_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
+NVIC.DMA2_Stream2_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
+NVIC.DMA2_Stream3_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.EXTI15_10_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.FDCAN1_IT0_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
@@ -777,10 +837,10 @@ SPI1.Direction=SPI_DIRECTION_2LINES_TXONLY
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler,CLKPolarity
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
-SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
+SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_8
SPI2.CLKPhase=SPI_PHASE_2EDGE
SPI2.CLKPolarity=SPI_POLARITY_HIGH
-SPI2.CalculateBaudRate=3.75 MBits/s
+SPI2.CalculateBaudRate=15.0 MBits/s
SPI2.DataSize=SPI_DATASIZE_8BIT
SPI2.Direction=SPI_DIRECTION_2LINES
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler,CLKPolarity,CLKPhase
@@ -820,7 +880,7 @@ UART7.IPParameters=BaudRate
USART1.BaudRate=921600
USART1.IPParameters=VirtualMode-Asynchronous,BaudRate
USART1.VirtualMode-Asynchronous=VM_ASYNC
-USART10.BaudRate=115200
+USART10.BaudRate=921600
USART10.IPParameters=VirtualMode,BaudRate
USART10.VirtualMode=VM_ASYNC
USART2.BaudRate=4000000
diff --git a/MDK-ARM/CtrBoard-H7_ALL.uvoptx b/MDK-ARM/CtrBoard-H7_ALL.uvoptx
index 917779f..6dee191 100644
--- a/MDK-ARM/CtrBoard-H7_ALL.uvoptx
+++ b/MDK-ARM/CtrBoard-H7_ALL.uvoptx
@@ -1,1533 +1,1576 @@
-
-
-
- 1.0
-
- ### uVision Project, (C) Keil Software
-
-
- *.c
- *.s*; *.src; *.a*
- *.obj; *.o
- *.lib
- *.txt; *.h; *.inc; *.md
- *.plm
- *.cpp
- 0
-
-
-
- 0
- 0
-
-
-
- CtrBoard-H7_ALL
- 0x4
- ARM-ADS
-
- 24000000
-
- 1
- 1
- 0
- 1
- 0
-
-
- 1
- 65535
- 0
- 0
- 0
-
-
- 79
- 66
- 8
-
-
-
- 1
- 1
- 1
- 0
- 1
- 1
- 0
- 1
- 0
- 0
- 0
- 0
-
-
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 0
- 0
-
-
- 1
- 0
- 1
-
- 18
-
- 0
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 1
- 0
- 0
- 1
- 0
- 0
- 3
-
-
-
-
-
-
-
-
-
-
- BIN\CMSIS_AGDI.dll
-
-
-
- 0
- ARMRTXEVENTFLAGS
- -L70 -Z18 -C0 -M0 -T1
-
-
- 0
- DLGTARM
- (1010=-1,-1,-1,-1,0)(6017=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(6016=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)
-
-
- 0
- ARMDBGFLAGS
-
-
-
- 0
- CMSIS_AGDI
- -X"" -O206 -S8 -C0 -P00000000 -N00("ARM CoreSight SW-DP") -D00(6BA02477) -L00(0) -TO65554 -TC10000000 -TT10000000 -TP20 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC8000 -FN1 -FF0STM32H72x-73x_1024.FLM -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM)
-
-
- 0
- DLGUARM
-
-
-
- 0
- UL2CM3
- UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32H72x-73x_1024 -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM))
-
-
- 0
- ST-LINKIII-KEIL_SWO
- -U-O142 -O2254 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(5BA02477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC1000 -FN1 -FF0STM32H72x-73x_1024.FLM -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM)
-
-
-
-
-
- 0
- 1
- dr16
-
-
- 1
- 1
- bmi088
-
-
- 2
- 1
- eulr_to_send
-
-
- 3
- 1
- cmd_rc
-
-
- 4
- 1
- go
-
-
- 5
- 1
- task_runtime.freq.ctrl_leg
-
-
- 6
- 1
- go_feedback
-
-
- 7
- 1
- cmd.chassis
-
-
- 8
- 1
- chassis
-
-
- 9
- 1
- go_feedback
-
-
-
- 0
-
-
- 0
- 1
- 1
- 0
- 0
- 0
- 0
- 1
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 0
- 1
- 0
- 0
- 0
-
-
-
- 0
- 0
- 0
-
-
-
-
-
-
-
-
-
- 1
- 1
- 0
- 2
- 10000000
-
-
-
-
-
- Application/MDK-ARM
- 0
- 0
- 0
- 0
-
- 1
- 1
- 2
- 0
- 0
- 0
- startup_stm32h723xx.s
- startup_stm32h723xx.s
- 0
- 0
-
-
-
-
- Application/User/Core
- 1
- 0
- 0
- 0
-
- 2
- 2
- 1
- 0
- 0
- 0
- ../Core/Src/main.c
- main.c
- 0
- 0
-
-
- 2
- 3
- 1
- 0
- 0
- 0
- ../Core/Src/gpio.c
- gpio.c
- 0
- 0
-
-
- 2
- 4
- 1
- 0
- 0
- 0
- ../Core/Src/freertos.c
- freertos.c
- 0
- 0
-
-
- 2
- 5
- 1
- 0
- 0
- 0
- ../Core/Src/adc.c
- adc.c
- 0
- 0
-
-
- 2
- 6
- 1
- 0
- 0
- 0
- ../Core/Src/dma.c
- dma.c
- 0
- 0
-
-
- 2
- 7
- 1
- 0
- 0
- 0
- ../Core/Src/fdcan.c
- fdcan.c
- 0
- 0
-
-
- 2
- 8
- 1
- 0
- 0
- 0
- ../Core/Src/memorymap.c
- memorymap.c
- 0
- 0
-
-
- 2
- 9
- 1
- 0
- 0
- 0
- ../Core/Src/octospi.c
- octospi.c
- 0
- 0
-
-
- 2
- 10
- 1
- 0
- 0
- 0
- ../Core/Src/spi.c
- spi.c
- 0
- 0
-
-
- 2
- 11
- 1
- 0
- 0
- 0
- ../Core/Src/tim.c
- tim.c
- 0
- 0
-
-
- 2
- 12
- 1
- 0
- 0
- 0
- ../Core/Src/usart.c
- usart.c
- 0
- 0
-
-
- 2
- 13
- 1
- 0
- 0
- 0
- ../Core/Src/stm32h7xx_it.c
- stm32h7xx_it.c
- 0
- 0
-
-
- 2
- 14
- 1
- 0
- 0
- 0
- ../Core/Src/stm32h7xx_hal_msp.c
- stm32h7xx_hal_msp.c
- 0
- 0
-
-
- 2
- 15
- 1
- 0
- 0
- 0
- ../Core/Src/stm32h7xx_hal_timebase_tim.c
- stm32h7xx_hal_timebase_tim.c
- 0
- 0
-
-
-
-
- Application/User/USB_DEVICE/App
- 0
- 0
- 0
- 0
-
- 3
- 16
- 1
- 0
- 0
- 0
- ../USB_DEVICE/App/usb_device.c
- usb_device.c
- 0
- 0
-
-
- 3
- 17
- 1
- 0
- 0
- 0
- ../USB_DEVICE/App/usbd_desc.c
- usbd_desc.c
- 0
- 0
-
-
- 3
- 18
- 1
- 0
- 0
- 0
- ../USB_DEVICE/App/usbd_cdc_if.c
- usbd_cdc_if.c
- 0
- 0
-
-
-
-
- Application/User/USB_DEVICE/Target
- 0
- 0
- 0
- 0
-
- 4
- 19
- 1
- 0
- 0
- 0
- ../USB_DEVICE/Target/usbd_conf.c
- usbd_conf.c
- 0
- 0
-
-
-
-
- Drivers/STM32H7xx_HAL_Driver
- 0
- 0
- 0
- 0
-
- 5
- 20
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_tim.c
- stm32h7xx_hal_tim.c
- 0
- 0
-
-
- 5
- 21
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_tim_ex.c
- stm32h7xx_hal_tim_ex.c
- 0
- 0
-
-
- 5
- 22
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pcd.c
- stm32h7xx_hal_pcd.c
- 0
- 0
-
-
- 5
- 23
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pcd_ex.c
- stm32h7xx_hal_pcd_ex.c
- 0
- 0
-
-
- 5
- 24
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_usb.c
- stm32h7xx_ll_usb.c
- 0
- 0
-
-
- 5
- 25
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_rcc.c
- stm32h7xx_hal_rcc.c
- 0
- 0
-
-
- 5
- 26
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_rcc_ex.c
- stm32h7xx_hal_rcc_ex.c
- 0
- 0
-
-
- 5
- 27
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_flash.c
- stm32h7xx_hal_flash.c
- 0
- 0
-
-
- 5
- 28
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_flash_ex.c
- stm32h7xx_hal_flash_ex.c
- 0
- 0
-
-
- 5
- 29
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_gpio.c
- stm32h7xx_hal_gpio.c
- 0
- 0
-
-
- 5
- 30
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_hsem.c
- stm32h7xx_hal_hsem.c
- 0
- 0
-
-
- 5
- 31
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_dma.c
- stm32h7xx_hal_dma.c
- 0
- 0
-
-
- 5
- 32
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_dma_ex.c
- stm32h7xx_hal_dma_ex.c
- 0
- 0
-
-
- 5
- 33
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_mdma.c
- stm32h7xx_hal_mdma.c
- 0
- 0
-
-
- 5
- 34
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pwr.c
- stm32h7xx_hal_pwr.c
- 0
- 0
-
-
- 5
- 35
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pwr_ex.c
- stm32h7xx_hal_pwr_ex.c
- 0
- 0
-
-
- 5
- 36
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_cortex.c
- stm32h7xx_hal_cortex.c
- 0
- 0
-
-
- 5
- 37
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal.c
- stm32h7xx_hal.c
- 0
- 0
-
-
- 5
- 38
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_i2c.c
- stm32h7xx_hal_i2c.c
- 0
- 0
-
-
- 5
- 39
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_i2c_ex.c
- stm32h7xx_hal_i2c_ex.c
- 0
- 0
-
-
- 5
- 40
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_exti.c
- stm32h7xx_hal_exti.c
- 0
- 0
-
-
- 5
- 41
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_adc.c
- stm32h7xx_hal_adc.c
- 0
- 0
-
-
- 5
- 42
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_adc_ex.c
- stm32h7xx_hal_adc_ex.c
- 0
- 0
-
-
- 5
- 43
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_fdcan.c
- stm32h7xx_hal_fdcan.c
- 0
- 0
-
-
- 5
- 44
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_ospi.c
- stm32h7xx_hal_ospi.c
- 0
- 0
-
-
- 5
- 45
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_spi.c
- stm32h7xx_hal_spi.c
- 0
- 0
-
-
- 5
- 46
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_spi_ex.c
- stm32h7xx_hal_spi_ex.c
- 0
- 0
-
-
- 5
- 47
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart.c
- stm32h7xx_hal_uart.c
- 0
- 0
-
-
- 5
- 48
- 1
- 0
- 0
- 0
- ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart_ex.c
- stm32h7xx_hal_uart_ex.c
- 0
- 0
-
-
-
-
- Drivers/CMSIS
- 0
- 0
- 0
- 0
-
- 6
- 49
- 1
- 0
- 0
- 0
- ../Core/Src/system_stm32h7xx.c
- system_stm32h7xx.c
- 0
- 0
-
-
-
-
- Middlewares/USB_Device_Library
- 0
- 0
- 0
- 0
-
- 7
- 50
- 1
- 0
- 0
- 0
- ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c
- usbd_core.c
- 0
- 0
-
-
- 7
- 51
- 1
- 0
- 0
- 0
- ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c
- usbd_ctlreq.c
- 0
- 0
-
-
- 7
- 52
- 1
- 0
- 0
- 0
- ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c
- usbd_ioreq.c
- 0
- 0
-
-
- 7
- 53
- 1
- 0
- 0
- 0
- ../Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
- usbd_cdc.c
- 0
- 0
-
-
-
-
- Middlewares/FreeRTOS
- 0
- 0
- 0
- 0
-
- 8
- 54
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/croutine.c
- croutine.c
- 0
- 0
-
-
- 8
- 55
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/event_groups.c
- event_groups.c
- 0
- 0
-
-
- 8
- 56
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/list.c
- list.c
- 0
- 0
-
-
- 8
- 57
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/queue.c
- queue.c
- 0
- 0
-
-
- 8
- 58
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c
- stream_buffer.c
- 0
- 0
-
-
- 8
- 59
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/tasks.c
- tasks.c
- 0
- 0
-
-
- 8
- 60
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/timers.c
- timers.c
- 0
- 0
-
-
- 8
- 61
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c
- cmsis_os2.c
- 0
- 0
-
-
- 8
- 62
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c
- heap_4.c
- 0
- 0
-
-
- 8
- 63
- 1
- 0
- 0
- 0
- ../Middlewares/Third_Party/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c
- port.c
- 0
- 0
-
-
-
-
- User/bsp
- 0
- 0
- 0
- 0
-
- 9
- 64
- 1
- 0
- 0
- 0
- ..\User\bsp\uart.c
- uart.c
- 0
- 0
-
-
- 9
- 65
- 1
- 0
- 0
- 0
- ..\User\bsp\delay.c
- delay.c
- 0
- 0
-
-
- 9
- 66
- 1
- 0
- 0
- 0
- ..\User\bsp\gpio.c
- gpio.c
- 0
- 0
-
-
- 9
- 67
- 1
- 0
- 0
- 0
- ..\User\bsp\spi.c
- spi.c
- 0
- 0
-
-
- 9
- 68
- 1
- 0
- 0
- 0
- ..\User\bsp\pwm.c
- pwm.c
- 0
- 0
-
-
- 9
- 69
- 1
- 0
- 0
- 0
- ..\User\bsp\flash.c
- flash.c
- 0
- 0
-
-
- 9
- 70
- 1
- 0
- 0
- 0
- ..\User\bsp\usb.c
- usb.c
- 0
- 0
-
-
- 9
- 71
- 1
- 0
- 0
- 0
- ..\User\bsp\buzzer.c
- buzzer.c
- 0
- 0
-
-
-
-
- User/component
- 1
- 0
- 0
- 0
-
- 10
- 72
- 1
- 0
- 0
- 0
- ..\User\component\ahrs.c
- ahrs.c
- 0
- 0
-
-
- 10
- 73
- 1
- 0
- 0
- 0
- ..\User\component\user_math.c
- user_math.c
- 0
- 0
-
-
- 10
- 74
- 1
- 0
- 0
- 0
- ..\User\component\filter.c
- filter.c
- 0
- 0
-
-
- 10
- 75
- 1
- 0
- 0
- 0
- ..\User\component\pid.c
- pid.c
- 0
- 0
-
-
- 10
- 76
- 1
- 0
- 0
- 0
- ..\User\component\cmd.c
- cmd.c
- 0
- 0
-
-
- 10
- 77
- 1
- 0
- 0
- 0
- ..\User\component\FreeRTOS_CLI.c
- FreeRTOS_CLI.c
- 0
- 0
-
-
- 10
- 78
- 1
- 0
- 0
- 0
- ..\User\component\kinematics.c
- kinematics.c
- 0
- 0
-
-
-
-
- Usr/device
- 1
- 0
- 0
- 0
-
- 11
- 79
- 1
- 0
- 0
- 0
- ..\User\device\dr16.c
- dr16.c
- 0
- 0
-
-
- 11
- 80
- 1
- 0
- 0
- 0
- ..\User\device\bmi088.c
- bmi088.c
- 0
- 0
-
-
- 11
- 81
- 1
- 0
- 0
- 0
- ..\User\device\go.c
- go.c
- 0
- 0
-
-
-
-
- User/module
- 1
- 0
- 0
- 0
-
- 12
- 82
- 1
- 0
- 0
- 0
- ..\User\module\chassis.c
- chassis.c
- 0
- 0
-
-
- 12
- 83
- 1
- 0
- 0
- 0
- ..\User\module\config.c
- config.c
- 0
- 0
-
-
-
-
- User/task
- 1
- 0
- 0
- 0
-
- 13
- 84
- 1
- 0
- 0
- 0
- ..\User\task\init.c
- init.c
- 0
- 0
-
-
- 13
- 85
- 1
- 0
- 0
- 0
- ..\User\task\rc.c
- rc.c
- 0
- 0
-
-
- 13
- 86
- 1
- 0
- 0
- 0
- ..\User\task\user_task.c
- user_task.c
- 0
- 0
-
-
- 13
- 87
- 5
- 0
- 0
- 0
- ..\User\task\user_task.h
- user_task.h
- 0
- 0
-
-
- 13
- 88
- 1
- 0
- 0
- 0
- ..\User\task\atti_esti.c
- atti_esti.c
- 0
- 0
-
-
- 13
- 89
- 1
- 0
- 0
- 0
- ..\User\task\test.c
- test.c
- 0
- 0
-
-
- 13
- 90
- 1
- 0
- 0
- 0
- ..\User\task\cli.c
- cli.c
- 0
- 0
-
-
- 13
- 91
- 1
- 0
- 0
- 0
- ..\User\task\monitor.c
- monitor.c
- 0
- 0
-
-
- 13
- 92
- 1
- 0
- 0
- 0
- ..\User\task\cmd.c
- cmd.c
- 0
- 0
-
-
- 13
- 93
- 1
- 0
- 0
- 0
- ..\User\task\ctrl_leg.c
- ctrl_leg.c
- 0
- 0
-
-
- 13
- 94
- 1
- 0
- 0
- 0
- ..\User\task\ctrl_chassis.c
- ctrl_chassis.c
- 0
- 0
-
-
-
-
- Unitree
- 0
- 0
- 0
- 0
-
- 14
- 95
- 1
- 0
- 0
- 0
- ..\Middlewares\Third_Party\Unitree\crc_ccitt.c
- crc_ccitt.c
- 0
- 0
-
-
- 14
- 96
- 1
- 0
- 0
- 0
- ..\Middlewares\Third_Party\Unitree\gom_protocol.c
- gom_protocol.c
- 0
- 0
-
-
-
-
- ::CMSIS
- 0
- 0
- 0
- 1
-
-
-
+
+
+
+ 1.0
+
+ ### uVision Project, (C) Keil Software
+
+
+ *.c
+ *.s*; *.src; *.a*
+ *.obj; *.o
+ *.lib
+ *.txt; *.h; *.inc; *.md
+ *.plm
+ *.cpp
+ 0
+
+
+
+ 0
+ 0
+
+
+
+ CtrBoard-H7_ALL
+ 0x4
+ ARM-ADS
+
+ 24000000
+
+ 1
+ 1
+ 0
+ 1
+ 0
+
+
+ 1
+ 65535
+ 0
+ 0
+ 0
+
+
+ 79
+ 66
+ 8
+
+
+
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+
+
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+
+
+ 1
+ 0
+ 1
+
+ 18
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+ 1
+ 0
+ 0
+ 3
+
+
+
+
+
+
+
+
+
+
+ BIN\CMSIS_AGDI.dll
+
+
+
+ 0
+ ARMRTXEVENTFLAGS
+ -L70 -Z18 -C0 -M0 -T1
+
+
+ 0
+ DLGTARM
+ (1010=-1,-1,-1,-1,0)(6017=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(6016=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)
+
+
+ 0
+ ARMDBGFLAGS
+
+
+
+ 0
+ CMSIS_AGDI
+ -X"Any" -UAny -O206 -S8 -C0 -P00000000 -N00("ARM CoreSight SW-DP") -D00(6BA02477) -L00(0) -TO65554 -TC10000000 -TT10000000 -TP20 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC8000 -FN1 -FF0STM32H72x-73x_1024.FLM -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM)
+
+
+ 0
+ DLGUARM
+
+
+
+ 0
+ UL2CM3
+ UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32H72x-73x_1024 -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM))
+
+
+ 0
+ ST-LINKIII-KEIL_SWO
+ -U-O142 -O2254 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(5BA02477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC1000 -FN1 -FF0STM32H72x-73x_1024.FLM -FS08000000 -FL0100000 -FP0($$Device:STM32H723VGTx$CMSIS\Flash\STM32H72x-73x_1024.FLM)
+
+
+
+
+
+ 0
+ 1
+ dr16
+
+
+ 1
+ 1
+ chassis
+
+
+ 2
+ 1
+ n100
+
+
+ 3
+ 1
+ go_feedback
+
+
+ 4
+ 1
+ param_default
+
+
+ 5
+ 1
+ angle_pose
+
+
+ 6
+ 1
+ chassis_cmd
+
+
+ 7
+ 1
+ target_pose
+
+
+ 8
+ 1
+ c->param->mech_param.sign.leg[i]
+
+
+
+ 0
+
+
+ 0
+ 1
+ 1
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+
+ 1
+ 1
+ 0
+ 2
+ 10000000
+
+
+
+
+
+ Application/MDK-ARM
+ 0
+ 0
+ 0
+ 0
+
+ 1
+ 1
+ 2
+ 0
+ 0
+ 0
+ startup_stm32h723xx.s
+ startup_stm32h723xx.s
+ 0
+ 0
+
+
+
+
+ Application/User/Core
+ 1
+ 0
+ 0
+ 0
+
+ 2
+ 2
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/main.c
+ main.c
+ 0
+ 0
+
+
+ 2
+ 3
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/gpio.c
+ gpio.c
+ 0
+ 0
+
+
+ 2
+ 4
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/freertos.c
+ freertos.c
+ 0
+ 0
+
+
+ 2
+ 5
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/adc.c
+ adc.c
+ 0
+ 0
+
+
+ 2
+ 6
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/dma.c
+ dma.c
+ 0
+ 0
+
+
+ 2
+ 7
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/fdcan.c
+ fdcan.c
+ 0
+ 0
+
+
+ 2
+ 8
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/memorymap.c
+ memorymap.c
+ 0
+ 0
+
+
+ 2
+ 9
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/octospi.c
+ octospi.c
+ 0
+ 0
+
+
+ 2
+ 10
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/spi.c
+ spi.c
+ 0
+ 0
+
+
+ 2
+ 11
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/tim.c
+ tim.c
+ 0
+ 0
+
+
+ 2
+ 12
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/usart.c
+ usart.c
+ 0
+ 0
+
+
+ 2
+ 13
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/stm32h7xx_it.c
+ stm32h7xx_it.c
+ 0
+ 0
+
+
+ 2
+ 14
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/stm32h7xx_hal_msp.c
+ stm32h7xx_hal_msp.c
+ 0
+ 0
+
+
+ 2
+ 15
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/stm32h7xx_hal_timebase_tim.c
+ stm32h7xx_hal_timebase_tim.c
+ 0
+ 0
+
+
+
+
+ Application/User/USB_DEVICE/App
+ 0
+ 0
+ 0
+ 0
+
+ 3
+ 16
+ 1
+ 0
+ 0
+ 0
+ ../USB_DEVICE/App/usb_device.c
+ usb_device.c
+ 0
+ 0
+
+
+ 3
+ 17
+ 1
+ 0
+ 0
+ 0
+ ../USB_DEVICE/App/usbd_desc.c
+ usbd_desc.c
+ 0
+ 0
+
+
+ 3
+ 18
+ 1
+ 0
+ 0
+ 0
+ ../USB_DEVICE/App/usbd_cdc_if.c
+ usbd_cdc_if.c
+ 0
+ 0
+
+
+
+
+ Application/User/USB_DEVICE/Target
+ 0
+ 0
+ 0
+ 0
+
+ 4
+ 19
+ 1
+ 0
+ 0
+ 0
+ ../USB_DEVICE/Target/usbd_conf.c
+ usbd_conf.c
+ 0
+ 0
+
+
+
+
+ Drivers/STM32H7xx_HAL_Driver
+ 0
+ 0
+ 0
+ 0
+
+ 5
+ 20
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_tim.c
+ stm32h7xx_hal_tim.c
+ 0
+ 0
+
+
+ 5
+ 21
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_tim_ex.c
+ stm32h7xx_hal_tim_ex.c
+ 0
+ 0
+
+
+ 5
+ 22
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pcd.c
+ stm32h7xx_hal_pcd.c
+ 0
+ 0
+
+
+ 5
+ 23
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pcd_ex.c
+ stm32h7xx_hal_pcd_ex.c
+ 0
+ 0
+
+
+ 5
+ 24
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_ll_usb.c
+ stm32h7xx_ll_usb.c
+ 0
+ 0
+
+
+ 5
+ 25
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_rcc.c
+ stm32h7xx_hal_rcc.c
+ 0
+ 0
+
+
+ 5
+ 26
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_rcc_ex.c
+ stm32h7xx_hal_rcc_ex.c
+ 0
+ 0
+
+
+ 5
+ 27
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_flash.c
+ stm32h7xx_hal_flash.c
+ 0
+ 0
+
+
+ 5
+ 28
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_flash_ex.c
+ stm32h7xx_hal_flash_ex.c
+ 0
+ 0
+
+
+ 5
+ 29
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_gpio.c
+ stm32h7xx_hal_gpio.c
+ 0
+ 0
+
+
+ 5
+ 30
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_hsem.c
+ stm32h7xx_hal_hsem.c
+ 0
+ 0
+
+
+ 5
+ 31
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_dma.c
+ stm32h7xx_hal_dma.c
+ 0
+ 0
+
+
+ 5
+ 32
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_dma_ex.c
+ stm32h7xx_hal_dma_ex.c
+ 0
+ 0
+
+
+ 5
+ 33
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_mdma.c
+ stm32h7xx_hal_mdma.c
+ 0
+ 0
+
+
+ 5
+ 34
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pwr.c
+ stm32h7xx_hal_pwr.c
+ 0
+ 0
+
+
+ 5
+ 35
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_pwr_ex.c
+ stm32h7xx_hal_pwr_ex.c
+ 0
+ 0
+
+
+ 5
+ 36
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_cortex.c
+ stm32h7xx_hal_cortex.c
+ 0
+ 0
+
+
+ 5
+ 37
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal.c
+ stm32h7xx_hal.c
+ 0
+ 0
+
+
+ 5
+ 38
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_i2c.c
+ stm32h7xx_hal_i2c.c
+ 0
+ 0
+
+
+ 5
+ 39
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_i2c_ex.c
+ stm32h7xx_hal_i2c_ex.c
+ 0
+ 0
+
+
+ 5
+ 40
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_exti.c
+ stm32h7xx_hal_exti.c
+ 0
+ 0
+
+
+ 5
+ 41
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_adc.c
+ stm32h7xx_hal_adc.c
+ 0
+ 0
+
+
+ 5
+ 42
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_adc_ex.c
+ stm32h7xx_hal_adc_ex.c
+ 0
+ 0
+
+
+ 5
+ 43
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_fdcan.c
+ stm32h7xx_hal_fdcan.c
+ 0
+ 0
+
+
+ 5
+ 44
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_ospi.c
+ stm32h7xx_hal_ospi.c
+ 0
+ 0
+
+
+ 5
+ 45
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_spi.c
+ stm32h7xx_hal_spi.c
+ 0
+ 0
+
+
+ 5
+ 46
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_spi_ex.c
+ stm32h7xx_hal_spi_ex.c
+ 0
+ 0
+
+
+ 5
+ 47
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart.c
+ stm32h7xx_hal_uart.c
+ 0
+ 0
+
+
+ 5
+ 48
+ 1
+ 0
+ 0
+ 0
+ ../Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart_ex.c
+ stm32h7xx_hal_uart_ex.c
+ 0
+ 0
+
+
+
+
+ Drivers/CMSIS
+ 0
+ 0
+ 0
+ 0
+
+ 6
+ 49
+ 1
+ 0
+ 0
+ 0
+ ../Core/Src/system_stm32h7xx.c
+ system_stm32h7xx.c
+ 0
+ 0
+
+
+
+
+ Middlewares/USB_Device_Library
+ 0
+ 0
+ 0
+ 0
+
+ 7
+ 50
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c
+ usbd_core.c
+ 0
+ 0
+
+
+ 7
+ 51
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c
+ usbd_ctlreq.c
+ 0
+ 0
+
+
+ 7
+ 52
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c
+ usbd_ioreq.c
+ 0
+ 0
+
+
+ 7
+ 53
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
+ usbd_cdc.c
+ 0
+ 0
+
+
+
+
+ Middlewares/FreeRTOS
+ 0
+ 0
+ 0
+ 0
+
+ 8
+ 54
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/croutine.c
+ croutine.c
+ 0
+ 0
+
+
+ 8
+ 55
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/event_groups.c
+ event_groups.c
+ 0
+ 0
+
+
+ 8
+ 56
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/list.c
+ list.c
+ 0
+ 0
+
+
+ 8
+ 57
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/queue.c
+ queue.c
+ 0
+ 0
+
+
+ 8
+ 58
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c
+ stream_buffer.c
+ 0
+ 0
+
+
+ 8
+ 59
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/tasks.c
+ tasks.c
+ 0
+ 0
+
+
+ 8
+ 60
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/timers.c
+ timers.c
+ 0
+ 0
+
+
+ 8
+ 61
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c
+ cmsis_os2.c
+ 0
+ 0
+
+
+ 8
+ 62
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c
+ heap_4.c
+ 0
+ 0
+
+
+ 8
+ 63
+ 1
+ 0
+ 0
+ 0
+ ../Middlewares/Third_Party/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c
+ port.c
+ 0
+ 0
+
+
+
+
+ User/bsp
+ 0
+ 0
+ 0
+ 0
+
+ 9
+ 64
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\uart.c
+ uart.c
+ 0
+ 0
+
+
+ 9
+ 65
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\delay.c
+ delay.c
+ 0
+ 0
+
+
+ 9
+ 66
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\gpio.c
+ gpio.c
+ 0
+ 0
+
+
+ 9
+ 67
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\spi.c
+ spi.c
+ 0
+ 0
+
+
+ 9
+ 68
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\pwm.c
+ pwm.c
+ 0
+ 0
+
+
+ 9
+ 69
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\flash.c
+ flash.c
+ 0
+ 0
+
+
+ 9
+ 70
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\usb.c
+ usb.c
+ 0
+ 0
+
+
+ 9
+ 71
+ 1
+ 0
+ 0
+ 0
+ ..\User\bsp\buzzer.c
+ buzzer.c
+ 0
+ 0
+
+
+
+
+ User/component
+ 1
+ 0
+ 0
+ 0
+
+ 10
+ 72
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\ahrs.c
+ ahrs.c
+ 0
+ 0
+
+
+ 10
+ 73
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\user_math.c
+ user_math.c
+ 0
+ 0
+
+
+ 10
+ 74
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\filter.c
+ filter.c
+ 0
+ 0
+
+
+ 10
+ 75
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\pid.c
+ pid.c
+ 0
+ 0
+
+
+ 10
+ 76
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\cmd.c
+ cmd.c
+ 0
+ 0
+
+
+ 10
+ 77
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\FreeRTOS_CLI.c
+ FreeRTOS_CLI.c
+ 0
+ 0
+
+
+ 10
+ 78
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\crc8.c
+ crc8.c
+ 0
+ 0
+
+
+ 10
+ 79
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\crc16.c
+ crc16.c
+ 0
+ 0
+
+
+ 10
+ 80
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\limiter.c
+ limiter.c
+ 0
+ 0
+
+
+
+
+ Usr/device
+ 1
+ 0
+ 0
+ 0
+
+ 11
+ 81
+ 1
+ 0
+ 0
+ 0
+ ..\User\device\dr16.c
+ dr16.c
+ 0
+ 0
+
+
+ 11
+ 82
+ 1
+ 0
+ 0
+ 0
+ ..\User\device\bmi088.c
+ bmi088.c
+ 0
+ 0
+
+
+ 11
+ 83
+ 1
+ 0
+ 0
+ 0
+ ..\User\device\go.c
+ go.c
+ 0
+ 0
+
+
+ 11
+ 84
+ 1
+ 0
+ 0
+ 0
+ ..\User\device\n100.c
+ n100.c
+ 0
+ 0
+
+
+
+
+ User/module
+ 1
+ 0
+ 0
+ 0
+
+ 12
+ 85
+ 1
+ 0
+ 0
+ 0
+ ..\User\component\kinematics.c
+ kinematics.c
+ 0
+ 0
+
+
+ 12
+ 86
+ 1
+ 0
+ 0
+ 0
+ ..\User\module\chassis.c
+ chassis.c
+ 0
+ 0
+
+
+ 12
+ 87
+ 1
+ 0
+ 0
+ 0
+ ..\User\module\config.c
+ config.c
+ 0
+ 0
+
+
+
+
+ User/task
+ 1
+ 0
+ 0
+ 0
+
+ 13
+ 88
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\init.c
+ init.c
+ 0
+ 0
+
+
+ 13
+ 89
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\rc.c
+ rc.c
+ 0
+ 0
+
+
+ 13
+ 90
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\user_task.c
+ user_task.c
+ 0
+ 0
+
+
+ 13
+ 91
+ 5
+ 0
+ 0
+ 0
+ ..\User\task\user_task.h
+ user_task.h
+ 0
+ 0
+
+
+ 13
+ 92
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\atti_esti.c
+ atti_esti.c
+ 0
+ 0
+
+
+ 13
+ 93
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\test.c
+ test.c
+ 0
+ 0
+
+
+ 13
+ 94
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\cli.c
+ cli.c
+ 0
+ 0
+
+
+ 13
+ 95
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\monitor.c
+ monitor.c
+ 0
+ 0
+
+
+ 13
+ 96
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\cmd.c
+ cmd.c
+ 0
+ 0
+
+
+ 13
+ 97
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\ctrl_leg.c
+ ctrl_leg.c
+ 0
+ 0
+
+
+ 13
+ 98
+ 1
+ 0
+ 0
+ 0
+ ..\User\task\ctrl_chassis.c
+ ctrl_chassis.c
+ 0
+ 0
+
+
+
+
+ Unitree
+ 0
+ 0
+ 0
+ 0
+
+ 14
+ 99
+ 1
+ 0
+ 0
+ 0
+ ..\Middlewares\Third_Party\Unitree\crc_ccitt.c
+ crc_ccitt.c
+ 0
+ 0
+
+
+ 14
+ 100
+ 1
+ 0
+ 0
+ 0
+ ..\Middlewares\Third_Party\Unitree\gom_protocol.c
+ gom_protocol.c
+ 0
+ 0
+
+
+
+
+ ::CMSIS
+ 0
+ 0
+ 0
+ 1
+
+
+
diff --git a/MDK-ARM/CtrBoard-H7_ALL.uvprojx b/MDK-ARM/CtrBoard-H7_ALL.uvprojx
index e5699b1..49064c2 100644
--- a/MDK-ARM/CtrBoard-H7_ALL.uvprojx
+++ b/MDK-ARM/CtrBoard-H7_ALL.uvprojx
@@ -1,7 +1,10 @@
-
-
+
+
+
2.1
+
### uVision Project, (C) Keil Software
+
CtrBoard-H7_ALL
@@ -16,28 +19,28 @@
Keil.STM32H7xx_DFP.4.0.0
https://www.keil.com/pack/
IRAM(0x20000000-0x2001FFFF) IRAM2(0x24000000-0x2401FFFF) IROM(0x8000000-0x80FFFFF) CLOCK(12000000) FPU3(DFPU) CPUTYPE("Cortex-M7") ELITTLE TZ
-
-
-
+
+
+
0
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
$$Device:STM32H723VGTx$CMSIS\SVD\STM32H723.svd
0
0
-
-
-
-
-
+
+
+
+
+
0
0
@@ -52,15 +55,15 @@
1
1
1
-
+
1
0
0
0
0
-
-
+
+
0
0
0
@@ -69,8 +72,8 @@
0
0
-
-
+
+
0
0
0
@@ -78,16 +81,16 @@
0
- 1
-
-
+ 0
+
+
0
0
0
0
1
-
+
0
@@ -101,8 +104,8 @@
0
0
3
-
-
+
+
0
@@ -135,11 +138,11 @@
1
BIN\UL2V8M.DLL
-
-
-
-
-
+
+
+
+
+
0
@@ -172,7 +175,7 @@
0
0
"Cortex-M7"
-
+
0
0
0
@@ -306,7 +309,7 @@
0x20000
-
+
1
@@ -333,9 +336,9 @@
0
0
-
+
USE_PWR_LDO_SUPPLY,USE_HAL_DRIVER,STM32H723xx
-
+
../Core/Inc;../USB_DEVICE/App;../USB_DEVICE/Target;../Drivers/STM32H7xx_HAL_Driver/Inc;../Drivers/STM32H7xx_HAL_Driver/Inc/Legacy;../Middlewares/ST/STM32_USB_Device_Library/Core/Inc;../Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc;../Drivers/CMSIS/Device/ST/STM32H7xx/Include;../Drivers/CMSIS/Include;../Middlewares/Third_Party/FreeRTOS/Source/include;../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2;../Middlewares/Third_Party/FreeRTOS/Source/portable/RVDS/ARM_CM4F;../User;../Middlewares/Third_Party/Unitree
@@ -351,9 +354,9 @@
0
1
-
-
-
+
+
+
../Drivers/CMSIS/Include
@@ -364,15 +367,15 @@
0
1
0
-
-
-
+
+
+
CtrBoard-H7_ALL\CtrBoard-H7_ALL.sct
-
-
-
-
-
+
+
+
+
+
@@ -417,6 +420,8 @@
2
2
11
+
+
1
@@ -444,6 +449,12 @@
2
2
2
+
+
+
+
+
+
@@ -735,6 +746,8 @@
2
2
11
+
+
1
@@ -762,6 +775,12 @@
2
2
2
+
+
+
+
+
+
2
@@ -774,6 +793,12 @@
2
2
1
+
+
+
+
+
+
@@ -795,6 +820,8 @@
2
2
11
+
+
1
@@ -822,6 +849,12 @@
2
2
2
+
+
+
+
+
+
@@ -843,6 +876,8 @@
2
2
11
+
+
1
@@ -870,6 +905,12 @@
2
2
2
+
+
+
+
+
+
@@ -891,6 +932,8 @@
2
2
11
+
+
1
@@ -918,6 +961,12 @@
2
2
2
+
+
+
+
+
+
@@ -939,6 +988,8 @@
2
2
11
+
+
1
@@ -966,6 +1017,12 @@
2
2
2
+
+
+
+
+
+
@@ -987,6 +1044,8 @@
2
2
11
+
+
1
@@ -1014,6 +1073,12 @@
2
2
2
+
+
+
+
+
+
@@ -1035,6 +1100,8 @@
2
2
11
+
+
1
@@ -1062,6 +1129,12 @@
2
2
2
+
+
+
+
+
+
@@ -1083,6 +1156,8 @@
2
2
11
+
+
1
@@ -1110,6 +1185,12 @@
2
2
2
+
+
+
+
+
+
@@ -1131,6 +1212,8 @@
2
2
11
+
+
1
@@ -1158,6 +1241,12 @@
2
2
2
+
+
+
+
+
+
@@ -1179,6 +1268,8 @@
2
2
11
+
+
1
@@ -1206,6 +1297,12 @@
2
2
2
+
+
+
+
+
+
@@ -1227,6 +1324,8 @@
2
2
11
+
+
1
@@ -1254,6 +1353,12 @@
2
2
2
+
+
+
+
+
+
@@ -1339,9 +1444,19 @@
..\User\component\FreeRTOS_CLI.c
- kinematics.c
+ crc8.c
1
- ..\User\component\kinematics.c
+ ..\User\component\crc8.c
+
+
+ crc16.c
+ 1
+ ..\User\component\crc16.c
+
+
+ limiter.c
+ 1
+ ..\User\component\limiter.c
@@ -1363,11 +1478,21 @@
1
..\User\device\go.c
+
+ n100.c
+ 1
+ ..\User\device\n100.c
+
User/module
+
+ kinematics.c
+ 1
+ ..\User\component\kinematics.c
+
chassis.c
1
@@ -1461,18 +1586,20 @@
+
-
+
-
+
-
+
-
+
+
@@ -1481,5 +1608,5 @@
-
+
diff --git a/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.axf b/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.axf
index 768db2d..9000d26 100644
Binary files a/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.axf and b/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.axf differ
diff --git a/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.hex b/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.hex
index 2d5256b..3d879a1 100644
--- a/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.hex
+++ b/MDK-ARM/CtrBoard-H7_ALL/CtrBoard-H7_ALL.hex
@@ -1,29 +1,29 @@
:020000040800F2
-:1000000050080120190500089FC3000869B60008C0
-:100010009DC3000895320008A9F9000800000000FF
+:10000000100B01201905000835C7000845B8000885
+:1000100091C500089D32000835FD00080000000071
:10002000000000000000000000000000590400086B
-:10003000413C000800000000B5040008E3CA0008C5
+:10003000313D000800000000B5040008CFCD0008E5
:1000400037050008370500083705000837050008A0
:100050003705000837050008370500083705000890
-:10006000370500083705000837050008CD350008BA
-:10007000D9350008E5350008F1350008FD350008E0
-:10008000093600081536000837050008F53C000859
-:100090000D3D0008013D0008193D00083705000826
+:1000600037050008370500083705000899360008ED
+:10007000A5360008B1360008BD360008C9360008AC
+:10008000D5360008E136000837050008E53D0008D0
+:10009000FD3D0008F13D0008093E00083705000855
:1000A0003705000837050008370500083705000840
:1000B0003705000837050008370500083705000830
:1000C0003705000837050008370500083705000820
-:1000D0002DC900085DDE000869DE000881DE000829
-:1000E000B73C00083705000800000000370500088D
-:1000F00037050008370500083705000821360008D5
+:1000D00019CC0008DDE10008F5E100080DE2000898
+:1000E000A73D00083705000800000000370500089C
+:1000F000370500083705000837050008ED36000809
:1001000037050008370500083705000837050008DF
-:1001100037050008A5D50008370500083705000891
-:100120002D36000837050008370500083705000898
+:1001100037050008F5D8000837050008370500083E
+:10012000F936000805370008113700081D370008A8
:1001300037050008370500083705000837050008AF
:1001400000000000000000000000000000000000AF
:10015000370500083705000837050008370500088F
:10016000370500083705000837050008370500087F
-:1001700037050008C5C40008370500080000000066
-:100180003705000837050008B1D500083705000815
+:10017000370500085DC800083705000800000000CA
+:1001800037050008370500080DD9000837050008B5
:10019000370500083705000837050008370500084F
:1001A0003705000837050008370500080000000083
:1001B000370500083705000837050008370500082F
@@ -42,12 +42,12 @@
:10028000370500083705000837050008370500085E
:1002900000000000370500083705000800000000D6
:1002A0000000000037050008370500083705000882
-:1002B00051DE00083705000837050008253D000815
-:1002C000313D00087DCC00083705000800F002F839
+:1002B000C5E100083705000837050008153E0008AD
+:1002C000213E000869CF00083705000800F002F859
:1002D00000F0B2F80AA090E8000C82448344AAF12E
:1002E0000107DA4501D100F0A7F8AFF2090EBAE82C
:1002F0000F0013F0010F18BFFB1A43F0010318475A
-:100300007C300100AC3001000A444FF0000C10F8C2
+:100300002C3601005C3601000A444FF0000C10F856
:10031000013B13F0070408BF10F8014B1D1108BF83
:1003200010F8015B641E05D010F8016B641E01F823
:10033000016BF9D113F0080F1EBF10F8014BAD1C73
@@ -56,18 +56,18 @@
:10036000704700000023002400250026103A28BF13
:1003700078C1FBD8520728BF30C148BF0B60704717
:100380006E2900F08983702900F0D384662912F069
-:10039000C283652912F0BF83672912F0BC836129EB
-:1003A00012F0BB8303681B0A28BF41F08001692952
+:10039000A286652912F09F86672912F09C86612942
+:1003A00012F09B8603681B0A28BF41F0800169296F
:1003B00000F03683642900F03383752900F0308320
:1003C0006F2900F06084782900F09F84E92900F00B
:1003D000FB83E42900F0F883F52900F0F583EF2989
:1003E00000F05D84F82900F09E840368DB0928BFD3
:1003F00041F08001632901F0A581732901F0AA81F0
:10040000E32901F0B581F32901F0BA81002070479A
-:100410001FB512F07BFB01F009FA04000020002157
-:1004200012F05EFB401C60600020002112F042FBD5
+:100410001FB512F05BFE01F009FA04000020002174
+:1004200012F03EFE401C60600020002112F022FE0F
:10043000E0601FBD10B510BD01F0CAF91146FFF70D
-:10044000E7FF10F00FFA01F0A7FA03B4FFF7F2FF8D
+:10044000E7FF10F08FFC01F0A7FA03B4FFF7F2FF0B
:1004500003BC01F0DFFA00002C4B19680868B0E813
:10046000F04F80F30988BFF36F8F4FF0000080F3E7
:10047000118870470000000008480068006880F399
@@ -77,14 +77,14 @@
:1004B00088ED00E0EFF30980BFF36F8F134B1A68EC
:1004C0001EF0100F08BF20ED108A20E9F04F1060D9
:1004D00009B44FF0500080F31188BFF34F8FBFF382
-:1004E0006F8F11F0FDFB4FF0000080F3118809BC05
+:1004E0006F8F11F0DDFE4FF0000080F3118809BC22
:1004F00019680868B0E8F04F1EF0100F08BFB0ECA4
:10050000108A80F30988BFF36F8F704720010020A5
:10051000EFF30580704700000A4880470A4880478B
:100520000A480047FEE7FEE7FEE7FEE7FEE7FEE7D4
:10053000FEE7FEE7FEE7FEE705480649064A074BE9
-:1005400070470000D93C0008A5CB0008CD02000888
-:1005500050A800205008012050C8002050C800209A
+:1005400070470000C93D000891CE0008CD020008A8
+:1005500010AB0020100B012010CB002010CB00208E
:1005600053EA020C00F069802DE9F04B4FF00006D1
:10057000002B1FBFB3FA83F503FA05F424FA05F63E
:100580005E4012BF1643B2FA82F502FA05F4C5F1D5
@@ -187,7 +187,7 @@
:100B900000250DF1080B05E0D4E901211BF8050043
:100BA00090476D1C4D45F7D308F10100B0428046D7
:100BB000E4DB206A384420622046FFF7E4FEBDE80B
-:100BC000FF9F0000362501002DE9F0418046D21D2F
+:100BC000FF9F0000E22A01002DE9F0418046D21D7E
:100BD00022F007020025D2E90002F52915A614D05B
:100BE000011E72F1000106DA0023D0EB030063EB73
:100BF000020211A608E0D8F800108B0701D50FA655
@@ -211,19 +211,19 @@
:100D100021461068FFF751FE024629462046BDE8ED
:100D200070400023C6E7D21D22F00703D3E9002359
:100D3000C0E70368126843F0200303600823C3611F
-:100D40000023B7E7982301002DE9F05F89460446A8
+:100D40000023B7E7442901002DE9F05F89460446F6
:100D50004FF0000ADFF874B1FB44C0F820A0204631
:100D6000E1688847002874D0252806D0D4E90121FD
:100D70009047206A401C2062F1E700265F4620462B
:100D8000E16888472028054607DB312D05D2781910
:100D900010F8200C08B10643F1E7B00701D526F0A2
:100DA0000406C4F81CA00027C4F818A02A2D09D0F6
-:100DB00028460FF085FC38B304EB8708303DC8F8AF
+:100DB00028460FF005FF38B304EB8708303DC8F82C
:100DC000185019E059F8041B204604EB8702916182
:100DD000E1688847012F054618D1E069002820DA2C
:100DE00026F020061DE0D8F8180000EB800005EB87
:100DF00040003038C8F818002046E16888470546AA
-:100E00000FF05EFC0028EED1012F0AD02E2D08D164
+:100E00000FF0DEFE0028EED1012F0AD02E2D08D1E2
:100E10002046E16888477F1C0546022F46F02006E1
:100E2000C4DBA069002803DA404246F00106A06155
:100E3000F00701D026F010066C2D0BD0682D09D0DC
@@ -235,8 +235,8 @@
:100E90004A462946204626604E46FFF771FA80B141
:100EA00001280BD0F61D26F0070000F1080956E7CF
:100EB0004020E4E78020D8E70020D6E706F10409C7
-:100EC0004DE7284652E7206ABDE8F09F282301003D
-:100ED00000487047F0A7002030B5B0F10A024FEA91
+:100EC0004DE7284652E7206ABDE8F09FD42801008C
+:100ED00000487047ACAA002030B5B0F10A024FEAD2
:100EE000900E71F100034EEA817EB0EB0E0061EBD3
:100EF00091014FEA101E4EEA017E10EB0E0041EB0D
:100F000011114FEA102E4EEA016E10EB0E0041EB6C
@@ -285,7 +285,7 @@
:1011B0000B98099AC0F80880C0E9002B7AE711263D
:1011C0004FF0000857E72DE9F04F88460446D21D3E
:1011D00022F0070191B0D1E90001CDE90A010EF03A
-:1011E000E4FB02460B98C00F01D02D2007E02068D9
+:1011E000AAFD02460B98C00F01D02D2007E0206811
:1011F000810701D52B2002E0202101EAC000032A4B
:10120000099001D0072A05DB03464146204600F03D
:1012100011FB0BE12078800601D5E06900E0062093
@@ -323,7 +323,7 @@
:10141000012118F8010B9047206A401C2062381EF9
:10142000A7F10107F3DC2046FFF7ADFA032011B066
:1014300041E600002DE9F04F04460D46D21D22F092
-:10144000070089B0D0E90097484639460EF0ADFA5A
+:10144000070089B0D0E90097484639460EF073FC92
:101450000246F80F01D02D2307E02068810701D54F
:101460002B2302E0202101EAC0038DF820300BB1CC
:10147000012000E00020032A824601D0072A04DB75
@@ -369,7 +369,7 @@
:1016F0000FD0D4E901219047206A401C2062B8F144
:101700000108F2D22046FFF73EF909B00320BDE8F8
:10171000F08F206A2844206203E0D4E901213020C0
-:1017200090476D1EEBD3F8E72D1C010002FCFFFF74
+:1017200090476D1EEBD3F8E7DD21010002FCFFFFBF
:1017300010B5436913B1AFF3008001E0FFF746F93C
:10174000012010BD127800F124010A7000224A70B5
:101750000122EDE711684FF0FF32E9E710B5436968
@@ -379,14 +379,14 @@
:1017900000F044F8036893F80101012806D0FF2CFB
:1017A0000FD8185D68B101202C7070BDD3F8070107
:1017B0003246214603F2071303442846BDE8704031
-:1017C00018474FF0FF3070BD00487047F0A7002069
+:1017C00018474FF0FF3070BD00487047ACAA0020AA
:1017D0007546FFF7F9FFAE4605006946534620F00F
:1017E0000700854618B020B5FEF7A6FEBDE82040EC
:1017F0004FF000064FF000074FF000084FF0000BCD
:1018000021F00701AC46ACE8C009ACE8C009ACE87F
:10181000C009ACE8C0098D467047000010B500F063
-:1018200005F8001D10BD00BFB91201000048704747
-:1018300010A800202DE9F0411F4604460326016848
+:1018200005F8001D10BD00BF791801000048704781
+:10183000CCAA00202DE9F0411F460446032601688A
:10184000072A01F4006004DB08B116A505E016A51F
:1018500003E008B115A500E015A521F010002060F7
:10186000A069C01EA0610FB1401EA0612046FFF715
@@ -408,7 +408,7 @@
:1019600083E807006D10641C002DE3D14FF00103E4
:1019700032466946B8F1000F03A802D000F0CDFA54
:1019800001E000F0DFFAC9E90001C9F808200AB057
-:10199000BDE8F0873819010010B50446AFF30080A8
+:10199000BDE8F087E81E010010B50446AFF30080F3
:1019A0002046BDE81040FEF750BD00004FF0013C5E
:1019B00050F8042B51F8043B9A4215D1A2EB0C03CA
:1019C000934313EACC130BD150F8042B51F8043B8A
@@ -540,10 +540,10 @@
:1021A0001C4148BF7047921841EB0101A3F10103A4
:1021B0007047000010B5324904460068884202D0DA
:1021C000304A904202D1D1F8080302E02E48D0F8FC
-:1021D000080310F4403F10D006F0C4FE6168B1F56A
+:1021D000080310F4403F10D006F03CFF6168B1F5F1
:1021E000803F06D0B1F5003F03D0B1F5403F26D186
:1021F00001E0090C17E0800821E000214FF40020E5
-:1022000005F068FF61688A03920B18D18A140C2AC2
+:1022000005F0E0FF61688A03920B18D18A140C2A4A
:1022100015D2DFE802F0140606060606060B0D0FBF
:102220001113890C4900B0FBF1F008E0000906E049
:10223000400904E0800902E0C00900E0000A1349F7
@@ -557,19 +557,19 @@
:1022B000D4ED001A94ED020A20EEA01A61EEA01AE5
:1022C00094ED032AF7EE008A00EE001A40EE021A9F
:1022D000B0EE008AF0EE680A41EE480A21EE880A64
-:1022E0000DF022FE85ED010A94ED000AD4ED021AEC
+:1022E0000EF07AF885ED010A94ED000AD4ED021A99
:1022F000D4ED030A94ED011A20EE210A00EEC10A82
:1023000020EE080AF0EEC00A10EE900AB0F17E5FEF
:1023100006DB10EE101A134860F31E01A96003E0FB
-:102320000DF080FB85ED020A94ED021AD4ED001A3F
+:102320000DF0D8FD85ED020A94ED021AD4ED001AE5
:1023300094ED030A21EE012AD4ED012A61EE801A00
:10234000F0EE680A00EE002A42EE811A42EE480AD8
-:1023500021EE880A0DF0E8FD002085ED000ABDECB5
+:1023500021EE880A0EF040F8002085ED000ABDEC61
:10236000028B70BDDB0FC93F70B504000D463ED037
:10237000B7EE001ADFED380AC1EE001A84ED001A3C
:10238000C4ED010AC4ED020AC4ED030AC4ED041A47
:1023900065B3D5ED000A95ED010AB7EEE01AB7EE88
-:1023A000C00A0DF0DDFCB7EEC00BD5ED002ADFED65
+:1023A000C00A0DF035FFB7EEC00BD5ED002ADFED0A
:1023B0002B0A9FED2B1ADFED2B1A9FED2B2AF5EE42
:1023C000C02AB1EE400AF1EE10FA13D1D5ED012A80
:1023D000F5EEC02AF1EE10FA0CD1D5ED022AF5EE99
@@ -598,10 +598,10 @@
:10254000604A42EE013A42EEC14A25EE00FA64EEDC
:1025500000EA23EE80EA64EE80DA09D1B5EEC0AA83
:10256000F1EE10FA04D1B5EEC08AF1EE10FA7CD08B
-:102570002AEEAA0A0AEE0A0A08EE080A09F092F8F8
+:102570002AEEAA0A0AEE0A0A08EE080A09F080F909
:102580006AEE801ACDED0B1A6AEE001ACDED0A1A2A
:1025900000E0B4E168EE001A29EEA90ACDED091AAF
-:1025A00008EEA80A09EE090A09F07CF8D4EC021A30
+:1025A00008EEA80A09EE090A09F06AF9D4EC021A41
:1025B000B0EE008AD4ED030A69EE80AA94ED021A07
:1025C00061EEA12A20EE883A21EE88BA62EE08BABE
:1025D000F0EE629A61EE822A8DED163A21EE08AA9B
@@ -617,7 +617,7 @@
:102670002BEE013A02EE200A2AEE092A42EE201A37
:102680000AEECC0A61EE200ACDED000A48EECD1A22
:102690000AEECD0A8DED043A20EE000A01EEA10A01
-:1026A00009F000F8DDED1C2ADDED1D1ADDED000A54
+:1026A00009F0EEF8DDED1C2ADDED1D1ADDED000A66
:1026B000B7EE002A32EEE11ADDED122A9DED043A62
:1026C000DDED0A1A72EEA04AC2EE000A9DED1B0A69
:1026D0001FEE883A0CEEC82A02EE880A6AEE285AE3
@@ -644,14 +644,14 @@
:1028200045EEA0AA4CEE23BA01EE427A40EE069A9B
:1028300008EE20AA2AEEAA0A46EE86BA47EE209AA9
:102840000AEE0A0A44EEA0BA09EEA90A0BEEAB0A98
-:1028500008F028FF6AEE800A2AEE001A69EE801A54
+:1028500009F016F86AEE800A2AEE001A69EE801A6C
:102860002BEE802A95ED000A00EE60FA40EE41EA78
:1028700000EE61EA40EE42DA94ED040A94ED002A9B
:1028800094ED011AD4ED020A0FEE002A0EEE801A22
:102890004EEE000AD4ED031A04E000009EEF273D3F
:1028A000A80100204DEE801A22EE020A84ED002AD3
:1028B00084ED011AC4ED020A01EE010AC4ED031A07
-:1028C00000EEA00A01EEA10A08F0ECFE94ED001A59
+:1028C00000EEA00A01EEA10A08F0DAFF94ED001A6A
:1028D00094ED012AD4ED021AD4ED030A21EE001A78
:1028E00022EE002A61EE801A20EE800A84ED001AA2
:1028F00084ED012AC4ED021A002084ED030A21B000
@@ -666,7 +666,7 @@
:1029800042EEA04A02EE603A65EE21AA24EE21AAA8
:1029900064EEA19A23EE219A09D1F5EEC08AF1EEF8
:1029A00010FA04D1B5EEC08AF1EE10FA7ED02BEE0B
-:1029B0000B0A08EEA80A08EE080A08F073FE94ED68
+:1029B0000B0A08EEA80A08EE080A08F061FF94ED79
:1029C000004AF1EE000AD4ED011AF0EE003A94ED5F
:1029D000022A94ED033A2BEE001AB2EE005A68EE8A
:1029E000802A68EE004A24EE047A24EE23BA64EECC
@@ -680,27 +680,27 @@
:102A6000620A0BEEE28A37EE40BA4DEE628A70EEF1
:102A7000E6BA0CEE27BA43EEA7BA0CEE04BA43EE60
:102A800084BA00EE24BA28EEA80A46EEA4BA0BEEE9
-:102A90000B0A0BEEAB0A08EE080A08F003FE28EE5C
+:102A90000B0A0BEEAB0A08EE080A08F0F1FE28EE6E
:102AA000801A6BEE000A6BEE801A00E00BE028EE55
:102AB000002A95ED000A40EE41AA00EE60AA40EE21
:102AC000619A00EE429A201D94ED002A94ED040ACA
:102AD000D0EC030A0AEE802A4AEE000A09EE801AB8
:102AE00049EE001A22EE020A84ED002A00EEA00A46
-:102AF000C0EC030A01EE010A01EEA10A08F0D2FDC2
+:102AF000C0EC030A01EE010A01EEA10A08F0C0FED3
:102B000094ED001A94ED012AD4ED021AD4ED030AD3
:102B100021EE001A22EE002A61EE801A20EE800AD1
:102B200084ED001A84ED012AC4ED021A002084ED20
:102B3000030ABDEC0C8B70BD022B073DA8010020E1
-:102B40000248022140680EF0E3B80000C8010020EE
+:102B40000248022140680EF063BB0000C80100206B
:102B5000044A13231221002010B500F097F9002039
:102B600010BD00001200002401214FF0FF320820A8
-:102B70000EF008B99FED010A704700000000C8433D
-:102B80000248012140680EF0C3B80000C8010020CF
+:102B70000EF088BB9FED010A70470000000048433B
+:102B80000248012140680EF043BB0000C80100204C
:102B9000044A06230221012010B500F077F9002035
:102BA00010BD00001900002401214FF0FF32042065
-:102BB0000EF0E8B82DE9F04106000D466FF0010770
+:102BB0000EF068BB2DE9F04106000D466FF00107ED
:102BC00026D02DB3434C207818B16FF00200BDE839
-:102BD000F0810EF023F96060D0B1B622F5617E215C
+:102BD000F0810EF0A3FB6060D0B1B622F5617E21DA
:102BE000002000F0BBF9B6221421012000F0B6F954
:102BF0001E2000F02BFA1E21002000F073F90021A6
:102C0000084600F06FF91E286FF0030508D101E0B7
@@ -738,4229 +738,4323 @@
:102E0000030AD1ED010A00E009E071EE600AC0EDAD
:102E1000040AD1ED020A30EE600A80ED050A104680
:102E20001EBD0000120000246F12034235FA8E3CD2
-:102E300070B5114D0121284603F0BEFD0F4C40B97D
-:102E400001222846114603F0BCFD606808210DF000
-:102E50005FFF0821284603F0AFFD00280AD10122B8
-:102E60002846082103F0ADFD60680421BDE87040EC
-:102E70000DF04EBF70BD000000080258C8010020D0
-:102E800001214FF0FF3203200DF07CBF70B514001C
+:102E300070B5114D0121284603F036FE0F4C40B904
+:102E400001222846114603F034FE606808210EF086
+:102E5000DFF90821284603F027FE00280AD10122C5
+:102E60002846082103F025FE60680421BDE8704073
+:102E70000EF0CEB970BD000000080258C801002055
+:102E800001214FF0FF3203200EF0FCB970B51400A1
:102E90001E460D4621D0114B10B1012808D102E089
-:102EA0000022012101E000220821184603F089FDDB
+:102EA0000022012101E000220821184603F001FE62
:102EB0000B4945F080000870002000F04FF90849E8
-:102EC0001423012207F04FF9002000F047F93246A1
-:102ED0002146BDE8704007F04BB870BD00080258AD
+:102EC0001423012207F0C9F9002000F047F9324627
+:102ED0002146BDE8704007F0C5B870BD0008025833
:102EE000C901002070B50D460446012000F0AEF87F
:102EF000184E14B1012C08D102E00022012101E09A
-:102F000000220821304603F05CFD45F08000124DA0
+:102F000000220821304603F0D4FD45F08000124D28
:102F10002870002000F022F914232946012207F02E
-:102F200022F9002000F01AF914232946022206F0A3
-:102F3000E5FE44B1012C05D101223046082103F001
-:102F400040FD287870BD01223046114603F039FD5E
+:102F20009CF9002000F01AF914232946022206F029
+:102F30005FFF44B1012C05D101223046082103F086
+:102F4000B8FD287870BD01223046114603F0B1FD6E
:102F5000687870BD00080258C901002070B50446A9
:102F6000154801F07F0101704270012000F06EF8F9
:102F7000124D14B1012C08D102E00022012101E020
-:102F800000220821284603F01CFD002000F0E6F88E
-:102F900009491423022207F0E6F844B1012C09D1B3
-:102FA000012208212846BDE8704003F00ABD012235
+:102F800000220821284603F094FD002000F0E6F816
+:102F900009491423022207F060F944B1012C09D138
+:102FA000012208212846BDE8704003F082BD0122BD
:102FB0001146F7E770BD0000C90100200008025863
:102FC00010B52DED028BF0EE408AB0EE608AF5EE82
:102FD000C08AF1EE10FA09D9B5EEC08AF1EE10FA06
:102FE00004D318EE100AB0F17E5F04DD4FF0FF301D
-:102FF000BDEC028B10BD05F0D7FF134900EE100A9F
+:102FF000BDEC028B10BD06F04FF8134900EE100A2D
:10300000D1E90030F8EE400A401C00EE100AB8EE9C
:10301000400A20EE280A80EE801ABCEEC10A10EEAB
:10302000100A0246401ED86200EE102AC8600968E5
:10303000B8EE400A28EE000ABCEEC00A10EE100AF4
-:1030400088630020D4E70000E408002070B505463E
-:103050000DF055FD4FF47A71B1FBF0F0B5FBF0F4D3
-:103060000DF036FD02284FF0FF3110D005DC88420C
+:1030400088630020D4E700006009002070B50546C1
+:103050000DF0D5FF4FF47A71B1FBF0F0B5FBF0F451
+:103060000DF0B6FF02284FF0FF3110D005DC88428A
:103070000BD090B1012813D10FE0032805D004280C
:1030800003D06FF0004290420AD1084670BD04B9E7
-:10309000012420460DF0F6FC02E0284602F0A0FFD5
+:10309000012420460DF076FF02E0284603F018F8E0
:1030A000002070BDB0F5806F10B508D0B0F5805F1E
:1030B00005D0B0F5004F02D04FF0FF3010BD2820F2
-:1030C00003F014FD002010BDB0F5806F10B508D0DE
+:1030C00003F08CFD002010BDB0F5806F10B508D066
:1030D000B0F5805F05D0B0F5004F02D04FF0FF3063
-:1030E00010BD282003F013FD002010BD10B549B11C
+:1030E00010BD282003F08BFD002010BD10B549B1A4
:1030F0000124002204FA02F3034206D0064840F8F5
:10310000221006E06FF0010010BD521CD2B2102A4E
-:10311000F0D3002010BD0000089900200A460E4997
+:10311000F0D3002010BD0000109B00200A460E498D
:1031200010B530B1012808D002280AD04FF0FF3086
:1031300010BD08464FF4804106E008464FF40051A8
:1031400002E008464FF40041012A00D0002203F0BB
-:1031500038FC002010BD00000008025808B1002013
-:1031600070470148704700008806002032B1054BC7
+:10315000B0FC002010BD00000008025808B100209B
+:1031600070470148704700000407002032B1054B4A
:1031700003EB401040F82120002070476FF0010061
-:10318000704700004899002038B1012807D0022874
-:1031900007D0032807D00020704704487047044830
-:1031A0007047044870470448704700003009002009
-:1031B000EC0A0020800B0020140C002070B504469F
-:1031C0000068C169C90617D51021016220460AF0BE
-:1031D00093FB0A4D00EBC00005EB8000006A00285D
-:1031E0000AD020460AF088FB00EBC00005EB800007
-:1031F000006ABDE87040004770BD0000789800206C
-:1032000042B1064B00EBC00003EB800040F82120E8
-:10321000002070476FF00100704700007898002090
-:103220000FB4104840F2FF3170B505AB049AFDF7BA
-:103230000FFA05042D0C11D00A4E00242946304601
-:1032400000F04CF830B1641C0A20E4B2FFF7FEFE37
-:10325000032CF3D3002070BC5DF814FB6FF0010069
-:10326000F9E70000E89900200849002070B5084EF1
-:103270000A88B35C002B08D000251846541CA3B262
-:10328000B554802B0B8000D30D8070BDA0010020B1
-:1032900068990020FEE7002070470020704700007A
-:1032A00005490022054810B50AF0C0FF044903484B
-:1032B0000AF0AFFF002010BDA01C0020C40F0020AA
-:1032C000A01400200348012110B500680DF020FD76
-:1032D000002010BDA401002000207047094A10B54D
-:1032E000D2F8BC22D2F814220AB1012010BD0A463D
-:1032F000014604480AF09AFFBDE8104001480BF06F
-:103300000BB80000C40F002008B1002070474FF038
-:10331000FF3070474FF0FF3210B560B159B1437CB8
-:10332000002253B1047C44B1012B08D0022B09D0F8
-:10333000032B08D105E0104610BD0A711CE00A718C
-:1033400001E001230B71037C2BB1012B03D0022B75
-:1033500001D0032B00D14A7190ED020A81ED030ADE
-:1033600090ED030A81ED040A90ED000A81ED050A53
-:1033700090ED050A81ED020A002010BD2DE9F04113
-:1033800004006FF001002DED048BBCB057D0002974
-:1033900055D02068101A00EE100ADFED560A564E7E
-:1033A000B8EE400A80EE201A84ED011A22600878F7
-:1033B00084F89001F0B3012857D002283FD130782B
-:1033C0000227B1EE048A0228F2EE048AB9EE049ACA
-:1033D000FAEE049A6CD000254FF00308B5FBF8F123
-:1033E00008FB1150002805EB850050D0424904EB42
-:1033F0008000142218319C30FDF7F3F994ED630A34
-:103400006D1CEDB260EE081A20EE281A60EE090A73
-:1034100020EE290AC4ED2E1A84ED331AC4ED3D0ABC
-:1034200084ED420AC4ED4C1A84ED511A0C2DC4ED02
-:103430005B0A00E008E084ED600A3770CED33CB050
-:10344000BDEC048BBDE8F081F0216846FDF725FA5C
-:103450002A49F0226846FDF7C4F9F022694604F1D2
-:103460009C00FDF7BEF900200FE000252249142240
-:1034700005EB8500091D04EB80009C30FDF7B1F9D8
-:103480006D1CEDB20C2DF1D301203070D7E79FED0C
-:103490001C0A9FED1C1A04EB800000F1A401F7EE5A
-:1034A000000A81EC030A80ED270A80ED280AA5E7CF
-:1034B000D1ED010A94ED630A00EE810A84ED630AFE
-:1034C00060EE081A20EE281A60EE090A20EE292A7A
-:1034D000C4ED2E1A84ED331AC4ED3D0A84ED422A60
-:1034E000C4ED4C1A84ED511AC4ED5B0A84ED602AD8
-:1034F0003770A4E700007A44D4010020F02B0108C3
-:1035000000000000CDCCCC3D2DE9F04105000E4679
-:103510001ED0002E1CD004274FF064085FF000047A
-:10352000A86807EB840308EB840204EB84010344DE
-:10353000024405EB81009C30D3ED000A92ED000AB5
-:1035400006EB810108F0E2F8641CE4B20C2CE7D32E
-:10355000BDE8F08148B19FED060A8160002280F845
-:10356000902180ED630A104670476FF001007047AC
-:10357000CDCC4C3E2DE9F04104270E4600240546F3
-:103580004FF0640807EB8403A86808EB840204EB9F
-:1035900044010344024405EB81000C30D3ED000AE2
-:1035A00092ED000A06EB810108F09AF8641CE4B27F
-:1035B0000C2CE7D3BDE8F081002803D00249D822C3
-:1035C000FDF70FB97047000000020020014801F02C
-:1035D00067BE00004C030020014801F061BE0000FE
-:1035E000A80C0020014801F05BBE0000100700207D
-:1035F000014801F055BE000088070020014801F095
-:103600004FBE0000100E0020014801F049BE00002E
-:10361000880E0020014801F043BE0000200D00206C
-:10362000014801F03DBE0000980D0020014801F066
-:1036300037BE0000000F0020294A016891423AD0AD
-:10364000274A1832914236D0254A3032914232D040
-:10365000234A483291422ED0214A603291422AD0E8
-:103660001F4A7832914226D01D4A9032914222D090
-:103670001B4AA83291421ED01A4A91421BD0194AC5
-:103680001832914217D0174A3032914213D0154A5E
-:10369000483291420FD0134A603291420BD0114A06
-:1036A0007832914207D00F4A9032914203D00D4AAE
-:1036B000A832914211D1CAB21823103AB2FBF3F2E8
-:1036C0006FF30901032A02F00703074AD25CC265BF
-:1036D00000D9091D81650846704721F0FF01F9E70F
-:1036E0001000024010040240442B010830B5224A69
-:1036F000012301689142CAB21BD01F4C1434A1426D
-:1037000017D01D4C2834A14213D01B4C3C34A1428D
-:103710000FD0194C5034A1420BD0174C6434A14245
-:1037200007D0154C7834A14203D0134C8C34A142FD
-:103730000CD11421114C083AB2FBF1F10F4A80323E
-:1037400001F01F0504EB8101AB4010E00C4D182483
-:10375000103A0D44B2FBF4F1A82D00D80831094A03
-:1037600001F01F0402EB8101064AA3408032603061
-:1037700080E80E0030BD000008540258005802587E
-:10378000F0FBFDBF0008024010B50279531E072B65
-:103790002DD8174C0168A1421BD0154C1434A142FE
-:1037A00017D0134C2834A14213D0114C3C34A14201
-:1037B0000FD00F4C5034A1420BD00D4C6434A142B9
-:1037C00007D00B4C7834A14203D0094C8C34A14271
-:1037D00003D10849074C443102E00749064C443103
-:1037E00004EB8202C0E91B2101219940416710BD11
-:1037F00008540258FC580258FC08024010B583696E
-:103800004FF0C074826A0146002053B1B3F5005FE7
-:1038100015D072B1012A0CD0022A0AD0032A09D18C
-:1038200004E01AB1012A06D0022A03D1C96AC901EB
-:1038300000D5012010BDC96AA142FAD010BD002AEE
-:10384000F7D0012AF2D0022AF3D0032AF3D010BD18
-:103850002DE9F04F804E804FDFF8FC911836DFF8ED
-:10386000F8A148370468856D0AF1300ADFF8ECB139
-:103870004C45DFF8ECC1DFF8ECE16DD0B4426BD021
-:10388000544569D0BC4267D0DFF8D081A8F1180850
-:10389000444561D05C455FD064455DD074455BD0E4
-:1038A000DFF8C481444557D0DFF8BC8108F118081F
-:1038B000444551D0DFF8B08108F1300844454BD081
-:1038C000DFF8A48108F14808444545D0DFF8988125
-:1038D00008F1600844453FD0DFF88C8108F1780892
-:1038E000444539D0DFF8808108F19008444533D051
-:1038F000DFF8748108F1A80844452DD0DFF86C8109
-:10390000444529D0DFF8648108F11408444523D0E8
-:10391000DFF8588108F1280844451DD0DFF84C81B4
-:1039200008F13C08444517D0DFF8408108F1500801
-:10393000444511D0DFF8348108F1640844450BD0C8
-:10394000DFF8288108F17808444505D0DFF81C81AC
-:1039500008F18C08444509D1D0E91948C4F804801D
-:10396000C46E1CB1D0E91C48C4F8048004684C45FE
-:103970002ED0B4422CD054452AD0BC4228D0374E49
-:10398000183EB44224D05C4522D0644520D0744512
-:103990001ED0354EB4421BD0334E1836B44217D029
-:1039A000314E3036B44213D02F4E4836B4420FD089
-:1039B0002D4E6036B4420BD02B4E7836B44207D031
-:1039C000294E9036B44203D0274EA836B44215D1C2
-:1039D00090F85C603F2406F01F06B440AC600468B9
-:1039E000256825F4802525602EE09A600068C16076
-:1039F000BDE8F08F99600068C260F9E71B4EB442E1
-:103A00001BD01A4E1436B44217D0184E2836B44282
-:103A100013D0164E3C36B4420FD0144E5036B4423A
-:103A20000BD0124E6436B44207D0104E7836B442F2
-:103A300003D00E4E8C36B442DAD190F85C6001248B
-:103A400006F01F06B4406C60046863608368402B16
-:103A50000368CFD1C9E7000010000240880002408F
-:103A6000A0000240B800024010040240085402586E
-:103A700000F0AEB810B520B11621FCF7ECFE002026
-:103A800010BD6FF0010010BD70B56FF00105B8B149
-:103A90000C4C207810B16FF0020070BD0DF0BEF933
-:103AA000606068B1084A03210020FFF7A9FB074ABC
-:103AB00004210020FFF7A4FB01202070002070BD2E
-:103AC000284670BDC0010020F93B0008713A00088B
-:103AD00010B504001ED0124900F0B3F821884FF44D
-:103AE000A560A1F5B671814217D86188A1F5B671BC
-:103AF000814212D8A188A1F5B67181420DD8E18822
-:103B0000A1F5B671814208D8207A30B1607A20B12F
-:103B1000002010BD6FF0010010BD4FF0FF3010BD50
-:103B200000000024F0B3E9B30288DFED270A01EEBC
-:103B3000902AB0EE001A9FED250AF8EE611A71EE98
-:103B4000E01A61EE811A81EE802A81ED002A428816
-:103B500001EE902AF8EE611A71EEE01A61EE811A18
-:103B600081EE802A81ED012A828801EE902AF8EE0A
-:103B7000611A71EEE01A61EE811A81EE802A81ED00
-:103B8000022AC28801EE902AF8EE611A71EEE01A5C
-:103B900021EE811AC1EE001AC1ED031A427A0A74AD
-:103BA000027A00E00DE04A74808A01EE100A0020DB
-:103BB000B8EE411A71EE600A80EE801A81ED051AA6
-:103BC00070476FF001007047000080440000A5447A
-:103BD000002010B5FFF7D8FA0068016821F0010154
-:103BE00001600020FFF7D0FA0068016841F0010190
-:103BF0000160002010BD00000248102140680DF057
-:103C000087B80000C0010020002010B5FFF7BCFA03
-:103C10000449122207F070FC002801D04FF0FF3059
-:103C200010BD00000000002401210246102010B544
-:103C30000DF0A8F8102801D0002010BD012010BD03
-:103C40007047002810B535D0002933D00A88C2F358
-:103C50000A0202804A788B78D20842EA4312C2F301
-:103C60000A0242808A78CB780C79920942EA830270
-:103C700042EA8422C2F30A0282800A794B7952080E
-:103C800042EAC312C2F30A02C2804A79C2F30112A5
-:103C900042724A7992090272CA8842810A898281F3
-:103CA0004A89C2810A7B02744A7B4274CA89428271
-:103CB000098A818210BD4FF4806010B502F062FD68
-:103CC0004FF4805002F05EFDBDE810404FF400401C
-:103CD00002F058BD72B6FEE705480549083902688A
-:103CE00042F00202026008688004FCD570470000C0
-:103CF0000C480258014802F089B90000C4030020B2
-:103D0000014802F083B90000C4030020014802F01A
-:103D10007DB9000064040020014802F077B900007A
-:103D200064040020014802F071B90000040500207D
-:103D3000014802F06BB9000004050020F0B50368EB
-:103D40004FF6FC716D4C426BD3F884508D4345EABD
-:103D50008205C3F88450036853F8845F068F25F406
-:103D60007F0545EA06451D60836B654D9F18026817
-:103D7000D2F888308B4343EA8703C2F88830026860
-:103D800052F8883F868F23F4FE0343EA064313600C
-:103D9000066856F8A03FC26B8B4307EB420243EA2A
-:103DA00082033360076857F8A03FB0F8406023F4FF
-:103DB000FE0343EA06433B60D0E9103603FB0622CC
-:103DC0000368D3F8B0608E4346EA8206C3F8B06059
-:103DD0000368B0F84860D3F8B07027F4FE0747EAEC
-:103DE0000646C3F8B060D0E91267036806FB0722F5
-:103DF000D3F8AC608E4346EA8206C3F8AC60D0E9E3
-:103E00001467036806FB0722D3F8F0608E4346EA86
-:103E10008206C3F8F0600368B0F85860D3F8F07019
-:103E200027F47C1747EA0646C3F8F0600368876DFD
-:103E300053F8C06F02EB47028E4346EA82011960D5
-:103E40000168B0F85C20D1F8C03023F47C1343EA59
-:103E50000242C1F8C020016890F86020D1F8C0305B
-:103E600023F07C5343EA0262C1F8C020416B04EBAB
-:103E70008101C166826B01EB82020267C36B02EBB8
-:103E8000C3024267D0E91034634302EB83028267C6
-:103E9000D0E91234634302EB8302C267D0E91434E1
-:103EA000634302EB8302C0F88020836D02EBC303FF
-:103EB000C0F88430C46D826E544303EB8403C0F8B1
-:103EC0008830046E544303EB8402C0F89020AA4269
-:103ED0000AD9D0F89C20032142F02002C0F89C208F
-:103EE00080F898100120F0BD002200E004C1D0F855
-:103EF00090308B42FAD80020F0BD000000AC0040AA
-:103F0000FCD3004000487047E89D00202DE9F047B1
-:103F10002F4C0546012691468A464FF000086068FE
-:103F2000A0BB04F10C0010E0006807683846FCF7FD
-:103F3000A9FB0246A85C202800D020B939462846B3
-:103F4000FCF7BFFB28B16068406860600028EBD1D7
-:103F500034E0D4F804C0DCF8000090F90C70002FB5
-:103F600010DB00202946024603E0202B18D0002257
-:103F7000491C0B78002BF8D10AB1401E40B2B84260
-:103F800000D00026BCF1000F18D07EB160682A4630
-:103F90004946006883685046984706000BD013E0F6
-:103FA000002AE5D10122401C40B2E1E709494A4616
-:103FB0005046FCF799FCC4F8048005E006494A46DF
-:103FC0005046FCF791FC00263046BDE8F087000023
-:103FD000AC01002058320108B032010870B505006C
-:103FE00011D008200DF060FB040014D00DF05EFC31
-:103FF0000D480021C4E9005101684C6004600DF0D7
-:1040000075FC012070BD502080F31188BFF34F8FE5
-:10401000BFF36F8FFEE7502080F31188BFF34F8FFF
-:10402000BFF36F8FFEE70000AC01002070B5040005
-:104030006FF0010006D0002904D00B4D287810B194
-:104040006FF0020070BD2046C4F8E0144FF4047114
-:10405000FCF723FC4FF4347104F50470FCF71DFCED
-:1040600001202870002070BDD00100202DE9F04112
-:10407000060025D02A48007830B301275FF00004FD
-:1040800004EB440000EBC40006EB800526F820405A
-:1040900028466F800CF018FC032C02D3A01F0328C5
-:1040A00015D2D6F8E0040078FFF76EF8012311224C
-:1040B00005F1180107F06CFAD6F8E004007814E076
-:1040C0006FF00100BDE8F0816FF00200FAE7D6F86A
-:1040D000E0044078FFF758F80123112205F1180198
-:1040E00007F056FAD6F8E0044078FFF74DF8C4EB35
-:1040F0000411012306EB8101102201F50F7107F075
-:1041000087F9C4EB041006EB800000F504700CF096
-:1041100035FB641CE4B20C2CB2D30020D2E70000C3
-:10412000D001002030B56FF0010228B321B3002286
-:10413000551C02EB820302EB420401EB830304EB08
-:10414000C20293ED030A00EB8204EAB284ED040A92
-:1041500093ED040A0C2A84ED050A93ED020A84ED1E
-:10416000030A93ED010A84ED020A93ED000A84ED3F
-:10417000010ADDD3002030BD104630BD6FF00102D2
-:1041800010B5D8B1D1B10022C2EB021402EB420348
-:1041900000EB840401EB830394ED890A521C83ED48
-:1041A000020A94ED880AD2B283ED010A94ED870ADF
-:1041B0000C2A83ED000AE7D3002010BD104610BD85
-:1041C0002DE9F0470F4690F85C109CB00446012999
-:1041D0004FF0000915D00026DFF8F880012084F8A0
-:1041E0005C0018961996216841450ED13A4D00950C
-:1041F000284607F0B5FA8246206807F0B1FA60B1A8
-:104200000EE002201CB0BDE8F087206E84F85C60F0
-:1042100040F0200020660120F4E7BAF1000F09D039
-:10422000216E4FF0010941F020002066484684F8D5
-:104230005C60E7E720684146884201D0A84201D18E
-:10424000264800E0264840F61F72D7F800C0254BEC
-:10425000BCF1000F23D0D0F808C0D7F804802CF4AC
-:10426000404C4CEA080CC0F808C0D4F800C08C459B
-:1042700001D0AC4507D18968AB6801F0010103F0BA
-:104280000103194302E0996801F001010029CDD131
-:10429000BD683968836829439343194317E08768E9
-:1042A00027F44047876027688F4201D0AF4207D18B
-:1042B0008968AB6801F0010103F00103194302E0D2
-:1042C000996801F001010029B0D1816891438160B2
-:1042D000ACE7000000200240002102400023024021
-:1042E00000630258006002582DE9F84F0446DFF8D9
-:1042F000ECB30020FA4E0090814694F85C000D4625
-:10430000F84F012808D04FF0010A84F85CA020681B
-:1043100007F022FA18B18FE20220BDE8F88F286872
-:1043200000280FDB2168B1420CD0CA69030327D0F3
-:1043300090FAA0F0B0FA80F000F01F030AFA03F040
-:104340000243CA61D5E900124FF00C0C20681F230C
-:10435000C1F384610CEA921C02F01F026044934096
-:104360009140026B9A430A430263206807F0F4F914
-:104370008046206807F0ECF958EA000003D054E1C9
-:10438000C0F38460D8E729684FF0040C2068072345
-:10439000AA680CEAD15CC1F3045160448B408A40A6
-:1043A00041699943114341612068B04204D1C26818
-:1043B0006969C2F3C1020BE0CB4A1268BAEB127F03
-:1043C00002D0C168C90605D4C2686969C2F3820215
-:1043D000520004E0C268696902F01002520891407C
-:1043E0002A69042A5AD02B6800EB8202B04202F1FB
-:1043F000600207D103F0F8401368084340F0004022
-:10440000106008E0D2F800C003F0F84008430CF058
-:104410000041014311602068B0421CD12969EA695A
-:1044200000EB8100016E21F080711143016695F867
-:10443000201020682A6901290AD00021B0429ED1AB
-:1044400000EB8200026E22F000720A430266ECE08A
-:104450004FF00071F2E795F821102A69012917D071
-:104460005FF0000100EB8200026E22F000420A437E
-:104470000266297E20682A6901290CD0002103697F
-:1044800002F01F02914023F4F0420A430261CCE0A3
-:104490004FF00041E6E74FF40061F0E7B04273D11E
-:1044A000002107F04FF9000320684FF000016DD0A4
-:1044B00007F048F990FAA0F0B0FA80F128680203FA
-:1044C00069D090FAA0F0B0FA80F0814204D10022C5
-:1044D0002068114607F048F92068012107F032F9F9
-:1044E000000320684FF0010158D007F02BF990FA33
-:1044F000A0F0B0FA80F12868020354D090FAA0F03E
-:10450000B0FA80F0814204D120680022012107F036
-:104510002BF92068022107F015F9000320684FF0FD
-:10452000020143D007F00EF990FAA0F0B0FA80F142
-:10453000286802033FD090FAA0F0B0FA80F08142E0
-:1045400004D120680022022107F00EF9206803211F
-:1045500007F0F8F8000320684FF003012ED007F0B1
-:10456000F1F890FAA0F0B0FA80F1286802032AD09E
-:1045700090FAA0F0B0FA80F0814256D12068002273
-:10458000032107F0F1F850E020E0FFE707F0DAF848
-:10459000C0F3846192E7C0F3846096E707F0D2F835
-:1045A000C0F38461A7E7C0F38460ABE707F0CAF803
-:1045B000C0F38461BCE7C0F38460C0E707F0C2F8D1
-:1045C000C0F38461D1E7C0F38460D5E7016E2A7837
-:1045D00001F0F841B1EB826F03D1016E21F000418F
-:1045E000016620682978426E02F0F842B2EB816FD2
-:1045F00003D1416E21F00041416620682978826E26
-:1046000002F0F842B2EB816F03D1816E21F00041DC
-:10461000816620682978C26E02F0F842B2EB816FA1
-:1046200003D1C16E21F00041C1662068816811F09C
-:10463000010F52D12D4AB042EB6829680FD1D0F852
-:10464000B0C003F01808C1F3130322FA08F20A40BD
-:104650002CEA030C4CEA020CC0F8B0C00EE0D0F813
-:10466000C0C003F01808C1F3130322FA08F20A408D
-:104670002CEA030C4CEA020CC0F8C0C0E9685945AA
-:1046800070D11B482268DFF86CC0DFF86CB0824242
-:10469000DFF868E01A481B4BDFF86C8043D12968CB
-:1046A000614565D0B1EB4C0C6DD0714569D0A1F17D
-:1046B000865CBCF1100C75D0DFF850C061456DD040
-:1046C000DFF84CC061457FD0814273D0994247D01A
-:1046D0001048814222D1104876E0B3E00000FF4745
-:1046E00000600258002102400010005CFFFF0F0034
-:1046F0000020024002003004400020190800900C05
-:104700000008302E00106032002090362000F01497
-:104710000004002A00002143000052476E488142F5
-:1047200051D16E4850E0BA421DD1296861451FD071
-:10473000A1F1066CBCF1040C25D0714521D0A1F18A
-:10474000865CBCF1100C2DD0DFF894C1614525D0FA
-:10475000DFF890C1614537D081422BD09942DDD13D
-:10476000404631E040E0B2422DD12968614501D197
-:10477000012029E0A1F1066CBCF1040C03D07145C5
-:1047800003D1594820E058461EE0A1F1865CBCF1F7
-:10479000100C07D0DFF848C1614505D1534813E03C
-:1047A00000E007E052480FE0DFF838C161450BD068
-:1047B000814201D1184607E04E48414504D081426C
-:1047C00001D14D4800E00020B2420DD0D169030371
-:1047D0001AD090FAA0F0B0FA80F000BF00F01F03EA
-:1047E0000AFA03F00143D161D5F800C0BCF1000F13
-:1047F00028DA424B20684249DFF808A1984201D0EC
-:10480000B84203D10A4602E0800EE7E752469268BA
-:10481000984202F0E07201D0B84209D19D68D7F801
-:10482000088005F0010508F0010845EA080502E0E6
-:10483000B56805F0010555B1216E4FF0010941F051
-:1048400020002066002084F85C00484665E52E4D77
-:10485000AC451CD115021AD4B042F3D1984202D013
-:10486000B84200D051468B6842F4000023F0E07259
-:1048700002438A60264925480968B1FBF0F04000F0
-:10488000801C00E0401E00900028FBD1DAE7214D9B
-:10489000AC450CD1D5010AD4B042D3D1984202D054
-:1048A000B84200D051468B6842F080700EE01A4D3D
-:1048B000AC45C7D15502C5D4B042C3D1984202D04D
-:1048C000B84200D051468B6842F4800023F0E07279
-:1048D00002438A60B6E700000000844B0000B84F36
-:1048E0002000F0140004002A8000501D0002B025B2
-:1048F000000180210040C03A0080F03E00200240CC
-:104900000023024000630258000052C7400D03001C
-:1049100088000020000021C3000084CB2DE9F8436B
-:104920004FF0000504002E46009502D0206E18B10D
-:1049300008E00120BDE8F883204600F043F96566F1
-:1049400084F85C5020688168C1F3407119B18168B6
-:104950008E4A1140816020688168C1F3007181B97D
-:1049600081688B4A114041F0805181608A498948B1
-:104970000968B1FBF0F0401C00E0401E00900028E8
-:10498000FBD120688168C1F3007141B9216E012615
-:1049900041F010012166616E41F00101616606F08F
-:1049A000DBFE216EC90600D420B1206E012640F046
-:1049B0001000E0E0206E20F4807040F002002066DD
-:1049C00020688168754D11F0010F1ED1744B754A36
-:1049D000984201D0904207D19968976801F001018F
-:1049E00007F00107394302E0A96801F0010161B94C
-:1049F000984201D0904201D16B4800E06B48826838
-:104A0000616822F47C120A4382602168A9421FD1A6
-:104A1000637ED4E90207E26B5B033A43082805D0C2
-:104A20000C280FD01C280FD018280FD05FF00000E2
-:104A300000F00C0794F8200043EA47031A4342EAC7
-:104A400000400FE00420F3E70820F1E71C20EFE727
-:104A5000627E94F82030A768E06B520342EA03427A
-:104A60003843104394F82020012A04D1A28C504BE3
-:104A700003EB42421043A26A2AB1E36A02F478725D
-:104A8000024343EA0200CA68A9420BD1494B1A40CB
-:104A90000243CA602068626B016921F040611143E2
-:104AA000016103E0444B1A400243CA60206806F0EB
-:104AB00053FE0746206806F04BFE07434ED12068A0
-:104AC000A946484506D1217E94F83820890341EA59
-:104AD000420103E0227E216B41EA8231C26844F246
-:104AE00003039A430A43C26094F8440001282068F3
-:104AF00003D0016921F0010122E048450ED1D4E93B
-:104B0000121CD4E9143502692C4F41EA0C012B43E5
-:104B10003A401943114341F0010111E0D4E9131760
-:104B2000B4F848C0DFF89880636D026908EB0C4C5C
-:104B3000224D394343EA0C036D1E2A4019431143A9
-:104B400001612068236C026922F070421A430261FD
-:104B50002068484502D02046FDF72CFB206901283B
-:104B600020680BD0016B21F00F010163206E20F053
-:104B7000020040F0010020663046DBE6E269016B8E
-:104B8000521E21F00F011143EFE70000C0FFFF5F4D
-:104B9000C0FFFF7F400D0300880000200060025826
-:104BA000002002400021024000230240006302581E
-:104BB0000000FEFF0740F0FF03C0F0FF1FF800FCFD
-:104BC0000100FFFFF0B5B5B0064614212EA8FBF793
-:104BD00064FEB8216846FBF760FE314930688842C0
-:104BE0005BD1022000224FF400210091CDE9012089
-:104BF0001024154606AACDE90340C023059082E89B
-:104C0000290068460995289503F0B2FB08B1FFF723
-:104C100061F82448016841F020010160006800F05B
-:104C2000200033901F480830016841F00101016005
-:104C3000016801F001013391016841F00401016054
-:104C4000006803272EA9309500F00400339020203F
-:104C5000CDE92E07144801F0A1FD14482EA9CDE995
-:104C60002E47309501F09AFD114C092111484FF45F
-:104C7000807C021584E82300D700C4E90352C314E2
-:104C80002046C4E907C56562C4E9053700F07CFE2B
-:104C900008B1FFF71FF8B465A66335B0F0BD00009A
-:104CA00000200240D8440258000002580008025870
-:104CB0004C030020100002402DE9F84F044601F09B
-:104CC00085FE00903CB194F83500022806D0802182
-:104CD00061650020E4E00120BDE8F88FC74DC74EB4
-:104CE000C649183520683036DFF81483DFF814938E
-:104CF0008842DFF814A3DFF814B32ED0A8422CD0DA
-:104D0000B0422AD0404528D0484526D0504524D02E
-:104D1000584522D0BD4A183290421ED0BC4A90421B
-:104D20001BD0BB4A1832904217D0B94A3032904259
-:104D300013D0B74A483290420FD0B54A6032904201
-:104D40000BD0B34A7832904207D0B14A90329042A9
-:104D500003D0AF4AA832904209D1026822F01E0265
-:104D600002602068426922F08002426103E002682A
-:104D700022F00E02026027688F4238464DD0A842CA
-:104D80004BD0B04249D0404547D0484545D050452A
-:104D900043D0584541D09D4A183290423DD09C4A5C
-:104DA00090423AD09A4A1832904236D0984A3032DD
-:104DB000904232D0964A483290422ED0944A603285
-:104DC00090422AD0924A7832904226D0904A90322D
-:104DD000904222D08E4AA83290421ED08D4A9042F4
-:104DE0001BD08C4A1432904217D08A4A2832904203
-:104DF00013D0884A3C3290420FD0864A50329042BB
-:104E00000BD0844A6432904207D0824A7832904272
-:104E100003D0804A8C32974204D1206E026822F47B
-:104E20008072026075492068884228D0A84226D046
-:104E3000B04224D0404522D0484520D050451ED015
-:104E400058451CD071491831884218D070498842A1
-:104E500015D06F491831884211D06D4930318842E0
-:104E60000DD06B494831884209D069496031884288
-:104E700005D067497831884201D065499031016891
-:104E800021F0010101600EE001F0A0FD0099401A3F
-:104E9000052808D9202262650321002084F83510F6
-:104EA00084F8340017E73868C007EDD1534A012170
-:104EB000206890422ED0A8422CD0B0422AD0404543
-:104EC00028D0484526D0504524D0584522D04F4BB5
-:104ED000183398421ED04E4B98421BD04C4B18337F
-:104EE000984217D04A4B3033984213D0484B48333E
-:104EF00098420FD0464B603398420BD0444B7833E6
-:104F0000984207D0424B9033984203D0404BA8338D
-:104F1000984208D194F85C703F23A06D07F01F07FA
-:104F2000BB40836007E094F85C30A06D03F01F0382
-:104F300001FA03F34360206890424DD0A8424BD061
-:104F4000B04249D0404547D0484545D0504543D070
-:104F5000584541D02D4A183290423DD02C4A9042BB
-:104F60003AD02B4A1832904236D0294A30329042F9
-:104F700032D0274A483290422ED0254A60329042A1
-:104F80002AD0234A7832904226D0214A9032904249
-:104F900022D01F4AA83290421ED01E4A90421BD0F7
-:104FA0001C4A1432904217D01A4A2832904213D029
-:104FB000184A3C3290420FD0164A503290420BD0E1
-:104FC000144A6432904207D0124A7832904203D099
-:104FD000104A8C3290420BD1D4E919024260E06E43
-:104FE00030B1026822F480720260D4E91C0242608F
-:104FF000002084F8351084F834006DE6100002407B
-:10500000580002407000024088000240A0000240A8
-:1050100010040240085402582DE9F05F28B190F8BE
-:105020003510022904D0802141650120BDE8F09FA0
-:10503000904C904B0168183C18338E4ADFF83C9234
-:10504000A1428D4CDFF838E28E4FDFF83CB2DFF83A
-:105050003CA28F4D8F4E31D091422FD099422DD00E
-:10506000A1422BD0494529D0714527D0B94225D03E
-:10507000DFF810C20CF1180C61451FD0DFF808C230
-:10508000ACF1600C614519D0DFF8FCC1ACF1480C03
-:10509000614513D0DFF8F0C1ACF1300C61450DD0A3
-:1050A000DFF8E4C1ACF1180C614507D0594505D0D3
-:1050B000514503D0A94201D0B1422CD1DFF8B4C18F
-:1050C0004FF0040880F83580ACF1180C61451DD014
-:1050D00091421BD0994219D0A14217D0494515D011
-:1050E000714513D0B94211D06648183081420DD0B5
-:1050F00065486038814209D063484838814205D00C
-:1051000061483038814201D05F481838086820F083
-:1051100001000860ABE0D1F800C02CF00E08DFF809
-:1051200054C1C1F80080ACF1180C0168614527D06A
-:10513000914225D0994223D0A14221D049451FD088
-:1051400071451DD0B9421BD0DFF838C10CF1180CE5
-:10515000614515D0DFF830C1ACF1600C61450FD06E
-:10516000DFF824C1ACF1480C614509D0DFF818C163
-:10517000ACF1300C614503D0DFF80CC1ACF1180C78
-:10518000D1F800C02CF0010CC1F800C0DFF8E480B9
-:105190004FF0010C0168A8F11808414546D0914232
-:1051A00044D0994242D0A14240D049453ED07145B9
-:1051B0003CD0B9423AD0334A1832914236D0324AC2
-:1051C000603A914232D0304A483A91422ED02E4A2B
-:1051D000303A91422AD02C4A183A914226D0594569
-:1051E00024D0514522D0A94220D0B1421ED02A4A13
-:1051F00091421BD0284A1432914217D0264A2832B5
-:10520000914213D0244A3C3291420FD0224A50326C
-:1052100091420BD0204A6432914207D01E4A783224
-:10522000914203D01C4A8C32914218D1016E0A6817
-:1052300022F480720A6090F85C20816D02F01F02F7
-:105240000CFA02F24A60D0E919124A60C16E31B11B
-:105250000A6822F480720A60D0E91C124A600022B7
-:10526000016D80F835C080F8342001B188470020F6
-:10527000DCE60000280002405800024070000240B6
-:1052800088000240A00002407004024088040240EE
-:10529000A0040240B804024008540258406D704710
-:1052A0002DE9FC5F0446F74E0020DFF8D88300901C
-:1052B0004FF41652F44808F11808A56DDFF8C493AE
-:1052C000DFF8C0A3016809F1300920680AF1480A33
-:1052D000B1FBF2F1B04201912F68D5F800C0DFF8C0
-:1052E000ACB335D04146884232D0484530D05045E5
-:1052F0002ED058452CD0E5491831884228D0E349B2
-:105300003031884224D0E1494831884220D0E049F8
-:1053100088421DD0DE491831884219D0DC4930312D
-:10532000884215D0DA494831884211D0DFF860E36D
-:105330000EF1600E70450BD0D54A7832904207D0FE
-:10534000D34B9033984203D0D149A83188427DD1C4
-:1053500094F85C20082102F01F0201FA02F23A429E
-:105360004AD0B04232D0404530D048452ED050458A
-:105370002CD058452AD0C54A1832904226D0C34A6C
-:105380003032904222D0C14A483290421ED0C04AA8
-:1053900090421BD0BE4A1832904217D0BC4A3032DD
-:1053A000904213D0BA4A483290420FD0B84A603285
-:1053B00090420BD0B64A7832904207D0B44A90322D
-:1053C000904203D0B24AA832904203D1026802F060
-:1053D000040202E0026802F008026AB1026822F0E8
-:1053E0000402026094F85C0000F01F008140A96094
-:1053F000606D40F00100606594F85C00012100F0F0
-:105400001F008140394240D02068B04234D040452E
-:1054100032D0484530D050452ED058452CD09B4AEC
-:105420001832904228D0994A3032904224D0974A7C
-:105430004832904220D0964A90421DD0944A183269
-:10544000904219D0924A3032904200E0AFE113D03E
-:105450008F4A483290420FD08D4A603290420BD032
-:105460008B4A7832904207D0894A9032904203D0DA
-:10547000874AA83290427DD1406910F0800F04D055
-:10548000A960606D40F00200606594F85C00042142
-:1054900000F01F00814039423ED02068B04232D037
-:1054A000404530D048452ED050452CD058452AD0C4
-:1054B000764A1832904226D0744A3032904222D036
-:1054C000724A483290421ED0714A90421BD0704AB4
-:1054D0001832904217D06E4A3032904213D06C4A44
-:1054E000483290420FD06A4A603290420BD0684AEC
-:1054F0007832904207D0664A9032904203D0644A94
-:10550000A83290424ED1006810F0020F04D0A9607A
-:10551000606D40F00400606594F85C00102100F0BC
-:105520001F008140394258D02068B04234D04045F5
-:1055300032D0484530D050452ED058452CD0534A13
-:105540001832904228D0514A3032904224D04F4AEB
-:105550004832904220D04E4A90421DD04C4A1832D8
-:10556000904219D04A4A3032904215D0484A4832C7
-:10557000904200E014E00FD0454A603290420BD0D8
-:10558000434A7832904207D0414A9032904203D049
-:105590003F4AA832904207D1006800F0080006E0B8
-:1055A000006872E70068B7E7006800F00400A0B187
-:1055B000A96020680168490304D50068000308D584
-:1055C000A16C07E00168C90503D4016821F0080156
-:1055D0000160216C09B12046884794F85C002021C5
-:1055E00000F01F008140394279D02068B04232D0AB
-:1055F000404530D048452ED050452CD058452AD073
-:10560000224A1832904226D0204A3032904222D08C
-:105610001E4A483290421ED01D4A90421BD01C4A5E
-:105620001832904217D01A4A3032904213D0184A9A
-:10563000483290420FD0164A603290420BD0144A42
-:105640007832904207D0124A9032904203D0104AEA
-:10565000A832904203D1006800F0100002E0006818
-:1056600000F00200B0B3A96094F835000428206867
-:1056700001680FD049037ED5006800032BD4616C0C
-:105680002AE0000010000240880000207000024064
-:105690001004024021F0160101602068416921F0E8
-:1056A00080014161206C08B9A06C20B120680168BC
-:1056B00021F00801016094F85C303F21012003F0E3
-:1056C0001F0300229940A96084F8350084F8342033
-:1056D000216D65E003E0E16B09B120468847606D0C
-:1056E00000287DD0606DC00759D02068042184F85F
-:1056F0003510B0422BD0404529D0484527D05045E1
-:1057000025D0584523D09D49884220D09B49183147
-:1057100088421CD099493031884218D09849884233
-:1057200015D097491831884211D0954930318842B7
-:105730000DD093494831884209D09149603188425F
-:1057400005D08F497831884201D08D499031016868
-:1057500021F00101016020680099019A491C009123
-:10576000914202D80168C907F6D10068C00710D07D
-:1057700003200FE0FFE70168C905ACD403680121ED
-:10578000002223F01003036084F8351084F83420DD
-:10579000A1E7012084F83500002084F83400E16C92
-:1057A00000291DD002B02046BDE8F05F08477549CA
-:1057B00088421DD073491431884219D0714928316B
-:1057C000884215D06F493C31884211D06D49503123
-:1057D00088420DD06B496431884209D0694900E0A4
-:1057E00084E07831884203D066498C3188427DD18B
-:1057F00094F85C800427016808F01F0807FA08F78E
-:1058000017EA0C0F009746D04F0744D500980F04B5
-:10581000686003D5C8033CD4A16CC1E7880638D4BE
-:105820002068B0422DD055496039884229D048457A
-:1058300027D0504525D0584523D05049884220D004
-:105840004E49183188421CD04C493031884218D01A
-:105850004B49884215D04A491831884211D04849ED
-:10586000303188420DD046494831884209D07045D0
-:1058700007D0904205D0984203D04149A8318842D0
-:1058800003D1016821F0080102E0016821F0040160
-:105890000160216C84E7022707FA08F717EA0C0F6A
-:1058A00000974ED08F074CD500980F04686003D541
-:1058B000C80344D4616C73E7880640D42068B042C2
-:1058C0002FD02E49603988422BD0484529D05045E9
-:1058D00027D0584525D02949884222D02749183158
-:1058E00088421ED025493031884200E044E018D07B
-:1058F0002349884215D022491831884211D02049C5
-:10590000303188420DD01E494831884209D0704557
-:1059100007D0904205D0984203D01949A831884257
-:1059200003D1016821F0140102E0016821F00A01AD
-:105930000160012184F83510002084F83400E16B07
-:105940002EE7082202FA08F212EA0C0F14D0090717
-:1059500012D5016821F00E01016094F85C1001205D
-:10596000002201F01F0100FA01F16960606584F80E
-:10597000350084F8342012E7BDE8FC9F880002401F
-:1059800010040240085402582DE9F05F044601F06B
-:105990001DF8002C07467DD0E24E022120684FF012
-:1059A0000308DFF884934FF00005DFF880A3B042CE
-:1059B000DFF87CB334D0DB4A1832904230D048450F
-:1059C0002ED050452CD058452AD0D94A1832904272
-:1059D00026D0D74A3032904222D0D54A483290421F
-:1059E0001ED0D44A90421BD0D24A1832904217D0CF
-:1059F000D04A3032904213D0CE4A483290420FD033
-:105A0000CC4A603290420BD0CA4A7832904207D0DA
-:105A1000C84A9032904203D0C64AA83290427DD103
-:105A200084F83510B04284F834502ED0BD49183176
-:105A300088422AD0484528D0504526D0584524D001
-:105A4000BB491831884220D0B949303188421CD036
-:105A5000B7494831884218D0B649884215D0B5496F
-:105A60001831884211D0B349303188420DD0B14944
-:105A70004831884209D0AF496031884205D0AD49EC
-:105A80007831884201D0AB499031016821F00101A1
-:105A9000016008E025E100BF00F098FFC01B052869
-:105AA00001D920211AE120680068C007F4D1D4E9A7
-:105AB00002032168103418438E4694E88410D4E918
-:105AC000033809683A4310439B4A40EA0C0067696F
-:105AD00018431140103C40EA0800042F40EA01003E
-:105AE00003D1D4E90B12114308436168A1F12902E3
-:105AF000052A0BD9163A032A08D9083A012A05D9EA
-:105B0000083A032A02D97439032901D840F48010D5
-:105B1000CEF800002068676A406900E020E0042FAA
-:105B200020F0070047EA00070DD1D4E90A01074336
-:105B300049B12046FDF762FE28B140206065012191
-:105B400084F83510CDE0206847612046FDF774FDEC
-:105B500094F85C203F2102F01F029140816055E0E3
-:105B6000764A90421BD0754B1433984217D0734B32
-:105B70002833984213D0714B3C3398420FD06F4B6F
-:105B8000503398420BD06D4B6433984207D06B4B27
-:105B90007833984203D0694B8C3398427ED184F895
-:105BA000351084F83450664B0168A26801EA030E90
-:105BB000402A74D0802A73D05FF00002D4E90378C1
-:105BC000D4E9053142EAD70242EAD8085B4AD4E96F
-:105BD000077C48EAD30848EAD10141EAD70152429A
-:105BE00041EA1C11142341EA0E01016020681044AF
-:105BF000B0FBF3F08000E0652046FDF71DFD94F852
-:105C00005C20012102F01F02914041602068B042F7
-:105C100057D044491831884253D0484551D0504557
-:105C20004FD058454DD042491831884249D040495B
-:105C30003031884245D03E494831884241D03D49C3
-:105C400088423ED03B49183188423AD039493031F8
-:105C5000884236D037494831884232D035496031A0
-:105C600088422ED03349783188422AD03149903148
-:105C7000884226D02F49A831884222D02F49884215
-:105C80001FD02E49143188421BD02C49283188421C
-:105C900017D02A493C31884213D002E01DE017E0BA
-:105CA00018E02649503188420BD02449643188429B
-:105CB00007D022497831884203D020498C3188426C
-:105CC00029D12046FDF712FDA06880280CD00CE0F9
-:105CD000102273E74FF4804270E74021616584F839
-:105CE00035800120BDE8F09F6560216E2079086055
-:105CF000D4E9190141606068401E072808D8204691
-:105D0000FDF742FDE06E0560D4E91C01416002E050
-:105D1000E566256765670120656584F83500002024
-:105D2000E0E700001000024040000240580002403E
-:105D300070000240100402403F8010FE08540258D8
-:105D40000F00FEFF2DE9F84F04008C464FF00000D5
-:105D5000009014D094F83400012812D094F83550F3
-:105D60000120002184F83400012D0CD0C0026065B0
-:105D70000120009084F834100098BDE8F88F0120CD
-:105D8000FBE70220F9E78C4D0226206884F8356095
-:105D9000A8428A4D61658A4E8A4FDFF82C82DFF86F
-:105DA0002C92DFF82CA2DFF82CB226D0A84224D007
-:105DB000B04222D0B84220D040451ED048451CD029
-:105DC00050451AD0584518D08349884215D0824989
-:105DD0001831884211D08049303188420DD07E4937
-:105DE0004831884209D07C496031884205D07A49DF
-:105DF0007831884201D078499031016821F0010161
-:105E0000016061462046FDF723FD6B49206888420A
-:105E10002CD0A8422AD0B04228D0B84226D0404543
-:105E200024D0484522D0504520D058451ED06A4A3B
-:105E300090421BD0684A1832904217D0664A3032DE
-:105E4000904213D0644A483290420FD0624A603286
-:105E500090420BD0604A7832904207D05E4A90322E
-:105E6000904203D05C4AA83290420CD1026822F0E2
-:105E70001E0242F016020260206C88B1206802689F
-:105E800042F008020BE0026822F00E0242F00A0221
-:105E90000260206C20B12068026842F004020260B7
-:105EA000206888424BD0A84249D0B04247D0B8427F
-:105EB00045D0404543D0484541D050453FD0584556
-:105EC0003DD0454A90423AD0434A1832904236D0AB
-:105ED000414A3032904232D03F4A483290422ED02E
-:105EE0003D4A603290422AD03B4A7832904226D0D6
-:105EF000394A9032904222D0374AA83290421ED07E
-:105F0000364A90421BD0354A1432904217D0334A59
-:105F10002832904213D0314A3C3290420FD02F4A5F
-:105F2000503290420BD02D4A6432904207D02B4A17
-:105F30007832904203D0294A8C3290420DD1206EA3
-:105F40000268D20303D5026842F480720260E06EF8
-:105F500018B1026842F4807202602068884226D03C
-:105F6000A84224D0B04222D0B84220D040451ED012
-:105F700048451CD050451AD0584518D0164988427B
-:105F800015D015491831884211D013493031884253
-:105F90000DD011494831884209D00F4960318842FB
-:105FA00005D00D497831884201D00B499031016804
-:105FB00041F001010160DFE61000024028000240CC
-:105FC0004000024058000240700002408800024039
-:105FD000A0000240B80002401004024008540258D9
-:105FE00070B5044600F0F2FC0546601C02D004487F
-:105FF0000078044400F0EAFC401BA042FAD370BDD4
-:106000007C00002070477047704770472DE9FF5FA4
-:10601000DFF80CB304460BF10401DBF8000025683F
-:106020000F68AA468007D5F85090696DD5F8508062
-:106030006E6D2A6DD5F854C02B6D00EA8770009004
-:1060400009F470496F6D286D01EA09010191DAF8D0
-:106050005410DAF85490DAF8505008F00F0806EAB5
-:106060000806029602F0F00203F071536FEA090687
-:106070001F4000F060700CEA020CCDF80CC0F20575
-:1060800001EA00090CD4E843C00509D400214FF40B
-:106090008073CAF85030CBF800102046FFF7B5FFE8
-:1060A000700512D4E84340050FD4206800234FF454
-:1060B0008068D0F8DC20D0F8E410C0F85080CBF82D
-:1060C00000301140204600F042FBDFF858A2009853
-:1060D00050B12268830F00EA0A001065CBF8003047
-:1060E00020460099FFF78EFF019850B12268830F78
-:1060F00000EA0A001065CBF800302046019900F054
-:1061000028FB029850B12268830F00EA0A0010654C
-:10611000CBF800302046029900F011FB039850B1F3
-:106120002268830F00EA0A001065CBF80030204691
-:10613000039900F005FB30050CD4E843000509D4B1
-:10614000236800204FF400621A65CBF80000204657
-:1061500000F000FBB00512D4E84380050FD420689E
-:1061600000234FF40078D0F8D820D0F8E010C0F821
-:106170005080CBF800301140204600F0E9FA30039F
-:106180000CD4E843000309D4236800204FF4002214
-:106190001A65CBF80000204600F0D0FAF0030CD4CA
-:1061A000E843C00309D4236800204FF480321A6505
-:1061B000CBF80000204600F0C9FA70030CD4E84385
-:1061C000400309D4226800204FF480231365CBF8E4
-:1061D0000000204600F0B9FAB0030FD4E843800372
-:1061E0000CD4236800204FF400321A65CBF800006D
-:1061F000D4F89C0040F08000C4F89C00B9F1000F76
-:106200000BD022684FEA997309EA0A001065CBF8AF
-:10621000003049462046FFF7F7FE5FB12268BB0F0A
-:1062200007EA0A001065CBF80030D4F89C00384328
-:10623000C4F89C003C492068884268D16068814667
-:106240008068800763D0D9F82060D9F82410D9F885
-:106250002080D9F82400D9F820C0D9F82470D9F8C2
-:106260002030D9F82450D9F8202003F4FC4306F05C
-:106270000F0AD9F824601D40D9F824B008F030087E
-:106280000CF4C07C02F4F02211EA0A0100EA0808CA
-:1062900007EA0C0706EA0206D9F820A004D0C9F8DC
-:1062A0002010204600F04EFAB8F1000005D06168D9
-:1062B00008624146204600F047FA6FEA0B004006AC
-:1062C0000ED46FEA0A0040060AD460684021C36B0E
-:1062D000C26B01622046190C02F03F0200F033FA53
-:1062E0002FB1606807623946204600F02AFA35B1BE
-:1062F00060680562D4F89C002843C4F89C0036B15D
-:1063000060680662D4F89C003043C4F89C00D4F85E
-:106310009C00002802D02046FFF775FEBDE8FF9FD5
-:1063200010A80040FFFFCF3F00A000402DE9F04142
-:1063300094B08D494C2204466846FAF752FA64B18B
-:106340008A4D2068A84202D100F58070606094F800
-:1063500098004FF0000820B108E0012014B0BDE81B
-:10636000F081204684F8998000F002F92068816964
-:1063700021F01001816100F029FB0327064604E0AB
-:1063800000F024FB801B0A2811D8206880690007D0
-:10639000F6D42068816941F00101816100F016FBAB
-:1063A00006460DE000F012FB801B0A2808D9D4F83D
-:1063B0009C0040F00100C4F89C0084F89870CCE781
-:1063C00020688069C007EDD02068816941F0020132
-:1063D0008161207C01282068816937D041F040012B
-:1063E0008161607C01282068816932D021F480417C
-:1063F0008161A07C0128206881692DD041F4805101
-:1064000081612068A268816921F440711143816132
-:106410002068816921F0A40181612068016921F06F
-:1064200010010161E068012819D010B302281BD0C7
-:106430002068816941F0800181612068016941F033
-:1064400010010161E06803280ED012E021F0400144
-:10645000C6E741F48041CBE721F48051D0E72068C2
-:10646000816941F0040103E02068816941F0200165
-:106470008161207E6FF0FF02D4E90773A68A1102C2
-:10648000400602EB0727A0F10070384327685B1E27
-:10649000184301EB06463043F861A068B0F5407F31
-:1064A00011D104F12800A68C6FF00F0C89C801EB04
-:1064B0000641401E02EB0322104322680CEB071337
-:1064C00018430843D060206E30B12068626ED0F867
-:1064D000C0101143C0F8C010D4E917126846D14269
-:1064E00009D02168A36E51F8C82F50F8233022F04C
-:1064F00007021A430A60216C49B12168626C51F8A5
-:10650000BC3F50F8226023F0070232430A60A16CBE
-:1065100051B12168E36C51F8BC2F50F8233022F0C0
-:10652000700242EA03120A60216D51B12168626D66
-:1065300051F8BC3F50F8220023F4E06242EA002008
-:1065400008602068A84204D16068816821F00301D6
-:106550008160C4F894800121C4F89C8084F898106C
-:106560002046FDF7EBFBF9E65C2B010800A000409C
-:106570002DE9F047B4B0814614212EA8FAF78DF921
-:10658000B8216846FAF789F9664C0026D9F8000068
-:106590004FF08051644A0C3C614F4FF00208614D4E
-:1065A0009042DFF888A14FF0090938D100201B91F3
-:1065B0004A13CDE90020684601F0DAFE08B1FDF784
-:1065C00089FB3868401C3860012807D1286840F4EE
-:1065D00080702860286800F480703390206840F054
-:1065E00008002060206803222E922EA900F00800E7
-:1065F000CDE92F863196CDE93290504600F0CEF8A5
-:1066000000220521132000F08FFA132000F07FFAFA
-:1066100000220521152000F087FA15203BE0444AAE
-:1066200090423DD100201B914FF40042CDE9002063
-:10663000684601F09DFE08B1FDF74CFB3868401C30
-:106640003860012807D1286840F4807028602868E5
-:1066500000F480703390206840F0020020602068D1
-:1066600060222E922EA900F00200CDE92F863196ED
-:10667000CDE932902F4800F091F800220521142036
-:1066800000F052FA142000F042FA002205211620F0
-:1066900000F04AFA162000F03AFA34B0BDE8F0876C
-:1066A000254A9042F9D100201B914FF40042CDE9D8
-:1066B0000020684601F05CFE08B1FDF70BFB38686E
-:1066C000401C3860012807D1286840F48070286099
-:1066D000286800F480703390206840F00800206043
-:1066E00020684FF440512E91052200F00800CDE9BA
-:1066F0002F862EA93196CDE93220504600F04EF873
-:10670000002205219F2000F00FFA9F2000F0FFF9E2
-:1067100000220521A02000F007FAA020BBE700001E
-:1067200004000020EC44025800A00040000C025875
-:1067300000A400400004025800D400407047704795
-:106740007047704770477047704770477047704791
-:1067500070477047704700002DE9F041084F012550
-:106760000024064605FA04F0304203D057F824000E
-:1067700000B18047641CE4B2102CF3D3BDE8F08173
-:10678000089900204FF0B04110B5D1F8882002429E
-:1067900003D0C1F88800FFF7DFFF10BD2DE9F84FE7
-:1067A00003247A4D00234FF001094FF0B04B4FF016
-:1067B0000F0AE4E009FA03F6324078D00F7907F0C7
-:1067C0000307012F01D0022F1AD187684FEA430E29
-:1067D000D1F80CC004FA0EF827EA08070CFA0EFCF0
-:1067E0004CEA070CC0F808C0476891F804C0B743EA
-:1067F000CCF3001C0CFA03FC4CEA070CC0F804C0F4
-:106800000E79F643B6070BD0C6684FEA43088F6887
-:1068100004FA08FC26EA0C0607FA08F73743C760B3
-:106820000E7906F00306022E12D1DE080F694FEA38
-:10683000437C00EB8606B646366A4FEADC6C0AFA01
-:106840000CF807FA0CF726EA08063743CEF8207052
-:106850000F7906684FEA430807F0030704FA08FCBB
-:1068600007FA08F726EA0C06374307604E6816F465
-:10687000403F1CD0464E376847F002073760366805
-:106880009F0706F00206009623F0030606F1B046C5
-:10689000B6463F0FD6F80864DFF8F8800AFA07FC1E
-:1068A000404526EA0C0603D14FF0000C3AE065E0C3
-:1068B000DFF8E4C0604502D14FF0010C32E0DFF8B0
-:1068C000DCC0604502D14FF0020C2BE0DFF8D0C0F5
-:1068D000604502D14FF0030C24E0DFF8C8C06045EA
-:1068E00002D14FF0040C1DE0DFF8BCC0604502D1BE
-:1068F0004FF0050C16E0DFF8B4C0604502D14FF050
-:10690000060C0FE0DFF8A8C0604502D14FF0070C7D
-:1069100008E0DFF8A0C0604502D14FF0090C01E0AB
-:106920004FF00A0C0CFA07FC4CEA060CCEF808C42F
-:106930004F68DBF80060FF0226EA020600D5164326
-:106940005F46CBF80060D1F804C0DBF804605FEA72
-:106950008C2C26EA020600D516437E606E684F68CE
-:1069600026EA0206BF0300D516436E602E684F6804
-:1069700026EA0206FF0300D516432E605B1C0A6858
-:1069800032FA03F67FF416AFBDE8F88F80000058A6
-:10699000F44402580000025800040258000802584B
-:1069A000000C025800100258001402580018025837
-:1069B000001C0258002402580069084000D0012041
-:1069C00070470AB1816170470904FBE7014880689C
-:1069D000704700007C000020024881680278114462
-:1069E000816070477C000020032010B500F0BCF8E7
-:1069F00002F0FEFA0F4A104914681368C4F3032228
-:106A000003F00F038A5CC95C02F01F0201F01F0152
-:106A1000D0400A4A20FA01F11160094908600F20AC
-:106A200000F010F808B1012010BD00F04DF8002072
-:106A300010BD000018440258D02B01088C00002023
-:106A40008800002010B5102804468AB02AD20022FF
-:106A50000146A12000F068F8A12000F058F8154880
-:106A600004601548016841F080710160006808A960
-:106A700000F080700990684602F046FA02F0A6FA2B
-:106A80000E49400000220E4CB0FBF1F10D4840F2DF
-:106A9000E7330460C0E90332491EC0E9011203F084
-:106AA00069FD10B101200AB010BD064803F094FD45
-:106AB000F9E7000080000020EC44025840420F003B
-:106AC00000E00040780F0020074882B0016841F0E4
-:106AD00002010160006800220F2100F00200009016
-:106AE000901E02B000F020B8F444025800280DDBDC
-:106AF000410900F01F028900012001F1E0219040CE
-:106B0000C1F88001BFF34F8FBFF36F8F704700282C
-:106B100009DB410900F01F028900012001F1E02199
-:106B20009040C1F8000170470E4BF0B41B680D4651
-:106B3000C3F30223C3F10706042E00D90426191D4E
-:106B4000072901D2002300E0DB1E012404FA06F12C
-:106B50009C40491E2940641E994014402143F0BCCA
-:106B600008F04EBF0CED00E0064900F0070210B53A
-:106B70004FF6FF040868044B204040EA0220184307
-:106B8000086010BD0CED00E00000FA052DE9F04FA3
-:106B900002688346FF484FF0000A8DB00C468242DF
-:106BA000564602D10025012001E001250020E846DB
-:106BB0000027814607EB47017F1C08EBC101F8B2B3
-:106BC00005F0EEFB20B108204FF0010ACBF854008D
-:106BD000FFB2022FEED3BAF1000F7CD1DFF8B4E39D
-:106BE000DEF80000C00707D0DEF8001046F001060E
-:106BF00021F00101CEF80010E7480068C00706D078
-:106C0000E54846F00206016821F00101016005EB4C
-:106C100045030C93E148424608EBC303DFF880B319
-:106C20000121DC469F6800EB8707D7F8008428F431
-:106C30008078C7F80084DBF80070FF0732D0DCF8FA
-:106C40000070B9F1010F27F00107CCF800705CD19A
-:106C5000069B00EB8303D3F8007447F00207C3F8E8
-:106C60000074079B3BB100EB8303D3F8007447F03B
-:106C70002007C3F80074099B4BB121EA030700EB1E
-:106C80008703D3F8047447F48027C3F804740A9B7D
-:106C9000DBB321EA030700EB8703D3F8047447F062
-:106CA000806730E00C9F52F8377077B300EB8707AE
-:106CB000D7F800C42CF0010CC7F800C45F683FB1DE
-:106CC00000EB8707D7F800C42CF0100CC7F800C4FD
-:106CD000D3F80CC000E05AE1BCF1000F09D021EA62
-:106CE0000C0700EB8707D7F804C42CF4803CC7F8E6
-:106CF00004C41B694BB121EA030700EB8703D3F8F7
-:106D0000047427F08077C3F8047409EB4903D4F8BE
-:106D100000C0CDF830C0914652F83370BC451BD04E
-:106D200009EBC302D4F808C0D2F80880C44513D0D8
-:106D3000D4F804C0D2F80480C44502D1BCF1000FDD
-:106D40000AD1D4F80CC0D2F80C80C44504D0D4F8D1
-:106D500010C01269944551D10C9ABA4219D109EB6D
-:106D6000C302D4F804C0D2F80480C44511D1D4F8C9
-:106D70000CC0D2F80C80C4450BD1D4F810C01269F5
-:106D8000944506D1DBF8003043F00103CBF8003026
-:106D900034E000EB870709EBC302D7F8003423F097
-:106DA0000103C7F8003453683BB100EB8303D3F809
-:106DB000007427F01007C3F80074936800EB830396
-:106DC000D3F8007427F48077C3F80074D3684BB10C
-:106DD00021EA030700EB8703D3F8047427F4803714
-:106DE000C3F8047412694AB121EA020300EB83027A
-:106DF000D2F8043423F08073C2F80434A3685A46EE
-:106E000000EB8303D3F8007427F4407747EA452763
-:106E100047F48077C3F80074DBF800C063695F1E35
-:106E2000CCF3074C674508D95E4FD2F800C007EB9A
-:106E300003472CF47F033B4313601268D207226898
-:106E400000EB8202D2F800343FD023F003035B1C36
-:106E5000C2F8003462684AB100EB8202D2F8003412
-:106E600023F0300343F01003C2F80034E268D30388
-:106E70000AD521EA020300EB8302D2F8043423F49A
-:106E8000E02343F480330AE05AB121EA020300EB25
-:106E90008302D2F8043423F0E06343F08073C2F835
-:106EA00004342269D30307D5914300EB8100D0F865
-:106EB000041421F4E0214AE0F2B3914300EB810095
-:106EC000D0F8041421F0E0614EE001EB450723F017
-:106ED00003033B43C2F8003462685AB100EB8202FC
-:106EE000D2F8003423F0300343EA451343F0100393
-:106EF000C2F80034E268D3030CD521EA020300EBA8
-:106F00008302D2F8043423F4E02343EA854343F4B4
-:106F100080330CE06AB121EA020300EB8302D2F86D
-:106F2000043423F0E06343EA856343F08073C2F8DE
-:106F300004342269D30300E01AE00BD5914300EB3F
-:106F40008100D0F8041421F4E02141EA854141F4A4
-:106F500040310BE062B1914300EB8100D0F80414A2
-:106F600021F0E06141EA856141F04071C0F804140C
-:106F7000F00705D0DEF8001041F00101CEF8001056
-:106F8000B00704D50448016841F0010101600DB06B
-:106F9000504609E00050005200A0005200B00052DC
-:106FA00000B400520000FFFFBDE8F08FF8B50025E7
-:106FB0000446FFF70BFD064624B100206065206DF6
-:106FC00010B170E001256EE0204600F073F841F248
-:106FD0008830A065258A6FF0FF012268D4F814C0BC
-:106FE0000F02636B07EB0545E06801EB0C27D4F853
-:106FF0001CC0184393683D432D4F28433B4040EA53
-:107000000C00184390602068236AC26822F4E022D2
-:107010001A43C2602368228EA06B40EA02401861C6
-:107020002268E06B5061D4E90003026801EB03239E
-:1070300022F4F85119430160A06D0022202133464B
-:107040000090204605F01AFA05002CD12068626AEB
-:10705000C168521E21F0FF011143C1602068A2687F
-:10706000016821F04001114301602068D4E90A124F
-:10707000D0F80831114323F0A0421143C0F80811A1
-:107080002068016841F001010160A069022804D173
-:107090002068816841F002018160E068B0F1806F92
-:1070A00003D0022020652846F8BD0120FAE7000041
-:1070B000F4F8E0F82DE9F043B5B004461421684631
-:1070C000F9F7EBFBB82106A8F9F7E7FB4749206879
-:1070D00088427DD1002019904FF000710446CDE91F
-:1070E000061006A801F044F908B1FCF7F3FD40488A
-:1070F000016841F400110160016801F4001105917B
-:10710000016841F400210160006800F4002005904E
-:1071100037480C30016841F001010160016801F05D
-:1071200001010591016841F002010160016801F06F
-:1071300002010591016841F010010160016801F050
-:1071400010010591016841F0080101600068022505
-:107150000927009500F00800DFF8988003260396C1
-:107160006946CDE90470CDE901544046FFF716FBAE
-:10717000062102940820CDE90361CDE900056946A6
-:107180004046FFF70BFB0121DFF86C9002AA4FF09D
-:107190000408CDE900156946484682E85001FFF72A
-:1071A000FDFA02AA6946484682E8D000CDE900858A
-:1071B000FFF7F4FA0B2111484FF40068CDF8008076
-:1071C000CDE90361CDE901546946FFF7E7FA00E034
-:1071D00008E002AA0A48694682E8D000CDE90085A5
-:1071E000FFF7DCFA35B0BDE8F083000000A00052E4
-:1071F000D4440258000002580004025800100258FB
-:10720000000C025801680123C0F8D834002280F82D
-:10721000CC248869044A40F000608861486D1043BE
-:1072200048650020704700000300001070470068A8
-:10723000416200207047F0B503685D6A39B19F6A0A
-:107240004C1E00204FF4827605EB17450BE045EA13
-:107250000240986210E0471C06EB800053F800C023
-:10726000F8B205EB1C45A042F5D34FF4807000EB5B
-:10727000810045EA02421A500020F0BDD0F8E00437
-:1072800007F0DFBA01EBC10200EB8202D0F8E004A4
-:10729000126A07F032BA01EBC10200EB8202D0F8A9
-:1072A000E004D2F8602207F084BAD0F8E00407F0D6
-:1072B000CABA0A0601F00F0101EBC10100EB81011E
-:1072C00001D5143101E001F51571006808F0B8B975
-:1072D00001F00F020B0670B502EBC20104464FF03D
-:1072E00001004FF0000504EB810102D5487514310F
-:1072F00003E081F8555201F515710A7094F8942451
-:10730000012A08D084F89404206807F0B7FE002012
-:1073100084F8945470BD022070BD70B502790446A3
-:1073200001F00F00904201D9012070BD01F00F0261
-:107330004FF000050B0602EBC2014FF0010204EB17
-:10734000810102D54A75143103E081F8555201F5E7
-:1073500015718D70087094F89404012808D084F891
-:107360009424206807F0F4FF002084F8945470BD42
-:10737000022070BD01F00F0101EBC10100EB8100A3
-:10738000D0F8680270472DE9F04101F00F0604467D
-:107390000D064FF0010006EBC6014FF0000504EBAF
-:1073A000810102D54875143103E081F8555201F589
-:1073B0001571C2F30A024F780B718A600E7007B123
-:1073C0004E83022B00D14D7194F89424012A09D0E8
-:1073D00084F89404206807F099FD284684F89454B2
-:1073E000BDE8F0810220FBE770B501F00F05002435
-:1073F00005EBC50100EB810101F5187181E81C0066
-:1074000001F80B4C01F80C5D8379012B00D1CA61A6
-:107410008279006807F0F4FF002070BD70B50D465A
-:107420000179044605F00F00884201D9012070BDA2
-:1074300029064FF000064FF0010206D500EBC0010F
-:1074400004EB81014A75143107E005EBC50104EB3B
-:10745000810181F8556201F515718A70087094F800
-:107460009404012807D084F89424206807F09CFF36
-:10747000280702D007E0022070BDA17904F29C42E7
-:10748000206807F039FF002084F8946470BD70B55F
-:1074900001F00F04002504EBC401012600EB81017B
-:1074A000203181E82C0001F80B6C01F80C4D837938
-:1074B000012B00D1CA618279006807F0A1FF00208A
-:1074C00070BD00002DE9FC5F05680446284608F001
-:1074D00053F900287ED1206808F07AF9002879D085
-:1074E000D5F80808C0F30D20C4F8D404206808F0CB
-:1074F0006FF9800704D52068416901F002014161FC
-:10750000206808F065F9C10604F29C40009035D56A
-:107510002068816921F0100181612F6A07F00F0155
-:10752000C7F3434001EBC101022804EB810606F5D5
-:10753000157602D0062812D01BE047F6F0700742FD
-:1075400017D0C7F30A12F1681746284608F044F925
-:107550007169F068394471613844F06009E000995C
-:107560000822284608F038F97069C7F30A11084460
-:1075700070612068816941F010018161206808F024
-:1075800027F900034FF0080B4FF0000A4FF00109F4
-:107590007CD52068002608F0FAF8074674E0F80762
-:1075A00070D02068F1B208F00BF98046C00707D010
-:1075B00005EB4611C1F8089B3146204604F088FFD0
-:1075C0005FEA087024D505EB4611C1F808BBFA49FB
-:1075D000206800E03EE2026C00EB461001928A4215
-:1075E000D0F8081B05D9090403D54FF40041C0F8B1
-:1075F000081B204600F001FBEF490198884207D99B
-:10760000A079012804D120680121009A07F074FEB6
-:107610005FEAC86004D505EB46111020C1F8080BDD
-:107620005FEA88701DD56869000605D5D5F804089D
-:1076300040F48061C5F8041806EBC60004EB800036
-:1076400090F8571200F51570012905D180F803A0B4
-:107650002046F1B200F004FA05EB46110220C1F811
-:10766000080B5FEA886004D505EB46112020C1F8BD
-:10767000080B5FEA884005D505EB46114FF4005032
-:10768000C1F8080B7F08761C002F88D1206808F00D
-:107690009FF840036ED5206808F072F80026074670
-:1076A00066E0F80762D02068F1B208F077F880460B
-:1076B000C00723D0D5F8342806F00F0C05EB46138D
-:1076C00009FA0CF08243C5F83428C3F80899A07968
-:1076D00001280FD106EBC60004EB8000D0E907219A
-:1076E0001144016236B9606A20B920680121009A0C
-:1076F00007F002FE2046F1B2FFF7C4FD5FEA087012
-:1077000003D505EB4611C1F808B95FEAC86004D596
-:1077100005EB46111020C1F808095FEA486004D55E
-:1077200005EB46114020C1F808095FEA887016D5BC
-:107730003146284607F0F5FF06EBC60004EB800053
-:10774000C17D1430012905D180F803A02046F1B293
-:1077500000F082F905EB46110220C1F808095FEA42
-:10776000086003D53146204604F018FF7F08761CD8
-:10777000002F96D1206808F02BF8002811DAD5F8F0
-:10778000040820F00101C5F8041894F8CC0401287D
-:107790003BD0204600F016FA2068416901F0004114
-:1077A0004161206808F014F800050BD5D5F80808E9
-:1077B000C00702D0204600F049FA2068416901F470
-:1077C00000614161206808F003F800010AD52068D3
-:1077D000416901F00061416194F8CC04E0B12046B8
-:1077E00000F034FA206807F0F3FFC00472D5D5F832
-:1077F000040820F00100C5F804082068102107F0F3
-:1078000090FF00214FF67F322DE00021204684F8C2
-:10781000CCA4FFF70BFDBFE784F8CC942068406D43
-:107820000121C0F38300C4F8D0042046FFF7FEFC1A
-:10783000D8E700BF05EB4110C0F80829D0F800399F
-:1078400023F40013C0F80039C0F8082BD0F8003B2F
-:1078500023F40013C0F8003BD0F8003B43F0006372
-:10786000C0F8003B491C20798842E3D8D5F81C08B1
-:1078700040F00111C5F81C18E07B68B1D5F8840808
-:1078800040F00B01C5F88418D5F8440840F00B010E
-:107890002846C5F844180DE0D5F8140842F22B012B
-:1078A0000843C5F81408D5F8100840F00B01284625
-:1078B000C5F81018D0F8000820F4FE61C5F80018CB
-:1078C000A1792068009A07F017FD2068416901F44A
-:1078D00080514161206807F07BFF800416D5206845
-:1078E00007F054FB206807F03AFFE07101F03AFB23
-:1078F00023680146E279184607F0CEFF204600F0E3
-:107900004BF92068416901F400514161206807F09A
-:107910005FFF000707D5204600F058F9206841694D
-:1079200001F008014161206807F052FF000615D5FB
-:10793000A869012620F08001A9610CE006EBC600D1
-:1079400004EB800090F85702012803D12046F1B2E1
-:10795000FFF7AFFC761C2079B042EFD8206807F023
-:1079600037FFC0021FD501264F4614E006EBC600C4
-:1079700005EB461304EB8001D3F800090A7E012AC7
-:1079800008D1002806DAF0B2CF7540F08001204619
-:10799000FFF78FFC761C2079B042E7D82068416958
-:1079A00001F480114161206807F012FF800234D594
-:1079B00001204A4629E000000A30544F00EBC00382
-:1079C00005EB401604EB8301D6F8006B91F85832B2
-:1079D000012B19D1002E17DA94F8D434C6F30046DF
-:1079E00003F00103B3420FD181F85722A96941F096
-:1079F0008003AB616969090606D4D5F8040840F430
-:107A00000070C5F8040803E0401C21798142D5D8F4
-:107A10002068416901F400114161206807F0D8FE37
-:107A2000400007D52046FFF729FC2068416901F096
-:107A300080414161206807F0CBFE40070AD52068ED
-:107A40004568680702D52046FFF72FFC206841688B
-:107A500029434160BDE8FC9FD0F8E00406F04BBF2D
-:107A6000D0F8E00406F05BBFF8B5040004D094F849
-:107A70009504002510B106E00120F8BD204684F8E9
-:107A8000945400F057F8032084F89504206807F018
-:107A90002DFC207C8DF8000094E80F0007F084FA9C
-:107AA0000226B0BB2068002107F0B6FE88BB00208C
-:107AB00001270CE000EBC001421C04EB81014F7573
-:107AC0000D76CD610D624D620875C885D0B2217901
-:107AD0008142EFD8002011E000EBC001421C04EB12
-:107AE000810181F8555281F85852C1F85C52C1F8B1
-:107AF0006052C1F8645281F85402D0B221798142B7
-:107B0000EAD8207C8DF8000094E80F0007F038FBDD
-:107B100010B184F89564AFE7207B657484F89574A0
-:107B2000012802D12046FFF76DFB206807F01AFB01
-:107B30000020F8BD10B5B0B00446B8216846F8F78B
-:107B4000ACFE13492068884220D100204FF48021E8
-:107B50004FF440122192CDE90010684600F008FC75
-:107B600008B1FCF7B7F800F0B3F80A48016841F033
-:107B70000071016000680022052100F000702E9065
-:107B80004D20FEF7D1FF4D20FEF7C1FF30B010BDF4
-:107B900000000440D844025870B50446C07901255D
-:107BA00070B1022801D0FCF795F8D4F8E00429461A
-:107BB00006F024FFD4F8E004BDE8704006F0D8BE1B
-:107BC0000025F2E7D0F8E00406F001BFD0F8E004A9
-:107BD00006F007BF10B5044690F8940401280AD0B7
-:107BE0000120617484F89404206807F044FE0020AA
-:107BF00084F8940410BD022010BDD0F8E02400F2F7
-:107C00009C41104606F006BF10B590F89414044647
-:107C10000068012909D0012184F89414C16849063B
-:107C200009D5617B012902D005E0022010BD816BDE
-:107C300041F480318163206807F051FD206807F02E
-:107C400083FA002084F8940410BD000010B50446A7
-:107C5000D0F8E00406F020FF2068D0F8001E41F0C4
-:107C60000101C0F8001EE07A002804D00248016833
-:107C700041F00601016010BD10ED00E0134970B540
-:107C80000A68D243520705D5096801F0070181420D
-:107C900013D118E00A6822F0070202430A60FEF7D7
-:107CA00095FE0A4D4FF47A760446083D07E000BF82
-:107CB000FEF78CFE001BB04201D9012070BD286880
-:107CC000C0438004F4D4002070BD00000C4802586A
-:107CD0000248016841F08071016070470C48025809
-:107CE00010B501F03FF905490968054AC1F30211D1
-:107CF000515C01F01F01C84010BD00002044025833
-:107D0000D02B01084A4930B5494C0B1D0A680C3488
-:107D100009681D68246802F0030305F00102C1F33D
-:107D20000511C4F3CC04002914FB02F200EE102A62
-:107D3000F8EE400A76D0414A9FED3E1ADFED3E1A3A
-:107D4000B7EE000A23B1012B5AD0022B18D15CE008
-:107D5000374C283C23689B0612D5394B246801EE2A
-:107D6000901A1168C4F3C104F8EE612AE34001EEF1
-:107D7000903AC1F30801F8EE611A81EEA22A07E0F9
-:107D800002EE101A1168F8EE422A81EEA22A45E0AE
-:107D900001EE901A1168F8EE611A40EE811A71EE48
-:107DA000800A62EE200AC1F3462101EE101AB8EEF5
-:107DB000411A31EE001AC0EE811ABCEEE11A80EDD4
-:107DC000001A1168C1F3064101EE101AB8EE411A0B
-:107DD00031EE001AC0EE811ABCEEE11A80ED011AF4
-:107DE0001168C1F3066101EE101AB8EE411A31EEC6
-:107DF000000A80EE801ABCEEC10A80ED020A30BD96
-:107E000001EE901ADFED0F2A03E001EE901ADFED8C
-:107E10000E2A1168F8EE611A82EEA12AC1F3080158
-:107E2000B6E7FFE7002101604160816030BD0000DE
-:107E300028440258000000390024744C3044025891
-:107E40000090D0030024744A001BB74B494930B559
-:107E5000484C0B1D0A68143409681D68246802F038
-:107E60000303C5F30012C1F30531C4F3CC040029A8
-:107E700014FB02F200EE102AF8EE400A75D03F4AD9
-:107E80009FED3D1AB7EE000A6BB1DFED3D1A012BF5
-:107E900001D0022B64D002EE101A1168F8EE422ACB
-:107EA00081EEA22A21E0334C283C23689B0612D5A0
-:107EB000344B246801EE901A1168C4F3C104F8EE43
-:107EC000612AE34001EE903AC1F30801F8EE611A2D
-:107ED00081EEA22A0BE001EE901ADFED2B2A00BF03
-:107EE000F8EE611A116882EEA12AC1F3080101EED1
-:107EF000901A1168F8EE611A40EE811A71EE800A4C
-:107F000062EE200AC1F3462101EE101AB8EE411AC2
-:107F100031EE001AC0EE811ABCEEE11A80ED001AB3
-:107F20001168C1F3064101EE101AB8EE411A31EEA4
-:107F3000001AC0EE811ABCEEE11A80ED011A116838
-:107F4000C1F3066101EE101AB8EE411A31EE000AD3
-:107F500080EE801ABCEEC10A80ED020A30BD04E05A
-:107F600001EE901ADFED092ABAE7002101604160B5
-:107F70008160F3E728440258000000393844025871
-:107F80000024744A0090D0030024744C001BB74BAB
-:107F9000494930B5484C0B1D0A681C3409681D68F6
-:107FA000246802F00303C5F30022C1F30551C4F3B2
-:107FB000CC04002914FB02F200EE102AF8EE400A6D
-:107FC00075D03F4A9FED3D1AB7EE000A6BB1DFED69
-:107FD0003D1A012B01D0022B64D002EE101A116859
-:107FE000F8EE422A81EEA22A21E0334C283C236895
-:107FF0009B0612D5344B246801EE901A1168C4F325
-:10800000C104F8EE612AE34001EE903AC1F30801A1
-:10801000F8EE611A81EEA22A0BE001EE901ADFED74
-:108020002B2A00BFF8EE611A116882EEA12AC1F373
-:10803000080101EE901A1168F8EE611A40EE811AFB
-:1080400071EE800A62EE200AC1F3462101EE101A99
-:10805000B8EE411A31EE001AC0EE811ABCEEE11AF8
-:1080600080ED001A1168C1F3064101EE101AB8EE56
-:10807000411A31EE001AC0EE811ABCEEE11A80ED11
-:10808000011A1168C1F3066101EE101AB8EE411A27
-:1080900031EE000A80EE801ABCEEC10A80ED020AC1
-:1080A00030BD04E001EE901ADFED092ABAE70021A5
-:1080B000016041608160F3E7284402580000003904
-:1080C000404402580024744A0090D0030024744CA9
-:1080D000001BB74B2DE9F04FA14A0546DFF87CA203
-:1080E00080F48070DFF8809289B013119F4C0843B0
-:1080F0009C48AAF104064FF0805C4FF0005828D04D
-:10810000DFF858B285F480670F430BF1080B4FD0AE
-:1081100085F400670F4360D085F480570F4372D019
-:1081200085F400570F434FF480394FF4003E69D077
-:1081300085F400270F4373D085F480370F4370D048
-:1081400085F480460E436DD085F400420A436AD020
-:108150002AE0DAF8001001F00701052924D2DFE84F
-:1081600001F0F9AA6A259F0006A8FFF7CBFD079842
-:1081700009B0BDE8F08F6846FFF768FE0098F7E7A2
-:1081800003A8FFF705FF0398F2E72068C0F3C100DA
-:1081900022FA00F0ECE72268D2056ED561456CD179
-:1081A0001846E5E74145E3D00020E1E74846DFE730
-:1081B000DBF8001001F46001B1F5800F3BD005DC65
-:1081C00000294AD0B1F5001FEED174E0B1F5C00F1F
-:1081D000ECD0B1F5000FE7D162E0DBF8001001F060
-:1081E000E061B1F1007F26D004DCB1B3B1F1807F52
-:1081F000DAD160E0B1F1407FD8D0B1F1806FD3D156
-:108200004EE000E01BE0DAF8001001F4E041B1F5C7
-:10821000005F10D008DC01B3B1F5805FC4D14AE043
-:1082200035E058E065E088E0B1F5405FBED0B1F5DB
-:10823000804FB9D134E020688000B5D5A0E7DAF8E6
-:10824000001001F4E021B1F5403F6DD006DC61B1D2
-:1082500049457BD07145A7D158E07BE0B1F5802F2F
-:1082600066D0B1F5A02F9FD10DE000F09DFE7FE715
-:108270006846FFF7EBFD01987AE728E003A8FFF7CF
-:1082800087FE049874E7216889038AD48CE7DBF8B9
-:10829000001011F440310ED0494510D0714583D102
-:1082A0003168256801F040516D077FF574AF0029F2
-:1082B0007FF471AF69E720680001E7D55BE72068CC
-:1082C0008000E3D503A8FFF763FE059850E7226816
-:1082D0009203DBD566E7306810F480303AD0484529
-:1082E000D4D120680001D1D56846FFF7AFFD0298D0
-:1082F0003EE7DBF8001001F0E041B1F1405F13D040
-:1083000008DC71B1614521D04145BFD120688000B2
-:10831000B4D449E7B1F1804F0AD0B1F1A04FB2D047
-:1083200042E7FFF7DDFC23E720684007AED52CE7E6
-:108330002068C005AAD533E708E0DAF8001011F08C
-:108340004051A0D0614505D041459FD12068000132
-:108350008ED429E72068800198D505E7504402585B
-:108360000090D00300366E010080BB00004402582C
-:108370002DE9FE4F0546DFF800A450F8081B002445
-:10838000FD4FC943019005F1280026460AF1240A51
-:10839000009008011DD4686E50B1B0F5801F0CD05C
-:1083A000B0F5001F0ED0B0F5401F1ED001240FE025
-:1083B000386840F40030386017E00198022104F07A
-:1083C00095F903E00098022104F020FA04000CD093
-:1083D00026462888C043C00523D4A86D05281ED290
-:1083E000DFE800F00C11161B1B006A6EDAF80010B3
-:1083F00021F440111143CAF80010EAE7386840F44C
-:108400000030386009E00198002104F06FF903E0C2
-:108410000098002104F0FAF90446C4B100E00124F8
-:1084200026462888DFF85083C04308F12C08400511
-:108430002FD4D5F8A400B0F5C00F28D010DCB8B107
-:10844000B0F5001F19D0B0F5800F0FD11AE0AA6D5A
-:10845000DAF8001021F007011143CAF80010E0E734
-:10846000B0F5000F13D0B0F5200F10D001240FE0AD
-:10847000386840F40030386009E00198002104F0C9
-:1084800035F903E00098002104F0C0F9044694B1E6
-:1084900026462888C043000530D4D5F8A800B0F19E
-:1084A000407F29D011DCC0B1B0F1807F1AD0B0F18B
-:1084B000007F10D11BE0D5F8A420D8F8001021F4DB
-:1084C00060011143C8F80010E3E7B0F1806F13D0EA
-:1084D000B0F1A06F10D001240FE0386840F40030F4
-:1084E000386009E00198002104F000F903E00098E9
-:1084F000002104F08BF9044694B126462868DFF881
-:1085000078B2C0430BF1200B80011FD4E86CD8B1C6
-:1085100010280FD0202812D0302815D0012414E0C4
-:10852000D5F8A820D8F8001021F0E0611143C8F870
-:108530000010E3E7386840F40030386004E0019848
-:10854000022104F0D3F8044674B126462888C043BB
-:10855000C0042BD4E86DB0F5005F20D00DDCA0B1D5
-:10856000B0F5805F0FD115E0EA6CDBF8001021F068
-:1085700030011143CBF80010E8E7B0F5405F13D0AD
-:10858000B0F5804F10D001240FE0386840F400307F
-:10859000386009E00198002104F0A8F803E0009891
-:1085A000002104F033F904468CB126462888C043E4
-:1085B000800429D4286EB0F5403F23D010DC08B3E6
-:1085C000B0F5803F14D0B0F5003F0FD115E0EA6D53
-:1085D000DAF8001021F4E0411143CAF80010E5E791
-:1085E000B0F5802F0ED0B0F5A02F0BD001240AE0FB
-:1085F0000198012104F07AF803E00098012104F0C9
-:1086000005F9044694B126462888C04340042AD47C
-:10861000D5F8AC00B0F1405F23D010DC08B3B0F166
-:10862000805F14D0B0F1005F0FD115E02A6EDAF848
-:10863000001021F4E0211143CAF80010E4E7B0F182
-:10864000804F0ED0B0F1A04F0BD001240AE001986A
-:10865000012104F04BF803E00098012104F0D6F862
-:10866000044674B126462888C04300041FD4E86E2F
-:10867000D8B1B0F1805F0ED0B0F1005F10D001240E
-:1086800014E0D5F8AC20D8F8001021F0E0411143F7
-:10869000C8F80010E7E7386840F40030386004E0BC
-:1086A0000198012104F022F8044674B12646286896
-:1086B000C043C0011ED4A86CD0B101280ED002283E
-:1086C00011D0032814D0012413E0EA6EDAF8001068
-:1086D00021F040511143CAF80010E8E7386840F42F
-:1086E0000030386004E00198022103F0FFFF0446E7
-:1086F0006CB126462868C043400255D41F48016823
-:1087000041F480710160FEF761F981460EE0AA6CC8
-:10871000DBF8001021F003011143CBF80010E9E76A
-:10872000FEF754F9A0EB090064283BD81348006811
-:10873000C005F5D5BCBBDFF84090B5F8B01009F125
-:108740004409D9F8000001F4407100F440708842F7
-:1087500011D0D9F80010D9F8002021F4407142F46A
-:108760008032C9F80020D9F8002022F48032C9F8FC
-:108770000020C9F8001003E02C44025800480258B9
-:10878000D5F8B000B0F5807F19D1FEF71FF902903F
-:1087900011E000BFFEF71AF90299411A41F2883040
-:1087A000814208D9032426462878DFF81494C04370
-:1087B000C00721D03CE0D9F800008007EAD5D5F801
-:1087C000B010C1F301200328FE480DD0016821F448
-:1087D0007C510160B5F8B020D9F80010C2F30B024B
-:1087E0001143C9F80010DFE7F74A036802EA1112E3
-:1087F00023F47C511143ECE7A86F182816D005DC50
-:10880000A0B1082808D0102804D10AE020280DD0F3
-:1088100028280BD001240AE00198012103F066FF0B
-:1088200003E00098012103F0F1FF044664B12646FD
-:108830002878C04380071ED4686F062819D2DFE865
-:1088400000F0160C11161616AA6FD9F8001021F0B8
-:1088500038011143C9F80010EAE70198012103F03B
-:1088600045FF03E00098012103F0D0FF04467CB1EE
-:1088700000E0012426462878C04340071FD4D5F8DD
-:108880009000062819D2DFE800F0160C1116161613
-:108890006A6FD9F8001021F007011143C9F80010E0
-:1088A000E9E70198012103F021FF03E0009801218D
-:1088B00003F0ACFF0446A4B100E00124264628786A
-:1088C000C04380062BD4D5F88C00B0F1405F24D093
-:1088D00011DC10B3B0F1805F15D0B0F1005F10D1A2
-:1088E00016E0D5F89020D8F8001021F007011143C8
-:1088F000C8F80010E3E7B0F1804F0ED0B0F1A04F00
-:108900000BD001240AE00198002103F0EFFE03E000
-:108910000098022103F07AFF044694B12646287895
-:10892000C04340062BD4D5F89800B0F5406F24D052
-:1089300011DC10B3B0F5806F15D0B0F5006F10D119
-:1089400016E0D5F88C20D9F8001021F0E041114351
-:10895000C9F80010E3E7B0F5805F0ED0B0F5A05F76
-:108960000BD001240AE00198002103F0BFFE03E0D0
-:108970000098022103F04AFF044694B12646287865
-:10898000C04300062BD4D5F89C00B0F5C04F24D0CE
-:1089900011DC10B3B0F5005F15D0B0F5804F10D1E9
-:1089A00016E0D5F89820D8F8001021F4E0511143D2
-:1089B000C8F80010E3E7B0F5004F0ED0B0F5204F37
-:1089C0000BD001240AE00198002103F08FFE03E0A0
-:1089D0000098022103F01AFF044654B12646287875
-:1089E000C04300071ED4D5F88000B0F5805F0AD0E0
-:1089F0000FE0D5F89C20D8F8001021F46041114315
-:108A0000C8F80010EBE70098022103F0FFFE00B168
-:108A10000126D5F88020D9F8001021F440511143E7
-:108A2000C9F800102878C043C00613D4D5F89400C4
-:108A3000B0F5807F05D10098022103F0E7FE00B178
-:108A40000126D5F89420D8F8001021F44071114384
-:108A5000C8F800102868C043000316D4D5F8A00059
-:108A600038B1B0F5803F09D0B0F5003F0BD00124FC
-:108A70000AE00198002103F039FE03E0009802218A
-:108A800003F0C4FE04468CB126462868C043400368
-:108A900022D4D5F88400B0F5801F11D0B0F5001FA6
-:108AA00013D0B0F5401F15D0012414E0D5F8A02054
-:108AB000D8F8001021F440311143C8F80010E4E761
-:108AC000386840F40030386004E00098012103F079
-:108AD0009DFE04465CB126462868C043C0031CD4F2
-:108AE000286D70B1B0F5803F10D0012414E0D5F8A6
-:108AF0008420D9F8001021F440111143C9F8001066
-:108B0000EAE7386840F40030386004E00198022158
-:108B100003F0ECFD0446DCB126462868C043800023
-:108B200005D40098022103F071FE00B101262868E7
-:108B3000C04380031BD4E86FB8B1B0F5807F10D07C
-:108B4000B0F5007F11D0B0F5407F0ED001240DE0CC
-:108B50002A6DDBF8001021F480311143CBF80010AE
-:108B6000DBE7386840F4003038607CB3264628687C
-:108B7000C043C00207D42A6FDAF8001021F0004188
-:108B80001143CAF800102868C043800207D4AA6EB7
-:108B9000DAF8001021F080711143CAF8001028683B
-:108BA000C043400009D40748016821F40041016036
-:108BB0000168D5F8B420114301602868C04306E07D
-:108BC0005444025810440258CFFFFF001DE007D460
-:108BD0006A6DDBF8001021F040511143CBF8001012
-:108BE0002868C043000208D4D5F88820D9F80010BE
-:108BF00021F440011143C9F8001028790024C04332
-:108C000000F00100204309D00EE0EA6FD9F800100F
-:108C100021F440711143C9F80010A8E70198002120
-:108C200003F064FD00B106462879C04300F002005D
-:108C3000204305D10198012103F058FD00B10646FB
-:108C40002879C04300F00400204305D10198022197
-:108C500003F04CFD00B106462879C04300F008003F
-:108C6000204305D10098002103F0D0FD00B1064655
-:108C70002879C04300F01000204305D1009801215D
-:108C800003F0C4FD00B106462879C04300F020007F
-:108C9000044304D10098022103F0B8FD00B916B1D5
-:108CA0000120BDE8FE8F0020FBE700002DE9F05F0A
-:108CB00004000F467ED0DFF83882D8F8000000F0BC
-:108CC0000F00B8420CD2D8F8001021F00F01394340
-:108CD000C8F80010D8F8000000F00F00B84269D1C1
-:108CE0002078844D40070AD52069296801F0700179
-:108CF000884204D9296821F0700101432960207855
-:108D00007C4E361D00070AD56069316801F070019C
-:108D1000884204D9316821F0700101433160207824
-:108D2000C0060AD5A069316801F4E061884204D91F
-:108D3000316821F4E061014331602078DFF8B4B19B
-:108D400080060BF1080B0CD5E1695846DBF80020D2
-:108D500002F07002914204D9026822F070020A43C4
-:108D60000260207880070AD5E068296801F00F01C9
-:108D7000884204D9296821F00F0101432960207835
-:108D8000C0073ED05B49A2682868183920F470609B
-:108D9000104328606068022818D0032819D0096899
-:108DA000012819D0490700294ADADFF848A1AAF1B9
-:108DB000080A00E044E0DAF8002022F0070202434B
-:108DC000CAF80020FDF702FE814612E00968890317
-:108DD000E9E709688901E6E7C905E4E7FDF7F6FD7B
-:108DE000A0EB090141F28830814202D90320BDE89D
-:108DF000F09F6168DAF8000000F03800B0EBC10FB6
-:108E0000ECD1207880070AD5E068296801F00F01CD
-:108E1000884204D2296821F00F0101432960D8F863
-:108E20000010404601F00F01B9420BD9016821F052
-:108E30000F0139430160006800F00F00B84201D013
-:108E40000120D4E7207840070AD52069296801F07D
-:108E50007001884204D2296821F070010143296021
-:108E6000207800070AD56069316801F070018842F6
-:108E700004D2316821F07001014331602078C006CE
-:108E80000AD5A069316801F4E061884204D23168F2
-:108E900021F4E06101433160207880060CD5E1695E
-:108EA0005846DBF8002002F07002914204D20268BA
-:108EB00022F070020A43026000F09AF80E492A6814
-:108EC0002B68C2F3032203F00F038A5CC95C02F033
-:108ED0001F0201F01F01D040084A20FA01F1116081
-:108EE0000749086007480068BDE8F05FFDF7AABDC4
-:108EF0000020005218440258D02B01088C0000209A
-:108F0000880000208000002070B5144C3F220260D1
-:108F1000124A24680832131D114D04F007044460FE
-:108F200016681C1D06F470668660166806F00F064B
-:108F3000C660126802F0700202611A6802F07002E4
-:108F400042611A6802F4E0628261226802F07002F3
-:108F5000C261286800F00F00086070BD104402581C
-:108F60000020005230B500F043F80B4A0B490C4B7F
-:108F700015681468C5F3032204F00F048A5C095DC8
-:108F800002F01F0201F01F01D040064A20FA01F151
-:108F900019601060084630BD18440258D02B0108F3
-:108FA0008C0000208800002000B5FFF7DBFF05499A
-:108FB0000968054AC1F30211515C01F01F01C84064
-:108FC00000BD00001C440258D02B010800B5FFF77B
-:108FD000C9FF05490968054AC1F30221515C01F046
-:108FE0001F01C84000BD00001C440258D02B0108DE
-:108FF000454970B545480968434B103B11F03802AC
-:1090000008D00111082A03D0102A0BD0182A0BD03F
-:10901000084670BD19688906FBD51968C1F3C101FE
-:10902000C84070BD3A4870BD3749374D18310C1DE6
-:1090300024350A68096826682D6802F0030406F0E2
-:109040000102C1F30511C5F3CC0515FB02F200EED8
-:10905000102AB8EE400AE9B32F4ADFED2E0AB7EE28
-:10906000001A6CB1DFED2D1A012C01D0022C43D077
-:1090700002EE101A1068F8EE422A81EEA22A1EE0D3
-:109080001C68A40611D51B6801EE901A1168C3F381
-:10909000C103F8EE612AD84001EE900AC1F308003E
-:1090A000F8EE611A81EEA22A0BE001EE901ADFEDD4
-:1090B0001C2A00BFF8EE611A106882EEA12AC0F3E4
-:1090C000080001EE900AF8EE611A40EE201A31EE27
-:1090D000810A00E015E022EE000A1068C0F3462085
-:1090E000401C00EE900AF8EE600A80EE201ABCEEFA
-:1090F000C10A10EE100A70BD01EE901ADFED092AC8
-:10910000D8E7002070BD0000104402580090D00342
-:1091100000366E0100000039304402580024744AC1
-:109120000024744C001BB74BF0B50D461F49204C72
-:10913000002887B016464FF000004FF002020F687B
-:109140004FF0030319D047F004070F60096801F0DE
-:109150000401059111020091CDE90120CDE9033010
-:1091600014486946FDF71AFB206845EAC61120F04D
-:109170007E400843206007B0F0BD47F001070F6054
-:10918000096801F0010105914FF480710091CDE96A
-:109190000120CDE9033008486946FDF7FFFA206851
-:1091A000354320F0FE702843E4E70000E044025815
-:1091B0001044025800080258000002582DE9F05FE0
-:1091C00004007DD0FF4F2078FE4D1837DFF8F48380
-:1091D000103DC00748D0D8F80000396800F03800CA
-:1091E000102815D0182803D101F0030002280FD051
-:1091F0006068B0F5803F12D010B1B0F5A02F18D044
-:10920000286820F480302860286820F4802009E055
-:109210002868800328D560680028D2D024E0286818
-:1092200040F480302860606888B1FDF7CFFB0646C7
-:1092300009E0286840F480202860F0E7FDF7C6FBCD
-:10924000801B64287ED828688003F7D50CE0FDF7E2
-:10925000BDFB064605E000BFFDF7B8FB801B642898
-:10926000F0D828688003F7D42078800756D5D8F83E
-:109270000000DFF85093396810F03800A9F10C09AC
-:109280000ED0182801D188070AD0E068A8B3296851
-:1092900021F0190101432960FDF798FB064628E0FB
-:1092A0002868400702D5E06800288AD0E16828686D
-:1092B00020F0190008432860FDF788FB064606E009
-:1092C000D2E000BFFDF782FB801B0228BAD82868D5
-:1092D0004007F7D5217CD9F8002022F0FE4242EA6F
-:1092E0000161C9F8001019E0FDF770FB801B02282E
-:1092F000A8D828684007F7D5ECE7FFE7286820F0F2
-:1093000001002860FDF762FB064604E0FDF75EFB06
-:10931000801B022896D828684007F7D42078C0061A
-:1093200046D5D8F80000DFF89C92396800F0380084
-:10933000A9F10409082812D0182805D101F003006A
-:10934000012800E0CEE00AD0E0690028286820D09B
-:1093500040F080002860FDF739FB064615E02868DC
-:10936000C00502D5E06980287ED194F82010D9F894
-:10937000002022F07C5242EA0161C9F8001017E097
-:10938000FDF724FB801B0228A0D82868C005F7D56C
-:10939000EBE720F080002860FDF718FB064604E0AC
-:1093A000FDF714FB801B022890D82868C005F7D46D
-:1093B0002078000729D583486169643000298146F7
-:1093C000016811D041F001010160FDF7FFFA064686
-:1093D00005E000BFFDF7FAFA801B022888D8D9F80B
-:1093E00000008007F6D510E021F001010160FDF7D3
-:1093F000EDFA064605E000BFFDF7E8FA801B0228FB
-:1094000070D8D9F800008007F6D42078800623D5DC
-:10941000A0690028286810D040F480502860FDF72B
-:10942000D5FA064605E000BFFDF7D0FA801B0228FA
-:1094300058D828688004F7D50EE020F480502860C2
-:10944000FDF7C4FA064604E0FDF7C0FA801B0228C7
-:1094500048D828688004F7D42078400751D5DFF831
-:109460006891D9F8001000E015E141F48071C9F865
-:109470000010FDF7ABFA064605E000BFFDF7A6FABF
-:10948000801B64282ED8D9F80000C005F6D54D4EB3
-:10949000A068603601280AD008B1052813D03068CA
-:1094A00020F001003060306820F0040002E03068F5
-:1094B00040F001003060A06841F2883A98B1FDF7B1
-:1094C00085FA81460AE0306840F004003060EEE73B
-:1094D000FDF77CFAA0EB0901514503D830688007FD
-:1094E000F6D50EE072E0FDF771FA814606E000BFA6
-:1094F000FDF76CFAA0EB0901514567D83068800789
-:10950000F6D4606A00287CD0DFF8B8A0D8F8001044
-:109510000AF1200A4FF6F87B0AF10408C1F3C201F0
-:109520000329AAF104096DD00228286820F0807070
-:10953000286003D0FDF74AFA044681E0FDF746FAB9
-:10954000064604E0FDF742FA801B022875D8286819
-:109550008001F7D4E26A40F2F331386854F8283FCA
-:10956000884340EA021018433860217B4FF4FE0C18
-:1095700022894FF0FE47208A4902267D521E401E56
-:10958000A1F5007189B2C2F308021143761E0CEAFC
-:1095900000400143484607EA06621143CAF800103A
-:1095A000D9F8001021F00101C9F80010D8F80030F6
-:1095B000266A23EA0B0343EAC601C8F80010D9F86B
-:1095C000001004E0104402580048025835E0A26937
-:1095D00021F00C011143C9F800100168E26921F083
-:1095E000020111430160016841F4803101600168AA
-:1095F00041F400310160016841F48021016001689B
-:1096000001E06CE020E041F001010160286840F0D9
-:1096100080702860FDF7DAF9044604E0FDF7D6F91A
-:10962000001B022809D828688001F7D557E000BF41
-:10963000FDF7CCF9001B022802D90320BDE8F09FFA
-:1096400028688001F4D44AE039680128DAF800007B
-:1096500021D0A26A01F0030393421CD1E26AC1F354
-:1096600005118A4217D1216BC0F30802491E8A42B4
-:1096700011D1616BC0F34622491E91420BD1A16BFF
-:10968000C0F30642491E914205D1E16BC0F306606A
-:10969000491E814201D00120D0E7A16C4646D8F88E
-:1096A0000000C0F3CC00814219D0D9F800004D462B
-:1096B00020F00100C9F80000FDF788F94FEA000723
-:1096C000FDF784F9B842FBD0A26C306820EA0B00A9
-:1096D00040EAC2003060286840F0010028600020A5
-:1096E000ACE700002DE9F04104001D4616460F4688
-:1096F00003D0D4F8880018B108E00120BDE8F0815B
-:10970000002084F88400204601F056FC2420C4F890
-:1097100088002068016821F001010160A06A10B191
-:10972000204603F06DFF204604F006F90128E5D03D
-:10973000206871050D4A41EA0541836843F480437E
-:1097400083602068836823F400433B438360206880
-:10975000036813400B4303602068016841F0010176
-:1097600001602046BDE8F04103F0AEBFFFFF00FC02
-:1097700070B5044603F07AF9022811D0204603F0B0
-:1097800075F9084D05EB40108069002808D0204687
-:1097900003F06CF905EB40108069BDE870400047AC
-:1097A00070BD0000489900202DE9F047044600688C
-:1097B000002103694269876894F8816000F13009EB
-:1097C0005FEA025C03EA02050AD51A0708D5816937
-:1097D00041F400618161204600F0C4FCBDE8F087DF
-:1097E00015F0600F08D1680706D5616F20468847DD
-:1097F000216F20468847012105F04100012805D14D
-:10980000680703D4216F20468847012105F0220014
-:10981000022806D1680704D4616F2046BDE8F047EE
-:1098200008470029DAD128074FF001085BD52068E6
-:10983000816941F0080181612068816941F010016E
-:1098400081612068816941F400618161206801695A
-:1098500021F0080101612068806810F4404F20D099
-:1098600023E0E0680F2806D92068616E006B08606D
-:10987000606E001D0FE0072806D9B9F80000616E80
-:109880000880606E801C06E02068616E90F83000F1
-:109890000870606E401C6066B4F86A00401EA4F850
-:1098A0006A00B4F86A000028DBD1204603F044F8CF
-:1098B00084F88180D4F8840018B12046FFF758FF5F
-:1098C0008CE7052E07D0042E09D0032E86D1204622
-:1098D00000F06AFD82E7204600F078FD7EE7204632
-:1098E00000F008FC7AE715F4587FE9D068060AD53D
-:1098F000D4F8840040F00400C4F884002068816932
-:1099000041F040018161A8050AD5D4F8840040F0F7
-:109910000100C4F884002068816941F4007181610C
-:10992000E8050AD5D4F8840040F00800C4F88400A3
-:109930002068816941F480718161A8060AD5D4F854
-:10994000840040F08000C4F884002068816941F000
-:1099500020018161D4F884000028B1D0206840F251
-:109960006B32C7F381310368032923F001010160E1
-:109970002068016921EA0201016102D084F8818036
-:109980009BE72068104D816821F440418160E06FC1
-:1099900050B10565E06FFBF73FFB28B1D4F88400B8
-:1099A00040F04000C4F88400A06F002888D005650E
-:1099B000A06FFBF731FB00288CD0D4F8840040F076
-:1099C0004000C4F8840009E7F5C900082DE9F04714
-:1099D000040029D0594A4FF000092068584B594DCE
-:1099E0009042C4F8289006D0984204D0A84202D0F1
-:1099F000E1680F2918D8E1684FF0010AE76B0831D8
-:109A0000C9080AEB57167143904205D0984203D01B
-:109A1000A84201D0082907D8904203D0984201D02B
-:109A2000A84204D1102902D90120BDE8F08794F89A
-:109A3000810020B9204684F8809000F085F802204B
-:109A400084F881002068016821F00101016020682C
-:109A5000A1698268B1F1806F02F4F81110D16268D7
-:109A6000B2F5800F01D01AB10AE0A26B22B107E073
-:109A7000A26BB2F1805F03D1026842F480520260AF
-:109A80006068400209D5E068072806D32068236D86
-:109A9000026822F480721A4303E02068026822F40C
-:109AA00080720260A66AE069E26B25683043E36871
-:109AB0000A4310431843A860D4E90D02D4E9058194
-:109AC000636A25691843D4F820C00A432668104306
-:109AD0002843A56DD4E90172D4E9123140EA0800A7
-:109AE00040EA0C0038430843104318432843F06011
-:109AF000606868B92068816821F4C05141F4006150
-:109B000081602068816821F4C06141F480618160D6
-:109B10002068016D21F0010101656068400206D5F1
-:109B20002068626DC16821F000411143C160C4F832
-:109B3000849084F881A0002077E700000030014085
-:109B400000380040003C00402DE9F047B4B0074623
-:109B500014212EA8F6F7A1FEB8216846F6F79DFE5F
-:109B600060490225386800245C4E4FF00308DFF896
-:109B700070A188424FF005093DD18114179400204F
-:109B8000CDE900106846FEF7F3FB08B1FAF7A2F83A
-:109B900052481030016841F480510160006800F4BF
-:109BA00080503390306840F008003060306800F03A
-:109BB00008003390306840F002003060306830AA0E
-:109BC00046464F4600F0020033908020CDE92E0536
-:109BD00082E8D00044482EA9FCF7E0FD082030AA16
-:109BE000CDE92E052EA9504682E8D000FCF7D6FD1F
-:109BF00034B0BDE8F0873D498842F9D1811417940B
-:109C00000020CDE900106846FEF7B2FB08B1FAF774
-:109C100061F832480830016841F480410160006811
-:109C200000F480403390306840F0040030603068C9
-:109C300000F004003390306840F00200306030687B
-:109C400006214646C84600F00200CDE92E15CDE9B2
-:109C50003046CDE9329026482EA9FCF79FFD4FF4FF
-:109C60000051504630AACDE92E152EA982E85001A8
-:109C7000FCF794FD1F4E27221F494FF480683046A1
-:109C800086E81600C6E903487461B461F461346281
-:109C90007462FBF779FE08B1FAF71CF8154D28221B
-:109CA000154940237835FE671831B763284685E8A3
-:109CB0001E016C61AC61EC612C626C62FBF764FEAE
-:109CC00008B1FAF707F8BD6700220521AF63242029
-:109CD000FCF72AFF2420FCF71AFF89E7E04402582A
-:109CE0000004025800300140000C025800380040C7
-:109CF0000008025810070020400002402DE9F84FEC
-:109D00008946C16B044600689A4616464909491CB3
-:109D10001FFA81F830300090FCF758FE834694F823
-:109D20008100012838D1B9F1000F6FD0002EFCD08E
-:109D300094F8800001282FD0A1680025012784F81D
-:109D40008070042084F88100C4F88450C4F86490C2
-:109D5000E565A4F86050256765672C34B1F5C02F20
-:109D6000A687E687E58654F82C0D18D0C16821F443
-:109D7000C02141F48021C160206841686FF30F0168
-:109D8000314341602068016841F001010160606871
-:109D9000B0F5800F08D00CE00220BDE8F88F016814
-:109DA00021F400610160E7E72068016841F4007177
-:109DB0000160E0680F2824D829E0206841694269E1
-:109DC000D20705D1B4F86A3043450DD209040BD54A
-:109DD000006B616E0860606E001D6066B4F86A001A
-:109DE000401EA4F86A000CE0FCF7F0FDA0EB0B01AC
-:109DF000514503D3BAF1FF3F03D0AAE0BAF1000FF7
-:109E000040D0B4F86A000028D7D194E09FE007283A
-:109E10003CD88CE0216848694969C9070AD0009894
-:109E20000088616E0880606E801C6066B4F86A000D
-:109E3000401E15E0B4F86A20424514D2010412D540
-:109E400000980088616E0880606E801C60660099D2
-:109E500009880180606E801C6066B4F86A00801E0C
-:109E6000A4F86A0012E0B4F86A10012901D1800454
-:109E7000D5D4FCF7ABFDA0EB0B01514503D3BAF1F0
-:109E8000FF3F03D065E0BAF1000F62D0B4F86A007A
-:109E90000028BFD14FE0206841694269D2070AD04B
-:109EA00090F83000616E0870606E401C6066B4F817
-:109EB0006A00401E24E0B4F86A30434523D20A0405
-:109EC00021D590F83000616E0870606E401C6066AD
-:109ED000216891F830100170606E401C6066216846
-:109EE00091F830100170606E401C6066216891F836
-:109EF00030100170606E401C6066B4F86A00001F8C
-:109F0000A4F86A0013E0B4F86A20042A02D211F41B
-:109F1000C04FC5D1FCF75AFDA0EB0B01514503D34F
-:109F2000BAF1FF3F03D014E0BAF1000F11D0B4F83A
-:109F30006A000028AFD1204602F0FEFC84F8817050
-:109F4000D4F8840084F8805000283FF426AF012024
-:109F500023E7204602F0F0FCD4F8840084F8805017
-:109F600040F48070C4F8840084F88170032014E702
-:109F70002DE9F041044690F881001646002501289D
-:109F800002D084F880502FE059B356B394F8800083
-:109F9000012829D0A268012784F88070042084F861
-:109FA0008100C4F88450256765676166A4F8605035
-:109FB0002C34B2F5C02FA687E687E58654F82C0D21
-:109FC00015D0C16821F4C02141F48021C0F80C10E3
-:109FD000E0684FF480410F280ED9E26F92698A42FF
-:109FE0000AD084F8805055E00220BDE8F081016875
-:109FF00021F400610160EBE707284FF4005205D916
-:10A00000E06F8069904201D08842EAD1206883687D
-:10A0100023F480438360E068072811D8E06F8369E8
-:10A02000934205D1B4F86A20521C5208A4F86A2061
-:10A030008069884210D1B4F86A00C01C800809E029
-:10A040000F2809D8E06F8069884205D1B4F86A000A
-:10A05000401C4008A4F86A00E06F23490164E16FE6
-:10A060002248C863E16F2248C864E06F0565B4F810
-:10A070006A302168626EE06F3031FBF763FE58B1E1
-:10A08000D4F8840084F8805040F01000C4F88400B4
-:10A0900084F881700120A8E7E06FC069B0F5807F87
-:10A0A000206841686FF30F0100D0314341602068A0
-:10A0B000816841F4804181602068016941F45071F8
-:10A0C00001612068016841F0010101606068B0F53C
-:10A0D000800F04D12068016841F400710160002004
-:10A0E00084F8805081E700003BCA000845CA000898
-:10A0F0000FCA000870B5044602F0B8FC022811D05F
-:10A10000204602F0B3FC084D05EB401040680028E3
-:10A1100008D0204602F0AAFC05EB40104068BDE8DC
-:10A120007040004770BD00004899002070B504469B
-:10A1300002F09CFC022811D0204602F097FC084D4A
-:10A1400005EB40100069002808D0204602F08EFC84
-:10A1500005EB40100069BDE87040004770BD00008D
-:10A160004899002070472DE9F84F04460068994649
-:10A17000174600F1200B8A46FCF728FC064694F8A7
-:10A180008100012839D1BAF1000F7ED0002FFCD018
-:10A1900094F88000012830D0A26800254FF0010813
-:10A1A00084F88080032184F88110C4F88450C4F8B6
-:10A1B0005CA06566A4F86850656725672C34B2F525
-:10A1C000C02FA786E786E58754F82C0D18D0C16804
-:10A1D00021F4C02141F40031C160206841686FF36F
-:10A1E0000F01394341602068016841F001010160BD
-:10A1F0006068B0F5800F08D00CE00220BDE8F88F51
-:10A20000016841F400610160E7E72068016841F4FA
-:10A2100000710160E0680F281CD820E020684169C7
-:10A2200089070BD5E16D09680162E06D001DE065ED
-:10A23000B4F86200401EA4F862000BE0FCF7C6FB15
-:10A24000811B494503D3B9F1FF3F03D09DE0B9F12C
-:10A25000000F32D0B4F862000028DFD179E007287F
-:10A260002FD872E02068416989071ED5B4F86210C2
-:10A2700001290DD9E16B59B1E16D09680162E06D09
-:10A28000001DE065B4F8620000E07CE0801E09E09B
-:10A29000E06D0188ABF80010E06D801CE065B4F85B
-:10A2A0006200401EA4F862000BE0FCF78FFB811BEC
-:10A2B000494503D3B9F1FF3F03D066E0B9F1000F80
-:10A2C00063D0B4F862000028CCD142E02068416934
-:10A2D00089072ED5B4F8621003290CD9E16B402907
-:10A2E00009D9E16D09680162E06D001DE065B4F80F
-:10A2F0006200001F1AE0B4F8621001290CD9E16B6A
-:10A3000051B1E06D0188ABF80010E06D801CE06594
-:10A31000B4F86200801E09E0E16D097880F8201031
-:10A32000E06D401CE065B4F86200401EA4F86200D5
-:10A330000BE0FCF74BFB811B494503D3B9F1FF3F11
-:10A3400003D022E0B9F1000F1FD0B4F8620000285A
-:10A35000BCD100224B4608212046009602F090FB1B
-:10A3600028B1D4F8840040F02000C4F884002046CE
-:10A3700002F0E2FA84F88180D4F8840084F88050F6
-:10A3800000283FF43BAF012038E7204602F0D4FA22
-:10A39000D4F8841084F8805041F48071C4F884109B
-:10A3A00084F88180032029E710B502F05FFB0228C2
-:10A3B00008D0054901EB40100068002802D0BDE834
-:10A3C0001040004710BD00004899002070B50446B9
-:10A3D00002F04CFB022811D0204602F047FB084D4A
-:10A3E00005EB40108068002808D0204602F03EFBB4
-:10A3F00005EB40108068BDE87040004770BD00006C
-:10A4000048990020024A136883430B431360704746
-:10A41000040400587047704770470000F0B590F88A
-:10A420003C20012A43D0012280F83C20D1E902429D
-:10A43000204ECD6922F440722243D1E9004322F438
-:10A4400080621A4322F400622243D1E9043422F4E8
-:10A4500080521A430B6B22F4005222430C8B22F4DD
-:10A4600080421A43036822F4702242EA0442002424
-:10A4700022F08052B34242EA050202D00E4DAB42B6
-:10A4800010D10F8D22F4700CD1E90862CD6A4CEA2C
-:10A49000075121F08071314321F00071114321F007
-:10A4A00000522A435A6480F83C400020F0BD02204C
-:10A4B000F0BD00000000014000040140F0B590F83C
-:10A4C0003C20012A41D0224E012480F83C40022247
-:10A4D00080F83D2002681F4D5368B242D2F808C090
-:10A4E00001D0AA4203D14F6823F470033B430F68A5
-:10A4F00023F070031F4357600268B24219D0B2F1D3
-:10A50000804F16D0144B9A4213D0144B9A4210D05D
-:10A51000134B9A420DD0AA420BD0124B9A4208D04C
-:10A52000114B9A4205D0114B9A4202D0104B9A42DD
-:10A5300004D189682CF0800319439160002180F8D0
-:10A540003D4080F83C100846F0BD0220F0BD000000
-:10A5500000000140000401400004004000080040E9
-:10A56000000C0040001800400040014000E00040A6
-:10A5700000E4004010B5040003D094F83D0010B191
-:10A5800007E0012010BD002084F83C00204600F0C8
-:10A5900022F8022084F83D002068211D02F074FB9F
-:10A5A000012084F8480084F83E0084F83F0084F8D5
-:10A5B000400084F8410084F8420084F8430084F8A5
-:10A5C000440084F8450084F8460084F8470084F885
-:10A5D0003D00002010BD704790F83D10012901D0CA
-:10A5E000012070471A4A022180F83D100168CB68AB
-:10A5F00043F00103CB60006890421AD0B0F1804F65
-:10A6000017D01449884214D01349884211D01349F5
-:10A6100088420ED0124988420BD01249884208D095
-:10A620001149884205D01149884202D01049884218
-:10A6300007D181680F4A1140062906D0B1F5803F45
-:10A6400003D0016841F00101016000207047000063
-:10A65000000001400004004000080040000C0040E1
-:10A6600000040140001800400040014000E00040AC
-:10A6700000E400400700010070472DE9F041044666
-:10A6800000680027C6680569A90713D5B10711D569
-:10A69000FA1E026101212177206880698007204627
-:10A6A00002D0FFF7E9FF04E000F0F8F8204600F0E0
-:10A6B000EDF92777680716D5700714D522680220B0
-:10A6C0006FF00401116120772068806910F4407FE9
-:10A6D000204602D0FFF7D0FF04E000F0DFF820466C
-:10A6E00000F0D4F92777280715D5300713D522684D
-:10A6F00004206FF00801116120772068C06980078D
-:10A70000204602D0FFF7B8FF04E000F0C7F820466B
-:10A7100000F0BCF92777E80616D5F00614D52268B4
-:10A7200008206FF01001116120772068C06910F4D3
-:10A73000407F204602D0FFF79FFF04E000F0AEF814
-:10A74000204600F0A3F92777E80708D0F00706D0E5
-:10A7500021686FF001000861204600F099F9280691
-:10A7600001D4A80408D5300606D521686FF402503C
-:10A7700008612046FFF74FFEE80508D5300606D5EC
-:10A7800021686FF4807008612046FFF743FE680679
-:10A7900008D5700606D521686FF040000861204694
-:10A7A00000F080F9A8060AD5B00608D521686FF038
-:10A7B000200008612046BDE8F041FFF72DBEBDE84E
-:10A7C000F081000030B587B0044614216846F6F7E2
-:10A7D00064F8246800222B4D022329490120AC4251
-:10A7E00011D10C6844F010040C60096801F01001EC
-:10A7F00005914FF408510091CDE90132CDE90320D4
-:10A800002148694625E0B4F1804F12D01F4D204801
-:10A81000AC4222D10C6844F002040C600968009339
-:10A8200001F00201CDE901320392CDE9043169461C
-:10A830000FE00C6844F001040C60096801F00101AC
-:10A84000059105210091CDE90132CDE903201148A0
-:10A850006946FBF7A3FF07B030BD0F4DAC42FAD1FC
-:10A860000C6844F002040C60096801F002010591D3
-:10A87000E9130091CDE90132CDE903236946E8E708
-:10A88000E04402580000014000100258000400405B
-:10A89000000402580000025800180040704770B5CC
-:10A8A000044690F83C0000260D4601280BD00120FC
-:10A8B00084F83C000C2A4AD007DC82B1042A20D05C
-:10A8C000082A06D131E0022070BD102A53D0142A84
-:10A8D00063D00126002084F83C00304670BD20681B
-:10A8E00002F042FA2068816941F008018161206824
-:10A8F000816921F00401816120682A69816911431D
-:10A9000011E0206802F082FA2068816941F4006158
-:10A9100081612068816921F48061816120682969F1
-:10A92000826942EA01218161D4E7206802F0BAFA23
-:10A930002068C16941F00801C1612068C16921F046
-:10A940000401C16120682A69C169114311E02068CE
-:10A9500002F0F4FA2068C16941F40061C161206825
-:10A96000C16921F48061C16120682969C26942EA34
-:10A970000121C161AEE7206802F01CFB2068416D37
-:10A9800041F0080141652068416D21F004014165F5
-:10A9900020682A69416D114311E0206802F044FBF0
-:10A9A0002068416D41F4006141652068416D21F4EA
-:10A9B0008061416520682969426D42EA0121416553
-:10A9C00088E710B5040003D094F83D0010B107E00B
-:10A9D000012010BD002084F83C00204600F022F841
-:10A9E000022084F83D002068211D02F04DF901206D
-:10A9F00084F8480084F83E0084F83F0084F8400062
-:10AA000084F8410084F8420084F8430084F844004C
-:10AA100084F8450084F8460084F8470084F83D0037
-:10AA2000002010BD08B501681348814201D11348C8
-:10AA30000FE01348B1F1804F0BD0124A914210D170
-:10AA4000016841F002010160006800F0020000901E
-:10AA500008BD016841F001010160006800F00100DB
-:10AA6000F5E7094A9142F3D1016841F040010160E4
-:10AA7000006800F04000EAE700000140F04402589E
-:10AA8000E8440258000400400018004070470000ED
-:10AA900000680349884201D1FBF79EBF7047000060
-:10AAA00000E00040704730B590F88410012918D0BC
-:10AAB000012280F884202421C0F88810002220245C
-:10AAC00001680B680D6823F0005325F001050D6047
-:10AAD000426601680B60C0F8884080F88420104608
-:10AAE00030BD022030BD7047704770B5044690F805
-:10AAF000840001281DD0012284F884202420C4F879
-:10AB0000880020680568026822F00102026020685F
-:10AB1000826822F060620A438260204602F04EFDA5
-:10AB20002268202100201560C4F8881084F8840071
-:10AB300070BD022070BD70B5044690F884000128F5
-:10AB40001DD0012284F884202420C4F888002068C5
-:10AB50000568026822F0010202602068826822F023
-:10AB600060420A438260204602F028FD22682021CC
-:10AB700000201560C4F8881084F8840070BD02209D
-:10AB800070BD70477047000010B502F0B5FE052893
-:10AB90000AD000EBC001054800EB810000690028E5
-:10ABA00002D0BDE81040004710BD0000789800209A
-:10ABB0002DE9F04107680025044640F60F03022600
-:10ABC000F8693968BA6818420AD183067ED501F05F
-:10ABD000200302F0805C53EA0C0377D0616F7EE1C2
-:10ABE000D44BDFF854C3134001EA0C0C53EA0C0CAD
-:10ABF0006CD05FEAC07C0CD05FEAC15C09D54FF035
-:10AC0000010CC7F820C0D4F8907047F00107C4F8D1
-:10AC10009070870709D5D70707D027683E62D4F818
-:10AC2000906046F00406C4F8906046070AD5D6073F
-:10AC300008D0276804263E62D4F8906046F00206E9
-:10AC4000C4F8906006070CD501F020061E4308D01A
-:10AC5000266808233362D4F8903043F00803C4F820
-:10AC6000903003050BD54B0109D526684FF40063DE
-:10AC70003362D4F8903043F02003C4F89030D4F815
-:10AC80009030002B3DD0800609D501F0200002F065
-:10AC90008051084303D0616F09B12046884721687D
-:10ACA000D4F890008968490602D410F0280F2AD001
-:10ACB000204602F0DFFD2068806840061ED520682F
-:10ACC000083050E8001F21F0400100E021E040E89A
-:10ACD0000012002AF3D1D4F8800078B197490165B9
-:10ACE000D4F88000FAF798F900280AD0D4F8800048
-:10ACF000016D00E02046BDE8F04108472046FFF71F
-:10AD000043FFBDE8F0812046FFF73EFFC4F89050B6
-:10AD1000F7E7D4F86CC02023BCF1010F7ED15FEAC5
-:10AD2000C06C7BD55FEAC16C78D510203862206892
-:10AD30008068400673D5D4F8802081491068884225
-:10AD400034D07F491831884230D07D493031884233
-:10AD50002CD07B494831884228D0794960318842DB
-:10AD600024D077497831884220D075499031884283
-:10AD70001CD07349A831884218D07249884215D036
-:10AD800070491831884211D06E49303188420DD057
-:10AD90006C494831884209D06A496031884205D0FF
-:10ADA00068497831884201D06649903140684FF453
-:10ADB00080770004000C40D0B4F85C1081423CD98C
-:10ADC000A4F85E00D069B8422FD0216851E8000F86
-:10ADD00020F4807041E80002002AF6D12068083093
-:10ADE00050E8001F21F0010140E80012002AF5D1CF
-:10ADF0002068083050E8001F21F0400140E80012B0
-:10AE0000002AF5D1C4F88C30E566206850E8001FB0
-:10AE100021F0100140E80012002A01E04AE019E0A8
-:10AE2000F3D1D4F88000F9F747FF2667B4F85C0047
-:10AE3000B4F85E10401A81B208E0B4F85C108142A8
-:10AE40007FF466AFD069B842FAD126672046FFF793
-:10AE50004AFE56E7B4F85C00B4F85E10B4F85E2021
-:10AE6000401A81B2002AF4D00029F2D0226852E8B8
-:10AE7000000F20F4907042E80007002FF6D1324F07
-:10AE8000206800F1080050E8002F02EA070240E8BD
-:10AE9000002CBCF1000FF3D1C4F88C30E566656777
-:10AEA000226852E8000F20F0100042E80003002B57
-:10AEB000F6D1CAE7C60209D5560207D54FF480106D
-:10AEC00038622046BDE8F041FFF75CBE06060AD5B1
-:10AED00001F0800602F40002164304D0A16F00299D
-:10AEE0007FF408AF0DE7420611D54A060FD520467C
-:10AEF000016851E8002F22F0400241E80024002CB4
-:10AF0000F6D1C0F88830856700F09AFBF9E60202B6
-:10AF100006D54A0004D52046BDE8F041FFF731BE12
-:10AF2000C00196D5002994DA2046BDE8F041FFF72C
-:10AF3000DBBD0000010000102001000473D70008F1
-:10AF40001000024010040240FEFFFFEF10B50400A5
-:10AF500003D0D4F8880010B107E0012010BD002014
-:10AF600084F88400204600F027F82420C4F88800E4
-:10AF70002068016821F001010160A06A10B120463B
-:10AF800002F03EFB204602F0D7FC0128E6D0206804
-:10AF9000416821F4904141602068816821F02A01D4
-:10AFA00081602068016841F0010101602046BDE830
-:10AFB000104002F089BB00002DE9F04FB5B0044607
-:10AFC00014212EA8F5F769FCB8216846F5F765FC51
-:10AFD000FE4D0226FE494FF480692068083DFB4F74
-:10AFE0004FF00008884256D10020CDF8748002222C
-:10AFF000CDE900206846FDF7BBF908B1F8F76AFE15
-:10B00000386840F480103860386800F4801033905D
-:10B01000286840F004002860286800F0040033909D
-:10B02000286840F008002860286808252EA94746AF
-:10B0300000F008003390680281E8C100E548CDE9DE
-:10B040003185FBF7ABFB2EA9042081E8C100E24863
-:10B05000CDE93175FBF7A2FBE04D4122E0492846DE
-:10B0600029604FF44031C5E90127C5E903796F61D3
-:10B07000AF61C5E907716F62FAF786FC08B1F8F7AE
-:10B0800029FEC4F8805000220521AC633520FBF76F
-:10B090004BFD352032E0D3494FF0070A884232D1C8
-:10B0A0000020CDF874800221CDE900106846FDF73C
-:10B0B0005FF908B1F8F70EFE386840F0804038605C
-:10B0C000386800F080403390286840F01000286015
-:10B0D00028682EAA4FF4C07100F0100082E84201E7
-:10B0E000CDE932A0C0482EA9CDF8C480FBF756FBAD
-:10B0F000002205215220FBF717FD5220FBF707FD28
-:10B1000035B0BDE8F08FB949884230D10020CDF884
-:10B1100078800121CDE900106846FDF729F908B1D2
-:10B12000F8F7D8FDA9480830016841F01001016026
-:10B13000006800F010003390286840F0010028609B
-:10B1400028682EAA4FF4C06100F0010082E8420195
-:10B15000CDE932A0A6482EA9CDF8C480FBF71EFB8E
-:10B16000002205212520FBF7DFFC2520C6E7A149A9
-:10B170004FF0400B88425DD1002168460222CDF895
-:10B180007480CDE90021FDF7F3F808B1F8F7A2FDCE
-:10B19000386840F400303860386800F4003033908C
-:10B1A000286840F008002860286870212E912EA998
-:10B1B00000F008004546CDE92F68CDF8C480CDE900
-:10B1C00032A08548FBF7EAFA844F2B23844A4FF4D8
-:10B1D000003878377832384687E82C00C7E90359B9
-:10B1E0007D61BD61C7E907587D62FAF7CDFB08B103
-:10B1F000F8F770FD794E2C23C4F88070F036BC63EC
-:10B20000774A3046C6E9035975619032B561C6E99F
-:10B210000758756286E80C08FAF7B6FB08B1F8F72C
-:10B2200059FDE66700220521B4632620FBF77CFC6C
-:10B23000262063E77049884271D1002168460222C6
-:10B24000CDF87480CDE90021FDF792F808B1F8F748
-:10B2500041FD386840F480203860386800F4802070
-:10B260003390286840F002002860286800F002004F
-:10B270003390286840F00800286028682EA94546C9
-:10B28000574600F0080033904FF480402E90CDE9EF
-:10B290002F685A48CDE9318AFBF780FA4FF44070A5
-:10B2A0002E90CDE92F654C482EA9CDE93157FBF7FB
-:10B2B00075FA534F2D234A4A4FF400383846483226
-:10B2C00087E82C00C7E903597D61BD61C7E90758CC
-:10B2D0007D62FAF759FB08B1F8F7FCFC484E2E23C3
-:10B2E000C4F880707836BC633D4A3046C6E90359DD
-:10B2F00075616032B561C6E90758756286E80C0869
-:10B30000FAF742FB08B1F8F7E5FCE66700220521F1
-:10B31000B4632720FBF708FC2720EFE6FFE7394955
-:10B3200088427FF4EDAE0020CDF878800121CDE990
-:10B3300000106846FDF71CF808B1F8F7CBFC23486D
-:10B340000830016841F080010160006800F0800071
-:10B350003390286840F01000286028682EA9224DFC
-:10B3600000F010003390042081E84101CDE93180E4
-:10B370002846FBF713FA2EAA08200B2182E8410188
-:10B38000CDE931812EA92846FBF708FA1C4D772319
-:10B390001D4AF0352846C5E90389C5F81480C5F86B
-:10B3A0001880C5F81C80C5F82080C5F8248085E881
-:10B3B0000C08FAF7E9FA08B1F8F78CFCE567002207
-:10B3C0000521AC639C20FBF7AFFB1FE0E84402586B
-:10B3D0000050004000080258000C0258A80C002041
-:10B3E0002800024000780040001002580010014080
-:10B3F0000000025800440040004800400004025889
-:10B40000100E0020001C0140100402409C2075E634
-:10B410002DE9F84F0446D0F88C009B4616460D46A1
-:10B42000202802D00220BDE8F88FC5B1BEB10027A8
-:10B43000C4F890702220C4F88C00E7662034FBF733
-:10B44000C5FA824654F8180CA6874FF48053E68755
-:10B45000FF21203C984207D1226912B119E0012056
-:10B46000E1E740F2FF1114E04FF07F0278B1B0F154
-:10B47000805F11D0A4F860709842B4F860704FF00B
-:10B48000200801D1206970B12E4600250CE0266904
-:10B4900036B9A4F86010EFE7216909B13F21F8E758
-:10B4A000A4F86020E8E7002607F0FF09B4F85E0082
-:10B4B000F0B10022534620212046CDF800B002F022
-:10B4C0007DFC18B1C4F88C800320ACE72068406A8A
-:10B4D00056B100EA090006F8010B00BFB4F85E009F
-:10B4E000401EA4F85E00E1E7384025F8020BF5E7BE
-:10B4F000C4F88C80002096E730B4D0F88C30202B34
-:10B5000002D0022030BC7047A9B1A2B10B4D00247B
-:10B510000368C466AB420BD05B681B0208D50468A5
-:10B5200054E8003F43F0806344E80035002DF6D135
-:10B5300030BC02F0EFBB0120E4E70000000C005833
-:10B5400010B502F0D9F905280AD000EBC001054872
-:10B5500000EB8100C068002802D0BDE81040004721
-:10B5600010BD00007898002010B502F0C5F905283C
-:10B570000AD000EBC001054800EB8100806800287C
-:10B5800002D0BDE81040004710BD000078980020B0
-:10B590002DE9F8430446D0F88800984616460D4633
-:10B5A000202802D00220BDE8F883A5B19EB1002179
-:10B5B000C4F890102120C4F888001834FBF706FA6C
-:10B5C000814654F8100CA687E6872027183CB0F572
-:10B5D000805F02D003E00120E5E7206910B12E462C
-:10B5E000002510E000260EE08021204602F0E6FB58
-:10B5F000C0B9DEB116F8010B21688862B4F85600B4
-:10B60000401EA4F85600B4F856004B464FF0000216
-:10B61000CDF800800028E7D14FF04001204602F02D
-:10B62000CDFB48B1C4F888700320BCE735F8020BA5
-:10B630002168C0F30800E0E7C4F888700020B2E792
-:10B6400010B502F059F905280AD000EBC0010548F1
-:10B6500000EB81004068002802D0BDE810400047A0
-:10B6600010BD000078980020FEE70000F0B5002330
-:10B670000A251C463026372711E000BFB5EB107FA6
-:10B6800002D906EB107C01E007EB107C01F813C037
-:10B6900001EB430C00015B1C8CF80140DBB29342D0
-:10B6A000ECD3F0BD10EE100A0C49B6EE001AF7EE1E
-:10B6B000080A20EE011AA1EB600000EE100AF0EE7D
-:10B6C000601A21EE002A42EE401A21EE800A21EE95
-:10B6D000001A41EE400A20EE800A7047DF59375FBA
-:10B6E00091ED021A71EE600A80EE801A80ED021A66
-:10B6F000D1ED000A60EE800AC0ED000AD1ED010A2A
-:10B7000080EE801A80ED011A0020704790ED021A39
-:10B7100041EE000AC1ED020AD0ED000A80EE801A67
-:10B7200081ED001AD0ED010A20EE800A81ED010AB8
-:10B7300090ED030A81ED030A90ED040A002081EDEB
-:10B74000040A704700EB8100006E00F0F84070477B
-:10B750008068C0F3C00070478068C0F38000704705
-:10B760008068C0F38000704700EB8101034B51F803
-:10B77000600F20F0004010430860704700600258DE
-:10B7800038B390ED061AD0ED012AF0EE400AD0ED64
-:10B79000071A41EE620A90ED022A4FF07F4241EE15
-:10B7A000C20A10EE901AB2EB410F01D1F0EE400A3E
-:10B7B00090ED040AD0ED032A90ED052A21EE000A4F
-:10B7C00080ED071AC0ED060A00EEA20A01EE820A19
-:10B7D00070479FED010A70470000000010B504009B
-:10B7E0002DED068B18D0F5EEC00A9FED2C1AC4ED96
-:10B7F000000AF1EE10FA84ED061AF7EE008A84EDE5
-:10B80000071A0CD8C4ED038A84ED041A84ED051AD6
-:10B8100084ED011A80ED021ABDEC068B10BD80EE9E
-:10B82000201ADFED1F0A80EE810A04F07FFD9FEDF4
-:10B830001DAAB0EE408AB0EE4A0A04F0CFFCF0EE4A
-:10B84000009AB0EE689A20EE291AB0EE680A68EE07
-:10B85000080A18EE080A01EE089A20EE291A08EEE6
-:10B86000089A80EE890AC1EE090A84ED030A20EEE7
-:10B87000291A84ED050AB0EE4A0AC4ED010A84EDE6
-:10B88000041A04F0ABFC20EE290A40EE488A48EE88
-:10B89000088A88EE890A84ED020ABDE700000000EC
-:10B8A000DB0F4940DB0F493FB8B190ED031AD0EDF3
-:10B8B000041AD0ED050A31EE211A31EE201AC0EE3D
-:10B8C000010A10EE901A6FEAD15111F0FF0F07D064
-:10B8D000C0ED060AC0ED070A06E09FED040A7047B6
-:10B8E00080ED060A80ED070AFFF74ABF000000005E
-:10B8F00030B58DB000246846242109940A940B9435
-:10B90000F4F7CBFF24480425224B4FF410120121F9
-:10B9100003600223C0E90124C0E904150476032270
-:10B920004176C36180F820408462C0E90B42C46361
-:10B93000046480F844408164F8F7F0FF08B1F8F738
-:10B94000C9F9154809A90994F8F73AFC08B1F8F7BC
-:10B95000C1F91248062140F2FF7203928DE82300DC
-:10B960000D486946CDE904548DF82140F8F7BCFC38
-:10B9700008B1F8F7AFF90C210948CDE900010648F4
-:10B980006946F8F7B1FC002801D0F8F7A3F90DB02B
-:10B9900030BD000000200240DC0200201000C0107A
-:10B9A0000000B84F2D4808B5016841F00101016061
-:10B9B000016801F001010091016841F0020101609C
-:10B9C00000680022052100F0020000900B20FBF728
-:10B9D000ABF80B20FBF79BF8002205210C20FBF7AE
-:10B9E000A3F80C20FBF793F8002205210D20FBF7AC
-:10B9F0009BF80D20FBF78BF8002205210E20FBF7AA
-:10BA000093F80E20FBF783F8002205210F20FBF7A7
-:10BA10008BF80F20FBF77BF8002205211020FBF7A5
-:10BA200083F81020FBF773F8002205211120FBF7A3
-:10BA30007BF81120FBF76BF8002205212F20FBF784
-:10BA400073F82F20FBF763F8002205213820FBF75D
-:10BA50006BF8BDE808403820FBF759B8D8440258C5
-:10BA60001748002170B5154D012281601826056028
-:10BA70000225C1602024017404234174817446614D
-:10BA8000C0E90625026242628262C262C0E90C21FC
-:10BA90000464C0E90E21C0E91131C0E91331C0E9E5
-:10BAA0001531C0E91714C0E91913FAF73FFC002853
-:10BAB00003D0BDE87040F8F70DB970BD00A000409C
-:10BAC000C40300201848002170B5164D01220560FE
-:10BAD000182581602024C16004230174417481749D
-:10BAE000C0E90552C26140F20645026242628262CA
-:10BAF000C262C0E90C250464C0E90E21C0E911311D
-:10BB0000C0E91331C0E91531C0E91714C0E91913B0
-:10BB1000FAF70CFC002803D0BDE87040F8F7DAB85B
-:10BB200070BD000000A400406404002018480021FB
-:10BB300070B5164D01220560182581602024C16072
-:10BB40000423017441748174C0E90552C26140F656
-:10BB50001205026242628262C262C0E90C2504647C
-:10BB6000C0E90E21C0E91131C0E91331C0E9153136
-:10BB7000C0E91714C0E91913FAF7D8FB002803D05D
-:10BB8000BDE87040F8F7A6B870BD000000D40040D2
-:10BB900004050020074A0021074810B505F040F9C8
-:10BBA0000649074A08600021BDE81040054805F035
-:10BBB00037B90000202B0108D1CA0008000000207E
-:10BBC000E02C01089DD000082DE9F04F87B014212A
-:10BBD0006846F4F762FE5E48016841F010010160BA
-:10BBE000016801F010010591016841F00401016054
-:10BBF000016801F004010591016841F080010160D4
-:10BC0000016801F080010591016841F001010160C6
-:10BC1000016801F001010591016841F00201016034
-:10BC2000016801F002010591016841F0080101601D
-:10BC300000684FF46044DFF81C81002200F0080027
-:10BC4000214605904046FAF7BCFE012240462921D4
-:10BC5000FAF7B7FE4FF400463F4800223146FAF7A4
-:10BC6000B0FE4FF440693D4800224946FAF7A9FE6C
-:10BC70004FF4805A394801225146FAF7A2FE4FF498
-:10BC8000806B374800225946FAF79BFE012569462A
-:10BC90004046CDE90045002402940394FAF77EFD66
-:10BCA000032769462920CDE90005CDE90247404632
-:10BCB000FAF774FD4FF4881869464FF4A0500294C7
-:10BCC000CDE900082448FAF769FD00966946CDE9F8
-:10BCD000015421480394FAF761FDCDF800906946BC
-:10BCE000CDE901541D480394FAF758FD1B486946F5
-:10BCF000CDE900A5CDE90257FAF750FDCDF800B027
-:10BD00006946CDE9015416480394FAF747FD280225
-:10BD1000144D02218DE813006946284603940494CB
-:10BD2000FAF73CFD00966946CDE901842846FAF70A
-:10BD300035FD0021A802FEF765FB00220521282021
-:10BD4000FAF7F2FE2820FAF7E2FE07B0BDE8F08F1E
-:10BD5000E04402580008025800100258000402583B
-:10BD6000000C02580000025870B586B018216846D1
-:10BD7000F4F793FD18480822164D002101241723DB
-:10BD80008160D606E0E80352032580E81A0000F13E
-:10BD90001403C0E9031483E862000162C0E90912D8
-:10BDA000C16201630C48FBF701F908B1F7F792FF94
-:10BDB0004FF0011041F2883269460094CDE902400B
-:10BDC0000548FAF7E3FE002801D0F7F783FF06B035
-:10BDD00070BD000000A00052A40500202DE9F04134
-:10BDE0004FF480051448134A07276E114FF0007C6A
-:10BDF0002C0180E8E4100021A300C0E90514C0E98B
-:10BE0000073141629A008162C162C0E90D21C163BC
-:10BE1000016441648164C164016541658165FDF728
-:10BE2000D5FD002803D0BDE8F041F7F753BFBDE8CA
-:10BE3000F081000000300140000600202DE9F041B3
-:10BE4000164807264FF08042DFF84CC000215511FC
-:10BE500005611311C0E90216C0E9072141621712FA
-:10BE600081629411C162C0E90D21C1630164416422
-:10BE70008164C164016541658165C0E90543C0E92C
-:10BE800000C7FDF7A3FD002803D0BDE8F041F7F798
-:10BE900021BFBDE8F0810000003800408806002086
-:10BEA00010B58AB0002468461C21079408940994B0
-:10BEB000F4F7F3FC164840F2CF711722134BC0E998
-:10BEC000024104618461C0E90032FEF77AFD08B1E5
-:10BED000F7F700FF0E4807A907940994FEF7EEFA5A
-:10BEE00008B1F7F7F7FE60206946CDE9000408487D
-:10BEF000042202940494FEF7D2FC08B1F7F7EAFE9C
-:10BF00000348FEF75FFC0AB010BD000000180040B7
-:10BF1000E408002010B598B000241C210DA814944A
-:10BF200015941694F4F7B9FC34216846F4F7B5FC7F
-:10BF300027481822254942F2107380E81600C0E90C
-:10BF4000033444618461FEF73CFD08B1F7F7C2FE9B
-:10BF50001F4814A9149415941694FEF7AFFA08B16B
-:10BF6000F7F7B8FE0DAA41F28831602082E813008D
-:10BF7000174800220DA91094119412941394FEF7FF
-:10BF80008EFC08B1F7F7A6FE114808220DA9FEF7AE
-:10BF900086FC08B1F7F79EFE4FF40050009403941E
-:10BFA00001030194CDE904400294CDE90841084819
-:10BFB000694606940A940C94FEF730FA08B1F7F734
-:10BFC00089FE0348FEF7FEFB18B010BD00000140DB
-:10BFD0000008002010B58AB0002468461C21079490
-:10BFE00008940994F4F759FC1A4842F21071182287
-:10BFF0004FF08043C0E9024104618461C0E900322E
-:10C00000FEF7DFFC08B1F7F765FE124807A90794B1
-:10C010000994FEF753FA08B1F7F75CFE602041F28D
-:10C0200088318DE813000B48002269460494FEF71E
-:10C0300036FC08B1F7F74EFE064808226946FEF7BF
-:10C040002EFC08B1F7F746FE0248FEF7BBFB0AB02C
-:10C0500010BD00004C08002030B58BB000246846AD
-:10C060001C21079408940994F4F717FC164842F22F
-:10C070000F721723134D8021C0E9024204618161D0
-:10C08000C0E90053FEF79DFC08B1F7F723FE0E4808
-:10C0900007A907940994FEF711FA08B1F7F71AFEF9
-:10C0A00060206946CDE9000407480C2202940494FC
-:10C0B000FEF7F5FB08B1F7F70DFE0348FEF782FB2C
-:10C0C0000BB030BD000400409808002070B518483F
-:10C0D0000021164C042300F10C0C164D22158CE89F
-:10C0E0000E008161A614C16101624162816280E833
-:10C0F0007000FEF72BFF08B1F7F7ECFD0C480021AC
-:10C10000FEF719FD08B1F7F7E5FD09480021FEF734
-:10C11000ECFC08B1F7F7DEFD0548FEF7C4FC00288B
-:10C1200003D0BDE87040F7F7D5BD70BD00500040AA
-:10C1300030090020A08601001848002110B5164CD7
-:10C140000C224FF461230460C0E90131C160C0E9F1
-:10C1500004128161C161016241628162FEF7F6FEF3
-:10C1600008B1F7F7B7FD0D480021FEF7E4FC08B170
-:10C17000F7F7B0FD09480021FEF7B7FC08B1F7F763
-:10C18000A9FD0648FEF78FFC002803D0BDE810404B
-:10C19000F7F7A0BD10BD000000780040C4090020E2
-:10C1A0001848002110B5164C0C224FF4E1330460FE
-:10C1B000C0E90131C160C0E904128161C16101625D
-:10C1C00041628162FEF7C2FE08B1F7F783FD0D48B8
-:10C1D0000021FEF7B0FC08B1F7F77CFD094800210B
-:10C1E000FEF783FC08B1F7F775FD0648FEF75BFC28
-:10C1F000002803D0BDE81040F7F76CBD10BD00006B
-:10C20000001C0140140C00201848002110B5164CE9
-:10C210000C224FF461230460C0E90131C160C0E920
-:10C2200004128161C161016241628162FEF78EFE8A
-:10C2300008B1F7F74FFD0D480021FEF77CFC08B16F
-:10C24000F7F748FD09480021FEF74FFC08B1F7F762
-:10C2500041FD0648FEF727FC002803D0BDE810404A
-:10C26000F7F738BD10BD000000100140580A00204B
-:10C270001848002110B5164C0C22174B0460C0E979
-:10C280000131C1600B46C0E9041281610A46C161F7
-:10C29000016241628162FDF725FA08B1F7F71AFDE4
-:10C2A0000C480021FEF747FC08B1F7F713FD0948D9
-:10C2B0000021FEF71AFC08B1F7F70CFD0548FEF760
-:10C2C000F2FB002803D0BDE81040F7F703BD10BD16
-:10C2D00000440040EC0A002000093D0018480021FD
-:10C2E00010B5164C0C22174B0460C0E90131C16037
-:10C2F0000B46C0E9041281610A46C16101624162D4
-:10C300008162FDF7EFF908B1F7F7E4FC0C48002172
-:10C31000FEF711FC08B1F7F7DDFC09480021FEF734
-:10C32000E4FB08B1F7F7D6FC0548FEF7BCFB002894
-:10C3300003D0BDE81040F7F7CDBC10BD0048004069
-:10C34000800B002000093D0010490122104810B563
-:10C3500002F0AEF908B1F7F7BDFC0E490C4802F047
-:10C36000C6FB08B1F7F7B6FC0B49094801F046FFD8
-:10C3700008B1F7F7AFFC064802F03EFC08B1F7F74A
-:10C38000A9FCBDE81040FBF7A3BC0000080000209A
-:10C39000C40F0020E800002068000020FEE7FEE750
-:10C3A000F0B503004FF0000004460BD0022B09D873
-:10C3B00041B100220A604A60022B8A60CA600A61A9
-:10C3C00002D007E00120F0BD294A1268D20734D01C
-:10C3D0004FF40074274D002205EB8203D3F8043498
-:10C3E000DE0707D003F0020604F00207BE4201D1C7
-:10C3F000561C0E60DE0607D503F0200604F0200769
-:10C40000BE4201D1561C4E60DE0507D503F400760E
-:10C4100004F40077BE4201D1561C8E60DE0311D5B4
-:10C4200003F4802604F48027BE420BD19E0302F160
-:10C43000010604D446F4803603E00F4CCAE746F008
-:10C440008076CE60DE010FD503F0806604F0806751
-:10C45000BE4209D19B0102F1010302D443F48033AF
-:10C4600001E043F080730B61521C022AB4D3F0BD8B
-:10C4700000B4005200B00052220204042DE9F04141
-:10C48000984616460F460446069D08E0681C06D0EE
-:10C49000FAF79CFAA0EB0800A8420AD84DB1206830
-:10C4A000006A384000D00120B042EFD10020BDE842
-:10C4B000F0814FF400702065606D40F00100606510
-:10C4C0000120F4E70148FAF7FDBF0000C026002074
-:10C4D0002DE9F041044680790D4620272368012884
-:10C4E0004FF4004604F29C4203EB4511D3F840C0E0
-:10C4F000D1F8080B09D0DFF89CE0F4453AD10204EA
-:10C5000033D500BFC1F8086B40E0234B5FEA007EE3
-:10C5100004D59C453AD90004F4D437E05FEA806E34
-:10C5200002D5C1F8087B31E010F0280F2ED19C45D0
-:10C5300001D90004E6D4D1F8101B05EBC50004EBCB
-:10C540008000C1F31201D0F87432A3EB0101C0F8EE
-:10C55000681200F51570ADB903691BB1C2681144CA
-:10C56000C1600FE0206801210AE080060AD5C1F809
-:10C57000087B07E035B9D4F8640218B900211846E1
-:10C5800002F0BAFE2046E9B2FAF785FE0020BDE8C7
-:10C59000F08100000A31544F0A30544F2DE9F84F12
-:10C5A0000E460568814601EBC60100EB8104D4E923
-:10C5B00009201434904202D90120BDE8F88FA16807
-:10C5C000101A814200D20846C01C05EB46188708A5
-:10C5D0001BE000BFA268A0EB010A524500D29246C0
-:10C5E00099F806100AF1030000911FFA8AF3E16836
-:10C5F00087082846F2B203F0C3F9E16801EB0A00AC
-:10C60000E060616901EB0A006061D8F8180980B246
-:10C61000B84205D3D4E90401814201D20028D9D11E
-:10C62000D4E90401884208D8D5F83418012006F06E
-:10C630000F0290408143C5F834180020BDE770B563
-:10C6400004000D464FF0FF3137D050686FEAD050EC
-:10C6500010F0FF0F31D090686FEAD05010F0FF0F4C
-:10C660002BD0D0686FEAD05010F0FF0F25D01069A2
-:10C670006FEAD05010F0FF0F1FD050696FEAD05012
-:10C6800010F0FF0F19D0B7EE001A6260C1EE000A79
-:10C6900010EE900A6FEAD05010F0FF0F0DD0C4EDED
-:10C6A000020AD2ED060A04F11C00FFF797F82046B3
-:10C6B000257000F005F8002070BD084670BD000030
-:10C6C00010B570B19FED080A80ED030A80ED040AF1
-:10C6D00080ED050A80ED060A1C30FFF7E5F8002022
-:10C6E00010BD4FF0FF3010BD000000002DE9F047F5
-:10C6F000454D044689464FF0000A2868C04380072C
-:10C700000AD0414E283E306820F080603060FAF751
-:10C710005DF90746B04608E00120BDE8F08700BF9C
-:10C72000FAF754F9C01B022867D8D8F800000001B6
-:10C73000F6D4206829684FF4FE0721F47C313E02CC
-:10C7400041EA00302860207AA389B4F804C040028E
-:10C750002D4D2D495B1E227CACF1010C1035091DBD
-:10C76000A0F5007080B2521ECCF3080C07EA034318
-:10C7700040EA0C00184306EA026210432860086889
-:10C78000626920F0C000104308600A68A06922F0C6
-:10C79000200202430A60281D0A6822F010020A6083
-:10C7A00002684FF6F873E4699A4342EAC4020260F1
-:10C7B0000868B9F1000F40F010020A6011D0086853
-:10C7C000B9F1010F11D040F400100860D8F8000052
-:10C7D000444640F08060C8F80000FAF7F7F80546D4
-:10C7E0000DE0086840F40020EFE740F48010ECE72B
-:10C7F000FAF7ECF8401B022801D903208DE72068E6
-:10C800000001F5D5504688E7284402582DE9F04745
-:10C81000454D044689464FF0000A2868C04380070A
-:10C820000AD0414E283E306820F080503060FAF740
-:10C83000CDF80746B04608E00120BDE8F08700BF0C
-:10C84000FAF7C4F8C01B022867D8D8F800008000A7
-:10C85000F6D4208829684FF4FE0721F07C713E024F
-:10C8600041EA00502860207AA389B4F804C040024D
-:10C870002D4D2D495B1E227CACF1010C1835091D94
-:10C88000A0F5007080B2521ECCF3080C07EA0343F7
-:10C8900040EA0C00184306EA026210432860086868
-:10C8A000626920F44060104308600A68A06922F4BD
-:10C8B000007202430A60281D0A6822F480720A602E
-:10C8C00002684FF6F873E4699A4342EAC4020260D0
-:10C8D0000868B9F1000F40F480720A6011D008684E
-:10C8E000B9F1010F11D040F080700860D8F8000055
-:10C8F000444640F08050C8F80000FAF767F8054653
-:10C900000DE0086840F48000EFE740F40000ECE739
-:10C91000FAF75CF8401B022801D903208DE7206854
-:10C920008000F5D5504688E7284402580148FCF7B6
-:10C930003BBF00008806002010B5026840F26F334C
-:10C940005169946944F0080494610268946944F060
-:10C95000100494610268146824F0010414600268F1
-:10C9600014699C4314610268936823F44043936004
-:10C9700090F88120042A0CD08A060AD5D0F88420A9
-:10C9800042F08002C0F884200268936943F02003DB
-:10C99000936190F88120032A0CD04A060AD5D0F87A
-:10C9A000842042F00402C0F884200268936943F0B6
-:10C9B000400393618A050AD5D0F8842042F0010231
-:10C9C000C0F884200268936943F400739361C90539
-:10C9D0000AD5D0F8841041F00801C0F8841001682D
-:10C9E0008A6942F480728A610021A0F86210A0F87E
-:10C9F0006A1010BD10B5806B00210122A0F86A10EA
-:10CA0000A0F8621080F88120FCF7B2FE10BD10B5CE
-:10CA1000846BF8F743FC02280ED02046FFF78CFF0A
-:10CA2000D4F88410012041F01001C4F8841084F877
-:10CA300081002046FCF79CFE10BD10B5806BFDF711
-:10CA400075FB10BD10B5806B90F88110072909D0D7
-:10CA5000C16FC969B1F5807F05D00068016941F0F7
-:10CA60000801016110BDFDF745FB10BD00680349D9
-:10CA7000884201D1002070470220704700380040F2
-:10CA80002DE9F0411C4616460D460746DDF8188094
-:10CA90000AE000BFF9F79AFFA0EB0800A04202D31A
-:10CAA000601C01D00BE054B13868406935EA0000E1
-:10CAB00007D00020B042EDD00020BDE8F081032077
-:10CAC000FBE70120F6E70178407841EA0020704753
-:10CAD00010B5FFF739FC04F0A1F9BDE8104004F0EF
-:10CAE000E7B94FF0E02010B5006905F0E1FD01283D
-:10CAF00003D0BDE8104005F09FB910BD70B59CB0E3
-:10CB00004C216846F3F7C9FE202113A8F3F7C5FEB0
-:10CB10000220FBF7B3F82248016821F4404101608C
-:10CB20000168002401F440411B9101688904FCD58F
-:10CB300002204025C30323220121CDE90023CDE9B2
-:10CB4000031528220990069104230D910C260A90C2
-:10CB5000CDE90B02CDE90E30CDE9106468461294A0
-:10CB6000FCF72CFB08B172B6FEE708221A95CDE956
-:10CB70001625D30113AA3F200321CDE9185382E8DB
-:10CB8000130013A8FCF792F808B172B6FEE7002173
-:10CB90004FF480220846FCF7C7FA1CB070BD0000B5
-:10CBA000184802582D48F0B52D4A016841F470012B
-:10CBB0000160106800F00F00072804D2106820F010
-:10CBC0000F00C01D106027490020264C10340B6850
-:10CBD000254D43F001030B6020600B682B400B6078
-:10CBE000136803F00F03072B04D9136823F00F0316
-:10CBF000DB1D13601B4C1D4A18341D4B261D371DB1
-:10CC00002060184C1B4D28343060261D3860371DBD
-:10CC100023603B1D35601C1D3A60251D2E1D1860CC
-:10CC2000331D22602860326018600B680D4A0D4C7D
-:10CC300023F48023D4320B60603420601068C00479
-:10CC40000BD4136843F2D2000B4943F480531360B2
-:10CC50000860106820F480501060F0BD88ED00E09E
-:10CC600000200052004402587FEDF6EA80020101E4
-:10CC7000000202020000FF01004000520148FDF7DF
-:10CC8000FCBC0000780F00202DE9F0472C4B4FF042
-:10CC9000804A2C4D026898422B4E2C4F2C4C09D0C8
-:10CCA000504507D0A84205D0B04203D0B84201D0C9
-:10CCB000A04205D1D1F804C022F070024CEA020271
-:10CCC000DFF890C0DFF890809842DFF8909015D0A0
-:10CCD000504513D0A84211D0B0420FD0B8420DD069
-:10CCE000A0420BD0604509D0404507D0484505D04B
-:10CCF0001B4DA84202D01B4DA84203D1CD6822F49F
-:10CD000040722A438E684D6922F08002C6620E6826
-:10CD10002A439842866207D0A04205D0604503D0DE
-:10CD2000404501D0484501D10969016303680121EB
-:10CD300043F00403036041610260BDE8F087000036
-:10CD4000000001400004004000080040000C0040CA
-:10CD500000040140004001400044014000480140FF
-:10CD600000E0004000E400402DE9F04FDFF884804F
-:10CD7000214EDFF88890DFF888B0026A036AB0427B
-:10CD8000DFF880A022F0020C1F4F23F001020262A4
-:10CD9000426885698B680C6805EA080525F003057B
-:10CDA00043EA0C0344EA050407D0484505D058453A
-:10CDB00003D0504501D0B84205D1CD6823F0080317
-:10CDC0001D4325F00403B04207D0484505D058451F
-:10CDD00003D0504501D0B84205D122F44076D1E9C4
-:10CDE000055235432A4342608461496841630362C6
-:10CDF000BDE8F08F8FFFFEFF0000014000040140FE
-:10CE0000004001400044014000480140F0B5DFF817
-:10CE10007CE01F4C1F4D026A036AA04222F02006EC
-:10CE200023F01003036242688369D1F808C00F68D9
-:10CE300003EA0E0323F4407E46EA0C134EEA07266B
-:10CE400001D0A84206D1CF6823F0800343EA07133C
-:10CE500023F04003A0420AD0A84208D00E4CA042C2
-:10CE600005D00E4CA04202D00D4CA04207D1D1E912
-:10CE7000054522F4406242EA840242EA85024260A9
-:10CE80008661496881630362F0BD0000FF8FFFFE89
-:10CE90000000014000040140004001400044014006
-:10CEA00000480140F0B5DFF87CE01F4D1F4E026ADC
-:10CEB000036AA84222F4007723F480730362436874
-:10CEC000C269D1F808C002EA0E020C6822F0030E13
-:10CED00047EA0C2244EA0E0401D0B04206D1CF68E2
-:10CEE00022F4006242EA072222F48062A8420AD0B9
-:10CEF000B04208D00E4DA84205D00E4DA84202D037
-:10CF00000D4DA84207D1D1E9055623F4405343EA19
-:10CF1000051343EA06134360C4614968C1630262B2
-:10CF2000F0BD00008FFFFEFF000001400004014043
-:10CF3000004001400044014000480140F0B5046A4F
-:10CF4000026A22F4805202624268C36924F40054E7
-:10CF5000DFF848C08E680D6803EA0C03104F23F415
-:10CF6000407344EA0634B84243EA05230BD00D4D22
-:10CF7000A84208D00C4DA84205D00C4DA84202D0C2
-:10CF80000B4DA84204D14D6922F4804242EA851239
-:10CF90004260C361496801640462F0BDFF8FFFFE17
-:10CFA00000000140000401400040014000440140F5
-:10CFB00000480140F0B5164F164B026A046A9842C9
-:10CFC00022F4003524F4803303624268436D0E89F5
-:10CFD0000C6803EA070344EA030445EA06430BD05E
-:10CFE0000D4DA84208D00D4DA84205D00C4DA842C9
-:10CFF00002D00C4DA84204D14D6922F4803242EA9D
-:10D00000052242604465496881650362F0BD000005
-:10D010008FFFFEFF0000014000040140004001407E
-:10D020000044014000480140F0B5164F164B026A1B
-:10D03000046A984224F48013036222F400144268C4
-:10D04000436D0E890D6803EA070344EA065443EA78
-:10D0500005230BD00D4DA84208D00D4DA84205D098
-:10D060000C4DA84202D00C4DA84204D14D6922F4C7
-:10D07000802242EA8522426043654968C1650462B4
-:10D08000F0BD0000FF8FFFFE0000014000040140E2
-:10D090000040014000440140004801402B4810B5C9
-:10D0A000F6F78AFA03F040FD294A0021294803F0E7
-:10D0B000B7FE264C0021284A403C2060274803F058
-:10D0C000AFFE60600021264A264803F0A9FEA0605A
-:10D0D0000021254A254803F0A3FEE0600021244AF0
-:10D0E000244803F09DFE20610021234A234803F0D9
-:10D0F00097FE60610021224A224803F091FEA06160
-:10D100000021214A214803F08BFE0022E061182112
-:10D11000022003F08BFD002220621421022003F084
-:10D1200085FD0022A0629021022003F07FFD0022F5
-:10D13000E062F021022003F079FD206303F026FD78
-:10D1400003F06CFEBDE8104003F0B2BE58A0002012
-:10D15000042D0108D9D40008282D010891D1000818
-:10D160004C2D010859D50008702D01082DD200085A
-:10D17000942D0108B9D40008B82D01082DD300085A
-:10D18000DC2D01083DD40008002E0108A5D30008BD
-:10D19000002003F077FC234901F11800F5F70AFDA0
-:10D1A00020481830F5F7E6FC1E490C3101F12C003F
-:10D1B000F5F7DAF81B481830F5F7DCFCF0EE400A1A
-:10D1C000B7EE001A1748002181EE200A164A58309F
-:10D1D000FFF735FA134C2434F5F752FEF5F7B8FC97
-:10D1E000F5F7C2FCF5F7D4FCF5F7DEFC03F09CFC88
-:10D1F0000C481830F5F776FD0A481830F5F7C2FDEF
-:10D20000084B22460C3303F10C0101F12000F5F725
-:10D210003BF90449383101F11400F5F73DF803F00A
-:10D22000B5FCD9E778A10020242E0108002003F0E6
-:10D2300029FC2748F6F7D2FE26A0F5F7F1FF33A028
-:10D24000F5F7EEFF334F0026334C00BFF6F70CF82E
-:10D250000500FBD0014631A0F5F7E2FF0D2D10D0FF
-:10D260000A2D0ED07F2D2AD0082D28D020887F2887
-:10D27000ECD2202DEAD37E2DE8D83D54411C2180EC
-:10D28000E4E727A0F5F7CCFF20883E5480B1F6F7FD
-:10D2900039FE4FF4007980461E484A464146F6F76B
-:10D2A00035FE054641461FA0F5F7BAFF002DF3D124
-:10D2B000184880212680F3F7CEFA14A005E02088D4
-:10D2C0000028C3D0401E208017A0F5F7A9FFBDE7B6
-:10D2D000442E01080D0AE6ACA2E8BF8EE4BDBFE70C
-:10D2E00094A8E591BDE4BBA4E8A18CEFBC8CE8BE9A
-:10D2F00093E585A52068656C7020E69FA5E79C8B6B
-:10D30000E591BDE4BBA40D0A000000006D723E2053
-:10D310000000000038A20020D80200202563000091
-:10D320000D0A000025730000082008002DED028B77
-:10D3300003F0E5FB4FF4FA71B0FBF1F6002003F0C7
-:10D34000A1FB1548F5F7E0FF03F0D2FB124F0546AD
-:10D35000134C9FED128A354403F0E6FB0E4900237F
-:10D36000206A1A46243103F02FFC30B90A49B0EE86
-:10D37000480A01F12400F5F7CDFF03F007FCA06A8D
-:10D3800003F0B4FC0023A06A391D1A4603F07AFCAE
-:10D39000284603F085FBDEE7B8A200206F12033BAE
-:10D3A00018A0002003F0ABFB4FF4FA71B0FBF1F6CC
-:10D3B000002003F067FB1D491D489FED1B0AF6F78F
-:10D3C000C9F803F095FB194D0446443D1949002363
-:10D3D00034441A46E86A03F0F7FB18B915491448B3
-:10D3E000F6F7C8F800231449A86A1A4603F0ECFBC4
-:10D3F00003F09AFB104922460D48F5F7BFFF0D498F
-:10D400000B489031F6F780F803F0C0FB286B03F06F
-:10D410006DFC08490023286B1A46903103F032FC5A
-:10D42000204603F03DFBD1E70000FA435CA000205A
-:10D4300074A400205CA60020DCA7002003F05FFBA2
-:10D440004FF4FA71B0FBF1F6002003F01BFB174913
-:10D450001748F6F7EBFD03F04BFB144D0446403D37
-:10D460001449002334441A46286B03F0ADFB18B965
-:10D4700010490F48F6F756FE03F056FB0C48F6F736
-:10D48000F5FD03F083FB0B4909489039F6F776FE6A
-:10D49000E86A03F02BFC07490023E86A1A46903932
-:10D4A00003F0F0FB204603F0FBFAD9E758A0002078
-:10D4B0002800002484A3002003F021FB6421B0FB9A
-:10D4C000F1F5002003F0DEFA03F012FB04462C44D1
-:10D4D000204603F0E5FAFAE7002003F0D3FA1A48F1
-:10D4E000F6F7D2FADFED190A9FED190AF5F768FD94
-:10D4F000184C1548F6F788FB1420F6F795FB002822
-:10D50000114807D0F6F7E4FA01210020F5F706FEEE
-:10D51000012106E0F6F7AEFA00210846F5F7FEFD18
-:10D5200000210120F5F7FAFD074907481831F6F701
-:10D53000F9FA206A03F0DAFB03490023206A1A464D
-:10D54000183103F09FFBD4E7E89F0020CDCC4C3E80
-:10D550000000964318A0002003F0D1FA4FF47A712E
-:10D56000B0FBF1F5002003F08DFA0D4800229FED8D
-:10D570000B0A01210280418080ED040A80ED050A3A
-:10D5800080ED030A80ED020A80ED010A03F0B0FA93
-:10D5900004462C44204603F083FAFAE7000000001A
-:10D5A0000CA200200148FDF703BB00003009002059
-:10D5B0000148FDF7FDBA0000C409002030B5416EF6
-:10D5C000B9B101680D4B03F108048A688968C2F398
-:10D5D0004262490F5D5C615C2D01B5FBF1F1A0F881
-:10D5E0006A10995CA25C0901B1FBF2F1A0F8681025
-:10D5F00030BD0121A0F86A10F8E70000C02B010837
-:10D6000090F82810090706D50168836B4A6822F450
-:10D6100000421A434A6090F82810C90706D00168F2
-:10D62000C36A4A6822F400321A434A6090F828100C
-:10D63000890706D50168036B4A6822F480321A43D1
-:10D640004A6090F82810490706D50168436B4A687C
-:10D6500022F480221A434A6090F82810C90606D5A1
-:10D660000168C36B8A6822F480521A438A6090F87A
-:10D670002810890606D50168036C8A6822F40052D6
-:10D680001A438A6090F82810490611D50168436C46
-:10D690004A6822F480121A434A60416CB1F5801F37
-:10D6A00006D10168836C4A6822F4C0021A434A60BA
-:10D6B00090F82810090606D50168C26C486820F465
-:10D6C00000201043486070472DE9F84300250446C8
-:10D6D000C0F89050F9F77AF98046206820266FF05C
-:10D6E0007E470068000713D50022434631042046D8
-:10D6F000009700F063FB58B1216851E8000F20F05B
-:10D70000800041E80002002AF6D1C4F8886021E0D8
-:10D7100020680068400722D5002243464FF480016C
-:10D720002046009700F04AFBC8B1206850E8001F6F
-:10D7300021F4907140E80012002AF6D120680830E8
-:10D7400050E8001F21F0010140E80012002AF5D145
-:10D75000C4F88C60032084F88450BDE8F883C4F8D2
-:10D760008860C4F88C60E5662567002084F88450E2
-:10D77000F3E710B5806B0021A0F85E10FDF704FA06
-:10D7800010BD70B5846B00252168D4F88800D4F8EA
-:10D790008C608968090606D5212804D1A4F8565062
-:10D7A000204600F091F820688068400606D5222EB9
-:10D7B00004D1A4F85E50204600F05CF8D4F8900044
-:10D7C00040F01000C4F890002046FDF7DDF970BD70
-:10D7D00010B5C1690022806BB1F5807F2DD0A0F813
-:10D7E0005E20036853E8001F21F4807143E80014B1
-:10D7F000002CF6D10168083151E8003F23F0010305
-:10D8000041E80034002CF5D10168083151E8003FAF
-:10D8100023F0400341E80034002CF5D12021C0F86A
-:10D820008C10C16E012908D1016851E8003F23F036
-:10D83000100341E80034002CF6D10267C16E0129C3
-:10D8400002D0FDF77DFE10BDB0F85C10FDF74BF97E
-:10D8500010BD10B5806B01210167C16E012902D096
-:10D86000FDF782FE10BDB0F85C104908FDF73BF9EA
-:10D8700010BD000010B5026852E8001F21F490713D
-:10D8800042E80013002BF6D10E4B0268083252E832
-:10D89000001F194042E80014002CF6D1C16E012986
-:10D8A00008D1026852E8001F21F0100142E800137D
-:10D8B000002BF6D100212022C0F88C20C1664167E0
-:10D8C00010BD0000FEFFFFEF026852E8001F21F0CC
-:10D8D000C00142E80013002BF6D10168083151E87D
-:10D8E000002F22F4000241E80023002BF5D1202173
-:10D8F000C0F888107047000000680B49884201D1C9
-:10D90000002070470949884201D101207047084929
-:10D91000884201D1022070470649884201D1032084
-:10D920007047052070470000005000400044004050
-:10D9300000480040001C01402DE9F0430446806887
-:10D94000E24E87B0E24B2168D4E90427D4F81CC02A
-:10D9500010430A68002547EA0C0738433240024367
-:10D960000A602068E268416821F440511143416037
-:10D970002268A1699A4201D0206A01439668DFF8C3
-:10D9800054C3D54FD54806EA0C060E43966021686D
-:10D99000666ACA6A22F00F023243CA622268BA4239
-:10D9A0000ED1006800F0380018286FD07ADCB8B3C8
-:10D9B00008286CD010286BD18BE0282868D18EE025
-:10D9C000C7498A4209D1006800F0070006285FD2E3
-:10D9D000DFE800F0507D7F818385C2498A4209D10A
-:10D9E000006800F0070006287BD2DFE800F04370F3
-:10D9F00072747678BC498A4209D1006800F0070049
-:10DA000006286ED2DFE800F036636567696BB749B8
-:10DA10008A420BD1006800F00700062861D200E0BE
-:10DA200043E0DFE800F0275456585A5CB0498A4278
-:10DA300006D1006800F0380018284CD0B7DD31E07E
-:10DA4000AC498A4209D1006800F00700062848D294
-:10DA5000DFE800F0103D3F414345A7498A420BD122
-:10DA6000006800F0070006283BD2DFE800F0033032
-:10DA700032343638002035E0A0498A4209D10068A6
-:10DA800000F03800182826D091DD0BE023E01EE0DE
-:10DA900027E09B498A420AD1006800F03800182824
-:10DAA00019D084DD202888D11CE001201AE09A4298
-:10DAB00017D18A48001D006800F00700062810D220
-:10DAC000DFE800F0030507090B0D02200AE004203F
-:10DAD00008E0082006E0102004E0202002E04020BA
-:10DAE00000E080208749DFF820829A42874A4FF47D
-:10DAF00000434FEA21174FF000064ED110281AD0EC
-:10DB000006DC022809D004280BD008287ED10DE0BD
-:10DB100020283ED0402879D13DE0FAF7E1F80146CF
-:10DB200010E06846FAF792F901990BE003A8FAF7BA
-:10DB30002FFA049906E01068800605D51068C0F336
-:10DB4000C100C140002970D0606A676838F81020B1
-:10DB500007EB4703B1FBF2F0834257D8B0EB073F26
-:10DB600054D8002308461946F2F7FAFC0246780812
-:10DB7000130E120243EA012110183A4671410023A4
-:10DB8000F2F7EEFC624AA0F5407191423ED821685E
-:10DB90008FE03946D8E71946D6E7D4F81CC04FF6CF
-:10DBA000EF799C4546D1082819D005DC58B10128E9
-:10DBB0000CD0042875D10DE0102815D0202835D0C0
-:10DBC00040286ED134E0FBF7EFF901E0FBF7FEF9F6
-:10DBD000014610E06846FAF739F901990BE003A80D
-:10DBE000FAF7D6F9049906E01068800604D51068A3
-:10DBF000C0F3C100C140C1B1636A606838F8133036
-:10DC0000B1FBF3F1490001EB500100E049E0B1FB49
-:10DC1000F0F0A0F11001494543D84FF6F0732168A8
-:10DC2000C0F342021840104343E043E03946E3E7C3
-:10DC30001946E1E7082819D005DC58B101280CD0B5
-:10DC400004282ED10DE0102815D020282BD04028F4
-:10DC500027D12AE0FBF7A8F901E0FBF7B7F9014665
-:10DC600010E06846FAF7F2F801990BE003A8FAF71A
-:10DC70008FF9049906E01068800604D51068C0F397
-:10DC8000C100C140B1B1636A606838F81330B1FBBC
-:10DC9000F3F101EB5001B1FBF0F0A0F110014945A7
-:10DCA00005D9012506E03946EDE71946EBE721687D
-:10DCB00080B2C8600120A4F86A00A4F86800284671
-:10DCC0006667A66707B0BDE8F0830000F369FFCF81
-:10DCD000000C0058FFF4FF1100100140544402589A
-:10DCE0000044004000480040004C0040005000400C
-:10DCF0000014014000780040007C00400018014002
-:10DD0000001C01400090D003A82B010800440258D9
-:10DD1000FFFC0F0070B50446D0F8800000232225D8
-:10DD2000A165A4F85C20C4F89030C4F88C50F0B120
-:10DD30001F49C163D4F880101E480864D4F88010CD
-:10DD40001D48C864D4F8800003651346A56D21689A
-:10DD5000D4F880002A462431F7F7F4FF38B11021B7
-:10DD6000C4F890102020C4F88C00012070BD2069F8
-:10DD700040B1216851E8000F40F4807041E8000292
-:10DD8000002AF6D12068083050E8001F41F0010158
-:10DD900040E80012002AF5D12068083050E8001F42
-:10DDA00041F0400140E80012002AF5D1002070BD8A
-:10DDB000D1D7000853D8000883D700082DE9F047D1
-:10DDC000994617460D460446089E4FF0000833E07A
-:10DDD000701C31D0F8F7FAFDA0EB0900B04218D85A
-:10DDE000BEB120680168490726D5802D24D0402D7A
-:10DDF00022D0C169C94309070DD408250562204610
-:10DE0000FFF738FDC4F89050012084F88480BDE805
-:10DE1000F0870320FBE7C069C04300050CD42168EC
-:10DE20004FF4006008622046FFF724FD2021C4F86B
-:10DE3000901084F88480ECE72068C06935EA00001F
-:10DE400004D00020B842C3D00020E0E70120F9E769
-:10DE50000148FCF7ADBE0000140C00200148FCF79F
-:10DE6000A7BE0000580A0020044810B5FCF7A0FE29
-:10DE7000BDE810400148F5F7A1B90000EC0A002008
-:10DE8000044810B5FCF794FEBDE810400148F5F7D2
-:10DE900095B90000800B00202DE9F0410C46D0F828
-:10DEA000D412D0F8C83200EB8101D1F8C01229B3E6
-:10DEB00004F00F02002702EB820500EB8506B5692E
-:10DEC0004DB102EBC20203EB8202D269B5FBF2F361
-:10DED00002FB1352A2B1C1F81472D0F8D42200EBA5
-:10DEE0008200D0F8C40203692BB1D1F8080201F511
-:10DEF0000471224698470020BDE8F0810320FBE72B
-:10DF0000002321461A46B76100F0D3FDF3E770B550
-:10DF10000546D0F8D40205EB8000D0F8C04294B199
-:10DF2000284600F0A0FCC4F80C02D5F8D40205EB9A
-:10DF30008000D0F8C412D4F80402CA6804F5037152
-:10DF40009047002070BD032070BD000070B5224DC9
-:10DF50000446297800F0C8FB2878002600F00F005E
-:10DF600000EB800004EB800086842046697800F096
-:10DF7000BBFB687800F00F0000EB800004EB800032
-:10DF8000A0F864612046A97800F0AEFBA87800F004
-:10DF90000F0000EB800004EB80008684C684D4F878
-:10DFA000D40204EB8000D0F8C01299B1D0F8C402BA
-:10DFB00040688047D4F8D40204EB8000D0F8C00257
-:10DFC00000F09FFFD4F8D40204EB8000C0F8C062D8
-:10DFD000C4F8BC62002070BD9400002010B5D0F8D9
-:10DFE000D41200EB8100D0F8C04284B1D0F8C41242
-:10DFF00059B194F80002FF2807D08B68214694F8A5
-:10E0000001229847FF2084F80002002010BD032061
-:10E0100010BD00000A2101800048704798000020D0
-:10E0200070B5822106460D4800F076FA01210546BA
-:10E030000A4800F071FA81210446084800F06CFAA1
-:10E040000DB11021A9714FF0400104B1A18000B1C0
-:10E05000818043203080014870BD0000A400002072
-:10E0600070B5822106460D4800F056FA012105469A
-:10E070000A4800F051FA81210446084800F04CFAA1
-:10E080000DB11021A9714FF4007104B1A18000B14C
-:10E09000818043203080014870BD0000A400002032
-:10E0A00070B5822106460D4800F036FA012105467A
-:10E0B0000A4800F031FA81210446084800F02CFAA1
-:10E0C0000DB11021A9714FF0400104B1A18000B140
-:10E0D000818043203080014870BD0000A4000020F2
-:10E0E0002DE9F0474FF407750446284600F00AFF73
-:10E0F00006004FF0000965D02946F2F7CEFBD4F8B0
-:10E10000D40201273C4D4FF4007A4FF0100804EB85
-:10E110008000C0F8C062C4F8BC62207CF0B32978EB
-:10E1200040230222204600F00EFC2878402300F015
-:10E130000F0000EB800004EB8000878402226978E6
-:10E14000204600F000FC697808230322204601F0F5
-:10E150000F0101EB810104EB8101A1F86471A97841
-:10E1600001F00F0101EB810104EB8101A1F8268090
-:10E17000A97800F0E8FBA978C84601F00F0101EB8F
-:10E18000810104EB81018F84C6F80492D4F8D40293
-:10E1900004EB8000D0F8C402006800E01AE006F545
-:10E1A00001768047C6F81080C6F8148032687AB1CC
-:10E1B000207CF8B140236978204600F0D0FB002095
-:10E1C000BDE8F087D4F8D41204EB8101C1F8C09205
-:10E1D0000220F5E7297802225346204600F0B3FBDF
-:10E1E0002878534600F00F0000EB800004EB80001D
-:10E1F0008784A3E75346DEE79400002039B1D0F8C6
-:10E20000D42200EB8200C0F8C41200207047032023
-:10E210007047D0F8D42200EB8200D0F8C00218B1C9
-:10E22000C0F804120020704703207047D0F8D432A1
-:10E2300000EB8300D0F8C00228B1C0F81022C0F86B
-:10E24000081200207047032070472DE9FC41064664
-:10E25000D0F8D4020C46002106EB80000D46D0F821
-:10E26000C0728DF80010ADF8041037B1217811F0AC
-:10E2700060022CD0202A48D102E00320BDE8FC81B6
-:10E28000E288E2B109060BD5D0F8C40239468368AA
-:10E2900060789847E288072A00D9072239462CE09F
-:10E2A000607887F80002E088402800D34020394693
-:10E2B000C2B2304687F8012200F07FF82AE0D0F899
-:10E2C000C4020022214683686078984722E0607883
-:10E2D00030B101281ED00A2809D00B2815D110E032
-:10E2E00096F89C02032810D1022201A905E096F8B5
-:10E2F0009C02032809D101226946304600F077F8D4
-:10E3000008E096F89C02032804D02146304600F02D
-:10E3100049F803252846B1E710B5D0F8D41200EB30
-:10E3200081020121D2F8C0221AB1D2F8143213B1FD
-:10E3300016E0032010BD0B490123C2F81432D2F8B5
-:10E340001032097801F00F0404EB840400EB84041C
-:10E35000A361D2F81032D2F8082200F0AAFB002103
-:10E36000084610BD9400002010B5D0F8B822002453
-:10E370005268904700B10324204610BD002070472A
-:10E380000020704713460A46002110B500F0E7FA56
-:10E39000002010BD13460A46002110B500F089FB8D
-:10E3A000002010BD10B58021044600F063FB20461C
-:10E3B000BDE81040002100F05DBB10B5C0F8582149
-:10E3C0000323C0F89432C0F85C2113460A460021AA
-:10E3D00000F0C5FA002010BD10B50521C0F8941258
-:10E3E00000231A46194600F0BAFA002010BD10B5F5
-:10E3F00082610223C0F89432C26113460A460021AA
-:10E4000000F057FB002010BD10B50421C0F8941295
-:10E4100000231A46194600F04CFB002010BDF8B549
-:10E4200004460D460020ADF800004888010A062980
-:10E4300047D006DC01290FD0022912D0032962D16E
-:10E440001DE0072946D00F295DD1D4F8B402C26976
-:10E4500020E0694690473BE0D4F8B412207C0A687B
-:10E46000F7E7207C02260028D4F8B80205D0C16A5C
-:10E47000684688470146467036E0816AF8E7C0B2D0
-:10E48000062840D2DFE800F003090D111519D4F871
-:10E49000B4024268B2B3207CDBE7D4F8B4028268ED
-:10E4A000F8E7D4F8B402C268F4E7D4F8B402026919
-:10E4B000F0E7D4F8B4024269ECE7D4F8B402826918
-:10E4C000E8E7207CF0B9D4F8B802416B6846884789
-:10E4D000014609E0207CA8B9D4F8B802016B68466F
-:10E4E0008847014607204870EA888AB1BDF80000D5
-:10E4F00040B1824200D902462046ADF80020FFF725
-:10E5000076FFF8BDFFE729462046FFF74BFFF8E707
-:10E510002046FFF779FFF4E778B542880D46017889
-:10E52000002604468A4212D9ADF800100AE0694676
-:10E5300000F019F84178052904D181780646A942EE
-:10E5400005D000266188BDF800209142EFD8304602
-:10E5500078BD002102E0491C401CC9B20278002AA3
-:10E56000F9D1084670470A8803781A440A8001786E
-:10E570000844704770B5002816460D4620D0044662
-:10E58000FFF7E7FF02220146100202EB4101814240
-:10E5900004D82046FFF7DDFF4000801C3080337830
-:10E5A000032102202B700022697006E0431C2954CD
-:10E5B000D8B2411C641C2A54C8B221780029F5D174
-:10E5C00070BD01004FF0000004D0012901D00229E4
-:10E5D00001D00320704701207047000004A00A46C4
-:10E5E000024910B5FFF7C6FF004810BDA012002079
-:10E5F00043444320436F6E66696700001220088021
-:10E60000004870472C00002004A00A46024910B5BB
-:10E61000FFF7B0FF004810BDA01200204344432084
-:10E62000496E7465726661636500000004200880AD
-:10E63000004870472800002004A00A46024910B58F
-:10E64000FFF798FF004810BDA01200204D526F62E6
-:10E650006F74000004A00A46024910B5FFF78AFF54
-:10E66000004810BDA01200204D726F626F742043ED
-:10E670006C69000010B51A2008800B480A49083060
-:10E68000021F096800681468081809D007490822A1
-:10E69000FCF7ECFF0549042220461031FCF7E6FFA9
-:10E6A0000248801E10BD000000E8F11F4E0000204F
-:10E6B00078B10023C0F8B832C0F8C432C0F8D03204
-:10E6C00009B1C0F8B4120121027080F89C1200F068
-:10E6D000CFB80320704710B5D0F8C802F8F71DFE78
-:10E6E000BDE81040FFF76DBF10B5D0F8C802F8F7CD
-:10E6F000EFFDBDE81040FFF764BF2DE9F04117467C
-:10E7000004464FF0000521B194F89C02032842D042
-:10E710004CE0D4F8941204F11400022935D1D0E968
-:10E7200002639E4206D9F21A394682602046FFF7FC
-:10E7300031FE0FE0B34214D14068984211D3D4F8AF
-:10E74000981288420DD2002220461146FFF722FE81
-:10E75000C4F8985200231A461946204600F0FFF8E4
-:10E7600013E094F89C02032808D1D4F8B802C168D9
-:10E7700021B1C4F8D452C168204688478021204680
-:10E7800000F078F92046FFF727FE94F8A00268B160
-:10E7900084F8A0520AE0D4F8B802426932B1C4F851
-:10E7A000D452426920469047002800D10020BDE89D
-:10E7B000F08170B5134604464FF0000221B194F881
-:10E7C0009C02032830D03AE0D4F8941204F5AA70E1
-:10E7D000032934D1D0E902518D420AD96A1A8260E4
-:10E7E0000846824200D3024619462046FFF7CAFD7A
-:10E7F00025E094F8AA0210F01F0003D0012802D0EF
-:10E80000022800D0002294F89C02032808D1D4F8F2
-:10E81000B802016921B1C4F8D422016920468847B1
-:10E820002046FFF7F1FD0AE0D4F8B802836933B15E
-:10E83000C4F8D422826920469047002800D10020E5
-:10E8400070BD0020704710B5D0F8B812012280F8D2
-:10E850009C22002429B103794A68D9B2904700B1BB
-:10E860000324204610BDD0F8C802F8F783BD00008D
-:10E8700070B50178012929D115490925154C0223C4
-:10E880000022C1F8E004C0F8C81208460C600D71FF
-:10E89000CB718A714B728A72CA720A738A73CA7395
-:10E8A0000A74F9F7E1F808B1F5F714FA08484FF4DB
-:10E8B0000071F8F7BCFC064880220021F8F7BBFC89
-:10E8C000034801214FF4BA72F8F7B5FC002070BD7F
-:10E8D000C026002000000440D0F8C82201F07F00CC
-:10E8E0000B0600EBC00002EB800001D5807D704775
-:10E8F00090F85602704710B5D0F8D42200EB82028F
-:10E90000D2F8B82222B190F89C32032B02D004E056
-:10E91000032010BD126A02B19047002010BD10B54F
-:10E92000D0F8D42200EB8202D2F8B82222B190F8BB
-:10E930009C32032B02D004E0032010BD526A02B1C6
-:10E940009047002010BD10B51C46D0F8C8021346F1
-:10E950002246F8F718FDBDE81040FFF732BE10B5AB
-:10E96000D0F8C802F8F740FDBDE81040FFF729BE17
-:10E970002DE9F041044601250020D4F8B8120646DE
-:10E9800084F89C52C4F894026060C4F8A40284F82D
-:10E99000A00231B14A6822B100212046904700B15F
-:10E9A00003262046002240231146FFF7CCFF4027D4
-:10E9B000A4F8645100223B4680212046C4F86071CF
-:10E9C000FFF7C1FFA58430462762BDE8F08190F8CB
-:10E9D0009C12042903D190F89D1280F89C1200200B
-:10E9E000704710B590F89C12032905D1D0F8B812E1
-:10E9F00011B1C96901B18847002010BD0174002020
-:10EA0000704710B5D0F8C802F9F7E4F8BDE8104037
-:10EA1000FFF7D7BD70B5044600F2AA20054600F006
-:10EA200051F894F8AA020123B4F8B01210F01F02B2
-:10EA3000C4F89432C4F898120AD0012A0ED0022ADF
-:10EA400012D000F080012046BDE8704000F012B8FE
-:10EA500029462046BDE8704000F0D0B8294620463F
-:10EA6000BDE8704000F013BA29462046BDE870406A
-:10EA700000F05BB910B5D0F8C802F8F7CFFCBDE8DC
-:10EA80001040FFF79EBD10B5D0F8C802F9F7BCF8EA
-:10EA9000BDE81040FFF795BD90F89C12042903D003
-:10EAA00090F89C1280F89D12042180F89C1200209E
-:10EAB000704710B5D0F8C802F8F7E9FCBDE810407F
-:10EAC000FFF77FBD70B5054608788C1C2870487824
-:10EAD00068702046FDF7F7FFA41C68802046FDF70C
-:10EAE000F2FFA880A01CFDF7EEFFE88070BD38B5EE
-:10EAF00004460020ADF80000A1B1C4F8B812D4F863
-:10EB0000D40204EB8000D0F8B802C16A19B168469B
-:10EB10008847C4F8D002D4F8D802401CC4F8D80200
-:10EB2000002038BD032038BDD0F8B832024600209E
-:10EB3000002B02D01B681046184770472DE9F041A2
-:10EB40002C4E0446887800258846C1B201293170D0
-:10EB500006D941462046FFF725FC0320BDE8F08199
-:10EB600094F89C02022702280CD003281DD04146AD
-:10EB70002046FFF717FC31782046FFF7F5FB032509
-:10EB80002846EBE789B320466160FFF7CDFF05001B
-:10EB900004D041462046FFF705FC1DE02046FFF764
-:10EBA00033FC032084F89C02EAE7C1B16068884224
-:10EBB0001BD0C1B22046FFF7D7FB317820466160F9
-:10EBC000FFF7B2FF050010D041462046FFF7EAFBF1
-:10EBD00021792046FFF7C8FB84F89C72D0E761607A
-:10EBE00084F89C722046FFF7BFFB2046FFF70CFC21
-:10EBF000C6E7000090000020FFF745BF2DE9F04177
-:10EC00000A784FF0000512F060020CD0202A01D0E3
-:10EC1000402A7DD1D0F8D42200EB8202D2F8B8226B
-:10EC20009268904731E04B78002201260A2B6FD280
-:10EC3000DFE803F041666E586E08056E2D29FFF778
-:10EC4000EEFB67E004468888D8B9C888C8B9488808
-:10EC5000802816D294F89C2200F07F07032A10D057
-:10EC60003946204684F89E72FFF7CBFE2046FFF718
-:10EC7000CBFB1FB1022084F89C024BE084F89C621D
-:10EC800048E0204644E0FFF759FF054642E0CB88C4
-:10EC9000012B3DD190F89C32012B04D0022B02D0E5
-:10ECA000032B35D104E000F108018260012216E057
-:10ECB0000122011D13E090F89C22012A03D0022AB0
-:10ECC00001D0032A24D1CA88022A21D1D0F8A41263
-:10ECD000C66009B10321C160022200F10C01FFF7F7
-:10ECE00086FB17E04A88012A02D0022A03D00FE0EF
-:10ECF000C0F8A46216E08988090A80F8A01211E021
-:10ED000090F89C32012B08D0022B06D0032B04D0A4
-:10ED1000FFF748FB2846BDE8F08149880129F9D171
-:10ED2000C0F8A422FFF770FBF4E72DE9F0410A7860
-:10ED30000E460979054612F060004FF00008CCB28B
-:10ED40000BD0202801D040286AD121462846FFF761
-:10ED500015FBFF2800D0D8B396E07078C8B301281F
-:10ED600024D003285CD195F89C02022802D0032805
-:10ED700056D10CE0002C53D0802C51D0214628468F
-:10ED8000FFF778FE80212846FFF774FE7CE070884C
-:10ED900040B93CB1802C05D0F08818B921462846EE
-:10EDA000FFF768FE2846FFF72FFB6DE095F89C0201
-:10EDB0000228DFD0032863D1708880BB600603D0AF
-:10EDC00021462846FFF787FC2846FFF71DFBBCE7D6
-:10EDD00000E00AE0C5F8D402D5F8B8028268F2B1C2
-:10EDE00031462846904780464EE095F89C02002721
-:10EDF000022802D0032843D113E00CB1802C3FD16C
-:10EE0000200604F07F0000EB800005EB800101D5B7
-:10EE1000143101E001F5AA7102220F602CE033E009
-:10EE20002EE0200604F00F0000EB800005EB8000D0
-:10EE300009D5808C20B304F07F0000EB800005EB47
-:10EE4000800614360AE0B0F86401C8B104F07F000F
-:10EE500000EB800005EB800606F5AA764CB1802C0D
-:10EE600007D021462846FFF737FD10B1012030605A
-:10EE700000E03760022231462846FFF7B8FA03E087
-:10EE800031462846FFF78EFA4046BDE8F08170B55E
-:10EE9000054608780E464FF0000410F0600003D0DD
-:10EEA000202801D0402827D195F89C02012803D0C2
-:10EEB000022801D003281FD1B088C1B201291AD875
-:10EEC000C1B22846FFF75CFAFF280CD058B9D5F834
-:10EED000B8128A683AB1C5F8D40228468A68314621
-:10EEE0009047044600E00324F088204307D12846D9
-:10EEF000FFF78AFA03E031462846FFF753FA204627
-:10EF000070BD704700487047A024002070B54D7850
-:10EF100001230A78012D1C4C02F00F0503FA05F3BA
-:10EF2000D0F81C5817D000EB421245EA0343C0F852
-:10EF30001C38D2F8000B00040BD40B890979D2F8E5
-:10EF4000000BC3F30A03184344EA81410843C2F8A3
-:10EF5000000B002070BD9EB23543C0F81C5800EB7A
-:10EF60004213D3F800090004F3D40D890979D3F8CA
-:10EF70000009C5F30A058904284341EA8251084380
-:10EF80002043C3F80009E4E700800010D0F800191E
-:10EF90006FF30A01C0F80019D0F8041841F4807129
-:10EFA000C0F804180020704770B50D460446C2F33F
-:10EFB00007211E460498012922D0E06840F0400055
-:10EFC000E060204600F03CF8C6F307210029A16B61
-:10EFD0002ED021F48031A163C5F3074101290ED160
-:10EFE000E16D154A89B2E165E16D1143E165A16802
-:10EFF00041F00601A160A16841F02001A16070BD4F
-:10F00000A26BC3B20D49012B22F48030A063E068EB
-:10F0100000EA0100E060E06820F44010E06003D105
-:10F02000E06840F48010E060204600F009F8D3E783
-:10F0300041F48031CFE700000000EE03BFFFBDFFC9
-:10F0400008B500214FF070620091009B5B1C00939B
-:10F0500093420CD80369002BF7DA0091016941F063
-:10F06000010101610099491C0091914201D90320DD
-:10F0700008BD0169C907F5D1002008BD70B50A783F
-:10F0800001234C78012C00EB42122CD0D2F8004B1B
-:10F09000002C0BDAD2F8004B44F00064C2F8004BAD
-:10F0A000D2F8004B44F08044C2F8004B0C78D0F802
-:10F0B0003C5804F00F0403FA04F425EA0444C0F8B1
-:10F0C0003C480978D0F81C4801F00F018B401C49DE
-:10F0D00024EA0343C0F81C38D2F8000B0840C2F8F9
-:10F0E000000B002070BDD2F80049002C0BDAD2F8DA
-:10F0F000004944F00064C2F80049D2F8004944F0E5
-:10F100008044C2F800490D78D0F83C4805F00F055E
-:10F110000C4E03FA05F5ADB2AC43C0F83C48D0F84C
-:10F120001C48097801F00F018B4099B28C43C0F85C
-:10F130001C48D2F800093040C2F80009D1E70000AD
-:10F140000078F3EF007833ECD0F8001E21F00301D3
-:10F15000C0F8001ED0F8041821F00201C0F804180D
-:10F1600000207047D0F8001E21F00301C0F8001EF7
-:10F17000D0F8041841F00201C0F8041800207047CC
-:10F180002DE9F04F00250F46904604462E462846AE
-:10F1900004EB8001C1F80451401C0F28F8D3C3F3DD
-:10F1A00007405FEA0009204610D0806B40F4001150
-:10F1B000C4F83810C8F30720C4F8005E01282046C0
-:10F1C00017D0D0F8001841F0030119E0D0F8040876
-:10F1D00040F00201C4F80418A06B20F40011A163F0
-:10F1E000206840F040012160206840F080012160EB
-:10F1F000E0E7D4F80018380E204601D041F00101B4
-:10F20000C0F80018102100F08CFA00B10126204649
-:10F2100000F06BFA00B101264FF67F3A4FF0006C18
-:10F22000C4F810584FF0904BC4F81458C4F81C5848
-:10F230000020FAB214E000BF04EB4011D1F800390D
-:10F24000002B06DA10B1C1F800B904E0C4F800C917
-:10F2500001E0C1F80059C1F81059C1F808A9401CD3
-:10F260008242E9D8002013E004EB4011D1F8003BC2
-:10F27000002B06DA10B1C1F800BB04E0C4F800CBE3
-:10F2800001E0C1F8005BC1F8105BC1F808AB401C9D
-:10F290008242E9D8D4F81008C7F30742002A6FF079
-:10F2A000804120F48072C4F81028A561616103D107
-:10F2B000A06940F01000A061A069C8F30741094AA5
-:10F2C0001043A06119B1A06940F00800A061B9F134
-:10F2D000010F03D1A06904490843A0613046BDE88D
-:10F2E000F08F000000383C8004000040816821F06D
-:10F2F000010181600020704710B5144C036CA342DB
-:10F3000003D9D0F8003B002B1EDB0023C0F8103BD4
-:10F310000129D0F8101B41F40021C0F8101BD0F8CF
-:10F32000101B41F01801C0F8101BD0F8101B41F061
-:10F33000C041C0F8101B07D1C0F8142BD0F8001B37
-:10F3400041F08021C0F8001B002010BD0A30544F4E
-:10F350000B784A78012A00EB43100BD0D0F8002B31
-:10F3600022F40012C0F8002B0979032914D00229D5
-:10F3700012D017E0D0F8002922F40012C0F80029BA
-:10F380000979032901D002290CD1D0F8001941F0E4
-:10F390008051C0F8001905E0D0F8001B41F0805101
-:10F3A000C0F8001B002070470A784B78D1B2012BBF
-:10F3B00000EB421012D0D0F8002B002A06DB29B156
-:10F3C000D0F8001B21F08041C0F8001BD0F8001BD2
-:10F3D00041F40011C0F8001B00207047D0F800294C
-:10F3E000002A06DB29B1D0F8001921F08041C0F8CD
-:10F3F0000019D0F8001941F40011C0F80019EBE72A
-:10F40000F8B50B786FF060464F788C4DDCB2012F69
-:10F4100000EB43132BD0D3F8107B002C07EAC54434
-:10F42000C3F8104BD3F8104B04EA0504C3F8104B93
-:10F430007ED00D69002D7CD08C6825446D1EB5FBF7
-:10F44000F4F5ADB26C430C6206EAC545D3F8104B37
-:10F450002C43C3F8104BD3F8104B0D6AC5F31205BB
-:10F4600054EA0504C3F8104B012A73D0CEE00F69AB
-:10F4700007B3D3F810796FF31207C3F81079D3F8F4
-:10F48000107907EA0507C3F810791CB3D1F810C04A
-:10F490008D68D3F81079AC44ACF1010CBCFBF5F5E8
-:10F4A000ADB206EAC5463743C3F810790E79012E8E
-:10F4B0001CD02AE0D3F810692E40C3F81069D3F8A5
-:10F4C000105945F40025C3F81059D3F810596FF3BB
-:10F4D000120520E00E698D68AE4200D90D61D0F8AA
-:10F4E000106946F40026C0F810690EE0D3F81069E0
-:10F4F0004FF0C04707EA457726F0C046C3F81069C9
-:10F50000D3F810593D43C3F810590E69D3F8105978
-:10F51000C6F312063543C3F81059012A1BD000EB7D
-:10F520004413D3F8004944F00444C3F8004901E00F
-:10F5300047E05AE00C79012C2ED00A695AB30B78B7
-:10F54000D0F83418012203F00F039A401143C0F899
-:10F55000341871E056E0CA691AB100EB4413C3F8DD
-:10F560001429097901290ED1D0F80818C90500EB32
-:10F570004411D1F8002902D442F0005201E042F0D7
-:10F580008052C1F8002900EB4410D0F8001941F076
-:10F590000441C0F800194FE0D0F80848E405D3F85A
-:10F5A000004902D444F0005401E044F08054C3F810
-:10F5B000004900920B8A0A78C9689BB200F0E0F912
-:10F5C0003AE00C690CB18C680C618C680C62C4F375
-:10F5D0001205D0F8104B2C43C0F8104BD0F8104B4C
-:10F5E00044F40024C0F8104B3EE78D68D3F8104B6C
-:10F5F000C5F312052C43C3F8104BD3F8104B44F459
-:10F6000000242FE7CA680AB1C3F8142B097901292D
-:10F610000CD1D0F80808C005D3F8000B02D440F094
-:10F62000005001E040F08050C3F8000BD3F8000B0D
-:10F6300040F00440C3F8000B0020F8BDFFFF07E0D6
-:10F6400038B5002242F21074002300920A784D78F7
-:10F65000012D00EB421219D0D2F8005B002D3CDAEC
-:10F66000D2F8005B45F00065C2F8005B0A7800EB59
-:10F670004212D2F8005B45F08045C2F8005B009A68
-:10F68000521C0092A24221D9012326E0D2F800594F
-:10F69000002D22DAD2F8005945F00065C2F8005971
-:10F6A0000A7800EB4212D2F8005945F08045C2F8C2
-:10F6B0000059009A521C0092A242E5D80A7800EB49
-:10F6C0004212D2F80029002AF3DB06E00A7800EBA8
-:10F6D0004212D2F8002B002AD1DB184638BD8168CF
-:10F6E00041F0010181600020704708B500214FF012
-:10F6F00070620091009B5B1C009393420AD80369DF
-:10F70000002BF7DA0091102303610099491C009146
-:10F71000914201D9032008BD0169C906F5D4002032
-:10F7200008BD18B500224FF070630092009C641C65
-:10F7300000949C420CD80469002CF7DA2024009233
-:10F7400044EA811101610099491C0091994201D953
-:10F75000032018BD01698906F5D4002018BDD0F832
-:10F76000080810F0060004D0022803D0062801D0B3
-:10F770000F20704702207047406900F00100704779
-:10F78000D0F81818D0F81C08084080B27047D0F89C
-:10F790001818D0F81C080840000C704710B5D0F8B5
-:10F7A000102801F00F0300EB4114D0F83418D4F8FE
-:10F7B0000809D94001F0010142EAC111084010BD19
-:10F7C00000EB4111D1F8081BD0F81408084070472D
-:10F7D00041698069084070470346084630B594087F
-:10F7E00002F00301002203F5805303E01D68521C60
-:10F7F00040F8045BA242F9D300290CD01C68002316
-:10F80000491EDD00090403F10103090C24FA05F285
-:10F8100000F8012BF4D130BD70B50446C068012951
-:10F820004FF0000520F0C040E06001D079B120E049
-:10F83000E06840F00050E0600A20F6F7D1FB606914
-:10F840000A3510F0010F10D1C82DF5D30DE0E06896
-:10F8500040F08040E0600A20F6F7C2FB60690A359C
-:10F8600010F0010F01D0C82DF5D3C82D01D0002014
-:10F8700070BD012070BDD0F800284FF4FE6303EA8C
-:10F88000011322F4FE62C0F80028D0F800181943D2
-:10F89000C0F8001800207047022A3ED1264A274BA4
-:10F8A0000A449A4201D20F2138E0254A254B0A44E6
-:10F8B0009A4201D20E2131E0234A244B0A449A4253
-:10F8C00001D20D212AE0224A224B0A449A4201D257
-:10F8D0000C2123E0204B214A0B44934201D20B21FF
-:10F8E0001CE01F4B1F4A0B44934201D20A2115E032
-:10F8F0001D4B1E4A0B4493420FD31D4B1D4A0B4414
-:10F90000934201D2082109E01B4B1C4A1944914241
-:10F9100001D2072102E0062100E00921C2684FF46C
-:10F92000705322F47052C26003EA8123C168194304
-:10F93000C160002070470000405327FF00350C00D5
-:10F94000401E1BFF40420F0000DC0BFF804F1200E7
-:10F95000808CF9FE20D6130060B6E5FE60E3160049
-:10F9600000D3CEFE40771B00C05BB3FEC0912100E8
-:10F9700000CA91FE20753800E05459FEE09C410019
-:10F9800010B5029C74B900EB0232DB1C00209B080E
-:10F9900002F5805204E000BF51F8044B1460401C93
-:10F9A0009842F9D3002010BDFEE703B4019841004E
-:10F9B000009850EAC12018BF04204A0D18BF40F03B
-:10F9C000010040F2FF72B2EB515F08BF40F002004D
-:10F9D000012808BF052002B070474100080218BF87
-:10F9E00004200A0E18BF40F001004FF07F4232EAB7
-:10F9F000010108BF40F00200012808BF0520704740
-:10FA0000090700284FEA116104DB00F1E02080F8CB
-:10FA10000014704700F00F0000F1E02080F8141D82
-:10FA20007047000010B54FF00E402DED028BB0EE88
-:10FA3000408A18EE104A00EB4400B0F1506F4AD8EB
-:10FA40004FF0FC40B0EB440F22D2B0EEC80ADFED1D
-:10FA5000360A30EEC00ADFED350A60EE208A18EE75
-:10FA6000900A01F0A7FE01EE100A14F0004F1DBF2E
-:10FA7000DFED2F0A9FED2F0AB1EE411ADFED2E0ABE
-:10FA800008BF9FED2E0ADFED2E1A21EE218A05E038
-:10FA9000DFED2C0A68EE088AB0EE600A9FED2A1AA4
-:10FAA000DFED2A1A30EE080A48EE811A9FED281A77
-:10FAB00008EEA11ADFED271A48EE811A9FED261AEB
-:10FAC00008EEA11A68EE281ABDEC028B01EE810A3D
-:10FAD00030EE200A10BD4FF0E440B0EB440F0CD9DB
-:10FAE00018EE100AFFF779FF042808BF00F036FD72
-:10FAF000B0EE480ABDEC028B10BD4FF07F40B0EB7A
-:10FB0000440F07D2B0EE480ABDEC028BBDE81040AE
-:10FB100000F016BD0120F0F71AFFBDEC028BBDE826
-:10FB2000104000F013BD00000000803F0000003FC7
-:10FB30000000C9BF22AAFDB90000C93F22AAFD39B1
-:10FB4000000000C00000000024FE1C3DC78AD83C15
-:10FB50001E67383D1B93993DAFAA2A3E0000000066
-:10FB600070B565482DED020B2DED048B059D25F03C
-:10FB70000044A04218DC6148844202DC0AD10498A7
-:10FB800040B19DED040BBDEC048B02B0BDE87040AC
-:10FB900000F0C4BC002DCCBF9FED590B9FED5A0B5C
-:10FBA000BDEC048B02B070BD5948A04215DD594828
-:10FBB000A042D8BF4FF0FF3455DD9DED040B51EC52
-:10FBC000100BFFF7F2FE042808BF00F0ADFC9DED1E
-:10FBD000040BBDEC048B02B070BD9DED040B51EC29
-:10FBE000100B00F031FECDE904014B489FED4C0BAA
-:10FBF000A0421CDD4C48A0420BDD9DED042B0024EF
-:10FC00009FED4B1B12EE010B32EE011B80EE012B20
-:10FC100027E09DED041B9DED042B012431EE401BDC
-:10FC200032EE000B81EE002B8DED042B1BE04248E1
-:10FC3000A0420FDD9DED042B02249FED411B9DEDA5
-:10FC4000043B32EE412B03EE010B82EE001B8DEDE7
-:10FC5000041B08E09DED040B9FED3B1B032481EE8C
-:10FC6000002B8DED042B9DED040B3948062120EE71
-:10FC7000009B29EE098BB0EE480B784400F016FC8F
-:10FC800020EE099B3348B0EE480B0521784400F084
-:10FC90000DFC20EE080B002C0BDA9DED042B39EE49
-:10FCA000001B9DED040BBDEC048B02B002EE410B7A
-:10FCB00070BD2948784439EE000B00EBC4009DED7F
-:10FCC000042B90ED001B254812EE001B9DED040B4C
-:10FCD00031EE400B784400EBC400002D90ED001B8A
-:10FCE00031EE400BB8BFB1EE400BBDEC048B02B05F
-:10FCF00070BD000000000000000010440000F07F14
-:10FD0000182D4454FB21F93F182D4454FB21F9BF11
-:10FD10000000DC3F0000203E0000F33F0000000038
-:10FD2000000000000000F03F0000E63F000000007F
-:10FD300000000000000000400080034000000000C0
-:10FD4000000000000000F83F000000000000F0BFCD
-:10FD5000823400004834000000340000C03300004A
-:10FD600070B5614E2DED040B2DED048B82B0DDF8E6
-:10FD700024C0DDE907235C422CF000411C4341EA2A
-:10FD8000D474069D22F00040B44205D86C422C4346
-:10FD900040EAD474B4420BD99DED081B9DED060BCF
-:10FDA00002B0BDEC048B04B0BDE8704000F0B9BBFC
-:10FDB000ACF14054A4F17F641C430BD0022404EA4C
-:10FDC000AC7444EAD27405439FED498B9FED4A2BF6
-:10FDD0000DD016E09DED060B51EC100B00F077FCFA
-:10FDE00041EC100B02B0BDEC048B04B070BD002CD4
-:10FDF00014BF012C9DED060BF4D0022C2ED0032C49
-:10FE00002FD00B439FED3E1B9FED3F0B0AD0B1421D
-:10FE10001DD1B04209D121F0804120F080400991EC
-:10FE2000079014E0002ADDDA15E0394B7B44002C02
-:10FE300008BF93ED000BD5D0012C04BF93ED000B50
-:10FE4000B1EE400BCED0022C08D0032C09D0B0422A
-:10FE50000AD1002AC6DAB0EE410BC3E7B0EE480B78
-:10FE6000C0E7B0EE420BBDE7401A00159FED2A9B9C
-:10FE70003C28C8BF8DED000B15DCBCF1000FBCBFEA
-:10FE800010F13C0F8DED009B0DDB9DED061B9DEDF4
-:10FE9000082B81EE020B51EC100B00F0D5FC00F0AA
-:10FEA00016FCCDE9000194B1012C0CD09DED001B96
-:10FEB0009FED1B0B022C31EE400B0CBF38EE400BBC
-:10FEC00030EE480B8EE7019880F0004001909DEDE8
-:10FED000000BB4EE490BF1EE10FA04BF0220F0F76C
-:10FEE00036FD9DED000B7DE70000F07F0000000077
-:10FEF000182D4454FB210940182D4454FB2109C0FE
-:10FF0000182D4454FB21F9BF182D4454FB21F93F0F
-:10FF100000330000000000000000000000000000AE
-:10FF2000075C143326A6A13C70B54FF068422DED56
-:10FF3000048BF0EE408A18EE900AB0EE608A18EE5C
-:10FF4000101A02EB4003B3F1654F3CBF02EB4102D4
-:10FF5000B2F1654F7DD200BFC0F3C753C1F3C752A2
-:10FF60009A1A1B2A09DD10F0004F14BF9FED830A77
-:10FF70009FED830ABDEC048B70BD12F11A0F36DAC7
-:10FF800011F0004F09D010F0004F0CBF9FED7D0A1B
-:10FF90009FED7D0ABDEC048B70BD88EE889A19EE4A
-:10FFA000100AFFF71AFD042808BF00F0D7FA18EE70
-:10FFB000900AFFF712FD054618EE100AFFF70DFD37
-:10FFC000044619EE100AFFF708FD042D18BF052D91
-:10FFD00008D1042C18BF052C04D1002804BF02202E
-:10FFE000F0F7B5FCB0EE490ABDEC048B70BD4200E1
-:10FFF000B2EB410F3AD910F0004F19BFDFED630AA1
+:1031800070470000509B002005280ED2DFE800F0B9
+:103190000305070B090006487047064870470648B4
+:1031A0007047064870470648704700207047000087
+:1031B000AC090020680B0020FC0B0020400A002016
+:1031C000900C002070B504460068C169C90617D587
+:1031D0001021016220460AF043FD0A4D00EBC000B9
+:1031E00005EB8000006A00280AD020460AF038FD6E
+:1031F00000EBC00005EB8000006ABDE870400047AE
+:1032000070BD00005C9A002042B1064B00EBC0008C
+:1032100003EB800040F82120002070476FF0010090
+:10322000704700005C9A00200FB4104840F2FF3154
+:1032300070B505AB049AFDF70BFA05042D0C11D0FF
+:103240000A4E00242946304600F04CF830B1641C88
+:103250000A20E4B2FFF7FAFE032CF3D3002070BC7F
+:103260005DF814FB6FF00100F9E70000F09B00200F
+:103270000849002070B5084E0A88B35C002B08D0BE
+:1032800000251846541CA3B2B554802B0B8000D3E4
+:103290000D8070BDA0010020709B0020FEE7002083
+:1032A000704700207047000005490022054810B50E
+:1032B0000BF082F9044903480BF071F9002010BDAE
+:1032C000841E0020A811002084160020034801213C
+:1032D00010B500680DF09CFF002010BDA401002077
+:1032E00000207047094A10B5D2F8BC22D2F8142247
+:1032F0000AB1012010BD0A46014604480BF05CF9F2
+:10330000BDE8104001480BF0CDB90000A811002025
+:1033100008B1002070474FF0FF3070474FF0FF3288
+:1033200010B560B159B1437C002253B1047C44B163
+:10333000012B08D0022B09D0032B08D105E0104641
+:1033400010BD0A711CE00A7101E001230B71037CBE
+:103350002BB1012B03D0022B01D0032B00D14A71DA
+:1033600090ED030A81ED030A90ED020A81ED040A53
+:1033700090ED000A81ED050A90ED050A81ED020A43
+:10338000002010BD2DE9F04304006FF001002DED89
+:10339000068BC3B07CD000297AD02068101A00EECA
+:1033A000100ADFED860A864DB8EE400A80EE201A3C
+:1033B00084ED011A2260087884F8900120B1012878
+:1033C00013D0022822D122E0F0216846FDF765FAE9
+:1033D0007C49F0226846FDF704FAF022694604F1C0
+:1033E0009C00FDF7FEF900200FE00026744914222E
+:1033F00006EB8600091D04EB80009C30FDF7F1F917
+:10340000761CF6B20C2EF1D301202870A5E09FEDBA
+:103410006E8A28780227F1EE049A0228B2EE04AAF6
+:10342000F9EE048ABAEE049A44D000264FF003085D
+:10343000B6FBF8F108FB1160002806EB860028D0E7
+:103440005F4904EB8000142218319C30FDF7C9F964
+:1034500094ED630A761CF6B260EE290A20EE0A1A91
+:1034600060EE281A20EE090AC4ED2E0A84ED331A04
+:10347000C4ED3D1A84ED420AC4ED4C0A84ED511AA4
+:10348000C4ED5B1A84ED600A0C2E2F70D0D364E07B
+:103490008FE0B7EE000ADFED4D0A04EB800080ED0F
+:1034A0002A0AC0ED2B0A80ED298A80ED278A80ED5B
+:1034B000288ACDE784ED298A84ED478A84ED388A0D
+:1034C00084ED568AD1ED010A94ED630A3D4E00EE7B
+:1034D000810A803684ED630A60EE290A20EE0A1A1A
+:1034E00060EE281A20EE092AC4ED2E0A84ED331A64
+:1034F000C4ED3D1A84ED422AC4ED4C0A84ED511A04
+:10350000C4ED5B1A84ED602A2F70DC275FF00005A4
+:1035100006F170003CAB07C883E8070005EB4500E7
+:10352000A1683FAA07EB80000B18C4313CA808F043
+:10353000C5F9C5EB05109DED3F0A04EB80006D1C3D
+:1035400080ED290A9DED400AEDB280ED2E0A9DED39
+:10355000410A042D80ED330ADAD394264FF0640833
+:103560009FED1B8A00254FF0340900BFA06809EBCE
+:10357000850C08EB8507844405EB45039CED000AA8
+:1035800006EB850105EB85020744014404EB830348
+:1035900060EE080A04EB8200A430D7ED001A91ED2A
+:1035A000001A93ED050A08F057FA6D1CEDB20C2DC8
+:1035B000DCD343B0BDEC068BBDE8F08300007A4459
+:1035C000E0010020B031010800000000CDCCCC3D6E
+:1035D0008FC2F53C2DE9F04105000E461ED0002EAD
+:1035E0001CD004274FF034085FF00004A86807EBF4
+:1035F000840308EB840204EB84010344024405EBDA
+:1036000081009C30D3ED000A92ED000A06EB8101A7
+:1036100008F0E7F9641CE4B20C2CE7D3BDE8F081B4
+:1036200048B19FED060A8160002280F8902180ED6C
+:10363000630A104670476FF001007047CDCC4C3ED6
+:103640002DE9F04104270E46002405464FF03408CA
+:1036500007EB8403A86808EB840204EB44010344ED
+:10366000024405EB81000C30D3ED000A92ED000A14
+:1036700006EB810108F09FF9641CE4B20C2CE7D33F
+:10368000BDE8F081002804D002494FF4A472FDF790
+:10369000A8B870470C020020014801F079BE000074
+:1036A000C8030020014801F073BE0000240D002073
+:1036B000014801F06DBE00008C070020014801F0B8
+:1036C00067BE000004080020014801F061BE000050
+:1036D0007C0F0020014801F05BBE0000F40F0020C9
+:1036E000014801F055BE00008C0E0020014801F099
+:1036F0004FBE0000040F0020014801F049BE000049
+:103700006C100020014801F043BE00009C0D002019
+:10371000014801F03DBE0000140E0020014801F0F8
+:1037200037BE0000E4100020294A016891423AD0D7
+:10373000274A1832914236D0254A3032914232D04F
+:10374000234A483291422ED0214A603291422AD0F7
+:103750001F4A7832914226D01D4A9032914222D09F
+:103760001B4AA83291421ED01A4A91421BD0194AD4
+:103770001832914217D0174A3032914213D0154A6D
+:10378000483291420FD0134A603291420BD0114A15
+:103790007832914207D00F4A9032914203D00D4ABD
+:1037A000A832914211D1CAB21823103AB2FBF3F2F7
+:1037B0006FF30901032A02F00703074AD25CC265CE
+:1037C00000D9091D81650846704721F0FF01F9E71E
+:1037D00010000240100402400431010830B5224AB2
+:1037E000012301689142CAB21BD01F4C1434A1427C
+:1037F00017D01D4C2834A14213D01B4C3C34A1429D
+:103800000FD0194C5034A1420BD0174C6434A14254
+:1038100007D0154C7834A14203D0134C8C34A1420C
+:103820000CD11421114C083AB2FBF1F10F4A80324D
+:1038300001F01F0504EB8101AB4010E00C4D182492
+:10384000103A0D44B2FBF4F1A82D00D80831094A12
+:1038500001F01F0402EB8101064AA3408032603070
+:1038600080E80E0030BD000008540258005802588D
+:10387000F0FBFDBF0008024010B50279531E072B74
+:103880002DD8174C0168A1421BD0154C1434A1420D
+:1038900017D0134C2834A14213D0114C3C34A14210
+:1038A0000FD00F4C5034A1420BD00D4C6434A142C8
+:1038B00007D00B4C7834A14203D0094C8C34A14280
+:1038C00003D10849074C443102E00749064C443112
+:1038D00004EB8202C0E91B2101219940416710BD20
+:1038E00008540258FC580258FC08024010B583697D
+:1038F0004FF0C074826A0146002053B1B3F5005FF7
+:1039000015D072B1012A0CD0022A0AD0032A09D19B
+:1039100004E01AB1012A06D0022A03D1C96AC901FA
+:1039200000D5012010BDC96AA142FAD010BD002AFD
+:10393000F7D0012AF2D0022AF3D0032AF3D010BD27
+:103940002DE9F04F804E804FDFF8FC911836DFF8FC
+:10395000F8A148370468856D0AF1300ADFF8ECB148
+:103960004C45DFF8ECC1DFF8ECE16DD0B4426BD030
+:10397000544569D0BC4267D0DFF8D081A8F118085F
+:10398000444561D05C455FD064455DD074455BD0F3
+:10399000DFF8C481444557D0DFF8BC8108F118082E
+:1039A000444551D0DFF8B08108F1300844454BD090
+:1039B000DFF8A48108F14808444545D0DFF8988134
+:1039C00008F1600844453FD0DFF88C8108F17808A1
+:1039D000444539D0DFF8808108F19008444533D060
+:1039E000DFF8748108F1A80844452DD0DFF86C8118
+:1039F000444529D0DFF8648108F11408444523D0F8
+:103A0000DFF8588108F1280844451DD0DFF84C81C3
+:103A100008F13C08444517D0DFF8408108F1500810
+:103A2000444511D0DFF8348108F1640844450BD0D7
+:103A3000DFF8288108F17808444505D0DFF81C81BB
+:103A400008F18C08444509D1D0E91948C4F804802C
+:103A5000C46E1CB1D0E91C48C4F8048004684C450D
+:103A60002ED0B4422CD054452AD0BC4228D0374E58
+:103A7000183EB44224D05C4522D0644520D0744521
+:103A80001ED0354EB4421BD0334E1836B44217D038
+:103A9000314E3036B44213D02F4E4836B4420FD098
+:103AA0002D4E6036B4420BD02B4E7836B44207D040
+:103AB000294E9036B44203D0274EA836B44215D1D1
+:103AC00090F85C603F2406F01F06B440AC600468C8
+:103AD000256825F4802525602EE09A600068C16085
+:103AE000BDE8F08F99600068C260F9E71B4EB442F0
+:103AF0001BD01A4E1436B44217D0184E2836B44292
+:103B000013D0164E3C36B4420FD0144E5036B44249
+:103B10000BD0124E6436B44207D0104E7836B44201
+:103B200003D00E4E8C36B442DAD190F85C6001249A
+:103B300006F01F06B4406C60046863608368402B25
+:103B40000368CFD1C9E7000010000240880002409E
+:103B5000A0000240B800024010040240085402587D
+:103B600000F0AEB810B520B11621FCF774FE0020AD
+:103B700010BD6FF0010010BD70B56FF00105B8B158
+:103B80000C4C207810B16FF0020070BD0DF0C6FB38
+:103B9000606068B1084A03210020FFF735FB074A3F
+:103BA00004210020FFF730FB01202070002070BDB1
+:103BB000284670BDC0010020E93C0008613B0008B8
+:103BC00010B504001ED0124900F0B3F821884FF45C
+:103BD000A560A1F5B671814217D86188A1F5B671CB
+:103BE000814212D8A188A1F5B67181420DD8E18831
+:103BF000A1F5B671814208D8207A30B1607A20B13F
+:103C0000002010BD6FF0010010BD4FF0FF3010BD5F
+:103C100000000024F0B3E9B30288DFED270A01EECB
+:103C2000902AB0EE001A9FED250AF8EE611A71EEA7
+:103C3000E01A61EE811A81EE802A81ED002A428825
+:103C400001EE902AF8EE611A71EEE01A61EE811A27
+:103C500081EE802A81ED012A828801EE902AF8EE19
+:103C6000611A71EEE01A61EE811A81EE802A81ED0F
+:103C7000022AC28801EE902AF8EE611A71EEE01A6B
+:103C800021EE811AC1EE001AC1ED031A427A0A74BC
+:103C9000027A00E00DE04A74808A01EE100A0020EA
+:103CA000B8EE411A71EE600A80EE801A81ED051AB5
+:103CB00070476FF001007047000080440000A54489
+:103CC000002010B5FFF760FA0068016821F00101DB
+:103CD00001600020FFF758FA0068016841F0010117
+:103CE0000160002010BD00000248202140680DF056
+:103CF0008FBA0000C0010020002010B5FFF744FA81
+:103D00000449122207F0E6FC002801D04FF0FF30F2
+:103D100010BD00000000002401210246202010B543
+:103D20000DF0B0FA202801D0002010BD012010BDF8
+:103D30007047002810B535D0002933D00A88C2F367
+:103D40000A0202804A788B78D20842EA4312C2F310
+:103D50000A0242808A78CB780C79920942EA83027F
+:103D600042EA8422C2F30A0282800A794B7952081D
+:103D700042EAC312C2F30A02C2804A79C2F30112B4
+:103D800042724A7992090272CA8842810A89828102
+:103D90004A89C2810A7B02744A7B4274CA89428280
+:103DA000098A818210BD4FF4806010B502F062FD77
+:103DB0004FF4805002F05EFDBDE810404FF400402B
+:103DC00002F058BD72B6FEE7054805490839026899
+:103DD00042F00202026008688004FCD570470000CF
+:103DE0000C480258014802F089B900004004002044
+:103DF000014802F083B9000040040020014802F0AD
+:103E00007DB90000E0040020014802F077B900000D
+:103E1000E0040020014802F071B900008005002094
+:103E2000014802F06BB9000080050020F0B503687E
+:103E30004FF6FC716D4C426BD3F884508D4345EACC
+:103E40008205C3F88450036853F8845F068F25F415
+:103E50007F0545EA06451D60836B654D9F18026826
+:103E6000D2F888308B4343EA8703C2F8883002686F
+:103E700052F8883F868F23F4FE0343EA064313601B
+:103E8000066856F8A03FC26B8B4307EB420243EA39
+:103E900082033360076857F8A03FB0F8406023F40E
+:103EA000FE0343EA06433B60D0E9103603FB0622DB
+:103EB0000368D3F8B0608E4346EA8206C3F8B06068
+:103EC0000368B0F84860D3F8B07027F4FE0747EAFB
+:103ED0000646C3F8B060D0E91267036806FB072204
+:103EE000D3F8AC608E4346EA8206C3F8AC60D0E9F2
+:103EF0001467036806FB0722D3F8F0608E4346EA96
+:103F00008206C3F8F0600368B0F85860D3F8F07028
+:103F100027F47C1747EA0646C3F8F0600368876D0C
+:103F200053F8C06F02EB47028E4346EA82011960E4
+:103F30000168B0F85C20D1F8C03023F47C1343EA68
+:103F40000242C1F8C020016890F86020D1F8C0306A
+:103F500023F07C5343EA0262C1F8C020416B04EBBA
+:103F60008101C166826B01EB82020267C36B02EBC7
+:103F7000C3024267D0E91034634302EB83028267D5
+:103F8000D0E91234634302EB8302C267D0E91434F0
+:103F9000634302EB8302C0F88020836D02EBC3030E
+:103FA000C0F88430C46D826E544303EB8403C0F8C0
+:103FB0008830046E544303EB8402C0F89020AA4278
+:103FC0000AD9D0F89C20032142F02002C0F89C209E
+:103FD00080F898100120F0BD002200E004C1D0F864
+:103FE00090308B42FAD80020F0BD000000AC0040B9
+:103FF000FCD3004000487047F09F00202DE9F047B7
+:104000002F4C0546012691468A464FF0000860680D
+:10401000A0BB04F10C0010E0006807683846FCF70C
+:1040200031FB0246A85C202800D020B9394628463A
+:10403000FCF747FB28B16068406860600028EBD15E
+:1040400034E0D4F804C0DCF8000090F90C70002FC4
+:1040500010DB00202946024603E0202B18D0002266
+:10406000491C0B78002BF8D10AB1401E40B2B8426F
+:1040700000D00026BCF1000F18D07EB160682A463F
+:104080004946006883685046984706000BD013E005
+:10409000002AE5D10122401C40B2E1E709494A4625
+:1040A0005046FCF721FCC4F8048005E006494A4666
+:1040B0005046FCF719FC00263046BDE8F0870000AA
+:1040C000AC010020083801086038010870B505000F
+:1040D00011D008200DF068FD040014D00DF0C6FECC
+:1040E0000D480021C4E9005101684C6004600DF0E6
+:1040F000DDFE012070BD502080F31188BFF34F8F8B
+:10410000BFF36F8FFEE7502080F31188BFF34F8F0E
+:10411000BFF36F8FFEE70000AC01002070B5040014
+:104120006FF0010006D0002904D00B4D287810B1A3
+:104130006FF0020070BD2046C4F8E0144FF4047123
+:10414000FCF7ABFB4FF4347104F50470FCF7A5FBEE
+:1041500001202870002070BDD00100202DE9F04121
+:10416000060025D02A48007830B301275FF000040C
+:1041700004EB440000EBC40006EB800526F8204069
+:1041800028466F800CF020FE032C02D3A01F0328CA
+:1041900015D2D6F8E0040078FEF7F6FF01231122CD
+:1041A00005F1180107F0E2FAD6F8E004007814E00F
+:1041B0006FF00100BDE8F0816FF00200FAE7D6F879
+:1041C000E0044078FEF7E0FF0123112205F1180119
+:1041D00007F0CCFAD6F8E0044078FEF7D5FFC4EB40
+:1041E0000411012306EB8101102201F50F7107F084
+:1041F000FDF9C4EB041006EB800000F504700CF030
+:104200003DFD641CE4B20C2CB2D30020D2E70000C8
+:10421000D001002030B56FF0010228B321B3002295
+:10422000551C02EB820302EB420401EB830304EB17
+:10423000C20293ED030A00EB8204EAB284ED040AA1
+:1042400093ED040A0C2A84ED050A93ED020A84ED2D
+:10425000030A93ED010A84ED020A93ED000A84ED4E
+:10426000010ADDD3002030BD104630BD6FF00102E1
+:1042700010B5D8B1D1B10022C2EB021402EB420357
+:1042800000EB840401EB830394ED890A521C83ED57
+:10429000020A94ED880AD2B283ED010A94ED870AEE
+:1042A0000C2A83ED000AE7D3002010BD104610BD94
+:1042B0002DE9F0470F4690F85C109CB004460129A8
+:1042C0004FF0000915D00026DFF8F880012084F8AF
+:1042D0005C0018961996216841450ED13A4D00951B
+:1042E000284607F0A8FB8246206807F0A4FB60B1CF
+:1042F0000EE002201CB0BDE8F087206E84F85C6000
+:1043000040F0200020660120F4E7BAF1000F09D048
+:10431000216E4FF0010941F020002066484684F8E4
+:104320005C60E7E720684146884201D0A84201D19D
+:10433000264800E0264840F61F72D7F800C0254BFB
+:10434000BCF1000F23D0D0F808C0D7F804802CF4BB
+:10435000404C4CEA080CC0F808C0D4F800C08C45AA
+:1043600001D0AC4507D18968AB6801F0010103F0C9
+:104370000103194302E0996801F001010029CDD140
+:10438000BD683968836829439343194317E08768F8
+:1043900027F44047876027688F4201D0AF4207D19A
+:1043A0008968AB6801F0010103F00103194302E0E1
+:1043B000996801F001010029B0D1816891438160C1
+:1043C000ACE7000000200240002102400023024030
+:1043D00000630258006002582DE9F84F0446DFF8E8
+:1043E000ECB30020FA4E0090814694F85C000D4634
+:1043F000F84F012808D04FF0010A84F85CA020682B
+:1044000007F015FB18B18FE20220BDE8F88F28688D
+:1044100000280FDB2168B1420CD0CA69030327D002
+:1044200090FAA0F0B0FA80F000F01F030AFA03F04F
+:104430000243CA61D5E900124FF00C0C20681F231B
+:10444000C1F384610CEA921C02F01F0260449340A5
+:104450009140026B9A430A430263206807F0E7FA2F
+:104460008046206807F0DFFA58EA000003D054E1E4
+:10447000C0F38460D8E729684FF0040C2068072354
+:10448000AA680CEAD15CC1F3045160448B408A40B5
+:1044900041699943114341612068B04204D1C26827
+:1044A0006969C2F3C1020BE0CB4A1268BAEB127F12
+:1044B00002D0C168C90605D4C2686969C2F3820224
+:1044C000520004E0C268696902F01002520891408B
+:1044D0002A69042A5AD02B6800EB8202B04202F10A
+:1044E000600207D103F0F8401368084340F0004031
+:1044F000106008E0D2F800C003F0F84008430CF068
+:104500000041014311602068B0421CD12969EA6969
+:1045100000EB8100016E21F080711143016695F876
+:10452000201020682A6901290AD00021B0429ED1BA
+:1045300000EB8200026E22F000720A430266ECE099
+:104540004FF00071F2E795F821102A69012917D080
+:104550005FF0000100EB8200026E22F000420A438D
+:104560000266297E20682A6901290CD0002103698E
+:1045700002F01F02914023F4F0420A430261CCE0B2
+:104580004FF00041E6E74FF40061F0E7B04273D12D
+:10459000002107F042FA000320684FF000016DD0BF
+:1045A00007F03BFA90FAA0F0B0FA80F12868020315
+:1045B00069D090FAA0F0B0FA80F0814204D10022D4
+:1045C0002068114607F03CFA2068012107F025FA1F
+:1045D000000320684FF0010158D007F01EFA90FA4E
+:1045E000A0F0B0FA80F12868020354D090FAA0F04D
+:1045F000B0FA80F0814204D120680022012107F046
+:104600001FFA2068022107F008FA000320684FF023
+:10461000020143D007F001FA90FAA0F0B0FA80F15D
+:10462000286802033FD090FAA0F0B0FA80F08142EF
+:1046300004D120680022022107F002FA2068032139
+:1046400007F0EBF9000320684FF003012ED007F0CC
+:10465000E4F990FAA0F0B0FA80F1286802032AD0B9
+:1046600090FAA0F0B0FA80F0814256D12068002282
+:10467000032107F0E5F950E020E0FFE707F0CDF96E
+:10468000C0F3846192E7C0F3846096E707F0C5F950
+:10469000C0F38461A7E7C0F38460ABE707F0BDF91E
+:1046A000C0F38461BCE7C0F38460C0E707F0B5F9EC
+:1046B000C0F38461D1E7C0F38460D5E7016E2A7846
+:1046C00001F0F841B1EB826F03D1016E21F000419E
+:1046D000016620682978426E02F0F842B2EB816FE1
+:1046E00003D1416E21F00041416620682978826E35
+:1046F00002F0F842B2EB816F03D1816E21F00041EC
+:10470000816620682978C26E02F0F842B2EB816FB0
+:1047100003D1C16E21F00041C1662068816811F0AB
+:10472000010F52D12D4AB042EB6829680FD1D0F861
+:10473000B0C003F01808C1F3130322FA08F20A40CC
+:104740002CEA030C4CEA020CC0F8B0C00EE0D0F822
+:10475000C0C003F01808C1F3130322FA08F20A409C
+:104760002CEA030C4CEA020CC0F8C0C0E9685945B9
+:1047700070D11B482268DFF86CC0DFF86CB0824251
+:10478000DFF868E01A481B4BDFF86C8043D12968DA
+:10479000614565D0B1EB4C0C6DD0714569D0A1F18C
+:1047A000865CBCF1100C75D0DFF850C061456DD04F
+:1047B000DFF84CC061457FD0814273D0994247D029
+:1047C0001048814222D1104876E0B3E00000FF4754
+:1047D00000600258002102400010005CFFFF0F0043
+:1047E0000020024002003004400020190800900C14
+:1047F0000008302E00106032002090362000F014A7
+:104800000004002A00002143000052476E48814204
+:1048100051D16E4850E0BA421DD1296861451FD080
+:10482000A1F1066CBCF1040C25D0714521D0A1F199
+:10483000865CBCF1100C2DD0DFF894C1614525D009
+:10484000DFF890C1614537D081422BD09942DDD14C
+:10485000404631E040E0B2422DD12968614501D1A6
+:10486000012029E0A1F1066CBCF1040C03D07145D4
+:1048700003D1594820E058461EE0A1F1865CBCF106
+:10488000100C07D0DFF848C1614505D1534813E04B
+:1048900000E007E052480FE0DFF838C161450BD077
+:1048A000814201D1184607E04E48414504D081427B
+:1048B00001D14D4800E00020B2420DD0D169030380
+:1048C0001AD090FAA0F0B0FA80F000BF00F01F03F9
+:1048D0000AFA03F00143D161D5F800C0BCF1000F22
+:1048E00028DA424B20684249DFF808A1984201D0FB
+:1048F000B84203D10A4602E0800EE7E752469268CA
+:10490000984202F0E07201D0B84209D19D68D7F810
+:10491000088005F0010508F0010845EA080502E0F5
+:10492000B56805F0010555B1216E4FF0010941F060
+:1049300020002066002084F85C00484665E52E4D86
+:10494000AC451CD115021AD4B042F3D1984202D022
+:10495000B84200D051468B6842F4000023F0E07268
+:1049600002438A60264925480968B1FBF0F04000FF
+:10497000801C00E0401E00900028FBD1DAE7214DAA
+:10498000AC450CD1D5010AD4B042D3D1984202D063
+:10499000B84200D051468B6842F080700EE01A4D4C
+:1049A000AC45C7D15502C5D4B042C3D1984202D05C
+:1049B000B84200D051468B6842F4800023F0E07288
+:1049C00002438A60B6E700000000844B0000B84F45
+:1049D0002000F0140004002A8000501D0002B025C1
+:1049E000000180210040C03A0080F03E00200240DB
+:1049F0000023024000630258000052C7400D03002C
+:104A000088000020000021C3000084CB2DE9F8437A
+:104A10004FF0000504002E46009502D0206E18B11C
+:104A200008E00120BDE8F883204600F043F9656600
+:104A300084F85C5020688168C1F3407119B18168C5
+:104A40008E4A1140816020688168C1F3007181B98C
+:104A500081688B4A114041F0805181608A498948C0
+:104A60000968B1FBF0F0401C00E0401E00900028F7
+:104A7000FBD120688168C1F3007141B9216E012624
+:104A800041F010012166616E41F00101616606F09E
+:104A9000CEFF216EC90600D420B1206E012640F061
+:104AA0001000E0E0206E20F4807040F002002066EC
+:104AB00020688168754D11F0010F1ED1744B754A45
+:104AC000984201D0904207D19968976801F001019E
+:104AD00007F00107394302E0A96801F0010161B95B
+:104AE000984201D0904201D16B4800E06B48826847
+:104AF000616822F47C120A4382602168A9421FD1B6
+:104B0000637ED4E90207E26B5B033A43082805D0D1
+:104B10000C280FD01C280FD018280FD05FF00000F1
+:104B200000F00C0794F8200043EA47031A4342EAD6
+:104B300000400FE00420F3E70820F1E71C20EFE736
+:104B4000627E94F82030A768E06B520342EA034289
+:104B50003843104394F82020012A04D1A28C504BF2
+:104B600003EB42421043A26A2AB1E36A02F478726C
+:104B7000024343EA0200CA68A9420BD1494B1A40DA
+:104B80000243CA602068626B016921F040611143F1
+:104B9000016103E0444B1A400243CA60206806F0FA
+:104BA00046FF0746206806F03EFF07434ED12068C7
+:104BB000A946484506D1217E94F83820890341EA68
+:104BC000420103E0227E216B41EA8231C26844F255
+:104BD00003039A430A43C26094F844000128206802
+:104BE00003D0016921F0010122E048450ED1D4E94A
+:104BF000121CD4E9143502692C4F41EA0C012B43F5
+:104C00003A401943114341F0010111E0D4E913176F
+:104C1000B4F848C0DFF89880636D026908EB0C4C6B
+:104C2000224D394343EA0C036D1E2A4019431143B8
+:104C300001612068236C026922F070421A4302610C
+:104C40002068484502D02046FDF7B4FA20690128C3
+:104C500020680BD0016B21F00F010163206E20F062
+:104C6000020040F0010020663046DBE6E269016B9D
+:104C7000521E21F00F011143EFE70000C0FFFF5F5C
+:104C8000C0FFFF7F400D0300880000200060025835
+:104C9000002002400021024000230240006302582D
+:104CA0000000FEFF0740F0FF03C0F0FF1FF800FC0C
+:104CB0000100FFFFF0B5B5B0064614212EA8FBF7A2
+:104CC000ECFDB8216846FBF7E8FD314930688842C1
+:104CD0005BD1022000224FF400210091CDE9012098
+:104CE0001024154606AACDE90340C023059082E8AA
+:104CF000290068460995289503F0B2FB08B1FFF733
+:104D000061F82448016841F020010160006800F06A
+:104D1000200033901F480830016841F00101016014
+:104D2000016801F001013391016841F00401016063
+:104D3000006803272EA9309500F00400339020204E
+:104D4000CDE92E07144801F0A1FD14482EA9CDE9A4
+:104D50002E47309501F09AFD114C092111484FF46E
+:104D6000807C021584E82300D700C4E90352C314F1
+:104D70002046C4E907C56562C4E9053700F07CFE3A
+:104D800008B1FFF71FF8B465A66335B0F0BD0000A9
+:104D900000200240D844025800000258000802587F
+:104DA000C8030020100002402DE9F84F044601F02E
+:104DB00085FE00903CB194F83500022806D0802191
+:104DC00061650020E4E00120BDE8F88FC74DC74EC3
+:104DD000C649183520683036DFF81483DFF814939D
+:104DE0008842DFF814A3DFF814B32ED0A8422CD0E9
+:104DF000B0422AD0404528D0484526D0504524D03E
+:104E0000584522D0BD4A183290421ED0BC4A90422A
+:104E10001BD0BB4A1832904217D0B94A3032904268
+:104E200013D0B74A483290420FD0B54A6032904210
+:104E30000BD0B34A7832904207D0B14A90329042B8
+:104E400003D0AF4AA832904209D1026822F01E0274
+:104E500002602068426922F08002426103E0026839
+:104E600022F00E02026027688F4238464DD0A842D9
+:104E70004BD0B04249D0404547D0484545D0504539
+:104E800043D0584541D09D4A183290423DD09C4A6B
+:104E900090423AD09A4A1832904236D0984A3032EC
+:104EA000904232D0964A483290422ED0944A603294
+:104EB00090422AD0924A7832904226D0904A90323C
+:104EC000904222D08E4AA83290421ED08D4A904203
+:104ED0001BD08C4A1432904217D08A4A2832904212
+:104EE00013D0884A3C3290420FD0864A50329042CA
+:104EF0000BD0844A6432904207D0824A7832904282
+:104F000003D0804A8C32974204D1206E026822F48A
+:104F10008072026075492068884228D0A84226D055
+:104F2000B04224D0404522D0484520D050451ED024
+:104F300058451CD071491831884218D070498842B0
+:104F400015D06F491831884211D06D4930318842EF
+:104F50000DD06B494831884209D069496031884297
+:104F600005D067497831884201D0654990310168A0
+:104F700021F0010101600EE001F0A0FD0099401A4E
+:104F8000052808D9202262650321002084F8351005
+:104F900084F8340017E73868C007EDD1534A01217F
+:104FA000206890422ED0A8422CD0B0422AD0404552
+:104FB00028D0484526D0504524D0584522D04F4BC4
+:104FC000183398421ED04E4B98421BD04C4B18338E
+:104FD000984217D04A4B3033984213D0484B48334D
+:104FE00098420FD0464B603398420BD0444B7833F5
+:104FF000984207D0424B9033984203D0404BA8339D
+:10500000984208D194F85C703F23A06D07F01F0709
+:10501000BB40836007E094F85C30A06D03F01F0391
+:1050200001FA03F34360206890424DD0A8424BD070
+:10503000B04249D0404547D0484545D0504543D07F
+:10504000584541D02D4A183290423DD02C4A9042CA
+:105050003AD02B4A1832904236D0294A3032904208
+:1050600032D0274A483290422ED0254A60329042B0
+:105070002AD0234A7832904226D0214A9032904258
+:1050800022D01F4AA83290421ED01E4A90421BD006
+:105090001C4A1432904217D01A4A2832904213D038
+:1050A000184A3C3290420FD0164A503290420BD0F0
+:1050B000144A6432904207D0124A7832904203D0A8
+:1050C000104A8C3290420BD1D4E919024260E06E52
+:1050D00030B1026822F480720260D4E91C0242609E
+:1050E000002084F8351084F834006DE6100002408A
+:1050F000580002407000024088000240A0000240B8
+:1051000010040240085402582DE9F05F28B190F8CD
+:105110003510022904D0802141650120BDE8F09FAF
+:10512000904C904B0168183C18338E4ADFF83C9243
+:10513000A1428D4CDFF838E28E4FDFF83CB2DFF849
+:105140003CA28F4D8F4E31D091422FD099422DD01D
+:10515000A1422BD0494529D0714527D0B94225D04D
+:10516000DFF810C20CF1180C61451FD0DFF808C23F
+:10517000ACF1600C614519D0DFF8FCC1ACF1480C12
+:10518000614513D0DFF8F0C1ACF1300C61450DD0B2
+:10519000DFF8E4C1ACF1180C614507D0594505D0E2
+:1051A000514503D0A94201D0B1422CD1DFF8B4C19E
+:1051B0004FF0040880F83580ACF1180C61451DD023
+:1051C00091421BD0994219D0A14217D0494515D020
+:1051D000714513D0B94211D06648183081420DD0C4
+:1051E00065486038814209D063484838814205D01B
+:1051F00061483038814201D05F481838086820F093
+:1052000001000860ABE0D1F800C02CF00E08DFF818
+:1052100054C1C1F80080ACF1180C0168614527D079
+:10522000914225D0994223D0A14221D049451FD097
+:1052300071451DD0B9421BD0DFF838C10CF1180CF4
+:10524000614515D0DFF830C1ACF1600C61450FD07D
+:10525000DFF824C1ACF1480C614509D0DFF818C172
+:10526000ACF1300C614503D0DFF80CC1ACF1180C87
+:10527000D1F800C02CF0010CC1F800C0DFF8E480C8
+:105280004FF0010C0168A8F11808414546D0914241
+:1052900044D0994242D0A14240D049453ED07145C8
+:1052A0003CD0B9423AD0334A1832914236D0324AD1
+:1052B000603A914232D0304A483A91422ED02E4A3A
+:1052C000303A91422AD02C4A183A914226D0594578
+:1052D00024D0514522D0A94220D0B1421ED02A4A22
+:1052E00091421BD0284A1432914217D0264A2832C4
+:1052F000914213D0244A3C3291420FD0224A50327C
+:1053000091420BD0204A6432914207D01E4A783233
+:10531000914203D01C4A8C32914218D1016E0A6826
+:1053200022F480720A6090F85C20816D02F01F0206
+:105330000CFA02F24A60D0E919124A60C16E31B12A
+:105340000A6822F480720A60D0E91C124A600022C6
+:10535000016D80F835C080F8342001B18847002005
+:10536000DCE60000280002405800024070000240C5
+:1053700088000240A00002407004024088040240FD
+:10538000A0040240B804024008540258406D70471F
+:105390002DE9FC5F0446F74E0020DFF8D88300902B
+:1053A0004FF41652F44808F11808A56DDFF8C493BD
+:1053B000DFF8C0A3016809F1300920680AF1480A42
+:1053C000B1FBF2F1B04201912F68D5F800C0DFF8CF
+:1053D000ACB335D04146884232D0484530D05045F4
+:1053E0002ED058452CD0E5491831884228D0E349C1
+:1053F0003031884224D0E1494831884220D0E04908
+:1054000088421DD0DE491831884219D0DC4930313C
+:10541000884215D0DA494831884211D0DFF860E37C
+:105420000EF1600E70450BD0D54A7832904207D00D
+:10543000D34B9033984203D0D149A83188427DD1D3
+:1054400094F85C20082102F01F0201FA02F23A42AD
+:105450004AD0B04232D0404530D048452ED0504599
+:105460002CD058452AD0C54A1832904226D0C34A7B
+:105470003032904222D0C14A483290421ED0C04AB7
+:1054800090421BD0BE4A1832904217D0BC4A3032EC
+:10549000904213D0BA4A483290420FD0B84A603294
+:1054A00090420BD0B64A7832904207D0B44A90323C
+:1054B000904203D0B24AA832904203D1026802F06F
+:1054C000040202E0026802F008026AB1026822F0F7
+:1054D0000402026094F85C0000F01F008140A960A3
+:1054E000606D40F00100606594F85C00012100F0FF
+:1054F0001F008140394240D02068B04234D040453E
+:1055000032D0484530D050452ED058452CD09B4AFB
+:105510001832904228D0994A3032904224D0974A8B
+:105520004832904220D0964A90421DD0944A183278
+:10553000904219D0924A3032904200E0AFE113D04D
+:105540008F4A483290420FD08D4A603290420BD041
+:105550008B4A7832904207D0894A9032904203D0E9
+:10556000874AA83290427DD1406910F0800F04D064
+:10557000A960606D40F00200606594F85C00042151
+:1055800000F01F00814039423ED02068B04232D046
+:10559000404530D048452ED050452CD058452AD0D3
+:1055A000764A1832904226D0744A3032904222D045
+:1055B000724A483290421ED0714A90421BD0704AC3
+:1055C0001832904217D06E4A3032904213D06C4A53
+:1055D000483290420FD06A4A603290420BD0684AFB
+:1055E0007832904207D0664A9032904203D0644AA3
+:1055F000A83290424ED1006810F0020F04D0A9608A
+:10560000606D40F00400606594F85C00102100F0CB
+:105610001F008140394258D02068B04234D0404504
+:1056200032D0484530D050452ED058452CD0534A22
+:105630001832904228D0514A3032904224D04F4AFA
+:105640004832904220D04E4A90421DD04C4A1832E7
+:10565000904219D04A4A3032904215D0484A4832D6
+:10566000904200E014E00FD0454A603290420BD0E7
+:10567000434A7832904207D0414A9032904203D058
+:105680003F4AA832904207D1006800F0080006E0C7
+:10569000006872E70068B7E7006800F00400A0B196
+:1056A000A96020680168490304D50068000308D593
+:1056B000A16C07E00168C90503D4016821F0080165
+:1056C0000160216C09B12046884794F85C002021D4
+:1056D00000F01F008140394279D02068B04232D0BA
+:1056E000404530D048452ED050452CD058452AD082
+:1056F000224A1832904226D0204A3032904222D09C
+:105700001E4A483290421ED01D4A90421BD01C4A6D
+:105710001832904217D01A4A3032904213D0184AA9
+:10572000483290420FD0164A603290420BD0144A51
+:105730007832904207D0124A9032904203D0104AF9
+:10574000A832904203D1006800F0100002E0006827
+:1057500000F00200B0B3A96094F835000428206876
+:1057600001680FD049037ED5006800032BD4616C1B
+:105770002AE0000010000240880000207000024073
+:105780001004024021F0160101602068416921F0F7
+:1057900080014161206C08B9A06C20B120680168CB
+:1057A00021F00801016094F85C303F21012003F0F2
+:1057B0001F0300229940A96084F8350084F8342042
+:1057C000216D65E003E0E16B09B120468847606D1B
+:1057D00000287DD0606DC00759D02068042184F86E
+:1057E0003510B0422BD0404529D0484527D05045F0
+:1057F00025D0584523D09D49884220D09B49183157
+:1058000088421CD099493031884218D09849884242
+:1058100015D097491831884211D0954930318842C6
+:105820000DD093494831884209D09149603188426E
+:1058300005D08F497831884201D08D499031016877
+:1058400021F00101016020680099019A491C009132
+:10585000914202D80168C907F6D10068C00710D08C
+:1058600003200FE0FFE70168C905ACD403680121FC
+:10587000002223F01003036084F8351084F83420EC
+:10588000A1E7012084F83500002084F83400E16CA1
+:1058900000291DD002B02046BDE8F05F08477549D9
+:1058A00088421DD073491431884219D0714928317A
+:1058B000884215D06F493C31884211D06D49503132
+:1058C00088420DD06B496431884209D0694900E0B3
+:1058D00084E07831884203D066498C3188427DD19A
+:1058E00094F85C800427016808F01F0807FA08F79D
+:1058F00017EA0C0F009746D04F0744D500980F04C5
+:10590000686003D5C8033CD4A16CC1E7880638D4CD
+:105910002068B0422DD055496039884229D0484589
+:1059200027D0504525D0584523D05049884220D013
+:105930004E49183188421CD04C493031884218D029
+:105940004B49884215D04A491831884211D04849FC
+:10595000303188420DD046494831884209D07045DF
+:1059600007D0904205D0984203D04149A8318842DF
+:1059700003D1016821F0080102E0016821F004016F
+:105980000160216C84E7022707FA08F717EA0C0F79
+:1059900000974ED08F074CD500980F04686003D550
+:1059A000C80344D4616C73E7880640D42068B042D1
+:1059B0002FD02E49603988422BD0484529D05045F8
+:1059C00027D0584525D02949884222D02749183167
+:1059D00088421ED025493031884200E044E018D08A
+:1059E0002349884215D022491831884211D02049D4
+:1059F000303188420DD01E494831884209D0704567
+:105A000007D0904205D0984203D01949A831884266
+:105A100003D1016821F0140102E0016821F00A01BC
+:105A20000160012184F83510002084F83400E16B16
+:105A30002EE7082202FA08F212EA0C0F14D0090726
+:105A400012D5016821F00E01016094F85C1001206C
+:105A5000002201F01F0100FA01F16960606584F81D
+:105A6000350084F8342012E7BDE8FC9F880002402E
+:105A700010040240085402582DE9F05F044601F07A
+:105A80001DF8002C07467DD0E24E022120684FF021
+:105A90000308DFF884934FF00005DFF880A3B042DD
+:105AA000DFF87CB334D0DB4A1832904230D048451E
+:105AB0002ED050452CD058452AD0D94A1832904281
+:105AC00026D0D74A3032904222D0D54A483290422E
+:105AD0001ED0D44A90421BD0D24A1832904217D0DE
+:105AE000D04A3032904213D0CE4A483290420FD042
+:105AF000CC4A603290420BD0CA4A7832904207D0EA
+:105B0000C84A9032904203D0C64AA83290427DD112
+:105B100084F83510B04284F834502ED0BD49183185
+:105B200088422AD0484528D0504526D0584524D010
+:105B3000BB491831884220D0B949303188421CD045
+:105B4000B7494831884218D0B649884215D0B5497E
+:105B50001831884211D0B349303188420DD0B14953
+:105B60004831884209D0AF496031884205D0AD49FB
+:105B70007831884201D0AB499031016821F00101B0
+:105B8000016008E025E100BF00F098FFC01B052878
+:105B900001D920211AE120680068C007F4D1D4E9B6
+:105BA00002032168103418438E4694E88410D4E927
+:105BB000033809683A4310439B4A40EA0C0067697E
+:105BC00018431140103C40EA0800042F40EA01004D
+:105BD00003D1D4E90B12114308436168A1F12902F2
+:105BE000052A0BD9163A032A08D9083A012A05D9F9
+:105BF000083A032A02D97439032901D840F48010E5
+:105C0000CEF800002068676A406900E020E0042FB9
+:105C100020F0070047EA00070DD1D4E90A01074345
+:105C200049B12046FDF762FE28B1402060650121A0
+:105C300084F83510CDE0206847612046FDF774FDFB
+:105C400094F85C203F2102F01F029140816055E0F2
+:105C5000764A90421BD0754B1433984217D0734B41
+:105C60002833984213D0714B3C3398420FD06F4B7E
+:105C7000503398420BD06D4B6433984207D06B4B36
+:105C80007833984203D0694B8C3398427ED184F8A4
+:105C9000351084F83450664B0168A26801EA030E9F
+:105CA000402A74D0802A73D05FF00002D4E90378D0
+:105CB000D4E9053142EAD70242EAD8085B4AD4E97E
+:105CC000077C48EAD30848EAD10141EAD7015242A9
+:105CD00041EA1C11142341EA0E01016020681044BE
+:105CE000B0FBF3F08000E0652046FDF71DFD94F861
+:105CF0005C20012102F01F02914041602068B04207
+:105D000057D044491831884253D0484551D0504566
+:105D10004FD058454DD042491831884249D040496A
+:105D20003031884245D03E494831884241D03D49D2
+:105D300088423ED03B49183188423AD03949303107
+:105D4000884236D037494831884232D035496031AF
+:105D500088422ED03349783188422AD03149903157
+:105D6000884226D02F49A831884222D02F49884224
+:105D70001FD02E49143188421BD02C49283188422B
+:105D800017D02A493C31884213D002E01DE017E0C9
+:105D900018E02649503188420BD0244964318842AA
+:105DA00007D022497831884203D020498C3188427B
+:105DB00029D12046FDF712FDA06880280CD00CE008
+:105DC000102273E74FF4804270E74021616584F848
+:105DD00035800120BDE8F09F6560216E2079086064
+:105DE000D4E9190141606068401E072808D82046A0
+:105DF000FDF742FDE06E0560D4E91C01416002E060
+:105E0000E566256765670120656584F83500002033
+:105E1000E0E700001000024040000240580002404D
+:105E200070000240100402403F8010FE08540258E7
+:105E30000F00FEFF2DE9F84F04008C464FF00000E4
+:105E4000009014D094F83400012812D094F8355002
+:105E50000120002184F83400012D0CD0C0026065BF
+:105E60000120009084F834100098BDE8F88F0120DC
+:105E7000FBE70220F9E78C4D0226206884F83560A4
+:105E8000A8428A4D61658A4E8A4FDFF82C82DFF87E
+:105E90002C92DFF82CA2DFF82CB226D0A84224D016
+:105EA000B04222D0B84220D040451ED048451CD038
+:105EB00050451AD0584518D08349884215D0824998
+:105EC0001831884211D08049303188420DD07E4946
+:105ED0004831884209D07C496031884205D07A49EE
+:105EE0007831884201D078499031016821F0010170
+:105EF000016061462046FDF723FD6B49206888421A
+:105F00002CD0A8422AD0B04228D0B84226D0404552
+:105F100024D0484522D0504520D058451ED06A4A4A
+:105F200090421BD0684A1832904217D0664A3032ED
+:105F3000904213D0644A483290420FD0624A603295
+:105F400090420BD0604A7832904207D05E4A90323D
+:105F5000904203D05C4AA83290420CD1026822F0F1
+:105F60001E0242F016020260206C88B120680268AE
+:105F700042F008020BE0026822F00E0242F00A0230
+:105F80000260206C20B12068026842F004020260C6
+:105F9000206888424BD0A84249D0B04247D0B8428E
+:105FA00045D0404543D0484541D050453FD0584565
+:105FB0003DD0454A90423AD0434A1832904236D0BA
+:105FC000414A3032904232D03F4A483290422ED03D
+:105FD0003D4A603290422AD03B4A7832904226D0E5
+:105FE000394A9032904222D0374AA83290421ED08D
+:105FF000364A90421BD0354A1432904217D0334A69
+:106000002832904213D0314A3C3290420FD02F4A6E
+:10601000503290420BD02D4A6432904207D02B4A26
+:106020007832904203D0294A8C3290420DD1206EB2
+:106030000268D20303D5026842F480720260E06E07
+:1060400018B1026842F4807202602068884226D04B
+:10605000A84224D0B04222D0B84220D040451ED021
+:1060600048451CD050451AD0584518D0164988428A
+:1060700015D015491831884211D013493031884262
+:106080000DD011494831884209D00F49603188420A
+:1060900005D00D497831884201D00B499031016813
+:1060A00041F001010160DFE61000024028000240DB
+:1060B0004000024058000240700002408800024048
+:1060C000A0000240B80002401004024008540258E8
+:1060D00070B5044600F0F2FC0546601C02D004488E
+:1060E0000078044400F0EAFC401BA042FAD370BDE3
+:1060F0007C00002070477047704770472DE9FF5FB4
+:10610000DFF80CB304460BF10401DBF8000025684E
+:106110000F68AA468007D5F85090696DD5F8508071
+:106120006E6D2A6DD5F854C02B6D00EA8770009013
+:1061300009F470496F6D286D01EA09010191DAF8DF
+:106140005410DAF85490DAF8505008F00F0806EAC4
+:106150000806029602F0F00203F071536FEA090696
+:106160001F4000F060700CEA020CCDF80CC0F20584
+:1061700001EA00090CD4E843C00509D400214FF41A
+:106180008073CAF85030CBF800102046FFF7B5FFF7
+:10619000700512D4E84340050FD4206800234FF463
+:1061A0008068D0F8DC20D0F8E410C0F85080CBF83C
+:1061B00000301140204600F042FBDFF858A2009862
+:1061C00050B12268830F00EA0A001065CBF8003056
+:1061D00020460099FFF78EFF019850B12268830F87
+:1061E00000EA0A001065CBF800302046019900F063
+:1061F00028FB029850B12268830F00EA0A0010655C
+:10620000CBF800302046029900F011FB039850B102
+:106210002268830F00EA0A001065CBF800302046A0
+:10622000039900F005FB30050CD4E843000509D4C0
+:10623000236800204FF400621A65CBF80000204666
+:1062400000F000FBB00512D4E84380050FD42068AD
+:1062500000234FF40078D0F8D820D0F8E010C0F830
+:106260005080CBF800301140204600F0E9FA3003AE
+:106270000CD4E843000309D4236800204FF4002223
+:106280001A65CBF80000204600F0D0FAF0030CD4D9
+:10629000E843C00309D4236800204FF480321A6514
+:1062A000CBF80000204600F0C9FA70030CD4E84394
+:1062B000400309D4226800204FF480231365CBF8F3
+:1062C0000000204600F0B9FAB0030FD4E843800381
+:1062D0000CD4236800204FF400321A65CBF800007C
+:1062E000D4F89C0040F08000C4F89C00B9F1000F85
+:1062F0000BD022684FEA997309EA0A001065CBF8BF
+:10630000003049462046FFF7F7FE5FB12268BB0F19
+:1063100007EA0A001065CBF80030D4F89C00384337
+:10632000C4F89C003C492068884268D16068814676
+:106330008068800763D0D9F82060D9F82410D9F894
+:106340002080D9F82400D9F820C0D9F82470D9F8D1
+:106350002030D9F82450D9F8202003F4FC4306F06B
+:106360000F0AD9F824601D40D9F824B008F030088D
+:106370000CF4C07C02F4F02211EA0A0100EA0808D9
+:1063800007EA0C0706EA0206D9F820A004D0C9F8EB
+:106390002010204600F04EFAB8F1000005D06168E8
+:1063A00008624146204600F047FA6FEA0B004006BB
+:1063B0000ED46FEA0A0040060AD460684021C36B1D
+:1063C000C26B01622046190C02F03F0200F033FA62
+:1063D0002FB1606807623946204600F02AFA35B1CD
+:1063E00060680562D4F89C002843C4F89C0036B16C
+:1063F00060680662D4F89C003043C4F89C00D4F86E
+:106400009C00002802D02046FFF775FEBDE8FF9FE4
+:1064100010A80040FFFFCF3F00A000402DE9F04151
+:1064200094B08D494C2204466846FAF7DAF964B113
+:106430008A4D2068A84202D100F58070606094F80F
+:1064400098004FF0000820B108E0012014B0BDE82A
+:10645000F081204684F8998000F002F92068816973
+:1064600021F01001816100F029FB0327064604E0BA
+:1064700000F024FB801B0A2811D8206880690007DF
+:10648000F6D42068816941F00101816100F016FBBA
+:1064900006460DE000F012FB801B0A2808D9D4F84C
+:1064A0009C0040F00100C4F89C0084F89870CCE790
+:1064B00020688069C007EDD02068816941F0020141
+:1064C0008161207C01282068816937D041F040013A
+:1064D0008161607C01282068816932D021F480418B
+:1064E0008161A07C0128206881692DD041F4805110
+:1064F00081612068A268816921F440711143816142
+:106500002068816921F0A40181612068016921F07E
+:1065100010010161E068012819D010B302281BD0D6
+:106520002068816941F0800181612068016941F042
+:1065300010010161E06803280ED012E021F0400153
+:10654000C6E741F48041CBE721F48051D0E72068D1
+:10655000816941F0040103E02068816941F0200174
+:106560008161207E6FF0FF02D4E90773A68A1102D1
+:10657000400602EB0727A0F10070384327685B1E36
+:10658000184301EB06463043F861A068B0F5407F40
+:1065900011D104F12800A68C6FF00F0C89C801EB13
+:1065A0000641401E02EB0322104322680CEB071346
+:1065B00018430843D060206E30B12068626ED0F876
+:1065C000C0101143C0F8C010D4E917126846D14278
+:1065D00009D02168A36E51F8C82F50F8233022F05B
+:1065E00007021A430A60216C49B12168626C51F8B4
+:1065F000BC3F50F8226023F0070232430A60A16CCE
+:1066000051B12168E36C51F8BC2F50F8233022F0CF
+:10661000700242EA03120A60216D51B12168626D75
+:1066200051F8BC3F50F8220023F4E06242EA002017
+:1066300008602068A84204D16068816821F00301E5
+:106640008160C4F894800121C4F89C8084F898107B
+:106650002046FDF7EBFBF9E61C31010800A00040E5
+:106660002DE9F047B4B0814614212EA8FAF715F9A8
+:10667000B8216846FAF711F9664C0026D9F80000EF
+:106680004FF08051644A0C3C614F4FF00208614D5D
+:106690009042DFF888A14FF0090938D100201B9102
+:1066A0004A13CDE90020684601F0DAFE08B1FDF793
+:1066B00089FB3868401C3860012807D1286840F4FD
+:1066C00080702860286800F480703390206840F063
+:1066D00008002060206803222E922EA900F00800F6
+:1066E000CDE92F863196CDE93290504600F0CEF8B4
+:1066F00000220521132000F08FFA132000F07FFA0A
+:1067000000220521152000F087FA15203BE0444ABD
+:1067100090423DD100201B914FF40042CDE9002072
+:10672000684601F09DFE08B1FDF74CFB3868401C3F
+:106730003860012807D1286840F4807028602868F4
+:1067400000F480703390206840F0020020602068E0
+:1067500060222E922EA900F00200CDE92F863196FC
+:10676000CDE932902F4800F091F800220521142045
+:1067700000F052FA142000F042FA002205211620FF
+:1067800000F04AFA162000F03AFA34B0BDE8F0877B
+:10679000254A9042F9D100201B914FF40042CDE9E7
+:1067A0000020684601F05CFE08B1FDF70BFB38687D
+:1067B000401C3860012807D1286840F480702860A8
+:1067C000286800F480703390206840F00800206052
+:1067D00020684FF440512E91052200F00800CDE9C9
+:1067E0002F862EA93196CDE93220504600F04EF882
+:1067F000002205219F2000F00FFA9F2000F0FFF9F2
+:1068000000220521A02000F007FAA020BBE700002D
+:1068100004000020EC44025800A00040000C025884
+:1068200000A400400004025800D4004070477047A4
+:1068300070477047704770477047704770477047A0
+:1068400070477047704700002DE9F041084F01255F
+:106850000024064605FA04F0304203D057F824001D
+:1068600000B18047641CE4B2102CF3D3BDE8F08182
+:10687000109B00204FF0B04110B5D1F888200242A3
+:1068800003D0C1F88800FFF7DFFF10BD2DE9F84FF6
+:1068900003247A4D00234FF001094FF0B04B4FF025
+:1068A0000F0AE4E009FA03F6324078D00F7907F0D6
+:1068B0000307012F01D0022F1AD187684FEA430E38
+:1068C000D1F80CC004FA0EF827EA08070CFA0EFCFF
+:1068D0004CEA070CC0F808C0476891F804C0B743F9
+:1068E000CCF3001C0CFA03FC4CEA070CC0F804C003
+:1068F0000E79F643B6070BD0C6684FEA43088F6897
+:1069000004FA08FC26EA0C0607FA08F73743C760C2
+:106910000E7906F00306022E12D1DE080F694FEA47
+:10692000437C00EB8606B646366A4FEADC6C0AFA10
+:106930000CF807FA0CF726EA08063743CEF8207061
+:106940000F7906684FEA430807F0030704FA08FCCA
+:1069500007FA08F726EA0C06374307604E6816F474
+:10696000403F1CD0464E376847F002073760366814
+:106970009F0706F00206009623F0030606F1B046D4
+:10698000B6463F0FD6F80864DFF8F8800AFA07FC2D
+:10699000404526EA0C0603D14FF0000C3AE065E0D2
+:1069A000DFF8E4C0604502D14FF0010C32E0DFF8BF
+:1069B000DCC0604502D14FF0020C2BE0DFF8D0C004
+:1069C000604502D14FF0030C24E0DFF8C8C06045F9
+:1069D00002D14FF0040C1DE0DFF8BCC0604502D1CD
+:1069E0004FF0050C16E0DFF8B4C0604502D14FF05F
+:1069F000060C0FE0DFF8A8C0604502D14FF0070C8D
+:106A000008E0DFF8A0C0604502D14FF0090C01E0BA
+:106A10004FF00A0C0CFA07FC4CEA060CCEF808C43E
+:106A20004F68DBF80060FF0226EA020600D5164335
+:106A30005F46CBF80060D1F804C0DBF804605FEA81
+:106A40008C2C26EA020600D516437E606E684F68DD
+:106A500026EA0206BF0300D516436E602E684F6813
+:106A600026EA0206FF0300D516432E605B1C0A6867
+:106A700032FA03F67FF416AFBDE8F88F80000058B5
+:106A8000F44402580000025800040258000802585A
+:106A9000000C025800100258001402580018025846
+:106AA000001C0258002402580069084000D0012050
+:106AB00070470AB1816170470904FBE701488068AB
+:106AC000704700007C000020024881680278114471
+:106AD000816070477C000020032010B500F0BCF8F6
+:106AE00002F0FEFA0F4A104914681368C4F3032237
+:106AF00003F00F038A5CC95C02F01F0201F01F0162
+:106B0000D0400A4A20FA01F11160094908600F20BB
+:106B100000F010F808B1012010BD00F04DF8002081
+:106B200010BD000018440258903101088C0000206C
+:106B30008800002010B5102804468AB02AD200220E
+:106B40000146A12000F068F8A12000F058F815488F
+:106B500004601548016841F080710160006808A96F
+:106B600000F080700990684602F046FA02F0A6FA3A
+:106B70000E49400000220E4CB0FBF1F10D4840F2EE
+:106B8000E7330460C0E90332491EC0E9011203F093
+:106B90006BFD10B101200AB010BD064803F096FD50
+:106BA000F9E7000080000020EC44025840420F004A
+:106BB00000E000405C110020074882B0016841F00D
+:106BC00002010160006800220F2100F00200009025
+:106BD000901E02B000F020B8F444025800280DDBEB
+:106BE000410900F01F028900012001F1E0219040DD
+:106BF000C1F88001BFF34F8FBFF36F8F704700283C
+:106C000009DB410900F01F028900012001F1E021A8
+:106C10009040C1F8000170470E4BF0B41B680D4660
+:106C2000C3F30223C3F10706042E00D90426191D5D
+:106C3000072901D2002300E0DB1E012404FA06F13B
+:106C40009C40491E2940641E994014402143F0BCD9
+:106C500009F09CB80CED00E0064900F0070210B501
+:106C60004FF6FF040868044B204040EA0220184316
+:106C7000086010BD0CED00E00000FA052DE9F04FB2
+:106C800002688346FF484FF0000A8DB00C468242EE
+:106C9000564602D10025012001E001250020E846EA
+:106CA0000027814607EB47017F1C08EBC101F8B2C2
+:106CB00005F042FD20B108204FF0010ACBF8540046
+:106CC000FFB2022FEED3BAF1000F7CD1DFF8B4E3AC
+:106CD000DEF80000C00707D0DEF8001046F001061D
+:106CE00021F00101CEF80010E7480068C00706D087
+:106CF000E54846F00206016821F00101016005EB5C
+:106D000045030C93E148424608EBC303DFF880B328
+:106D10000121DC469F6800EB8707D7F8008428F440
+:106D20008078C7F80084DBF80070FF0732D0DCF809
+:106D30000070B9F1010F27F00107CCF800705CD1A9
+:106D4000069B00EB8303D3F8007447F00207C3F8F7
+:106D50000074079B3BB100EB8303D3F8007447F04A
+:106D60002007C3F80074099B4BB121EA030700EB2D
+:106D70008703D3F8047447F48027C3F804740A9B8C
+:106D8000DBB321EA030700EB8703D3F8047447F071
+:106D9000806730E00C9F52F8377077B300EB8707BD
+:106DA000D7F800C42CF0010CC7F800C45F683FB1ED
+:106DB00000EB8707D7F800C42CF0100CC7F800C40C
+:106DC000D3F80CC000E05AE1BCF1000F09D021EA71
+:106DD0000C0700EB8707D7F804C42CF4803CC7F8F5
+:106DE00004C41B694BB121EA030700EB8703D3F806
+:106DF000047427F08077C3F8047409EB4903D4F8CE
+:106E000000C0CDF830C0914652F83370BC451BD05D
+:106E100009EBC302D4F808C0D2F80880C44513D0E7
+:106E2000D4F804C0D2F80480C44502D1BCF1000FEC
+:106E30000AD1D4F80CC0D2F80C80C44504D0D4F8E0
+:106E400010C01269944551D10C9ABA4219D109EB7C
+:106E5000C302D4F804C0D2F80480C44511D1D4F8D8
+:106E60000CC0D2F80C80C4450BD1D4F810C0126904
+:106E7000944506D1DBF8003043F00103CBF8003035
+:106E800034E000EB870709EBC302D7F8003423F0A6
+:106E90000103C7F8003453683BB100EB8303D3F818
+:106EA000007427F01007C3F80074936800EB8303A5
+:106EB000D3F8007427F48077C3F80074D3684BB11B
+:106EC00021EA030700EB8703D3F8047427F4803723
+:106ED000C3F8047412694AB121EA020300EB830289
+:106EE000D2F8043423F08073C2F80434A3685A46FD
+:106EF00000EB8303D3F8007427F4407747EA452773
+:106F000047F48077C3F80074DBF800C063695F1E44
+:106F1000CCF3074C674508D95E4FD2F800C007EBA9
+:106F200003472CF47F033B4313601268D2072268A7
+:106F300000EB8202D2F800343FD023F003035B1C45
+:106F4000C2F8003462684AB100EB8202D2F8003421
+:106F500023F0300343F01003C2F80034E268D30397
+:106F60000AD521EA020300EB8302D2F8043423F4A9
+:106F7000E02343F480330AE05AB121EA020300EB34
+:106F80008302D2F8043423F0E06343F08073C2F844
+:106F900004342269D30307D5914300EB8100D0F874
+:106FA000041421F4E0214AE0F2B3914300EB8100A4
+:106FB000D0F8041421F0E0614EE001EB450723F026
+:106FC00003033B43C2F8003462685AB100EB82020B
+:106FD000D2F8003423F0300343EA451343F01003A2
+:106FE000C2F80034E268D3030CD521EA020300EBB7
+:106FF0008302D2F8043423F4E02343EA854343F4C4
+:1070000080330CE06AB121EA020300EB8302D2F87C
+:10701000043423F0E06343EA856343F08073C2F8ED
+:1070200004342269D30300E01AE00BD5914300EB4E
+:107030008100D0F8041421F4E02141EA854141F4B3
+:1070400040310BE062B1914300EB8100D0F80414B1
+:1070500021F0E06141EA856141F04071C0F804141B
+:10706000F00705D0DEF8001041F00101CEF8001065
+:10707000B00704D50448016841F0010101600DB07A
+:10708000504609E00050005200A0005200B00052EB
+:1070900000B400520000FFFFBDE8F08FF8B50025F6
+:1070A0000446FFF70BFD064624B100206065206D05
+:1070B00010B170E001256EE0204600F073F841F257
+:1070C0008830A065258A6FF0FF012268D4F814C0CB
+:1070D0000F02636B07EB0545E06801EB0C27D4F862
+:1070E0001CC0184393683D432D4F28433B4040EA62
+:1070F0000C00184390602068236AC26822F4E022E2
+:107100001A43C2602368228EA06B40EA02401861D5
+:107110002268E06B5061D4E90003026801EB0323AD
+:1071200022F4F85119430160A06D0022202133465A
+:107130000090204605F06EFB05002CD12068626AA5
+:10714000C168521E21F0FF011143C1602068A2688E
+:10715000016821F04001114301602068D4E90A125E
+:10716000D0F80831114323F0A0421143C0F80811B0
+:107170002068016841F001010160A069022804D182
+:107180002068816841F002018160E068B0F1806FA1
+:1071900003D0022020652846F8BD0120FAE7000050
+:1071A000F4F8E0F82DE9F043B5B004461421684640
+:1071B000F9F773FBB82106A8F9F76FFB4749206878
+:1071C00088427DD1002019904FF000710446CDE92E
+:1071D000061006A801F044F908B1FCF7F3FD404899
+:1071E000016841F400110160016801F4001105918A
+:1071F000016841F400210160006800F4002005905E
+:1072000037480C30016841F001010160016801F06C
+:1072100001010591016841F002010160016801F07E
+:1072200002010591016841F010010160016801F05F
+:1072300010010591016841F0080101600068022514
+:107240000927009500F00800DFF8988003260396D0
+:107250006946CDE90470CDE901544046FFF716FBBD
+:10726000062102940820CDE90361CDE900056946B5
+:107270004046FFF70BFB0121DFF86C9002AA4FF0AC
+:107280000408CDE900156946484682E85001FFF739
+:10729000FDFA02AA6946484682E8D000CDE9008599
+:1072A000FFF7F4FA0B2111484FF40068CDF8008085
+:1072B000CDE90361CDE901546946FFF7E7FA00E043
+:1072C00008E002AA0A48694682E8D000CDE90085B4
+:1072D000FFF7DCFA35B0BDE8F083000000A00052F3
+:1072E000D44402580000025800040258001002580A
+:1072F000000C025801680123C0F8D834002280F83D
+:10730000CC248869044A40F000608861486D1043CD
+:1073100048650020704700000300001070470068B7
+:10732000416200207047F0B503685D6A39B19F6A19
+:107330004C1E00204FF4827605EB17450BE045EA22
+:107340000240986210E0471C06EB800053F800C032
+:10735000F8B205EB1C45A042F5D34FF4807000EB6A
+:10736000810045EA02421A500020F0BDD0F8E00446
+:1073700007F02DBC01EBC10200EB8202D0F8E00463
+:10738000126A07F080BB01EBC10200EB8202D0F869
+:10739000E004D2F8602207F0D2BBD0F8E00407F096
+:1073A00018BC0A0601F00F0101EBC10100EB8101DD
+:1073B00001D5143101E001F51571006808F006BB34
+:1073C00001F00F020B0670B502EBC20104464FF04C
+:1073D00001004FF0000504EB810102D5487514311E
+:1073E00003E081F8555201F515710A7094F8942460
+:1073F000012A08D084F89404206808F005F80020D9
+:1074000084F8945470BD022070BD70B502790446B2
+:1074100001F00F00904201D9012070BD01F00F0270
+:107420004FF000050B0602EBC2014FF0010204EB26
+:10743000810102D54A75143103E081F8555201F5F6
+:1074400015718D70087094F89404012808D084F8A0
+:107450009424206808F042F9002084F8945470BD08
+:10746000022070BD01F00F0101EBC10100EB8100B2
+:10747000D0F8680270472DE9F04101F00F0604468C
+:107480000D064FF0010006EBC6014FF0000504EBBE
+:10749000810102D54875143103E081F8555201F598
+:1074A0001571C2F30A024F780B718A600E7007B132
+:1074B0004E83022B00D14D7194F89424012A09D0F7
+:1074C00084F89404206807F0E7FE284684F8945472
+:1074D000BDE8F0810220FBE770B501F00F05002444
+:1074E00005EBC50100EB810101F5187181E81C0075
+:1074F00001F80B4C01F80C5D8379012B00D1CA61B6
+:107500008279006808F042F9002070BD70B50D4620
+:107510000179044605F00F00884201D9012070BDB1
+:1075200029064FF000064FF0010206D500EBC0011E
+:1075300004EB81014A75143107E005EBC50104EB4A
+:10754000810181F8556201F515718A70087094F80F
+:107550009404012807D084F89424206808F0EAF8FD
+:10756000280702D007E0022070BDA17904F29C42F6
+:10757000206808F087F8002084F8946470BD70B526
+:1075800001F00F04002504EBC401012600EB81018A
+:10759000203181E82C0001F80B6C01F80C4D837947
+:1075A000012B00D1CA618279006808F0EFF8002051
+:1075B00070BD00002DE9FC5F05680446284608F010
+:1075C000A1FA00287ED1206808F0C8FA002879D0F6
+:1075D000D5F80808C0F30D20C4F8D404206808F0DA
+:1075E000BDFA800704D52068416901F002014161BC
+:1075F000206808F0B3FAC10604F29C40009035D52B
+:107600002068816921F0100181612F6A07F00F0164
+:10761000C7F3434001EBC101022804EB810606F5E4
+:10762000157602D0062812D01BE047F6F07007420C
+:1076300017D0C7F30A12F1681746284608F092FAE5
+:107640007169F068394471613844F06009E000996B
+:107650000822284608F086FA7069C7F30A11084420
+:1076600070612068816941F010018161206808F033
+:1076700075FA00034FF0080B4FF0000A4FF00109B4
+:107680007CD52068002608F048FA074674E0F80721
+:1076900070D02068F1B208F059FA8046C00707D0D0
+:1076A00005EB4611C1F8089B3146204605F0DCF891
+:1076B0005FEA087024D505EB4611C1F808BBFA490A
+:1076C000206800E03EE2026C00EB461001928A4224
+:1076D000D0F8081B05D9090403D54FF40041C0F8C0
+:1076E000081B204600F001FBEF490198884207D9AA
+:1076F000A079012804D120680121009A07F0C2FF77
+:107700005FEAC86004D505EB46111020C1F8080BEC
+:107710005FEA88701DD56869000605D5D5F80408AC
+:1077200040F48061C5F8041806EBC60004EB800045
+:1077300090F8571200F51570012905D180F803A0C3
+:107740002046F1B200F004FA05EB46110220C1F820
+:10775000080B5FEA886004D505EB46112020C1F8CC
+:10776000080B5FEA884005D505EB46114FF4005041
+:10777000C1F8080B7F08761C002F88D1206808F01C
+:10778000EDF940036ED5206808F0C0F900260746E1
+:1077900066E0F80762D02068F1B208F0C5F98046CB
+:1077A000C00723D0D5F8342806F00F0C05EB46139C
+:1077B00009FA0CF08243C5F83428C3F80899A07977
+:1077C00001280FD106EBC60004EB8000D0E90721A9
+:1077D0001144016236B9606A20B920680121009A1B
+:1077E00007F050FF2046F1B2FFF7C4FD5FEA0870D2
+:1077F00003D505EB4611C1F808B95FEAC86004D5A6
+:1078000005EB46111020C1F808095FEA486004D56D
+:1078100005EB46114020C1F808095FEA887016D5CB
+:107820003146284608F043F906EBC60004EB800019
+:10783000C17D1430012905D180F803A02046F1B2A2
+:1078400000F082F905EB46110220C1F808095FEA51
+:10785000086003D53146204605F06CF87F08761C99
+:10786000002F96D1206808F079F9002811DAD5F8B0
+:10787000040820F00101C5F8041894F8CC0401288C
+:107880003BD0204600F016FA2068416901F0004123
+:107890004161206808F062F900050BD5D5F80808A9
+:1078A000C00702D0204600F049FA2068416901F47F
+:1078B00000614161206808F051F900010AD5206893
+:1078C000416901F00061416194F8CC04E0B12046C7
+:1078D00000F034FA206808F041F9C00472D5D5F8F8
+:1078E000040820F00100C5F804082068102108F001
+:1078F000DEF800214FF67F322DE00021204684F88B
+:10790000CCA4FFF70BFDBFE784F8CC942068406D52
+:107910000121C0F38300C4F8D0042046FFF7FEFC29
+:10792000D8E700BF05EB4110C0F80829D0F80039AE
+:1079300023F40013C0F80039C0F8082BD0F8003B3E
+:1079400023F40013C0F8003BD0F8003B43F0006381
+:10795000C0F8003B491C20798842E3D8D5F81C08C0
+:1079600040F00111C5F81C18E07B68B1D5F8840817
+:1079700040F00B01C5F88418D5F8440840F00B011D
+:107980002846C5F844180DE0D5F8140842F22B013A
+:107990000843C5F81408D5F8100840F00B01284634
+:1079A000C5F81018D0F8000820F4FE61C5F80018DA
+:1079B000A1792068009A07F065FE2068416901F40A
+:1079C00080514161206808F0C9F8800416D520680C
+:1079D00007F0A2FC206808F088F8E07101F03AFB9B
+:1079E00023680146E279184608F01CF9204600F0A9
+:1079F0004BF92068416901F400514161206808F0A9
+:107A0000ADF8000707D5204600F058F92068416915
+:107A100001F008014161206808F0A0F8000615D5C2
+:107A2000A869012620F08001A9610CE006EBC600E0
+:107A300004EB800090F85702012803D12046F1B2F0
+:107A4000FFF7AFFC761C2079B042EFD8206808F031
+:107A500085F8C0021FD501264F4614E006EBC6008C
+:107A600005EB461304EB8001D3F800090A7E012AD6
+:107A700008D1002806DAF0B2CF7540F08001204628
+:107A8000FFF78FFC761C2079B042E7D82068416967
+:107A900001F480114161206808F060F8800234D55B
+:107AA00001204A4629E000000A30544F00EBC00391
+:107AB00005EB401604EB8301D6F8006B91F85832C1
+:107AC000012B19D1002E17DA94F8D434C6F30046EE
+:107AD00003F00103B3420FD181F85722A96941F0A5
+:107AE0008003AB616969090606D4D5F8040840F43F
+:107AF0000070C5F8040803E0401C21798142D5D804
+:107B00002068416901F400114161206808F026F8FD
+:107B1000400007D52046FFF729FC2068416901F0A5
+:107B200080414161206808F019F840070AD52068B3
+:107B30004568680702D52046FFF72FFC206841689A
+:107B400029434160BDE8FC9FD0F8E00407F099B8F4
+:107B5000D0F8E00407F0A9B8F8B5040004D094F810
+:107B60009504002510B106E00120F8BD204684F8F8
+:107B7000945400F057F8032084F89504206807F027
+:107B80007BFD207C8DF8000094E80F0007F0D2FB0D
+:107B90000226B0BB2068002108F004F888BB002052
+:107BA00001270CE000EBC001421C04EB81014F7582
+:107BB0000D76CD610D624D620875C885D0B2217910
+:107BC0008142EFD8002011E000EBC001421C04EB21
+:107BD000810181F8555281F85852C1F85C52C1F8C0
+:107BE0006052C1F8645281F85402D0B221798142C6
+:107BF000EAD8207C8DF8000094E80F0007F086FC9E
+:107C000010B184F89564AFE7207B657484F89574AF
+:107C1000012802D12046FFF76DFB206807F068FCC1
+:107C20000020F8BD10B5B0B00446B8216846F8F79A
+:107C300034FE13492068884220D100204FF480216F
+:107C40004FF440122192CDE90010684600F008FC84
+:107C500008B1FCF7B7F800F0B3F80A48016841F042
+:107C60000071016000680022052100F000702E9074
+:107C70004D20FEF7D1FF4D20FEF7C1FF30B010BD03
+:107C800000000440D844025870B50446C07901256C
+:107C900070B1022801D0FCF795F8D4F8E004294629
+:107CA00007F072F8D4F8E004BDE8704007F026B899
+:107CB0000025F2E7D0F8E00407F04FB8D0F8E00470
+:107CC00007F055B810B5044690F8940401280AD07E
+:107CD0000120617484F89404206807F092FF00206A
+:107CE00084F8940410BD022010BDD0F8E02400F206
+:107CF0009C41104607F054B810B590F8941404460F
+:107D00000068012909D0012184F89414C16849064A
+:107D100009D5617B012902D005E0022010BD816BED
+:107D200041F480318163206807F09FFE206807F0EE
+:107D3000D1FB002084F8940410BD000010B5044667
+:107D4000D0F8E00407F06EF82068D0F8001E41F08B
+:107D50000101C0F8001EE07A002804D00248016842
+:107D600041F00601016010BD10ED00E0134970B54F
+:107D70000A68D243520705D5096801F0070181421C
+:107D800013D118E00A6822F0070202430A60FEF7E6
+:107D900095FE0A4D4FF47A760446083D07E000BF91
+:107DA000FEF78CFE001BB04201D9012070BD28688F
+:107DB000C0438004F4D4002070BD00000C48025879
+:107DC0000248016841F08071016070470C48025818
+:107DD00010B501F03FF905490968054AC1F30211E0
+:107DE000515C01F01F01C84010BD00002044025842
+:107DF000903101084A4930B5494C0B1D0A680C34D2
+:107E000009681D68246802F0030305F00102C1F34C
+:107E10000511C4F3CC04002914FB02F200EE102A71
+:107E2000F8EE400A76D0414A9FED3E1ADFED3E1A49
+:107E3000B7EE000A23B1012B5AD0022B18D15CE017
+:107E4000374C283C23689B0612D5394B246801EE39
+:107E5000901A1168C4F3C104F8EE612AE34001EE00
+:107E6000903AC1F30801F8EE611A81EEA22A07E008
+:107E700002EE101A1168F8EE422A81EEA22A45E0BD
+:107E800001EE901A1168F8EE611A40EE811A71EE57
+:107E9000800A62EE200AC1F3462101EE101AB8EE04
+:107EA000411A31EE001AC0EE811ABCEEE11A80EDE3
+:107EB000001A1168C1F3064101EE101AB8EE411A1A
+:107EC00031EE001AC0EE811ABCEEE11A80ED011A03
+:107ED0001168C1F3066101EE101AB8EE411A31EED5
+:107EE000000A80EE801ABCEEC10A80ED020A30BDA5
+:107EF00001EE901ADFED0F2A03E001EE901ADFED9C
+:107F00000E2A1168F8EE611A82EEA12AC1F3080167
+:107F1000B6E7FFE7002101604160816030BD0000ED
+:107F200028440258000000390024744C30440258A0
+:107F30000090D0030024744A001BB74B494930B568
+:107F4000484C0B1D0A68143409681D68246802F047
+:107F50000303C5F30012C1F30531C4F3CC040029B7
+:107F600014FB02F200EE102AF8EE400A75D03F4AE8
+:107F70009FED3D1AB7EE000A6BB1DFED3D1A012B04
+:107F800001D0022B64D002EE101A1168F8EE422ADA
+:107F900081EEA22A21E0334C283C23689B0612D5AF
+:107FA000344B246801EE901A1168C4F3C104F8EE52
+:107FB000612AE34001EE903AC1F30801F8EE611A3C
+:107FC00081EEA22A0BE001EE901ADFED2B2A00BF12
+:107FD000F8EE611A116882EEA12AC1F3080101EEE0
+:107FE000901A1168F8EE611A40EE811A71EE800A5B
+:107FF00062EE200AC1F3462101EE101AB8EE411AD2
+:1080000031EE001AC0EE811ABCEEE11A80ED001AC2
+:108010001168C1F3064101EE101AB8EE411A31EEB3
+:10802000001AC0EE811ABCEEE11A80ED011A116847
+:10803000C1F3066101EE101AB8EE411A31EE000AE2
+:1080400080EE801ABCEEC10A80ED020A30BD04E069
+:1080500001EE901ADFED092ABAE7002101604160C4
+:108060008160F3E728440258000000393844025880
+:108070000024744A0090D0030024744C001BB74BBA
+:10808000494930B5484C0B1D0A681C3409681D6805
+:10809000246802F00303C5F30022C1F30551C4F3C1
+:1080A000CC04002914FB02F200EE102AF8EE400A7C
+:1080B00075D03F4A9FED3D1AB7EE000A6BB1DFED78
+:1080C0003D1A012B01D0022B64D002EE101A116868
+:1080D000F8EE422A81EEA22A21E0334C283C2368A4
+:1080E0009B0612D5344B246801EE901A1168C4F334
+:1080F000C104F8EE612AE34001EE903AC1F30801B1
+:10810000F8EE611A81EEA22A0BE001EE901ADFED83
+:108110002B2A00BFF8EE611A116882EEA12AC1F382
+:10812000080101EE901A1168F8EE611A40EE811A0A
+:1081300071EE800A62EE200AC1F3462101EE101AA8
+:10814000B8EE411A31EE001AC0EE811ABCEEE11A07
+:1081500080ED001A1168C1F3064101EE101AB8EE65
+:10816000411A31EE001AC0EE811ABCEEE11A80ED20
+:10817000011A1168C1F3066101EE101AB8EE411A36
+:1081800031EE000A80EE801ABCEEC10A80ED020AD0
+:1081900030BD04E001EE901ADFED092ABAE70021B4
+:1081A000016041608160F3E7284402580000003913
+:1081B000404402580024744A0090D0030024744CB8
+:1081C000001BB74B2DE9F04FA14A0546DFF87CA212
+:1081D00080F48070DFF8809289B013119F4C0843BF
+:1081E0009C48AAF104064FF0805C4FF0005828D05C
+:1081F000DFF858B285F480670F430BF1080B4FD0BE
+:1082000085F400670F4360D085F480570F4372D028
+:1082100085F400570F434FF480394FF4003E69D086
+:1082200085F400270F4373D085F480370F4370D057
+:1082300085F480460E436DD085F400420A436AD02F
+:108240002AE0DAF8001001F00701052924D2DFE85E
+:1082500001F0F9AA6A259F0006A8FFF7CBFD079851
+:1082600009B0BDE8F08F6846FFF768FE0098F7E7B1
+:1082700003A8FFF705FF0398F2E72068C0F3C100E9
+:1082800022FA00F0ECE72268D2056ED561456CD188
+:108290001846E5E74145E3D00020E1E74846DFE73F
+:1082A000DBF8001001F46001B1F5800F3BD005DC74
+:1082B00000294AD0B1F5001FEED174E0B1F5C00F2E
+:1082C000ECD0B1F5000FE7D162E0DBF8001001F06F
+:1082D000E061B1F1007F26D004DCB1B3B1F1807F61
+:1082E000DAD160E0B1F1407FD8D0B1F1806FD3D165
+:1082F0004EE000E01BE0DAF8001001F4E041B1F5D7
+:10830000005F10D008DC01B3B1F5805FC4D14AE052
+:1083100035E058E065E088E0B1F5405FBED0B1F5EA
+:10832000804FB9D134E020688000B5D5A0E7DAF8F5
+:10833000001001F4E021B1F5403F6DD006DC61B1E1
+:1083400049457BD07145A7D158E07BE0B1F5802F3E
+:1083500066D0B1F5A02F9FD10DE000F09DFE7FE724
+:108360006846FFF7EBFD01987AE728E003A8FFF7DE
+:1083700087FE049874E7216889038AD48CE7DBF8C8
+:10838000001011F440310ED0494510D0714583D111
+:108390003168256801F040516D077FF574AF002901
+:1083A0007FF471AF69E720680001E7D55BE72068DB
+:1083B0008000E3D503A8FFF763FE059850E7226825
+:1083C0009203DBD566E7306810F480303AD0484538
+:1083D000D4D120680001D1D56846FFF7AFFD0298DF
+:1083E0003EE7DBF8001001F0E041B1F1405F13D04F
+:1083F00008DC71B1614521D04145BFD120688000C2
+:10840000B4D449E7B1F1804F0AD0B1F1A04FB2D056
+:1084100042E7FFF7DDFC23E720684007AED52CE7F5
+:108420002068C005AAD533E708E0DAF8001011F09B
+:108430004051A0D0614505D041459FD12068000141
+:108440008ED429E72068800198D505E7504402586A
+:108450000090D00300366E010080BB00004402583B
+:108460002DE9FE4F0546DFF800A450F8081B002454
+:10847000FD4FC943019005F1280026460AF1240A60
+:10848000009008011DD4686E50B1B0F5801F0CD06B
+:10849000B0F5001F0ED0B0F5401F1ED001240FE034
+:1084A000386840F40030386017E00198022104F089
+:1084B00093FA03E00098022104F01EFB04000CD0A4
+:1084C00026462888C043C00523D4A86D05281ED29F
+:1084D000DFE800F00C11161B1B006A6EDAF80010C2
+:1084E00021F440111143CAF80010EAE7386840F45B
+:1084F0000030386009E00198002104F06DFA03E0D3
+:108500000098002104F0F8FA0446C4B100E0012408
+:1085100026462888DFF85083C04308F12C08400520
+:108520002FD4D5F8A400B0F5C00F28D010DCB8B116
+:10853000B0F5001F19D0B0F5800F0FD11AE0AA6D69
+:10854000DAF8001021F007011143CAF80010E0E743
+:10855000B0F5000F13D0B0F5200F10D001240FE0BC
+:10856000386840F40030386009E00198002104F0D8
+:1085700033FA03E00098002104F0BEFA044694B1F7
+:1085800026462888C043000530D4D5F8A800B0F1AD
+:10859000407F29D011DCC0B1B0F1807F1AD0B0F19A
+:1085A000007F10D11BE0D5F8A420D8F8001021F4EA
+:1085B00060011143C8F80010E3E7B0F1806F13D0F9
+:1085C000B0F1A06F10D001240FE0386840F4003003
+:1085D000386009E00198002104F0FEF903E00098FA
+:1085E000002104F089FA044694B126462868DFF891
+:1085F00078B2C0430BF1200B80011FD4E86CD8B1D6
+:1086000010280FD0202812D0302815D0012414E0D3
+:10861000D5F8A820D8F8001021F0E0611143C8F87F
+:108620000010E3E7386840F40030386004E0019857
+:10863000022104F0D1F9044674B126462888C043CB
+:10864000C0042BD4E86DB0F5005F20D00DDCA0B1E4
+:10865000B0F5805F0FD115E0EA6CDBF8001021F077
+:1086600030011143CBF80010E8E7B0F5405F13D0BC
+:10867000B0F5804F10D001240FE0386840F400308E
+:10868000386009E00198002104F0A6F903E00098A1
+:10869000002104F031FA04468CB126462888C043F4
+:1086A000800429D4286EB0F5403F23D010DC08B3F5
+:1086B000B0F5803F14D0B0F5003F0FD115E0EA6D62
+:1086C000DAF8001021F4E0411143CAF80010E5E7A0
+:1086D000B0F5802F0ED0B0F5A02F0BD001240AE00A
+:1086E0000198012104F078F903E00098012104F0D9
+:1086F00003FA044694B126462888C04340042AD48D
+:10870000D5F8AC00B0F1405F23D010DC08B3B0F175
+:10871000805F14D0B0F1005F0FD115E02A6EDAF857
+:10872000001021F4E0211143CAF80010E4E7B0F191
+:10873000804F0ED0B0F1A04F0BD001240AE0019879
+:10874000012104F049F903E00098012104F0D4F973
+:10875000044674B126462888C04300041FD4E86E3E
+:10876000D8B1B0F1805F0ED0B0F1005F10D001241D
+:1087700014E0D5F8AC20D8F8001021F0E041114306
+:10878000C8F80010E7E7386840F40030386004E0CB
+:108790000198012104F020F9044674B126462868A6
+:1087A000C043C0011ED4A86CD0B101280ED002284D
+:1087B00011D0032814D0012413E0EA6EDAF8001077
+:1087C00021F040511143CAF80010E8E7386840F43E
+:1087D0000030386004E00198022104F0FDF80446FE
+:1087E0006CB126462868C043400255D41F48016832
+:1087F00041F480710160FEF761F981460EE0AA6CD8
+:10880000DBF8001021F003011143CBF80010E9E779
+:10881000FEF754F9A0EB090064283BD81348006820
+:10882000C005F5D5BCBBDFF84090B5F8B01009F134
+:108830004409D9F8000001F4407100F44070884206
+:1088400011D0D9F80010D9F8002021F4407142F479
+:108850008032C9F80020D9F8002022F48032C9F80B
+:108860000020C9F8001003E02C44025800480258C8
+:10887000D5F8B000B0F5807F19D1FEF71FF902904E
+:1088800011E000BFFEF71AF90299411A41F288304F
+:10889000814208D9032426462878DFF81494C0437F
+:1088A000C00721D03CE0D9F800008007EAD5D5F810
+:1088B000B010C1F301200328FE480DD0016821F457
+:1088C0007C510160B5F8B020D9F80010C2F30B025A
+:1088D0001143C9F80010DFE7F74A036802EA1112F2
+:1088E00023F47C511143ECE7A86F182816D005DC5F
+:1088F000A0B1082808D0102804D10AE020280DD003
+:1089000028280BD001240AE00198012104F064F822
+:1089100003E00098012104F0EFF8044664B1264614
+:108920002878C04380071ED4686F062819D2DFE874
+:1089300000F0160C11161616AA6FD9F8001021F0C7
+:1089400038011143C9F80010EAE70198012104F049
+:1089500043F803E00098012104F0CEF804467CB10E
+:1089600000E0012426462878C04340071FD4D5F8EC
+:108970009000062819D2DFE800F0160C1116161622
+:108980006A6FD9F8001021F007011143C9F80010EF
+:10899000E9E70198012104F01FF803E000980121A4
+:1089A00004F0AAF80446A4B100E001242646287881
+:1089B000C04380062BD4D5F88C00B0F1405F24D0A2
+:1089C00011DC10B3B0F1805F15D0B0F1005F10D1B1
+:1089D00016E0D5F89020D8F8001021F007011143D7
+:1089E000C8F80010E3E7B0F1804F0ED0B0F1A04F0F
+:1089F0000BD001240AE00198002103F0EDFF03E011
+:108A00000098022104F078F8044694B126462878AC
+:108A1000C04340062BD4D5F89800B0F5406F24D061
+:108A200011DC10B3B0F5806F15D0B0F5006F10D128
+:108A300016E0D5F88C20D9F8001021F0E041114360
+:108A4000C9F80010E3E7B0F5805F0ED0B0F5A05F85
+:108A50000BD001240AE00198002103F0BDFF03E0E0
+:108A60000098022104F048F8044694B1264628787C
+:108A7000C04300062BD4D5F89C00B0F5C04F24D0DD
+:108A800011DC10B3B0F5005F15D0B0F5804F10D1F8
+:108A900016E0D5F89820D8F8001021F4E0511143E1
+:108AA000C8F80010E3E7B0F5004F0ED0B0F5204F46
+:108AB0000BD001240AE00198002103F08DFF03E0B0
+:108AC0000098022104F018F8044654B1264628788C
+:108AD000C04300071ED4D5F88000B0F5805F0AD0EF
+:108AE0000FE0D5F89C20D8F8001021F46041114324
+:108AF000C8F80010EBE70098022103F0FDFF00B179
+:108B00000126D5F88020D9F8001021F440511143F6
+:108B1000C9F800102878C043C00613D4D5F89400D3
+:108B2000B0F5807F05D10098022103F0E5FF00B188
+:108B30000126D5F89420D8F8001021F44071114393
+:108B4000C8F800102868C043000316D4D5F8A00068
+:108B500038B1B0F5803F09D0B0F5003F0BD001240B
+:108B60000AE00198002103F037FF03E0009802219A
+:108B700003F0C2FF04468CB126462868C043400378
+:108B800022D4D5F88400B0F5801F11D0B0F5001FB5
+:108B900013D0B0F5401F15D0012414E0D5F8A02063
+:108BA000D8F8001021F440311143C8F80010E4E770
+:108BB000386840F40030386004E00098012103F088
+:108BC0009BFF04465CB126462868C043C0031CD402
+:108BD000286D70B1B0F5803F10D0012414E0D5F8B5
+:108BE0008420D9F8001021F440111143C9F8001075
+:108BF000EAE7386840F40030386004E00198022168
+:108C000003F0EAFE0446DCB126462868C043800033
+:108C100005D40098022103F06FFF00B101262868F7
+:108C2000C04380031BD4E86FB8B1B0F5807F10D08B
+:108C3000B0F5007F11D0B0F5407F0ED001240DE0DB
+:108C40002A6DDBF8001021F480311143CBF80010BD
+:108C5000DBE7386840F4003038607CB3264628688B
+:108C6000C043C00207D42A6FDAF8001021F0004197
+:108C70001143CAF800102868C043800207D4AA6EC6
+:108C8000DAF8001021F080711143CAF8001028684A
+:108C9000C043400009D40748016821F40041016045
+:108CA0000168D5F8B420114301602868C04306E08C
+:108CB0005444025810440258CFFFFF001DE007D46F
+:108CC0006A6DDBF8001021F040511143CBF8001021
+:108CD0002868C043000208D4D5F88820D9F80010CD
+:108CE00021F440011143C9F8001028790024C04341
+:108CF00000F00100204309D00EE0EA6FD9F800101F
+:108D000021F440711143C9F80010A8E7019800212F
+:108D100003F062FE00B106462879C04300F002006D
+:108D2000204305D10198012103F056FE00B106460B
+:108D30002879C04300F00400204305D101980221A6
+:108D400003F04AFE00B106462879C04300F008004F
+:108D5000204305D10098002103F0CEFE00B1064665
+:108D60002879C04300F01000204305D1009801216C
+:108D700003F0C2FE00B106462879C04300F020008F
+:108D8000044304D10098022103F0B6FE00B916B1E5
+:108D90000120BDE8FE8F0020FBE700002DE9F05F19
+:108DA00004000F467ED0DFF83882D8F8000000F0CB
+:108DB0000F00B8420CD2D8F8001021F00F0139434F
+:108DC000C8F80010D8F8000000F00F00B84269D1D0
+:108DD0002078844D40070AD52069296801F0700188
+:108DE000884204D9296821F0700101432960207864
+:108DF0007C4E361D00070AD56069316801F07001AC
+:108E0000884204D9316821F0700101433160207833
+:108E1000C0060AD5A069316801F4E061884204D92E
+:108E2000316821F4E061014331602078DFF8B4B1AA
+:108E300080060BF1080B0CD5E1695846DBF80020E1
+:108E400002F07002914204D9026822F070020A43D3
+:108E50000260207880070AD5E068296801F00F01D8
+:108E6000884204D9296821F00F0101432960207844
+:108E7000C0073ED05B49A2682868183920F47060AA
+:108E8000104328606068022818D0032819D00968A8
+:108E9000012819D0490700294ADADFF848A1AAF1C8
+:108EA000080A00E044E0DAF8002022F0070202435A
+:108EB000CAF80020FDF702FE814612E00968890326
+:108EC000E9E709688901E6E7C905E4E7FDF7F6FD8A
+:108ED000A0EB090141F28830814202D90320BDE8AC
+:108EE000F09F6168DAF8000000F03800B0EBC10FC5
+:108EF000ECD1207880070AD5E068296801F00F01DD
+:108F0000884204D2296821F00F0101432960D8F872
+:108F10000010404601F00F01B9420BD9016821F061
+:108F20000F0139430160006800F00F00B84201D022
+:108F30000120D4E7207840070AD52069296801F08C
+:108F40007001884204D2296821F070010143296030
+:108F5000207800070AD56069316801F07001884205
+:108F600004D2316821F07001014331602078C006DD
+:108F70000AD5A069316801F4E061884204D2316801
+:108F800021F4E06101433160207880060CD5E1696D
+:108F90005846DBF8002002F07002914204D20268C9
+:108FA00022F070020A43026000F09AF80E492A6823
+:108FB0002B68C2F3032203F00F038A5CC95C02F042
+:108FC0001F0201F01F01D040084A20FA01F1116090
+:108FD0000749086007480068BDE8F05FFDF7AABDD3
+:108FE0000020005218440258903101088C000020E3
+:108FF000880000208000002070B5144C3F220260E1
+:10900000124A24680832131D114D04F0070444600D
+:1090100016681C1D06F470668660166806F00F065A
+:10902000C660126802F0700202611A6802F07002F3
+:1090300042611A6802F4E0628261226802F0700202
+:10904000C261286800F00F00086070BD104402582B
+:109050000020005230B500F043F80B4A0B490C4B8E
+:1090600015681468C5F3032204F00F048A5C095DD7
+:1090700002F01F0201F01F01D040064A20FA01F160
+:1090800019601060084630BD18440258903101083C
+:109090008C0000208800002000B5FFF7DBFF0549A9
+:1090A0000968054AC1F30211515C01F01F01C84073
+:1090B00000BD00001C4402589031010800B5FFF7C4
+:1090C000C9FF05490968054AC1F30221515C01F055
+:1090D0001F01C84000BD00001C4402589031010827
+:1090E000454970B545480968434B103B11F03802BB
+:1090F00008D00111082A03D0102A0BD0182A0BD04F
+:10910000084670BD19688906FBD51968C1F3C1010D
+:10911000C84070BD3A4870BD3749374D18310C1DF5
+:1091200024350A68096826682D6802F0030406F0F1
+:109130000102C1F30511C5F3CC0515FB02F200EEE7
+:10914000102AB8EE400AE9B32F4ADFED2E0AB7EE37
+:10915000001A6CB1DFED2D1A012C01D0022C43D086
+:1091600002EE101A1068F8EE422A81EEA22A1EE0E2
+:109170001C68A40611D51B6801EE901A1168C3F390
+:10918000C103F8EE612AD84001EE900AC1F308004D
+:10919000F8EE611A81EEA22A0BE001EE901ADFEDE3
+:1091A0001C2A00BFF8EE611A106882EEA12AC0F3F3
+:1091B000080001EE900AF8EE611A40EE201A31EE36
+:1091C000810A00E015E022EE000A1068C0F3462094
+:1091D000401C00EE900AF8EE600A80EE201ABCEE09
+:1091E000C10A10EE100A70BD01EE901ADFED092AD7
+:1091F000D8E7002070BD0000104402580090D00352
+:1092000000366E0100000039304402580024744AD0
+:109210000024744C001BB74BF0B50D461F49204C81
+:10922000002887B016464FF000004FF002020F688A
+:109230004FF0030319D047F004070F60096801F0ED
+:109240000401059111020091CDE90120CDE903301F
+:1092500014486946FDF71AFB206845EAC61120F05C
+:109260007E400843206007B0F0BD47F001070F6063
+:10927000096801F0010105914FF480710091CDE979
+:109280000120CDE9033008486946FDF7FFFA206860
+:10929000354320F0FE702843E4E70000E044025824
+:1092A0001044025800080258000002582DE9F05FEF
+:1092B00004007DD0FF4F2078FE4D1837DFF8F4838F
+:1092C000103DC00748D0D8F80000396800F03800D9
+:1092D000102815D0182803D101F0030002280FD060
+:1092E0006068B0F5803F12D010B1B0F5A02F18D053
+:1092F000286820F480302860286820F4802009E065
+:109300002868800328D560680028D2D024E0286827
+:1093100040F480302860606888B1FDF7CFFB0646D6
+:1093200009E0286840F480202860F0E7FDF7C6FBDC
+:10933000801B64287ED828688003F7D50CE0FDF7F1
+:10934000BDFB064605E000BFFDF7B8FB801B6428A7
+:10935000F0D828688003F7D42078800756D5D8F84D
+:109360000000DFF85093396810F03800A9F10C09BB
+:109370000ED0182801D188070AD0E068A8B3296860
+:1093800021F0190101432960FDF798FB064628E00A
+:109390002868400702D5E06800288AD0E16828687C
+:1093A00020F0190008432860FDF788FB064606E018
+:1093B000D2E000BFFDF782FB801B0228BAD82868E4
+:1093C0004007F7D5217CD9F8002022F0FE4242EA7E
+:1093D0000161C9F8001019E0FDF770FB801B02283D
+:1093E000A8D828684007F7D5ECE7FFE7286820F001
+:1093F00001002860FDF762FB064604E0FDF75EFB16
+:10940000801B022896D828684007F7D42078C00629
+:1094100046D5D8F80000DFF89C92396800F0380093
+:10942000A9F10409082812D0182805D101F0030079
+:10943000012800E0CEE00AD0E0690028286820D0AA
+:1094400040F080002860FDF739FB064615E02868EB
+:10945000C00502D5E06980287ED194F82010D9F8A3
+:10946000002022F07C5242EA0161C9F8001017E0A6
+:10947000FDF724FB801B0228A0D82868C005F7D57B
+:10948000EBE720F080002860FDF718FB064604E0BB
+:10949000FDF714FB801B022890D82868C005F7D47C
+:1094A0002078000729D58348616964300029814606
+:1094B000016811D041F001010160FDF7FFFA064695
+:1094C00005E000BFFDF7FAFA801B022888D8D9F81A
+:1094D00000008007F6D510E021F001010160FDF7E2
+:1094E000EDFA064605E000BFFDF7E8FA801B02280A
+:1094F00070D8D9F800008007F6D42078800623D5EC
+:10950000A0690028286810D040F480502860FDF73A
+:10951000D5FA064605E000BFFDF7D0FA801B022809
+:1095200058D828688004F7D50EE020F480502860D1
+:10953000FDF7C4FA064604E0FDF7C0FA801B0228D6
+:1095400048D828688004F7D42078400751D5DFF840
+:109550006891D9F8001000E015E141F48071C9F874
+:109560000010FDF7ABFA064605E000BFFDF7A6FACE
+:10957000801B64282ED8D9F80000C005F6D54D4EC2
+:10958000A068603601280AD008B1052813D03068D9
+:1095900020F001003060306820F0040002E0306804
+:1095A00040F001003060A06841F2883A98B1FDF7C0
+:1095B00085FA81460AE0306840F004003060EEE74A
+:1095C000FDF77CFAA0EB0901514503D8306880070C
+:1095D000F6D50EE072E0FDF771FA814606E000BFB5
+:1095E000FDF76CFAA0EB0901514567D83068800798
+:1095F000F6D4606A00287CD0DFF8B8A0D8F8001054
+:109600000AF1200A4FF6F87B0AF10408C1F3C201FF
+:109610000329AAF104096DD00228286820F080707F
+:10962000286003D0FDF74AFA044681E0FDF746FAC8
+:10963000064604E0FDF742FA801B022875D8286828
+:109640008001F7D4E26A40F2F331386854F8283FD9
+:10965000884340EA021018433860217B4FF4FE0C27
+:1096600022894FF0FE47208A4902267D521E401E65
+:10967000A1F5007189B2C2F308021143761E0CEA0B
+:1096800000400143484607EA06621143CAF8001049
+:10969000D9F8001021F00101C9F80010D8F8003005
+:1096A000266A23EA0B0343EAC601C8F80010D9F87A
+:1096B000001004E0104402580048025835E0A26946
+:1096C00021F00C011143C9F800100168E26921F092
+:1096D000020111430160016841F4803101600168B9
+:1096E00041F400310160016841F4802101600168AA
+:1096F00001E06CE020E041F001010160286840F0E9
+:1097000080702860FDF7DAF9044604E0FDF7D6F929
+:10971000001B022809D828688001F7D557E000BF50
+:10972000FDF7CCF9001B022802D90320BDE8F09F09
+:1097300028688001F4D44AE039680128DAF800008A
+:1097400021D0A26A01F0030393421CD1E26AC1F363
+:1097500005118A4217D1216BC0F30802491E8A42C3
+:1097600011D1616BC0F34622491E91420BD1A16B0E
+:10977000C0F30642491E914205D1E16BC0F3066079
+:10978000491E814201D00120D0E7A16C4646D8F89D
+:109790000000C0F3CC00814219D0D9F800004D463A
+:1097A00020F00100C9F80000FDF788F94FEA000732
+:1097B000FDF784F9B842FBD0A26C306820EA0B00B8
+:1097C00040EAC2003060286840F0010028600020B4
+:1097D000ACE700002DE9F04104001D4616460F4697
+:1097E00003D0D4F8880018B108E00120BDE8F0816A
+:1097F000002084F88400204601F058FC2420C4F89E
+:1098000088002068016821F001010160A06A10B1A0
+:10981000204604F0A9F8204604F048FA0128E5D0D3
+:10982000206871050D4A41EA0541836843F480438D
+:1098300083602068836823F400433B43836020688F
+:10984000036813400B4303602068016841F0010185
+:1098500001602046BDE8F04104F0EAB8FFFF00FCDB
+:1098600070B5044603F078FA022811D0204603F0C0
+:1098700073FA084D05EB40108069002808D0204697
+:1098800003F06AFA05EB40108069BDE870400047BC
+:1098900070BD0000509B00202DE9F0470446006891
+:1098A000002103694269876894F8816000F13009FA
+:1098B0005FEA025C03EA02050AD51A0708D5816946
+:1098C00041F400618161204600F0C6FCBDE8F087EC
+:1098D00015F0600F08D1680706D5616F20468847EC
+:1098E000216F20468847012105F04100012805D15C
+:1098F000680703D4216F20468847012105F0220024
+:10990000022806D1680704D4616F2046BDE8F047FD
+:1099100008470029DAD128074FF001085BD52068F5
+:10992000816941F0080181612068816941F010017D
+:1099300081612068816941F4006181612068016969
+:1099400021F0080101612068806810F4404F20D0A8
+:1099500023E0E0680F2806D92068616E006B08607C
+:10996000606E001D0FE0072806D9B9F80000616E8F
+:109970000880606E801C06E02068616E90F8300000
+:109980000870606E401C6066B4F86A00401EA4F85F
+:109990006A00B4F86A000028DBD1204603F042F9DF
+:1099A00084F88180D4F8840018B12046FFF758FF6E
+:1099B0008CE7052E07D0042E09D0032E86D1204631
+:1099C00000F06CFD82E7204600F07AFD7EE720463D
+:1099D00000F00AFC7AE715F4587FE9D068060AD54A
+:1099E000D4F8840040F00400C4F884002068816941
+:1099F00041F040018161A8050AD5D4F8840040F007
+:109A00000100C4F884002068816941F4007181611B
+:109A1000E8050AD5D4F8840040F00800C4F88400B2
+:109A20002068816941F480718161A8060AD5D4F863
+:109A3000840040F08000C4F884002068816941F00F
+:109A400020018161D4F884000028B1D0206840F260
+:109A50006B32C7F381310368032923F001010160F0
+:109A60002068016921EA0201016102D084F8818045
+:109A70009BE72068104D816821F440418160E06FD0
+:109A800050B10565E06FFBF73FFB28B1D4F88400C7
+:109A900040F04000C4F88400A06F002888D005651D
+:109AA000A06FFBF731FB00288CD0D4F8840040F085
+:109AB0004000C4F8840009E7E1CC00082DE9F04734
+:109AC000040029D0594A4FF000092068584B594DDD
+:109AD0009042C4F8289006D0984204D0A84202D000
+:109AE000E1680F2918D8E1684FF0010AE76B0831E7
+:109AF000C9080AEB57167143904205D0984203D02B
+:109B0000A84201D0082907D8904203D0984201D03A
+:109B1000A84204D1102902D90120BDE8F08794F8A9
+:109B2000810020B9204684F8809000F085F802205A
+:109B300084F881002068016821F00101016020683B
+:109B4000A1698268B1F1806F02F4F81110D16268E6
+:109B5000B2F5800F01D01AB10AE0A26B22B107E082
+:109B6000A26BB2F1805F03D1026842F480520260BE
+:109B70006068400209D5E068072806D32068236D95
+:109B8000026822F480721A4303E02068026822F41B
+:109B900080720260A66AE069E26B25683043E36880
+:109BA0000A4310431843A860D4E90D02D4E90581A3
+:109BB000636A25691843D4F820C00A432668104315
+:109BC0002843A56DD4E90172D4E9123140EA0800B6
+:109BD00040EA0C0038430843104318432843F06020
+:109BE000606868B92068816821F4C05141F400615F
+:109BF00081602068816821F4C06141F480618160E6
+:109C00002068016D21F0010101656068400206D500
+:109C10002068626DC16821F000411143C160C4F841
+:109C2000849084F881A0002077E700000030014094
+:109C300000380040003C00402DE9F047B4B0074632
+:109C400014212EA8F6F729FEB8216846F6F725FE5E
+:109C500061490226386800245D4D4FF00308DFF8A3
+:109C600074A188424FF005093DD18114179400205A
+:109C7000CDE900106846FEF7F3FB08B1FAF7A2F849
+:109C800053481030016841F480510160006800F4CD
+:109C900080503390286840F008002860286800F061
+:109CA00008003390286840F002002860286830AA35
+:109CB00045464F4600F0020033908020CDE92E0645
+:109CC00082E8B00045482EA9FCF7E0FD082030AA44
+:109CD000CDE92E062EA9504682E8B000FCF7D6FD4D
+:109CE00034B0BDE8F0873E498842F9D18114179419
+:109CF0000020CDE900106846FEF7B2FB08B1FAF784
+:109D000061F833480830016841F48041016000681F
+:109D100000F480403390286840F0040028602868F0
+:109D200000F004003390286840F0020028602868A2
+:109D300006214546C84600F00200CDE92E16CDE9C1
+:109D40003045CDE9329027482EA9FCF79FFD4FF40E
+:109D50000051504630AACDE92E162EA982E83001D6
+:109D6000FCF794FD204E2723204A4FF480684FF4DF
+:109D70004039304686E81C00C6E903487461B46186
+:109D8000C6E907497462FBF777FE08B1FAF71AF8DB
+:109D9000154D2822154940237835FE671831B763E1
+:109DA000284685E81E016C61AC61C5E907496C6213
+:109DB000FBF762FE08B1FAF705F8BD67002205213E
+:109DC000AF632420FCF728FF2420FCF718FF87E767
+:109DD000E04402580004025800300140000C0258D0
+:109DE00000380040000802588C0700204000024064
+:109DF0002DE9F84F8946C16B044600689A4616461D
+:109E00004909491C1FFA81F830300090FCF756FED2
+:109E1000834694F88100012838D1B9F1000F6FD042
+:109E2000002EFCD094F8800001282FD0A1680025D6
+:109E3000012784F88070042084F88100C4F88450DD
+:109E4000C4F86490E565A4F86050256765672C3414
+:109E5000B1F5C02FA687E687E58654F82C0D18D0FB
+:109E6000C16821F4C02141F48021C16020684168AB
+:109E70006FF30F01314341602068016841F0010137
+:109E800001606068B0F5800F08D00CE00220BDE8EA
+:109E9000F88F016821F400610160E7E7206801683C
+:109EA00041F400710160E0680F2824D829E020689F
+:109EB00041694269D20705D1B4F86A3043450DD2F1
+:109EC00009040BD5006B616E0860606E001D606652
+:109ED000B4F86A00401EA4F86A000CE0FCF7EEFD3E
+:109EE000A0EB0B01514503D3BAF1FF3F03D0AAE029
+:109EF000BAF1000F40D0B4F86A000028D7D194E03E
+:109F00009FE007283CD88CE0216848694969C90767
+:109F10000AD000980088616E0880606E801C6066C0
+:109F2000B4F86A00401E15E0B4F86A20424514D225
+:109F3000010412D500980088616E0880606E801C54
+:109F40006066009909880180606E801C6066B4F8C4
+:109F50006A00801EA4F86A0012E0B4F86A100129B1
+:109F600001D18004D5D4FCF7A9FDA0EB0B0151452C
+:109F700003D3BAF1FF3F03D065E0BAF1000F62D01E
+:109F8000B4F86A000028BFD14FE0206841694269F7
+:109F9000D2070AD090F83000616E0870606E401CE5
+:109FA0006066B4F86A00401E24E0B4F86A304345A5
+:109FB00023D20A0421D590F83000616E0870606EDB
+:109FC000401C6066216891F830100170606E401C82
+:109FD0006066216891F830100170606E401C606608
+:109FE000216891F830100170606E401C6066B4F812
+:109FF0006A00001FA4F86A0013E0B4F86A20042A7B
+:10A0000002D211F4C04FC5D1FCF758FDA0EB0B01F3
+:10A01000514503D3BAF1FF3F03D014E0BAF1000F6A
+:10A0200011D0B4F86A000028AFD1204602F0FAFD42
+:10A0300084F88170D4F8840084F8805000283FF4BC
+:10A0400026AF012023E7204602F0ECFDD4F884007F
+:10A0500084F8805040F48070C4F8840084F88170E3
+:10A06000032014E72DE9F041044690F881001646DC
+:10A070000025012802D084F880502FE059B356B350
+:10A0800094F88000012829D0A268012784F8807004
+:10A09000042084F88100C4F88450256765676166F0
+:10A0A000A4F860502C34B2F5C02FA687E687E58669
+:10A0B00054F82C0D15D0C16821F4C02141F4802141
+:10A0C000C0F80C10E0684FF480410F280ED9E26F01
+:10A0D00092698A420AD084F8805055E00220BDE897
+:10A0E000F081016821F400610160EBE707284FF47B
+:10A0F000005205D9E06F8069904201D08842EAD1D0
+:10A100002068836823F480438360E068072811D8BF
+:10A11000E06F8369934205D1B4F86A20521C52085B
+:10A12000A4F86A208069884210D1B4F86A00C01C83
+:10A13000800809E00F2809D8E06F8069884205D1BE
+:10A14000B4F86A00401C4008A4F86A00E06F234994
+:10A150000164E16F2248C863E16F2248C864E06F80
+:10A160000565B4F86A302168626EE06F3031FBF744
+:10A1700061FE58B1D4F8840084F8805040F010009B
+:10A18000C4F8840084F881700120A8E7E06FC069FA
+:10A19000B0F5807F206841686FF30F0100D0314334
+:10A1A00041602068816841F48041816020680169D4
+:10A1B00041F4507101612068016841F001010160C2
+:10A1C0006068B0F5800F04D12068016841F4007127
+:10A1D0000160002084F8805081E7000027CD00084E
+:10A1E00031CD0008FBCC000870B5044602F0B4FD88
+:10A1F000022811D0204602F0AFFD084D05EB4010BB
+:10A200004068002808D0204602F0A6FD05EB40106B
+:10A210004068BDE87040004770BD0000509B0020C2
+:10A2200070B5044602F098FD022811D0204602F0D5
+:10A2300093FD084D05EB40100069002808D020462A
+:10A2400002F08AFD05EB40100069BDE87040004750
+:10A2500070BD0000509B002070472DE9F84F044668
+:10A2600000689946174600F1200B8A46FCF726FC49
+:10A27000064694F88100012839D1BAF1000F7ED04A
+:10A28000002FFCD094F88000012830D0A26800256F
+:10A290004FF0010884F88080032184F88110C4F80D
+:10A2A0008450C4F85CA06566A4F8685065672567AB
+:10A2B0002C34B2F5C02FA786E786E58754F82C0D1D
+:10A2C00018D0C16821F4C02141F40031C160206878
+:10A2D00041686FF30F01394341602068016841F024
+:10A2E000010101606068B0F5800F08D00CE0022029
+:10A2F000BDE8F88F016841F400610160E7E720687C
+:10A30000016841F400710160E0680F281CD820E06A
+:10A310002068416989070BD5E16D09680162E06D2C
+:10A32000001DE065B4F86200401EA4F862000BE076
+:10A33000FCF7C4FB811B494503D3B9F1FF3F03D0B0
+:10A340009DE0B9F1000F32D0B4F862000028DFD1EF
+:10A3500079E007282FD872E02068416989071ED567
+:10A36000B4F8621001290DD9E16B59B1E16D0968AA
+:10A370000162E06D001DE065B4F8620000E07CE081
+:10A38000801E09E0E06D0188ABF80010E06D801CD4
+:10A39000E065B4F86200401EA4F862000BE0FCF730
+:10A3A0008DFB811B494503D3B9F1FF3F03D066E024
+:10A3B000B9F1000F63D0B4F862000028CCD142E0BC
+:10A3C0002068416989072ED5B4F8621003290CD999
+:10A3D000E16B402909D9E16D09680162E06D001D5A
+:10A3E000E065B4F86200001F1AE0B4F862100129B9
+:10A3F0000CD9E16B51B1E06D0188ABF80010E06D54
+:10A40000801CE065B4F86200801E09E0E16D097807
+:10A4100080F82010E06D401CE065B4F86200401E3A
+:10A42000A4F862000BE0FCF749FB811B494503D30C
+:10A43000B9F1FF3F03D022E0B9F1000F1FD0B4F80B
+:10A4400062000028BCD100224B460821204600961D
+:10A4500002F08CFC28B1D4F8840040F02000C4F84D
+:10A460008400204602F0DEFB84F88180D4F884006A
+:10A4700084F8805000283FF43BAF012038E72046A5
+:10A4800002F0D0FBD4F8841084F8805041F480713D
+:10A49000C4F8841084F88180032029E710B502F005
+:10A4A0005BFC022808D0054901EB40100068002839
+:10A4B00002D0BDE81040004710BD0000509B0020B6
+:10A4C00070B5044602F048FC022811D0204602F084
+:10A4D00043FC084D05EB40108068002808D020465A
+:10A4E00002F03AFC05EB40108068BDE87040004780
+:10A4F00070BD0000509B0020024A136883430B4349
+:10A50000136070470404005870477047704700009C
+:10A51000F0B590F83C20012A43D0012280F83C207D
+:10A52000D1E90242204ECD6922F440722243D1E9A2
+:10A53000004322F480621A4322F400622243D1E9EC
+:10A54000043422F480521A430B6B22F4005222434B
+:10A550000C8B22F480421A43036822F4702242EAF0
+:10A560000442002422F08052B34242EA050202D0A3
+:10A570000E4DAB4210D10F8D22F4700CD1E9086260
+:10A58000CD6A4CEA075121F08071314321F000710E
+:10A59000114321F000522A435A6480F83C400020C5
+:10A5A000F0BD0220F0BD00000000014000040140A9
+:10A5B000F0B590F83C20012A41D0224E012480F8C9
+:10A5C0003C40022280F83D2002681F4D5368B24291
+:10A5D000D2F808C001D0AA4203D14F6823F4700317
+:10A5E0003B430F6823F070031F4357600268B24279
+:10A5F00019D0B2F1804F16D0144B9A4213D0144B9D
+:10A600009A4210D0134B9A420DD0AA420BD0124B53
+:10A610009A4208D0114B9A4205D0114B9A4202D06F
+:10A62000104B9A4204D189682CF080031943916041
+:10A63000002180F83D4080F83C100846F0BD022023
+:10A64000F0BD000000000140000401400004004093
+:10A6500000080040000C004000180040004001408D
+:10A6600000E0004000E4004010B5040003D094F87E
+:10A670003D0010B107E0012010BD002084F83C002F
+:10A68000204600F022F8022084F83D002068211DB9
+:10A6900002F070FC012084F8480084F83E0084F841
+:10A6A0003F0084F8400084F8410084F8420084F8B8
+:10A6B000430084F8440084F8450084F8460084F898
+:10A6C000470084F83D00002010BD704790F83D1011
+:10A6D000012901D0012070471A4A022180F83D105B
+:10A6E0000168CB6843F00103CB60006890421AD048
+:10A6F000B0F1804F17D01449884214D013498842D2
+:10A7000011D0134988420ED0124988420BD0124909
+:10A71000884208D01149884205D01149884202D0A8
+:10A720001049884207D181680F4A1140062906D096
+:10A73000B1F5803F03D0016841F0010101600020C4
+:10A740007047000000000140000400400008004085
+:10A75000000C00400004014000180040004001408F
+:10A7600000E0004000E400400700010070472DE9D0
+:10A77000F041044600680027C6680569A90713D59B
+:10A78000B10711D5FA1E0261012121772068806985
+:10A790008007204602D0FFF7E9FF04E000F0F8F858
+:10A7A000204600F0EDF92777680716D5700714D515
+:10A7B000226802206FF0040111612077206880690F
+:10A7C00010F4407F204602D0FFF7D0FF04E000F0F5
+:10A7D000DFF8204600F0D4F92777280715D5300791
+:10A7E00013D5226804206FF00801116120772068DA
+:10A7F000C0698007204602D0FFF7B8FF04E000F0F0
+:10A80000C7F8204600F0BCF92777E80616D5F00611
+:10A8100014D5226808206FF010011161207720689C
+:10A82000C06910F4407F204602D0FFF79FFF04E08C
+:10A8300000F0AEF8204600F0A3F92777E80708D02B
+:10A84000F00706D021686FF001000861204600F093
+:10A8500099F9280601D4A80408D5300606D5216840
+:10A860006FF4025008612046FFF74FFEE80508D557
+:10A87000300606D521686FF4807008612046FFF726
+:10A8800043FE680608D5700606D521686FF04000C3
+:10A890000861204600F080F9A8060AD5B00608D560
+:10A8A00021686FF0200008612046BDE8F041FFF705
+:10A8B0002DBEBDE8F081000030B587B004461421FC
+:10A8C0006846F5F7EAFF246800222B4D0223294948
+:10A8D0000120AC4211D10C6844F010040C600968EE
+:10A8E00001F0100105914FF408510091CDE90132BA
+:10A8F000CDE903202148694625E0B4F1804F12D00C
+:10A900001F4D2048AC4222D10C6844F002040C6078
+:10A910000968009301F00201CDE901320392CDE90B
+:10A92000043169460FE00C6844F001040C600968CA
+:10A9300001F00101059105210091CDE90132CDE938
+:10A94000032011486946FBF7A1FF07B030BD0F4D4A
+:10A95000AC42FAD10C6844F002040C60096801F0C2
+:10A9600002010591E9130091CDE90132CDE90323FC
+:10A970006946E8E7E0440258000001400010025830
+:10A980000004004000040258000002580018004073
+:10A99000704770B5044690F83C0000260D4601282B
+:10A9A0000BD0012084F83C000C2A4AD007DC82B18D
+:10A9B000042A20D0082A06D131E0022070BD102AD6
+:10A9C00053D0142A63D00126002084F83C0030467E
+:10A9D00070BD206802F03EFB2068816941F00801EB
+:10A9E00081612068816921F00401816120682A6900
+:10A9F0008169114311E0206802F07EFB20688169C3
+:10AA000041F4006181612068816921F48061816184
+:10AA100020682969826942EA01218161D4E72068BE
+:10AA200002F0B6FB2068C16941F00801C1612068ED
+:10AA3000C16921F00401C16120682A69C16911431B
+:10AA400011E0206802F0F0FB2068C16941F4006168
+:10AA5000C1612068C16921F48061C16120682969F0
+:10AA6000C26942EA0121C161AEE7206802F018FC28
+:10AA70002068416D41F0080141652068416D21F079
+:10AA80000401416520682A69416D114311E0206885
+:10AA900002F040FC2068416D41F40061416520688E
+:10AAA000416D21F48061416520682969426D42EA67
+:10AAB0000121416588E710B5040003D094F83D00FA
+:10AAC00010B107E0012010BD002084F83C002046B2
+:10AAD00000F022F8022084F83D002068211D02F0D9
+:10AAE00049FA012084F8480084F83E0084F83F00C9
+:10AAF00084F8400084F8410084F8420084F8430060
+:10AB000084F8440084F8450084F8460084F847003F
+:10AB100084F83D00002010BD08B50168134881424B
+:10AB200001D113480FE01348B1F1804F0BD0124A06
+:10AB3000914210D1016841F002010160006800F00B
+:10AB40000200009008BD016841F001010160006849
+:10AB500000F00100F5E7094A9142F3D1016841F0A4
+:10AB600040010160006800F04000EAE70000014099
+:10AB7000F0440258E8440258000400400018004025
+:10AB80007047000000680349884201D1FBF79CBF71
+:10AB90007047000000E00040704730B590F8841026
+:10ABA000012918D0012280F884202421C0F88810BF
+:10ABB0000022202401680B680D6823F0005325F063
+:10ABC00001050D60426601680B60C0F8884080F89E
+:10ABD0008420104630BD022030BD7047704770B5EC
+:10ABE000044690F8840001281DD0012284F88420B6
+:10ABF0002420C4F8880020680568026822F0010259
+:10AC000002602068826822F060620A438260204607
+:10AC100002F088FE2268202100201560C4F8881008
+:10AC200084F8840070BD022070BD70B5044690F8B1
+:10AC3000840001281DD0012284F884202420C4F837
+:10AC4000880020680568026822F00102026020681E
+:10AC5000826822F060420A438260204602F062FE6F
+:10AC60002268202100201560C4F8881084F8840030
+:10AC700070BD022070BD70477047000010B502F033
+:10AC8000EFFF06280AD000EBC001054800EB810069
+:10AC90000069002802D0BDE81040004710BD000048
+:10ACA0005C9A00202DE9F04107680025044640F633
+:10ACB0000F030226F8693968BA6818420AD1830678
+:10ACC0007ED501F0200302F0805C53EA0C0377D0BC
+:10ACD000616F7EE1D44BDFF854C3134001EA0C0CE2
+:10ACE00053EA0C0C6CD05FEAC07C0CD05FEAC15C0C
+:10ACF00009D54FF0010CC7F820C0D4F8907047F088
+:10AD00000107C4F89070870709D5D70707D02768CF
+:10AD10003E62D4F8906046F00406C4F8906046079E
+:10AD20000AD5D60708D0276804263E62D4F890607A
+:10AD300046F00206C4F8906006070CD501F0200624
+:10AD40001E4308D0266808233362D4F8903043F0BD
+:10AD50000803C4F8903003050BD54B0109D52668CC
+:10AD60004FF400633362D4F8903043F02003C4F80A
+:10AD70009030D4F89030002B3DD0800609D501F0FA
+:10AD8000200002F08051084303D0616F09B12046D2
+:10AD900088472168D4F890008968490602D410F0E9
+:10ADA000280F2AD0204602F019FF2068806840064C
+:10ADB0001ED52068083050E8001F21F0400100E057
+:10ADC00021E040E80012002AF3D1D4F8800078B1E5
+:10ADD00097490165D4F88000FAF796F900280AD05F
+:10ADE000D4F88000016D00E02046BDE8F04108473E
+:10ADF0002046FFF743FFBDE8F0812046FFF73EFF06
+:10AE0000C4F89050F7E7D4F86CC02023BCF1010FD0
+:10AE10007ED15FEAC06C7BD55FEAC16C78D510202B
+:10AE2000386220688068400673D5D4F88020814954
+:10AE30001068884234D07F491831884230D07D492B
+:10AE4000303188422CD07B494831884228D079491A
+:10AE50006031884224D077497831884220D07549C2
+:10AE6000903188421CD07349A831884218D0724969
+:10AE7000884215D070491831884211D06E4930315E
+:10AE800088420DD06C494831884209D06A49603106
+:10AE9000884205D068497831884201D066499031AE
+:10AEA00040684FF480770004000C40D0B4F85C1088
+:10AEB00081423CD9A4F85E00D069B8422FD0216805
+:10AEC00051E8000F20F4807041E80002002AF6D11A
+:10AED0002068083050E8001F21F0010140E800120E
+:10AEE000002AF5D12068083050E8001F21F0400109
+:10AEF00040E80012002AF5D1C4F88C30E5662068DD
+:10AF000050E8001F21F0100140E80012002A01E083
+:10AF10004AE019E0F3D1D4F88000F9F745FF26673D
+:10AF2000B4F85C00B4F85E10401A81B208E0B4F8DE
+:10AF30005C1081427FF466AFD069B842FAD12667CF
+:10AF40002046FFF74AFE56E7B4F85C00B4F85E10FE
+:10AF5000B4F85E20401A81B2002AF4D00029F2D061
+:10AF6000226852E8000F20F4907042E80007002F9A
+:10AF7000F6D1324F206800F1080050E8002F02EAB5
+:10AF8000070240E8002CBCF1000FF3D1C4F88C306C
+:10AF9000E5666567226852E8000F20F0100042E87D
+:10AFA0000003002BF6D1CAE7C60209D5560207D521
+:10AFB0004FF4801038622046BDE8F041FFF75CBED8
+:10AFC00006060AD501F0800602F40002164304D0FA
+:10AFD000A16F00297FF408AF0DE7420611D54A069C
+:10AFE0000FD52046016851E8002F22F0400241E8C9
+:10AFF0000024002CF6D1C0F88830856700F00EFCE4
+:10B00000F9E6020206D54A0004D52046BDE8F04123
+:10B01000FFF731BEC00196D5002994DA2046BDE87D
+:10B02000F041FFF7DBBD000001000010200100042B
+:10B03000DBDA00081000024010040240FEFFFFEFC0
+:10B0400010B5040003D0D4F8880010B107E0012047
+:10B0500010BD002084F88400204600F027F824204A
+:10B06000C4F888002068016821F001010160A06A2D
+:10B0700010B1204602F078FC204602F017FE0128AD
+:10B08000E6D02068416821F49041416020688168E1
+:10B0900021F02A0181602068016841F0010101600E
+:10B0A0002046BDE8104002F0C3BC00002DE9F04F7F
+:10B0B000B5B0044614212EA8F5F7EFFBB821684679
+:10B0C000F5F7EBFBFA4D0226FA494FF0000820682D
+:10B0D000083DDFF8DC93770288425DD100216846A5
+:10B0E0000222CDF87480CDE90021FDF7B9F908B14D
+:10B0F000F8F768FED9F8001041F48011C9F8001083
+:10B10000D9F8000000F480103390286840F0040063
+:10B110002860286800F004003390286840F0080098
+:10B12000286028680825B146464669022E9100F03D
+:10B130000800CDE92F982EA9CDF8C480CDE9325072
+:10B14000DD48FBF7A3FB04212E91CDE92F96DB48C8
+:10B150002EA9CDE93165FBF799FBD94D4121D9489D
+:10B1600028604FF44030C5E90116C5E903676E61F8
+:10B17000AE61C5E9076028466E62FAF77DFC08B14A
+:10B18000F8F720FEC4F8805000220521AC6335207A
+:10B19000FBF742FD35206CE0CB494FF0070A4FF03A
+:10B1A000400B88426AD1002168460222CDF87480A3
+:10B1B000CDE90021FDF754F908B1F8F703FED9F8FD
+:10B1C000001041F08041C9F80010D9F8000000F0EB
+:10B1D00080403390286840F01000286028684FF4C1
+:10B1E000C0712E912EA900F010004546CDE92F68C0
+:10B1F000CDF8C480CDE932A0B448FBF747FBDFF8B7
+:10B20000C0824F23B24A4FF4803908F17808404693
+:10B2100088E82C00C0E90357C8F81450C8F8185043
+:10B22000C8E90759C8F82450FAF726FC08B1F8F71E
+:10B23000C9FDA34E5022C4F88080F036C8F83840CB
+:10B24000A3493046C6E9035775611831B561C6E9AF
+:10B250000759756286E80608FAF70EFC08B1F8F798
+:10B26000B1FDE66700220521B4635220FBF7D4FC50
+:10B270005220FBF7C4FC35B0BDE8F08F95498842F9
+:10B2800030D10020CDF878800121CDE9001068464A
+:10B29000FDF7E6F808B1F8F795FD85480830016834
+:10B2A00041F010010160006800F010003390286840
+:10B2B00040F00100286028682EAA4FF4C06100F019
+:10B2C000010082E84201CDE932A083482EA9CDF8E1
+:10B2D000C480FBF7DBFA002205212520FBF79CFC4C
+:10B2E0002520C6E77D49884266D1002168460222B2
+:10B2F000CDF87480CDE90021FDF7B2F808B1F8F778
+:10B3000061FDD9F8001041F40031C9F80010D9F8F6
+:10B31000000000F400303390286840F008002860F6
+:10B32000286870212E912EA900F008004546CDE92D
+:10B330002F68CDF8C480CDE932A06048FBF7A6FAAB
+:10B34000674E2B225F494FF400383046783186E84B
+:10B350002600C6E903577561B561C6E907587562ED
+:10B36000FAF78AFB08B1F8F72DFDDFF874912C236A
+:10B37000C4F8806009F17809B4634846514A9032B4
+:10B38000C0E90357C9F81450C9F8185089E80C08E7
+:10B39000C9E90758C9F82450FAF76EFB08B1F8F765
+:10B3A00011FDC4F87C9000220521C9F83840262000
+:10B3B000FBF732FC26205CE74A49884276D100211F
+:10B3C00068460222CDF87480CDE90021FDF748F8E7
+:10B3D00008B1F8F7F7FCD9F8001041F48021C9F85A
+:10B3E0000010D9F8000000F480203390286840F065
+:10B3F00002002860286800F002003390286840F0BE
+:10B400000800286028684FF480412E912EA900F092
+:10B4100008004546CDE92F68CDF8C480CDE932A0BB
+:10B420003148FBF733FA4FF440712E91CDE92F6587
+:10B4300022482EA9CDE9315AFBF728FA284E2D22B1
+:10B4400020494FF40039F0364831304686E826006E
+:10B45000C6E903577561B561C6E907597562FAF720
+:10B460000BFB08B1F8F7AEFC204D2E23C4F880602A
+:10B47000B4632846134AC5E90387C5F814806032CF
+:10B48000C5F81880C5E90789C5F8248085E80C0847
+:10B49000FAF7F2FA08B1F8F795FCE5670022052102
+:10B4A000AC632720FBF7B8FB2720E2E620E0000092
+:10B4B000E84402580050004000080258000C0258AE
+:10B4C000240D00202800024000780040001002589F
+:10B4D00028040240001001400000025800440040CF
+:10B4E0008C0E00200048004000040258F40F002099
+:10B4F000394988427FF4BFAE0021CDF8788001221F
+:10B500006846CDE90021FCF7ABFF08B1F8F75AFC1B
+:10B510003248016841F080010160006800F080005D
+:10B520003390286840F010002860286845462EA90E
+:10B5300000F01000339004202E90CDE92F68DFF842
+:10B54000A080CDE931504046FBF7A0F90B2108203F
+:10B550002E90CDE92F65CDE931512EA94046FBF75C
+:10B5600095F9DFF8809077261F4B4FF44038484616
+:10B57000C0E90357C9F81450C9F8185089E84808B9
+:10B58000C9E90758C9F82450FAF776FA08B1F8F76C
+:10B5900019FC144E762114487836C4F87C90483053
+:10B5A000C9F8384086E82300C6E90357756130467C
+:10B5B000B561C6E907587562FAF75EFA08B1F8F79F
+:10B5C00001FCC4F8806000220521B4639C20FBF7D5
+:10B5D00023FB9C204DE60000001C0140F044025873
+:10B5E000001002586C100020100402402DE9F84FA2
+:10B5F0000446D0F88C009B4616460D46202802D003
+:10B600000220BDE8F88FC5B1BEB10027C4F8907024
+:10B610002220C4F88C00E7662034FBF74FFA8246FC
+:10B6200054F8180CA6874FF48053E687FF21203C7E
+:10B63000984207D1226912B119E00120E1E740F2F6
+:10B64000FF1114E04FF07F0278B1B0F1805F11D0AC
+:10B65000A4F860709842B4F860704FF0200801D1EF
+:10B66000206970B12E4600250CE0266936B9A4F891
+:10B670006010EFE7216909B13F21F8E7A4F86020E5
+:10B68000E8E7002607F0FF09B4F85E00F0B10022F9
+:10B69000534620212046CDF800B002F049FD18B1F4
+:10B6A000C4F88C800320ACE72068406A56B100EAF9
+:10B6B000090006F8010B00BFB4F85E00401EA4F8B4
+:10B6C0005E00E1E7384025F8020BF5E7C4F88C800E
+:10B6D000002096E730B4D0F88C30202B02D0022026
+:10B6E00030BC7047A9B1A2B10B4D00240368C466F9
+:10B6F000AB420BD05B681B0208D5046854E8003FDE
+:10B7000043F0806344E80035002DF6D130BC02F0F0
+:10B71000BBBC0120E4E70000000C005810B502F0AB
+:10B720009FFA06280AD000EBC001054800EB810013
+:10B73000C068002802D0BDE81040004710BD0000DE
+:10B740005C9A002010B502F08BFA06280AD000EBB4
+:10B75000C001054800EB81008068002802D0BDE8E8
+:10B760001040004710BD00005C9A00202DE9F8430E
+:10B770000446D0F88800984616460D46202802D088
+:10B780000220BDE8F883A5B19EB10021C4F8901055
+:10B790002120C4F888001834FBF790F9814654F84A
+:10B7A000100CA687E6872027183CB0F5805F02D0F2
+:10B7B00003E00120E5E7206910B12E46002510E0E6
+:10B7C00000260EE08021204602F0B2FCC0B9DEB1B6
+:10B7D00016F8010B21688862B4F85600401EA4F8E0
+:10B7E0005600B4F856004B464FF00002CDF80080EA
+:10B7F0000028E7D14FF04001204602F099FC48B103
+:10B80000C4F888700320BCE735F8020B2168C0F348
+:10B810000800E0E7C4F888700020B2E710B502F035
+:10B820001FFA06280AD000EBC001054800EB810092
+:10B830004068002802D0BDE81040004710BD00005D
+:10B840005C9A0020FEE70000F0B500230A251C46A4
+:10B850003026372711E000BFB5EB107F02D906EB89
+:10B86000107C01E007EB107C01F813C001EB430CE6
+:10B8700000015B1C8CF80140DBB29342ECD3F0BDBD
+:10B8800010EE100A0C49B6EE001AF7EE080A20EE88
+:10B89000011AA1EB600000EE100AF0EE601A21EE32
+:10B8A000002A42EE401A21EE800A21EE001A41EEF3
+:10B8B000400A20EE800A7047DF59375F70B51C469A
+:10B8C00015462DED088B93ED000AD1ED00AA90ED01
+:10B8D00000BAD0ED018A2AEE809A2BEE0B0A90ED89
+:10B8E000028AD1ED010A91ED021A08EEA80AB1EE22
+:10B8F00060AAF1EE419A08EE080A05F039F820EE48
+:10B90000000A0AEEEA0A05F033F8F0EE40AA4FF01A
+:10B91000FF30F4EE6AAAF1EE10FA49D1B0EECA0A8D
+:10B92000F0EEE90A30EE200AB4EEEA0AF1EE10FA7F
+:10B930003ED328EEA80A08EE080A09EE490A05F0E7
+:10B9400017F828EE091A68EE890A08EE801A48EE00
+:10B95000400AB0EE410A04F03FFDB0EE409AB0EE6E
+:10B960006A1AF0EE690AB0EE4A0A06F0D9F9F0EE6A
+:10B9700040AAB0EE693AF0EE4A2AB0EE482AF0EE5C
+:10B98000681AB0EE4B1AF0EE6A0AB0EE490A06F0F9
+:10B9900091F985ED009AD4ED010A002020EE800A8D
+:10B9A00085ED010A94ED020A20EE2A0A85ED020ACD
+:10B9B000BDEC088B70BD91ED021A71EE600A80EE4D
+:10B9C000801A80ED021AD1ED000A60EE800AC0ED07
+:10B9D000000AD1ED010A80EE801A80ED011A0020E4
+:10B9E000704790ED021A41EE000AC1ED020AD0ED57
+:10B9F000000A80EE801A81ED001AD0ED010A20EED7
+:10BA0000800A81ED010A90ED030A81ED030A90EDB1
+:10BA1000040A002081ED040A704700EB8100006EEB
+:10BA200000F0F84070478068C0F3C000704780683D
+:10BA3000C0F3800070478068C0F38000704700004A
+:10BA400000EB8101034B51F8600F20F000401043E0
+:10BA5000086070470060025890ED002A32EE402ADC
+:10BA6000B4EEE02AF1EE10FA02DD30EE200A0BE02F
+:10BA7000F1EE602AB4EEE22AF1EE10FA02D390ED74
+:10BA8000000A03E030EE600A80ED000AB4EEC10A5D
+:10BA9000F1EE10FA02DD80ED001A06E0B4EEE10AE4
+:10BAA000F1EE10FA01D2C0ED001A0020704700003C
+:10BAB00030B58DB000246846242109940A940B9473
+:10BAC000F4F7EBFE24480425224B4FF41012012119
+:10BAD00003600223C0E90124C0E9041504760322AF
+:10BAE0004176C36180F820408462C0E90B42C463A0
+:10BAF000046480F844408164F8F788FF08B1F8F7DF
+:10BB000061F9154809A90994F8F7D2FB08B1F8F7CB
+:10BB100059F91248062140F2FF7203928DE8230082
+:10BB20000D486946CDE904548DF82140F8F754FCDE
+:10BB300008B1F8F747F90C210948CDE9000106489A
+:10BB40006946F8F749FC002801D0F8F73BF90DB039
+:10BB500030BD000000200240580300201000C0103B
+:10BB60000000B84F394808B5016841F00101016093
+:10BB7000016801F001010091016841F002010160DA
+:10BB800000680022052100F0020000900B20FBF766
+:10BB900043F80B20FBF733F8002205210C20FBF7BC
+:10BBA0003BF80C20FBF72BF8002205210D20FBF7BA
+:10BBB00033F80D20FBF723F8002205210E20FBF7B8
+:10BBC0002BF80E20FBF71BF8002205210F20FBF7B6
+:10BBD00023F80F20FBF713F8002205211020FBF7B4
+:10BBE0001BF81020FBF70BF8002205211120FBF7B2
+:10BBF00013F81120FBF703F8002205212F20FBF793
+:10BC00000BF82F20FAF7FBFF002205213820FBF765
+:10BC100003F83820FAF7F3FF002205213920FAF75C
+:10BC2000FBFF3920FAF7EBFF002205213A20FAF753
+:10BC3000F3FF3A20FAF7E3FF002205213B20FAF751
+:10BC4000EBFFBDE808403B20FAF7D9BFD8440258C3
+:10BC50001748002170B5154D012281601826056036
+:10BC60000225C1602024017404234174817446615B
+:10BC7000C0E90625026242628262C262C0E90C210A
+:10BC80000464C0E90E21C0E91131C0E91331C0E9F3
+:10BC90001531C0E91714C0E91913FAF7BFFB0028E2
+:10BCA00003D0BDE87040F8F78DB870BD00A000402B
+:10BCB000400400201848002170B5164D012205608F
+:10BCC000182581602024C1600423017441748174AB
+:10BCD000C0E90552C26140F20645026242628262D8
+:10BCE000C262C0E90C250464C0E90E21C0E911312B
+:10BCF000C0E91331C0E91531C0E91714C0E91913BF
+:10BD0000FAF78CFB002803D0BDE87040F8F75AB86A
+:10BD100070BD000000A40040E0040020184800218D
+:10BD200070B5164D01220560182581602024C16080
+:10BD30000423017441748174C0E90552C26140F664
+:10BD40001205026242628262C262C0E90C2504648A
+:10BD5000C0E90E21C0E91131C0E91331C0E9153144
+:10BD6000C0E91714C0E91913FAF758FB002803D0EB
+:10BD7000BDE87040F8F726B870BD000000D4004060
+:10BD800080050020074A0021074810B505F0C8FAD1
+:10BD90000649074A08600021BDE81040054805F043
+:10BDA000BFBA0000E0300108BDCD0008000000204F
+:10BDB000AC32010889D300082DE9F04F87B0142177
+:10BDC0006846F4F76AFD5E48016841F010010160C1
+:10BDD000016801F010010591016841F00401016062
+:10BDE000016801F004010591016841F080010160E2
+:10BDF000016801F080010591016841F001010160D5
+:10BE0000016801F001010591016841F00201016042
+:10BE1000016801F002010591016841F0080101602B
+:10BE200000684FF46044DFF81C81002200F0080035
+:10BE3000214605904046FAF73CFE01224046292162
+:10BE4000FAF737FE4FF400463F4800223146FAF732
+:10BE500030FE4FF440693D4800224946FAF729FE7A
+:10BE60004FF4805A394801225146FAF722FE4FF426
+:10BE7000806B374800225946FAF71BFE01256946B8
+:10BE80004046CDE90045002402940394FAF7FEFCF5
+:10BE9000032769462920CDE90005CDE90247404640
+:10BEA000FAF7F4FC4FF4881869464FF4A050029456
+:10BEB000CDE900082448FAF7E9FC00966946CDE987
+:10BEC000015421480394FAF7E1FCCDF8009069464B
+:10BED000CDE901541D480394FAF7D8FC1B48694684
+:10BEE000CDE900A5CDE90257FAF7D0FCCDF800B0B6
+:10BEF0006946CDE9015416480394FAF7C7FC2802B5
+:10BF0000144D02218DE813006946284603940494D9
+:10BF1000FAF7BCFC00966946CDE901842846FAF799
+:10BF2000B5FC0021A802FEF7E7FA0022052128202F
+:10BF3000FAF772FE2820FAF762FE07B0BDE8F08F2C
+:10BF4000E044025800080258001002580004025849
+:10BF5000000C02580000025870B586B018216846DF
+:10BF6000F4F79BFC18480822164D002101241723E2
+:10BF70008160D606E0E80352032580E81A0000F14C
+:10BF80001403C0E9031483E862000162C0E90912E6
+:10BF9000C16201630C48FBF781F808B1F7F712FFA3
+:10BFA0004FF0011041F2883269460094CDE9024019
+:10BFB0000548FAF763FE002801D0F7F703FF06B043
+:10BFC00070BD000000A00052200600202DE9F041C5
+:10BFD0004FF480051448134A07276E114FF0007C78
+:10BFE0002C0180E8E4100021A300C0E90514C0E999
+:10BFF000073141629A008162C162C0E90D21C163CB
+:10C00000016441648164C164016541658165FDF736
+:10C0100055FD002803D0BDE8F041F7F7D3BEBDE8D9
+:10C02000F0810000003001407C0600202DE9F04145
+:10C0300017484FF48007DFF854C00021FA000726A4
+:10C04000C0F800C01301C0E90362C0E90171C0E992
+:10C05000073141625510540081625201C162C0E94A
+:10C060000D21C163016441648164C164016541655E
+:10C070008165C0E90554FDF721FD002803D0BDE826
+:10C08000F041F7F79FBEBDE8F081000000380040A6
+:10C090000407002010B58AB0002468461C210794CC
+:10C0A00008940994F4F7F9FB164840F2CF7117226F
+:10C0B000134BC0E9024104618461C0E90032FEF71C
+:10C0C000FAFC08B1F7F77EFE0E4807A90794099419
+:10C0D000FEF76EFA08B1F7F775FE60206946CDE904
+:10C0E00000040848042202940494FEF752FC08B1AC
+:10C0F000F7F768FE0348FEF7DFFB0AB010BD00004B
+:10C10000001800406009002010B598B000241C21E0
+:10C110000DA8149415941694F4F7BFFB34216846C7
+:10C12000F4F7BBFB27481822254942F2107380E838
+:10C130001600C0E9033444618461FEF7BCFC08B119
+:10C14000F7F740FE1F4814A9149415941694FEF7AF
+:10C150002FFA08B1F7F736FE0DAA41F288316020B8
+:10C1600082E81300174800220DA91094119412942C
+:10C170001394FEF70EFC08B1F7F724FE11480822CD
+:10C180000DA9FEF706FC08B1F7F71CFE4FF40050AE
+:10C190000094039401030194CDE904400294CDE995
+:10C1A00008410848694606940A940C94FEF7B0F9D1
+:10C1B00008B1F7F707FE0348FEF77EFB18B010BD85
+:10C1C000000001407C08002010B58AB000246846B9
+:10C1D0001C21079408940994F4F75FFB1A4842F273
+:10C1E000107118224FF08043C0E90241046184615C
+:10C1F000C0E90032FEF75FFC08B1F7F7E3FD124833
+:10C2000007A907940994FEF7D3F908B1F7F7DAFD07
+:10C21000602041F288318DE813000B480022694606
+:10C220000494FEF7B6FB08B1F7F7CCFD06480822E8
+:10C230006946FEF7AEFB08B1F7F7C4FD0248FEF70A
+:10C240003BFB0AB010BD0000C808002030B58BB021
+:10C25000002468461C21079408940994F4F71DFBF8
+:10C26000164842F20F721723134D8021C0E9024293
+:10C2700004618161C0E90053FEF71DFC08B1F7F7C6
+:10C28000A1FD0E4807A907940994FEF791F908B19A
+:10C29000F7F798FD60206946CDE9000407480C22B5
+:10C2A00002940494FEF775FB08B1F7F78BFD034881
+:10C2B000FEF702FB0BB030BD000400401409002063
+:10C2C00070B518480021164C042300F10C0C164DD3
+:10C2D00022158CE80E008161A614C16101624162E1
+:10C2E000816280E87000FEF7ABFE08B1F7F76AFDE7
+:10C2F0000C480021FEF799FC08B1F7F763FD0948E7
+:10C300000021FEF76CFC08B1F7F75CFD0548FEF76D
+:10C3100044FC002803D0BDE87040F7F753BD70BD62
+:10C3200000500040AC090020A08601001848002100
+:10C3300010B5164C0C224FF461230460C0E90131A2
+:10C34000C160C0E904128161C16101624162816220
+:10C35000FEF776FE08B1F7F735FD0D480021FEF730
+:10C3600064FC08B1F7F72EFD09480021FEF737FC01
+:10C3700008B1F7F727FD0648FEF70FFC002803D0A9
+:10C38000BDE81040F7F71EBD10BD0000007800406A
+:10C39000400A00201848002110B5164C0C224FF41A
+:10C3A00061230460C0E90131C160C0E90412816108
+:10C3B000C161016241628162FEF742FE08B1F7F796
+:10C3C00001FD0D480021FEF730FC08B1F7F7FAFC3B
+:10C3D00009480021FEF703FC08B1F7F7F3FC064813
+:10C3E000FEF7DBFB002803D0BDE81040F7F7EABCFE
+:10C3F00010BD0000001C0140900C002018480021D6
+:10C4000010B5164C0C224FF461230460C0E90131D1
+:10C41000C160C0E904128161C1610162416281624F
+:10C42000FEF70EFE08B1F7F7CDFC0D480021FEF730
+:10C43000FCFB08B1F7F7C6FC09480021FEF7CFFB6B
+:10C4400008B1F7F7BFFC0648FEF7A7FB002803D0AA
+:10C45000BDE81040F7F7B6BC10BD00000010014069
+:10C46000D40A00201848002110B5164C0C22174B96
+:10C470000460C0E90131C1600B46C0E9041281616A
+:10C480000A46C161016241628162FDF7A3F908B108
+:10C49000F7F798FC0C480021FEF7C7FB08B1F7F747
+:10C4A00091FC09480021FEF79AFB08B1F7F78AFCD6
+:10C4B0000548FEF772FB002803D0BDE81040F7F7EF
+:10C4C00081BC10BD00440040680B002000093D0005
+:10C4D0001848002110B5164C0C22174B0460C0E917
+:10C4E0000131C1600B46C0E9041281610A46C16195
+:10C4F000016241628162FDF76DF908B1F7F762FCF4
+:10C500000C480021FEF791FB08B1F7F75BFC0948E6
+:10C510000021FEF764FB08B1F7F754FC0548FEF76D
+:10C520003CFB002803D0BDE81040F7F74BBC10BD22
+:10C5300000480040FC0B002000093D00104901228A
+:10C54000104810B502F07AFA08B1F7F73BFC0E4933
+:10C550000C4802F092FC08B1F7F734FC0B4909488B
+:10C5600002F012F808B1F7F72DFC064802F00AFDB8
+:10C5700008B1F7F727FCBDE81040FBF721BC00002D
+:10C5800008000020A8110020E8000020680000201A
+:10C59000FEE770B505000C4631D0002C2FD0207876
+:10C5A0001022287204F11F0160786872A078A872C6
+:10C5B000E078E87220792873B4F805002882D4F86E
+:10C5C00007006861D4F80B00A861D4F80F00E86197
+:10C5D000D4F81300A862D4F817006862D4F81B00DE
+:10C5E000286205F12C00F4F7B7F8D4F82F0028647E
+:10C5F000D4F83300686494F8370085F8480070BDBB
+:10C6000000F060B810B520B17821F4F746F90020A9
+:10C6100010BD6FF0010010BD10B50D4C207810B1A9
+:10C620006FF0020010BD04F079FEA06068B1032134
+:10C63000084A0846F6F7E8FD074A04210320F6F702
+:10C64000E3FD01202070002010BD6FF0010010BD3F
+:10C65000D4010020EDC6000801C600082DE9F04114
+:10C66000040004D015480178FC2908D103E06FF0DC
+:10C670000100BDE8F08190F83700FD2806D0104891
+:10C680004168491C41604FF0FF30F2E70B492046FA
+:10C69000FFF77FFF04F12800D4E9081204F16408D1
+:10C6A000E9C8E16561692266D4E9062C503488E85E
+:10C6B000E90084E806100020DBE7000025000024E4
+:10C6C000D4010020032010B5F6F75EFD0068016874
+:10C6D00021F0010101600320F6F756FD00680168B2
+:10C6E00041F001010160002010BD0000024810214E
+:10C6F000806804F08DBD0000D4010020032010B537
+:10C70000F6F742FD04493822FEF7E4FF002801D085
+:10C710004FF0FF3010BD000025000024C822012189
+:10C72000102010B504F0AEFD102801D0002010BD7F
+:10C73000012010BDFEE70000F0B503004FF000003F
+:10C7400004460BD0022B09D841B100220A604A608E
+:10C75000022B8A60CA600A6102D007E00120F0BDA6
+:10C76000294A1268D20734D04FF40074274D0022B2
+:10C7700005EB8203D3F80434DE0707D003F002068A
+:10C7800004F00207BE4201D1561C0E60DE0607D53A
+:10C7900003F0200604F02007BE4201D1561C4E6073
+:10C7A000DE0507D503F4007604F40077BE4201D11C
+:10C7B000561C8E60DE0311D503F4802604F4802716
+:10C7C000BE420BD19E0302F1010604D446F480362A
+:10C7D00003E00F4CCAE746F08076CE60DE010FD54D
+:10C7E00003F0806604F08067BE4209D19B0102F12C
+:10C7F000010302D443F4803301E043F080730B6102
+:10C80000521C022AB4D3F0BD00B4005200B0005252
+:10C81000220204042DE9F041984616460F460446CC
+:10C82000069D08E0681C06D0FAF748F9A0EB08005E
+:10C83000A8420AD84DB12068006A384000D00120D3
+:10C84000B042EFD10020BDE8F0814FF400702065C8
+:10C85000606D40F0010060650120F4E70148FAF7DF
+:10C86000A9BE0000A42800202DE9F04104468079EB
+:10C870000D462027236801284FF4004604F29C420D
+:10C8800003EB4511D3F840C0D1F8080B09D0DFF80D
+:10C890009CE0F4453AD1020433D500BFC1F8086BDF
+:10C8A00040E0234B5FEA007E04D59C453AD9000462
+:10C8B000F4D437E05FEA806E02D5C1F8087B31E03E
+:10C8C00010F0280F2ED19C4501D90004E6D4D1F8F0
+:10C8D000101B05EBC50004EB8000C1F31201D0F87A
+:10C8E0007432A3EB0101C0F8681200F51570ADB900
+:10C8F00003691BB1C2681144C1600FE020680121C7
+:10C900000AE080060AD5C1F8087B07E035B9D4F8FB
+:10C91000640218B90021184602F0B4FE2046E9B2BC
+:10C92000FAF731FD0020BDE8F08100000A31544FD4
+:10C930000A30544F2DE9F84F0E460568814601EB49
+:10C94000C60100EB8104D4E909201434904202D9D5
+:10C950000120BDE8F88FA168101A814200D2084674
+:10C96000C01C05EB461887081BE000BFA268A0EBBF
+:10C97000010A524500D2924699F806100AF10300C6
+:10C9800000911FFA8AF3E16887082846F2B203F0A3
+:10C99000BDF9E16801EB0A00E060616901EB0A00A2
+:10C9A0006061D8F8180980B2B84205D3D4E904010F
+:10C9B000814201D20028D9D1D4E90401884208D8A3
+:10C9C000D5F83418012006F00F0290408143C5F8D5
+:10C9D00034180020BDE700002DE9F047454D04461E
+:10C9E00089464FF0000A2868C04380070AD0414EAC
+:10C9F000283E306820F080603060FAF75FF8074624
+:10CA0000B04608E00120BDE8F08700BFFAF756F80D
+:10CA1000C01B022867D8D8F800000001F6D42068AF
+:10CA200029684FF4FE0721F47C313E0241EA0030D0
+:10CA30002860207AA389B4F804C040022D4D2D4906
+:10CA40005B1E227CACF1010C1035091DA0F50070B5
+:10CA500080B2521ECCF3080C07EA034340EA0C00F4
+:10CA6000184306EA0262104328600868626920F0F1
+:10CA7000C000104308600A68A06922F02002024347
+:10CA80000A60281D0A6822F010020A6002684FF648
+:10CA9000F873E4699A4342EAC40202600868B9F193
+:10CAA000000F40F010020A6011D00868B9F1010FC0
+:10CAB00011D040F400100860D8F80000444640F05F
+:10CAC0008060C8F80000F9F7F9FF05460DE0086836
+:10CAD00040F40020EFE740F48010ECE7F9F7EEFFB8
+:10CAE000401B022801D903208DE720680001F5D5FD
+:10CAF000504688E7284402582DE9F047454D044642
+:10CB000089464FF0000A2868C04380070AD0414E8A
+:10CB1000283E306820F080503060F9F7CFFF07469C
+:10CB2000B04608E00120BDE8F08700BFF9F7C6FF76
+:10CB3000C01B022867D8D8F800008000F6D42088EF
+:10CB400029684FF4FE0721F07C713E0241EA005053
+:10CB50002860207AA389B4F804C040022D4D2D49E5
+:10CB60005B1E227CACF1010C1835091DA0F500708C
+:10CB700080B2521ECCF3080C07EA034340EA0C00D3
+:10CB8000184306EA0262104328600868626920F4CC
+:10CB90004060104308600A68A06922F400720243F2
+:10CBA0000A60281D0A6822F480720A6002684FF643
+:10CBB000F873E4699A4342EAC40202600868B9F172
+:10CBC000000F40F480720A6011D00868B9F1010FBB
+:10CBD00011D040F080700860D8F80000444640F062
+:10CBE0008050C8F80000F9F769FF05460DE00868B5
+:10CBF00040F48000EFE740F40000ECE7F9F75EFF57
+:10CC0000401B022801D903208DE720688000F5D55C
+:10CC1000504688E7284402580148FCF73DBE000012
+:10CC20000407002010B5026840F26F33516994691F
+:10CC300044F0080494610268946944F0100494611B
+:10CC40000268146824F001041460026814699C43AB
+:10CC500014610268936823F44043936090F8812044
+:10CC6000042A0CD08A060AD5D0F8842042F080022B
+:10CC7000C0F884200268936943F02003936190F820
+:10CC80008120032A0CD04A060AD5D0F8842042F02D
+:10CC90000402C0F884200268936943F04003936162
+:10CCA0008A050AD5D0F8842042F00102C0F8842019
+:10CCB0000268936943F400739361C9050AD5D0F8FB
+:10CCC000841041F00801C0F8841001688A6942F4B8
+:10CCD00080728A610021A0F86210A0F86A1010BD6D
+:10CCE00010B5806B00210122A0F86A10A0F8621034
+:10CCF00080F88120FCF7B4FD10BD10B5846BF8F707
+:10CD000045FB02280ED02046FFF78CFFD4F8841094
+:10CD1000012041F01001C4F8841084F881002046FD
+:10CD2000FCF79EFD10BD10B5806BFDF779FA10BDC4
+:10CD300010B5806B90F88110072909D0C16FC969BF
+:10CD4000B1F5807F05D00068016941F008010161FB
+:10CD500010BDFDF749FA10BD00680349884201D1B2
+:10CD60000020704702207047003800402DE9F04154
+:10CD70001C4616460D460746DDF818800AE000BF3F
+:10CD8000F9F79CFEA0EB0800A04202D3601C01D082
+:10CD90000BE054B13868406935EA000007D0002044
+:10CDA000B042EDD00020BDE8F0810320FBE7012078
+:10CDB000F6E70178407841EA0020704710B5FFF7A8
+:10CDC000BDFB04F0ABFABDE8104004F0F1BA4FF03F
+:10CDD000E02010B5006905F04BFF012803D0BDE845
+:10CDE000104005F009BB10BD70B59CB04C216846E1
+:10CDF000F3F753FD202113A8F3F74FFD0220FAF7B4
+:10CE0000B5FF2248016821F4404101600168002417
+:10CE100001F440411B9101688904FCD502204025A2
+:10CE2000C30323220121CDE90023CDE903152822E4
+:10CE30000990069104230D910C260A90CDE90B026E
+:10CE4000CDE90E30CDE9106468461294FCF72EFA55
+:10CE500008B172B6FEE708221A95CDE91625D3016E
+:10CE600013AA3F200321CDE9185382E8130013A829
+:10CE7000FBF794FF08B172B6FEE700214FF4802261
+:10CE80000846FCF7C9F91CB070BD000018480258EC
+:10CE90002D48F0B52D4A016841F470010160106819
+:10CEA00000F00F00072804D2106820F00F00C01D0A
+:10CEB000106027490020264C10340B68254D43F0A4
+:10CEC00001030B6020600B682B400B60136803F0BC
+:10CED0000F03072B04D9136823F00F03DB1D136026
+:10CEE0001B4C1D4A18341D4B261D371D2060184C45
+:10CEF0001B4D28343060261D3860371D23603B1DD4
+:10CF000035601C1D3A60251D2E1D1860331D2260E2
+:10CF10002860326018600B680D4A0D4C23F48023A2
+:10CF2000D4320B60603420601068C0040BD41368E6
+:10CF300043F2D2000B4943F4805313600860106839
+:10CF400020F480501060F0BD88ED00E00020005219
+:10CF5000004402587FEDF6EA80020101000202025D
+:10CF60000000FF01004000520148FDF700BC000036
+:10CF70005C1100202DE9F0472C4B4FF0804A2C4DDE
+:10CF8000026898422B4E2C4F2C4C09D0504507D0AC
+:10CF9000A84205D0B04203D0B84201D0A04205D18A
+:10CFA000D1F804C022F070024CEA0202DFF890C00F
+:10CFB000DFF890809842DFF8909015D0504513D05C
+:10CFC000A84211D0B0420FD0B8420DD0A0420BD031
+:10CFD000604509D0404507D0484505D01B4DA842C3
+:10CFE00002D01B4DA84203D1CD6822F440722A43DF
+:10CFF0008E684D6922F08002C6620E682A4398420C
+:10D00000866207D0A04205D0604503D0404501D0DC
+:10D01000484501D1096901630368012143F0040314
+:10D02000036041610260BDE8F0870000000001403C
+:10D030000004004000080040000C004000040140D3
+:10D0400000400140004401400048014000E0004031
+:10D0500000E400402DE9F04FDFF88480214EDFF836
+:10D060008890DFF888B0026A036AB042DFF880A0D7
+:10D0700022F0020C1F4F23F0010202624268856910
+:10D080008B680C6805EA080525F0030543EA0C03E4
+:10D0900044EA050407D0484505D0584503D050451B
+:10D0A00001D0B84205D1CD6823F008031D4325F017
+:10D0B0000403B04207D0484505D0584503D0504539
+:10D0C00001D0B84205D122F44076D1E9055235436A
+:10D0D0002A4342608461496841630362BDE8F08F7E
+:10D0E0008FFFFEFF000001400004014000400140AE
+:10D0F0000044014000480140F0B5DFF87CE01F4CDF
+:10D100001F4D026A036AA04222F0200623F010039A
+:10D11000036242688369D1F808C00F6803EA0E030E
+:10D1200023F4407E46EA0C134EEA072601D0A842BB
+:10D1300006D1CF6823F0800343EA071323F04003AE
+:10D14000A0420AD0A84208D00E4CA04205D00E4CF6
+:10D15000A04202D00D4CA04207D1D1E9054522F4EE
+:10D16000406242EA840242EA85024260866149687E
+:10D1700081630362F0BD0000FF8FFFFE00000140ED
+:10D1800000040140004001400044014000480140CB
+:10D19000F0B5DFF87CE01F4D1F4E026A036AA8421B
+:10D1A00022F4007723F4807303624368C269D1F8E4
+:10D1B00008C002EA0E020C6822F0030E47EA0C22B5
+:10D1C00044EA0E0401D0B04206D1CF6822F40062D6
+:10D1D00042EA072222F48062A8420AD0B04208D074
+:10D1E0000E4DA84205D00E4DA84202D00D4DA842CA
+:10D1F00007D1D1E9055623F4405343EA051343EA26
+:10D2000006134360C4614968C1630262F0BD000057
+:10D210008FFFFEFF0000014000040140004001407C
+:10D220000044014000480140F0B5046A026A22F45B
+:10D23000805202624268C36924F40054DFF848C097
+:10D240008E680D6803EA0C03104F23F4407344EA20
+:10D250000634B84243EA05230BD00D4DA84208D04E
+:10D260000C4DA84205D00C4DA84202D00B4DA8424F
+:10D2700004D14D6922F4804242EA85124260C361C2
+:10D28000496801640462F0BDFF8FFFFE00000140A9
+:10D2900000040140004001400044014000480140BA
+:10D2A000F0B5164F164B026A046A984222F4003514
+:10D2B00024F4803303624268436D0E890C6803EAEC
+:10D2C000070344EA030445EA06430BD00D4DA84288
+:10D2D00008D00D4DA84205D00C4DA84202D00C4DEF
+:10D2E000A84204D14D6922F4803242EA052242600C
+:10D2F0004465496881650362F0BD00008FFFFEFF51
+:10D300000000014000040140004001400044014091
+:10D3100000480140F0B5164F164B026A046A984265
+:10D3200024F48013036222F400144268436D0E89D2
+:10D330000D6803EA070344EA065443EA05230BD0C9
+:10D340000D4DA84208D00D4DA84205D00C4DA84265
+:10D3500002D00C4DA84204D14D6922F4802242EA49
+:10D360008522426043654968C1650462F0BD0000E2
+:10D37000FF8FFFFE0000014000040140004001401B
+:10D3800000440140004801402E4810B5F6F77AF9F4
+:10D3900003F04AFE2C4A00212C4803F0C1FF294C1F
+:10D3A00000212B4A443C20602A4803F0B9FF60600A
+:10D3B0000021294A294803F0B3FFA0600021284A30
+:10D3C000284803F0ADFFE0600021274A274803F01A
+:10D3D000A7FF20610021264A264803F0A1FF6061D3
+:10D3E0000021254A254803F09BFFA0610021244A23
+:10D3F000244803F095FF0022E0611821022003F089
+:10D4000095FE002260621421022003F08FFE0022AC
+:10D41000E0629021022003F089FE00222063F021C7
+:10D42000022003F083FE002260630C21022003F03F
+:10D430007DFE206203F02AFE03F070FFBDE810407D
+:10D4400003F0B6BF64A20020D032010829D800083A
+:10D45000F432010889D4000818330108A9D800085B
+:10D460003C3301087DD500086033010809D8000865
+:10D47000843301087DD60008A83301088DD7000841
+:10D48000CC330108F5D60008002003F07BFD394CB1
+:10D4900094F8880110B1012818D10FE0364901F144
+:10D4A0001800F5F787FB34481830F5F763FB32496D
+:10D4B0000C3101F1A400F4F757FF07E02E48383093
+:10D4C000FFF7AAF801210220F5F728FE94F8880159
+:10D4D00088B10128FAD128483830FFF70FF9FFF753
+:10D4E0001DF9B8B303F0A0FD23483830FFF7B6F8B4
+:10D4F00003F0CCFD33E0F5F7C3FCF5F729FBF5F7B6
+:10D5000033FBF5F745FBF5F74FFB03F08DFD1A48AC
+:10D510001830F5F7E7FB18481830F5F733FC164BD1
+:10D520000C3303F11802A2F10C0101F19800F4F799
+:10D53000ABFF1149B03101F11400F4F7ADFE03F077
+:10D54000A5FD206A03F052FE0B490023206A1A460B
+:10D55000C4310CE0FFE708483830FFF753F8206A81
+:10D5600003F044FE04490023206A1A46943103F074
+:10D5700009FEABE720A20020F8A30020002003F062
+:10D5800001FD2748F6F7A2FD26A0F5F74DFE33A0D2
+:10D59000F5F74AFE334F0026334C00BFF5F768FE1F
+:10D5A0000500FBD0014631A0F5F73EFE0D2D10D051
+:10D5B0000A2D0ED07F2D2AD0082D28D020887F2834
+:10D5C000ECD2202DEAD37E2DE8D83D54411C218099
+:10D5D000E4E727A0F5F728FE20883E5480B1F6F74F
+:10D5E00009FD4FF4007980461E484A464146F6F749
+:10D5F00005FD054641461FA0F5F716FE002DF3D1A7
+:10D60000184880212680F3F726F914A005E0208829
+:10D610000028C3D0401E208017A0F5F705FEBDE707
+:10D62000F03301080D0AE6ACA2E8BF8EE4BDBFE707
+:10D6300094A8E591BDE4BBA4E8A18CEFBC8CE8BE46
+:10D6400093E585A52068656C7020E69FA5E79C8B17
+:10D65000E591BDE4BBA40D0A000000006D723E2000
+:10D6600000000000F4A40020540300202563000003
+:10D670000D0A000025730000082008002DED028B24
+:10D6800003F0BDFC4FF4FA71B0FBF1F6002003F09B
+:10D6900079FC1548F5F73CFE03F0AAFC124F05464D
+:10D6A000134C9FED128A354403F0BEFC0E49002353
+:10D6B000606A1A46243103F007FD30B90A49B0EE1A
+:10D6C000480A01F12400F5F729FE03F0DFFCE06AC7
+:10D6D00003F08CFD0023E06A391D1A4603F052FD69
+:10D6E000284603F05DFCDEE774A500206F12033BC3
+:10D6F00020A2002003F083FC4FF4FA71B0FBF1F696
+:10D70000C82003F03FFC1D491D489FED1B0AF5F79B
+:10D7100087FF03F06DFC194D0446483D194900236D
+:10D7200034441A46286B03F0CFFC18B91549144845
+:10D73000F5F786FF00231449E86A1A4603F0C4FC93
+:10D7400003F072FC104922460D48F5F71BFE0D4907
+:10D750000B489031F5F73EFF03F098FC686B03F03F
+:10D7600045FD08490023686B1A46903103F00AFD15
+:10D77000204603F015FCD1E70000FA4368A2002020
+:10D7800030A7002018A9002098AA002003F037FC39
+:10D790004FF44871B0FBF1F6C82003F0F3FB1749D2
+:10D7A0001748F6F7BBFC03F023FC144D0446443D38
+:10D7B0001449002334441A46686B03F085FC18B9F9
+:10D7C00010490F48F6F726FD03F02EFC0C48F6F73B
+:10D7D000C5FC03F05BFC0B4909489039F6F746FDA0
+:10D7E000286B03F003FD07490023286B1A46903984
+:10D7F00003F0C8FC204603F0D3FBD9E764A2002065
+:10D800006000002440A6002003F0F9FB6421B0FB77
+:10D81000F1F5002003F0B6FB03F0EAFB04462C44CC
+:10D82000204603F0BDFBFAE7002003F0ABFB1A48EB
+:10D83000F6F7A2F9DFED190A9FED190AF5F7C0FB1B
+:10D84000184C1548F6F758FA1420F6F765FA002830
+:10D85000114807D0F6F7B4F901210020F5F75EFC76
+:10D86000012106E0F6F77EF900210846F5F756FC9F
+:10D8700000210120F5F752FC074907481831F6F757
+:10D88000C9F9606A03F0B2FC03490023606A1A46D2
+:10D89000183103F077FCD4E7F0A10020CDCC4C3E4A
+:10D8A0000000964320A2002003F0A9FB4FF47A71F8
+:10D8B000B0FBF1F5002003F065FB0D4800229FED61
+:10D8C0000B0A01210280418080ED040A80ED050AE7
+:10D8D00080ED030A80ED020A80ED010A03F088FB67
+:10D8E00004462C44204603F05BFBFAE700000000EE
+:10D8F000C8A40020044810B5FDF7D4F9BDE81040D5
+:10D900000148F5F75FBC0000AC090020044810B5E1
+:10D91000FDF7C8F9BDE810400148F5F753BC000019
+:10D92000400A002030B5416EB9B101680D4B03F1DA
+:10D9300008048A688968C2F34262490F5D5C615CD1
+:10D940002D01B5FBF1F1A0F86A10995CA25C090108
+:10D95000B1FBF2F1A0F8681030BD0121A0F86A1007
+:10D96000F8E700008031010890F82810090706D573
+:10D970000168836B4A6822F400421A434A6090F8B7
+:10D980002810C90706D00168C36A4A6822F4003229
+:10D990001A434A6090F82810890706D50168036B7E
+:10D9A0004A6822F480321A434A6090F828104907E6
+:10D9B00006D50168436B4A6822F480221A434A6004
+:10D9C00090F82810C90606D50168C36B8A6822F44E
+:10D9D00080521A438A6090F82810890606D501689B
+:10D9E000036C8A6822F400521A438A6090F8281067
+:10D9F000490611D50168436C4A6822F480121A4323
+:10DA00004A60416CB1F5801F06D10168836C4A6899
+:10DA100022F4C0021A434A6090F82810090606D57D
+:10DA20000168C26C486820F40020104348607047C9
+:10DA30002DE9F84300250446C0F89050F9F73EF868
+:10DA40008046206820266FF07E470068000713D5C7
+:10DA50000022434631042046009700F069FB58B18C
+:10DA6000216851E8000F20F0800041E80002002A00
+:10DA7000F6D1C4F8886021E020680068400722D50C
+:10DA8000002243464FF480012046009700F050FBEF
+:10DA9000C8B1206850E8001F21F4907140E80012DE
+:10DAA000002AF6D12068083050E8001F21F001015B
+:10DAB00040E80012002AF5D1C4F88C60032084F8F5
+:10DAC0008450BDE8F883C4F88860C4F88C60E566CB
+:10DAD0002567002084F88450F3E710B5806B00219F
+:10DAE000A0F85E10FDF7CAF810BD70B5846B002574
+:10DAF0002168D4F88800D4F88C608968090606D5B6
+:10DB0000212804D1A4F85650204600F091F820684E
+:10DB10008068400606D5222E04D1A4F85E50204627
+:10DB200000F05CF8D4F8900040F01000C4F89000C9
+:10DB30002046FDF7A3F870BD10B5C1690022806BC7
+:10DB4000B1F5807F2DD0A0F85E20036853E8001F58
+:10DB500021F4807143E80014002CF6D101680831EB
+:10DB600051E8003F23F0010341E80034002CF5D1D7
+:10DB70000168083151E8003F23F0400341E80034D8
+:10DB8000002CF5D12021C0F88C10C16E012908D1DC
+:10DB9000016851E8003F23F0100341E80034002CF5
+:10DBA000F6D10267C16E012902D0FDF7B7FD10BDA5
+:10DBB000B0F85C10FDF711F810BD10B5806B0121B5
+:10DBC0000167C16E012902D0FDF7BCFD10BDB0F8A0
+:10DBD0005C104908FDF701F810BD000010B502689F
+:10DBE00052E8001F21F4907142E80013002BF6D197
+:10DBF0000E4B0268083252E8001F194042E8001438
+:10DC0000002CF6D1C16E012908D1026852E8001F2C
+:10DC100021F0100142E80013002BF6D10021202250
+:10DC2000C0F88C20C166416710BD0000FEFFFFEF09
+:10DC3000026852E8001F21F0C00142E80013002BE7
+:10DC4000F6D10168083151E8002F22F4000241E8C2
+:10DC50000023002BF5D12021C0F888107047000068
+:10DC600000680D49884201D1002070470B49884265
+:10DC700001D1012070470A49884201D10220704732
+:10DC80000849884201D1032070470749884201D1E1
+:10DC900004207047062070470050004000440040B8
+:10DCA00000480040001C0140007800402DE9F0438E
+:10DCB00004468068E24E87B0E24B2168D4E904272D
+:10DCC000D4F81CC010430A68002547EA0C07384303
+:10DCD000324002430A602068E268416821F4405102
+:10DCE000114341602268A1699A4201D0206A014330
+:10DCF0009668DFF854C3D54FD54806EA0C060E43A4
+:10DD000096602168666ACA6A22F00F023243CA62CC
+:10DD10002268BA420ED1006800F0380018286FD08F
+:10DD20007ADCB8B308286CD010286BD18BE0282897
+:10DD300068D18EE0C7498A4209D1006800F0070027
+:10DD400006285FD2DFE800F0507D7F818385C249DD
+:10DD50008A4209D1006800F0070006287BD2DFE87C
+:10DD600000F0437072747678BC498A4209D1006829
+:10DD700000F0070006286ED2DFE800F03663656722
+:10DD8000696BB7498A420BD1006800F0070006288A
+:10DD900061D200E043E0DFE800F0275456585A5CB7
+:10DDA000B0498A4206D1006800F0380018284CD0EB
+:10DDB000B7DD31E0AC498A4209D1006800F00700C4
+:10DDC000062848D2DFE800F0103D3F414345A7490F
+:10DDD0008A420BD1006800F0070006283BD2DFE83A
+:10DDE00000F0033032343638002035E0A0498A4252
+:10DDF00009D1006800F03800182826D091DD0BE02A
+:10DE000023E01EE027E09B498A420AD1006800F027
+:10DE10003800182819D084DD202888D11CE0012082
+:10DE20001AE09A4217D18A48001D006800F00700E6
+:10DE3000062810D2DFE800F0030507090B0D0220C9
+:10DE40000AE0042008E0082006E0102004E020207A
+:10DE500002E0402000E080208749DFF820829A42DB
+:10DE6000874A4FF400434FEA21174FF000064ED186
+:10DE700010281AD006DC022809D004280BD0082864
+:10DE80007ED10DE020283ED0402879D13DE0F9F741
+:10DE90009FFF014610E06846FAF750F801990BE041
+:10DEA00003A8FAF7EDF8049906E01068800605D596
+:10DEB0001068C0F3C100C140002970D0606A676873
+:10DEC00038F8102007EB4703B1FBF2F0834257D834
+:10DED000B0EB073F54D8002308461946F2F740FB41
+:10DEE00002467808130E120243EA012110183A463E
+:10DEF00071410023F2F734FB624AA0F54071914270
+:10DF00003ED821688FE03946D8E71946D6E7D4F8DD
+:10DF10001CC04FF6EF799C4546D1082819D005DC86
+:10DF200058B101280CD0042875D10DE0102815D067
+:10DF3000202835D040286ED134E0FBF7ADF801E061
+:10DF4000FBF7BCF8014610E06846F9F7F7FF0199C6
+:10DF50000BE003A8FAF794F8049906E0106880062D
+:10DF600004D51068C0F3C100C140C1B1636A6068E4
+:10DF700038F81330B1FBF3F1490001EB500100E038
+:10DF800049E0B1FBF0F0A0F11001494543D84FF64C
+:10DF9000F0732168C0F342021840104343E043E0AD
+:10DFA0003946E3E71946E1E7082819D005DC58B1FE
+:10DFB00001280CD004282ED10DE0102815D02028DF
+:10DFC0002BD0402827D12AE0FBF766F801E0FBF7C9
+:10DFD00075F8014610E06846F9F7B0FF01990BE0CB
+:10DFE00003A8FAF74DF8049906E01068800604D5F6
+:10DFF0001068C0F3C100C140B1B1636A606838F80D
+:10E000001330B1FBF3F101EB5001B1FBF0F0A0F1E3
+:10E010001001494505D9012506E03946EDE71946C5
+:10E02000EBE7216880B2C8600120A4F86A00A4F878
+:10E03000680028466667A66707B0BDE8F083000061
+:10E04000F369FFCF000C0058FFF4FF1100100140EE
+:10E05000544402580044004000480040004C004036
+:10E06000005000400014014000780040007C004057
+:10E0700000180140001C01400090D00368310108E5
+:10E0800000440258FFFC0F0070B50446D0F8800031
+:10E0900000232225A165A4F85C20C4F89030C4F8C0
+:10E0A0008C50F0B11F49C163D4F880101E48086439
+:10E0B000D4F880101D48C864D4F880000365134666
+:10E0C000A56D2168D4F880002A462431F7F7B2FE06
+:10E0D00038B11021C4F890102020C4F88C00012021
+:10E0E00070BD206940B1216851E8000F40F4807094
+:10E0F00041E80002002AF6D12068083050E8001FED
+:10E1000041F0010140E80012002AF5D120680830F2
+:10E1100050E8001F41F0400140E80012002AF5D10C
+:10E12000002070BD39DB0008BBDB0008EBDA00081B
+:10E130002DE9F047994617460D460446089E4FF0D4
+:10E14000000833E0701C31D0F8F7B8FCA0EB0900F0
+:10E15000B04218D8BEB120680168490726D5802D85
+:10E1600024D0402D22D0C169C94309070DD4082508
+:10E1700005622046FFF732FDC4F89050012084F874
+:10E180008480BDE8F0870320FBE7C069C043000539
+:10E190000CD421684FF4006008622046FFF71EFD92
+:10E1A0002021C4F8901084F88480ECE72068C069CE
+:10E1B00035EA000004D00020B842C3D00020E0E7D8
+:10E1C0000120F9E7044810B5FCF76CFDBDE81040EC
+:10E1D0000148F4F7F7BF0000900C0020044810B588
+:10E1E000FCF760FDBDE810400148F4F7EBBF00000C
+:10E1F000D40A0020044810B5FCF754FDBDE81040D7
+:10E200000148F4F7DFBF0000680B0020044810B598
+:10E21000FCF748FDBDE810400148F4F7D3BF00000B
+:10E22000FC0B00202DE9F0410C46D0F8D412D0F8B8
+:10E23000C83200EB8101D1F8C01229B304F00F02FB
+:10E24000002702EB820500EB8506B5694DB102EBB4
+:10E25000C20203EB8202D269B5FBF2F302FB135256
+:10E26000A2B1C1F81472D0F8D42200EB8200D0F829
+:10E27000C40203692BB1D1F8080201F504712246EA
+:10E2800098470020BDE8F0810320FBE700232146EA
+:10E290001A46B76100F0D3FDF3E770B50546D0F834
+:10E2A000D40205EB8000D0F8C04294B1284600F0BB
+:10E2B000A0FCC4F80C02D5F8D40205EB8000D0F81D
+:10E2C000C412D4F80402CA6804F503719047002010
+:10E2D00070BD032070BD000070B5224D0446297842
+:10E2E00000F0C8FB2878002600F00F0000EB80004B
+:10E2F00004EB800086842046697800F0BBFB6878D8
+:10E3000000F00F0000EB800004EB8000A0F86461D7
+:10E310002046A97800F0AEFBA87800F00F0000EBD3
+:10E32000800004EB80008684C684D4F8D40204EB19
+:10E330008000D0F8C01299B1D0F8C402406880477C
+:10E34000D4F8D40204EB8000D0F8C00200F09FFFA4
+:10E35000D4F8D40204EB8000C0F8C062C4F8BC62F8
+:10E36000002070BD9400002010B5D0F8D41200EB4E
+:10E370008100D0F8C04284B1D0F8C41259B194F8E9
+:10E380000002FF2807D08B68214694F801229847A5
+:10E39000FF2084F80002002010BD032010BD000003
+:10E3A0000A210180004870479800002070B5822142
+:10E3B00006460D4800F076FA012105460A4800F0AD
+:10E3C00071FA81210446084800F06CFA0DB1102161
+:10E3D000A9714FF0400104B1A18000B181804320B8
+:10E3E0003080014870BD0000A400002070B582217B
+:10E3F00006460D4800F056FA012105460A4800F08D
+:10E4000051FA81210446084800F04CFA0DB1102160
+:10E41000A9714FF4007104B1A18000B18180432043
+:10E420003080014870BD0000A400002070B582213A
+:10E4300006460D4800F036FA012105460A4800F06C
+:10E4400031FA81210446084800F02CFA0DB1102160
+:10E45000A9714FF0400104B1A18000B18180432037
+:10E460003080014870BD0000A40000202DE9F04775
+:10E470004FF407750446284600F00AFF06004FF0E7
+:10E48000000965D02946F2F708FAD4F8D40201272A
+:10E490003C4D4FF4007A4FF0100804EB8000C0F8B8
+:10E4A000C062C4F8BC62207CF0B329784023022209
+:10E4B000204600F00EFC2878402300F00F0000EB0F
+:10E4C000800004EB8000878402226978204600F0F7
+:10E4D00000FC697808230322204601F00F0101EBBC
+:10E4E000810104EB8101A1F86471A97801F00F01A9
+:10E4F00001EB810104EB8101A1F82680A97800F0ED
+:10E50000E8FBA978C84601F00F0101EB810104EB9B
+:10E5100081018F84C6F80492D4F8D40204EB800001
+:10E52000D0F8C402006800E01AE006F501768047E2
+:10E53000C6F81080C6F8148032687AB1207CF8B131
+:10E5400040236978204600F0D0FB0020BDE8F0872A
+:10E55000D4F8D41204EB8101C1F8C0920220F5E78F
+:10E56000297802225346204600F0B3FB2878534610
+:10E5700000F00F0000EB800004EB80008784A3E72D
+:10E580005346DEE79400002039B1D0F8D42200EBE6
+:10E590008200C0F8C4120020704703207047D0F8F2
+:10E5A000D42200EB8200D0F8C00218B1C0F80412E7
+:10E5B0000020704703207047D0F8D43200EB83006E
+:10E5C000D0F8C00228B1C0F81022C0F8081200200C
+:10E5D0007047032070472DE9FC410646D0F8D4026D
+:10E5E0000C46002106EB80000D46D0F8C0728DF875
+:10E5F0000010ADF8041037B1217811F060022CD072
+:10E60000202A48D102E00320BDE8FC81E288E2B183
+:10E6100009060BD5D0F8C40239468368607898475C
+:10E62000E288072A00D9072239462CE0607887F86B
+:10E630000002E088402800D340203946C2B230466C
+:10E6400087F8012200F07FF82AE0D0F8C402002207
+:10E65000214683686078984722E0607830B10128CD
+:10E660001ED00A2809D00B2815D110E096F89C027C
+:10E67000032810D1022201A905E096F89C02032884
+:10E6800009D101226946304600F077F808E096F893
+:10E690009C02032804D02146304600F049F80325A7
+:10E6A0002846B1E710B5D0F8D41200EB8102012161
+:10E6B000D2F8C0221AB1D2F8143213B116E00320F6
+:10E6C00010BD0B490123C2F81432D2F81032097878
+:10E6D00001F00F0404EB840400EB8404A361D2F87E
+:10E6E0001032D2F8082200F0AAFB0021084610BD23
+:10E6F0009400002010B5D0F8B8220024526890474A
+:10E7000000B10324204610BD002070470020704750
+:10E7100013460A46002110B500F0E7FA002010BDAC
+:10E7200013460A46002110B500F089FB002010BDF9
+:10E7300010B58021044600F063FB2046BDE8104080
+:10E74000002100F05DBB10B5C0F858210323C0F8CC
+:10E750009432C0F85C2113460A46002100F0C5FA45
+:10E76000002010BD10B50521C0F8941200231A46F0
+:10E77000194600F0BAFA002010BD10B582610223DC
+:10E78000C0F89432C26113460A46002100F057FBDC
+:10E79000002010BD10B50421C0F8941200231A46C1
+:10E7A000194600F04CFB002010BDF8B504460D469C
+:10E7B0000020ADF800004888010A062947D006DC91
+:10E7C00001290FD0022912D0032962D11DE00729A7
+:10E7D00046D00F295DD1D4F8B402C26920E0694661
+:10E7E00090473BE0D4F8B412207C0A68F7E7207C1D
+:10E7F00002260028D4F8B80205D0C16A68468847C6
+:10E800000146467036E0816AF8E7C0B2062840D279
+:10E81000DFE800F003090D111519D4F8B4024268BD
+:10E82000B2B3207CDBE7D4F8B4028268F8E7D4F80E
+:10E83000B402C268F4E7D4F8B4020269F0E7D4F88D
+:10E84000B4024269ECE7D4F8B4028269E8E7207CBC
+:10E85000F0B9D4F8B802416B68468847014609E030
+:10E86000207CA8B9D4F8B802016B684688470146F5
+:10E8700007204870EA888AB1BDF8000040B18242A2
+:10E8800000D902462046ADF80020FFF776FFF8BD1C
+:10E89000FFE729462046FFF74BFFF8E72046FFF742
+:10E8A00079FFF4E778B542880D46017800260446E2
+:10E8B0008A4212D9ADF800100AE0694600F019F852
+:10E8C0004178052904D181780646A94205D0002661
+:10E8D0006188BDF800209142EFD8304678BD002114
+:10E8E00002E0491C401CC9B20278002AF9D108464E
+:10E8F00070470A8803781A440A80017808447047F0
+:10E9000070B5002816460D4620D00446FFF7E7FFF5
+:10E9100002220146100202EB4101814204D8204646
+:10E92000FFF7DDFF4000801C308033780321022098
+:10E930002B700022697006E0431C2954D8B2411C98
+:10E94000641C2A54C8B221780029F5D170BD010099
+:10E950004FF0000004D0012901D0022901D003208A
+:10E96000704701207047000004A00A46024910B514
+:10E97000FFF7C6FF004810BD841400204344432025
+:10E98000436F6E6669670000122008800048704778
+:10E990002C00002004A00A46024910B5FFF7B0FF82
+:10E9A000004810BD8414002043444320496E746520
+:10E9B00072666163650000000420088000487047AB
+:10E9C0002800002004A00A46024910B5FFF798FF6E
+:10E9D000004810BD841400204D526F626F74000017
+:10E9E00004A00A46024910B5FFF78AFF004810BD8F
+:10E9F000841400204D726F626F7420436C690000B4
+:10EA000010B51A2008800B480A490830021F09680F
+:10EA100000681468081809D007490822FCF714FF99
+:10EA20000549042220461031FCF70EFF0248801EE3
+:10EA300010BD000000E8F11F4E00002078B1002357
+:10EA4000C0F8B832C0F8C432C0F8D03209B1C0F84A
+:10EA5000B4120121027080F89C1200F0CFB803209C
+:10EA6000704710B5D0F8C802F8F7CFFCBDE81040E9
+:10EA7000FFF76DBF10B5D0F8C802F8F7A1FCBDE8EC
+:10EA80001040FFF764BF2DE9F041174604464FF0F0
+:10EA9000000521B194F89C02032842D04CE0D4F840
+:10EAA000941204F11400022935D1D0E902639E4288
+:10EAB00006D9F21A394682602046FFF731FE0FE090
+:10EAC000B34214D14068984211D3D4F898128842C6
+:10EAD0000DD2002220461146FFF722FEC4F89852BC
+:10EAE00000231A461946204600F0FFF813E094F878
+:10EAF0009C02032808D1D4F8B802C16821B1C4F837
+:10EB0000D452C168204688478021204600F078F919
+:10EB10002046FFF727FE94F8A00268B184F8A052BF
+:10EB20000AE0D4F8B802426932B1C4F8D45242695A
+:10EB300020469047002800D10020BDE8F08170B544
+:10EB4000134604464FF0000221B194F89C020328BA
+:10EB500030D03AE0D4F8941204F5AA70032934D1E5
+:10EB6000D0E902518D420AD96A1A8260084682426F
+:10EB700000D3024619462046FFF7CAFD25E094F867
+:10EB8000AA0210F01F0003D0012802D0022800D0F2
+:10EB9000002294F89C02032808D1D4F8B802016935
+:10EBA00021B1C4F8D4220169204688472046FFF7E6
+:10EBB000F1FD0AE0D4F8B802836933B1C4F8D42275
+:10EBC000826920469047002800D1002070BD0020B7
+:10EBD000704710B5D0F8B812012280F89C220024AA
+:10EBE00029B103794A68D9B2904700B1032420467D
+:10EBF00010BDD0F8C802F8F735BC000070B5017838
+:10EC0000012929D115490925154C02230022C1F8F3
+:10EC1000E004C0F8C81208460C600D71CB718A710F
+:10EC20004B728A72CA720A738A73CA730A74F8F7CB
+:10EC300093FF08B1F5F7C6F808484FF40071F8F7EC
+:10EC40006EFB064880220021F8F76DFB0348012186
+:10EC50004FF4BA72F8F767FB002070BDA4280020BB
+:10EC600000000440D0F8C82201F07F000B0600EB42
+:10EC7000C00002EB800001D5807D704790F85602FD
+:10EC8000704710B5D0F8D42200EB8202D2F8B82237
+:10EC900022B190F89C32032B02D004E0032010BD77
+:10ECA000126A02B19047002010BD10B5D0F8D422EE
+:10ECB00000EB8202D2F8B82222B190F89C32032BEA
+:10ECC00002D004E0032010BD526A02B19047002038
+:10ECD00010BD10B51C46D0F8C80213462246F8F7FE
+:10ECE000CAFBBDE81040FFF732BE10B5D0F8C8022D
+:10ECF000F8F7F2FBBDE81040FFF729BE2DE9F0411F
+:10ED0000044601250020D4F8B812064684F89C5227
+:10ED1000C4F894026060C4F8A40284F8A00231B17F
+:10ED20004A6822B100212046904700B103262046C0
+:10ED3000002240231146FFF7CCFF4027A4F864517E
+:10ED400000223B4680212046C4F86071FFF7C1FFD6
+:10ED5000A58430462762BDE8F08190F89C12042912
+:10ED600003D190F89D1280F89C120020704710B5D6
+:10ED700090F89C12032905D1D0F8B81211B1C969D5
+:10ED800001B18847002010BD01740020704710B504
+:10ED9000D0F8C802F8F796FFBDE81040FFF7D7BDDE
+:10EDA00070B5044600F2AA20054600F051F894F828
+:10EDB000AA020123B4F8B01210F01F02C4F8943272
+:10EDC000C4F898120AD0012A0ED0022A12D000F0FC
+:10EDD00080012046BDE8704000F012B82946204668
+:10EDE000BDE8704000F0D0B829462046BDE870402C
+:10EDF00000F013BA29462046BDE8704000F05BB928
+:10EE000010B5D0F8C802F8F781FBBDE81040FFF755
+:10EE10009EBD10B5D0F8C802F8F76EFFBDE81040EF
+:10EE2000FFF795BD90F89C12042903D090F89C122E
+:10EE300080F89D12042180F89C120020704710B5C4
+:10EE4000D0F8C802F8F79BFBBDE81040FFF77FBD84
+:10EE500070B5054608788C1C287048786870204684
+:10EE6000FDF7A7FFA41C68802046FDF7A2FFA8803D
+:10EE7000A01CFDF79EFFE88070BD38B50446002059
+:10EE8000ADF80000A1B1C4F8B812D4F8D40204EB74
+:10EE90008000D0F8B802C16A19B168468847C4F842
+:10EEA000D002D4F8D802401CC4F8D802002038BDE3
+:10EEB000032038BDD0F8B83202460020002B02D023
+:10EEC0001B681046184770472DE9F0412C4E044648
+:10EED000887800258846C1B20129317006D941469B
+:10EEE0002046FFF725FC0320BDE8F08194F89C0242
+:10EEF000022702280CD003281DD041462046FFF7E8
+:10EF000017FC31782046FFF7F5FB03252846EBE791
+:10EF100089B320466160FFF7CDFF050004D041466C
+:10EF20002046FFF705FC1DE02046FFF733FC0320D9
+:10EF300084F89C02EAE7C1B1606888421BD0C1B284
+:10EF40002046FFF7D7FB317820466160FFF7B2FF1C
+:10EF5000050010D041462046FFF7EAFB2179204604
+:10EF6000FFF7C8FB84F89C72D0E7616084F89C725C
+:10EF70002046FFF7BFFB2046FFF70CFCC6E700006A
+:10EF800090000020FFF745BF2DE9F0410A784FF0CF
+:10EF9000000512F060020CD0202A01D0402A7DD159
+:10EFA000D0F8D42200EB8202D2F8B82292689047BF
+:10EFB00031E04B78002201260A2B6FD2DFE803F004
+:10EFC00041666E586E08056E2D29FFF7EEFB67E06F
+:10EFD00004468888D8B9C888C8B94888802816D215
+:10EFE00094F89C2200F07F07032A10D0394620466F
+:10EFF00084F89E72FFF7CBFE2046FFF7CBFB1FB1D4
+:10F00000022084F89C024BE084F89C6248E0204691
+:10F0100044E0FFF759FF054642E0CB88012B3DD184
+:10F0200090F89C32012B04D0022B02D0032B35D157
+:10F0300004E000F108018260012216E00122011DB6
+:10F0400013E090F89C22012A03D0022A01D0032A5F
+:10F0500024D1CA88022A21D1D0F8A412C66009B1ED
+:10F060000321C160022200F10C01FFF786FB17E0CB
+:10F070004A88012A02D0022A03D00FE0C0F8A46215
+:10F0800016E08988090A80F8A01211E090F89C32F5
+:10F09000012B08D0022B06D0032B04D0FFF748FB2E
+:10F0A0002846BDE8F08149880129F9D1C0F8A42299
+:10F0B000FFF770FBF4E72DE9F0410A780E46097975
+:10F0C000054612F060004FF00008CCB20BD02028AB
+:10F0D00001D040286AD121462846FFF715FBFF28BA
+:10F0E00000D0D8B396E07078C8B3012824D00328A4
+:10F0F0005CD195F89C02022802D0032856D10CE07E
+:10F10000002C53D0802C51D021462846FFF778FEA2
+:10F1100080212846FFF774FE7CE0708840B93CB13E
+:10F12000802C05D0F08818B921462846FFF768FEE4
+:10F130002846FFF72FFB6DE095F89C020228DFD0F0
+:10F14000032863D1708880BB600603D0214628461F
+:10F15000FFF787FC2846FFF71DFBBCE700E00AE04D
+:10F16000C5F8D402D5F8B8028268F2B13146284613
+:10F17000904780464EE095F89C020027022802D076
+:10F18000032843D113E00CB1802C3FD1200604F0BA
+:10F190007F0000EB800005EB800101D5143101E018
+:10F1A00001F5AA7102220F602CE033E02EE0200668
+:10F1B00004F00F0000EB800005EB800009D5808C87
+:10F1C00020B304F07F0000EB800005EB80061436CE
+:10F1D0000AE0B0F86401C8B104F07F0000EB8000E1
+:10F1E00005EB800606F5AA764CB1802C07D02146A7
+:10F1F0002846FFF737FD10B10120306000E037608E
+:10F20000022231462846FFF7B8FA03E03146284685
+:10F21000FFF78EFA4046BDE8F08170B505460878E4
+:10F220000E464FF0000410F0600003D0202801D0FB
+:10F23000402827D195F89C02012803D0022801D04C
+:10F2400003281FD1B088C1B201291AD8C1B22846FB
+:10F25000FFF75CFAFF280CD058B9D5F8B8128A68C5
+:10F260003AB1C5F8D40228468A6831469047044628
+:10F2700000E00324F088204307D12846FFF78AFAEC
+:10F2800003E031462846FFF753FA204670BD704729
+:10F29000004870478426002070B54D7801230A7815
+:10F2A000012D1C4C02F00F0503FA05F3D0F81C5891
+:10F2B00017D000EB421245EA0343C0F81C38D2F8DD
+:10F2C000000B00040BD40B890979D2F8000BC3F3AF
+:10F2D0000A03184344EA81410843C2F8000B0020A6
+:10F2E00070BD9EB23543C0F81C5800EB4213D3F8F2
+:10F2F00000090004F3D40D890979D3F80009C5F396
+:10F300000A058904284341EA825108432043C3F88F
+:10F310000009E4E700800010D0F800196FF30A013B
+:10F32000C0F80019D0F8041841F48071C0F804182E
+:10F330000020704770B50D460446C2F307211E46F3
+:10F340000498012922D0E06840F04000E0602046A7
+:10F3500000F03CF8C6F307210029A16B2ED021F460
+:10F360008031A163C5F3074101290ED1E16D154A32
+:10F3700089B2E165E16D1143E165A16841F00601E3
+:10F38000A160A16841F02001A16070BDA26BC3B271
+:10F390000D49012B22F48030A063E06800EA0100EF
+:10F3A000E060E06820F44010E06003D1E06840F4E1
+:10F3B0008010E060204600F009F8D3E741F4803186
+:10F3C000CFE700000000EE03BFFFBDFF08B500213E
+:10F3D0004FF070620091009B5B1C009393420CD82D
+:10F3E0000369002BF7DA0091016941F00101016125
+:10F3F0000099491C0091914201D9032008BD01697F
+:10F40000C907F5D1002008BD70B50A7801234C78F2
+:10F41000012C00EB42122CD0D2F8004B002C0BDA5E
+:10F42000D2F8004B44F00064C2F8004BD2F8004B15
+:10F4300044F08044C2F8004B0C78D0F83C5804F0FB
+:10F440000F0403FA04F425EA0444C0F83C480978A0
+:10F45000D0F81C4801F00F018B401C4924EA0343FB
+:10F46000C0F81C38D2F8000B0840C2F8000B00208E
+:10F4700070BDD2F80049002C0BDAD2F8004944F0F4
+:10F480000064C2F80049D2F8004944F08044C2F850
+:10F4900000490D78D0F83C4805F00F050C4E03FAF2
+:10F4A00005F5ADB2AC43C0F83C48D0F81C4809782B
+:10F4B00001F00F018B4099B28C43C0F81C48D2F880
+:10F4C00000093040C2F80009D1E700000078F3EFEE
+:10F4D000007833ECD0F8001E21F00301C0F8001EC4
+:10F4E000D0F8041821F00201C0F804180020704779
+:10F4F000D0F8001E21F00301C0F8001ED0F8041857
+:10F5000041F00201C0F80418002070472DE9F04FC7
+:10F5100000250F46904604462E46284604EB8001FF
+:10F52000C1F80451401C0F28F8D3C3F307405FEA29
+:10F530000009204610D0806B40F40011C4F8381048
+:10F54000C8F30720C4F8005E0128204617D0D0F881
+:10F55000001841F0030119E0D0F8040840F002015E
+:10F56000C4F80418A06B20F40011A163206840F0D7
+:10F5700040012160206840F080012160E0E7D4F87C
+:10F580000018380E204601D041F00101C0F80018E3
+:10F59000102100F08CFA00B10126204600F06BFA31
+:10F5A00000B101264FF67F3A4FF0006CC4F81058B6
+:10F5B0004FF0904BC4F81458C4F81C580020FAB20D
+:10F5C00014E000BF04EB4011D1F80039002B06DA3B
+:10F5D00010B1C1F800B904E0C4F800C901E0C1F8F5
+:10F5E0000059C1F81059C1F808A9401C8242E9D855
+:10F5F000002013E004EB4011D1F8003B002B06DAA9
+:10F6000010B1C1F800BB04E0C4F800CB01E0C1F8C0
+:10F61000005BC1F8105BC1F808AB401C8242E9D81E
+:10F62000D4F81008C7F30742002A6FF0804120F495
+:10F630008072C4F81028A561616103D1A06940F00F
+:10F640001000A061A069C8F30741094A1043A061F6
+:10F6500019B1A06940F00800A061B9F1010F03D110
+:10F66000A06904490843A0613046BDE8F08F00005E
+:10F6700000383C8004000040816821F00101816075
+:10F680000020704710B5144C036CA34203D9D0F886
+:10F69000003B002B1EDB0023C0F8103B0129D0F8F3
+:10F6A000101B41F40021C0F8101BD0F8101B41F0D2
+:10F6B0001801C0F8101BD0F8101B41F0C041C0F871
+:10F6C000101B07D1C0F8142BD0F8001B41F080218B
+:10F6D000C0F8001B002010BD0A30544F0B784A7848
+:10F6E000012A00EB43100BD0D0F8002B22F40012BB
+:10F6F000C0F8002B0979032914D0022912D017E091
+:10F70000D0F8002922F40012C0F800290979032951
+:10F7100001D002290CD1D0F8001941F08051C0F875
+:10F72000001905E0D0F8001B41F08051C0F8001B23
+:10F73000002070470A784B78D1B2012B00EB4210C1
+:10F7400012D0D0F8002B002A06DB29B1D0F8001B1C
+:10F7500021F08041C0F8001BD0F8001B41F40011DB
+:10F76000C0F8001B00207047D0F80029002A06DBF3
+:10F7700029B1D0F8001921F08041C0F80019D0F863
+:10F78000001941F40011C0F80019EBE7F8B50B7847
+:10F790006FF060464F788C4DDCB2012F00EB4313C5
+:10F7A0002BD0D3F8107B002C07EAC544C3F8104BCC
+:10F7B000D3F8104B04EA0504C3F8104B7ED00D6952
+:10F7C000002D7CD08C6825446D1EB5FBF4F5ADB2E0
+:10F7D0006C430C6206EAC545D3F8104B2C43C3F8C2
+:10F7E000104BD3F8104B0D6AC5F3120554EA05040B
+:10F7F000C3F8104B012A73D0CEE00F6907B3D3F8DA
+:10F8000010796FF31207C3F81079D3F8107907EA6B
+:10F810000507C3F810791CB3D1F810C08D68D3F870
+:10F820001079AC44ACF1010CBCFBF5F5ADB206EAC5
+:10F83000C5463743C3F810790E79012E1CD02AE053
+:10F84000D3F810692E40C3F81069D3F8105945F465
+:10F850000025C3F81059D3F810596FF3120520E0B2
+:10F860000E698D68AE4200D90D61D0F8106946F47A
+:10F870000026C0F810690EE0D3F810694FF0C047B9
+:10F8800007EA457726F0C046C3F81069D3F8105947
+:10F890003D43C3F810590E69D3F81059C6F3120648
+:10F8A0003543C3F81059012A1BD000EB4413D3F899
+:10F8B000004944F00444C3F8004901E047E05AE03D
+:10F8C0000C79012C2ED00A695AB30B78D0F8341871
+:10F8D000012203F00F039A401143C0F8341871E07D
+:10F8E00056E0CA691AB100EB4413C3F81429097928
+:10F8F00001290ED1D0F80818C90500EB4411D1F840
+:10F90000002902D442F0005201E042F08052C1F8D6
+:10F91000002900EB4410D0F8001941F00441C0F870
+:10F9200000194FE0D0F80848E405D3F8004902D4A4
+:10F9300044F0005401E044F08054C3F800490092C0
+:10F940000B8A0A78C9689BB200F0E0F93AE00C69CA
+:10F950000CB18C680C618C680C62C4F31205D0F891
+:10F96000104B2C43C0F8104BD0F8104B44F400243B
+:10F97000C0F8104B3EE78D68D3F8104BC5F3120565
+:10F980002C43C3F8104BD3F8104B44F400242FE75A
+:10F99000CA680AB1C3F8142B097901290CD1D0F82F
+:10F9A0000808C005D3F8000B02D440F0005001E075
+:10F9B00040F08050C3F8000BD3F8000B40F0044037
+:10F9C000C3F8000B0020F8BDFFFF07E038B50022A8
+:10F9D00042F21074002300920A784D78012D00EB5A
+:10F9E000421219D0D2F8005B002D3CDAD2F8005B4D
+:10F9F00045F00065C2F8005B0A7800EB4212D2F8CD
+:10FA0000005B45F08045C2F8005B009A521C0092F2
+:10FA1000A24221D9012326E0D2F80059002D22DA92
+:10FA2000D2F8005945F00065C2F800590A7800EB99
+:10FA30004212D2F8005945F08045C2F80059009AA8
+:10FA4000521C0092A242E5D80A7800EB4212D2F88A
+:10FA50000029002AF3DB06E00A7800EB4212D2F814
+:10FA6000002B002AD1DB184638BD816841F0010126
+:10FA700081600020704708B500214FF0706200914E
+:10FA8000009B5B1C009393420AD80369002BF7DAB2
+:10FA90000091102303610099491C0091914201D902
+:10FAA000032008BD0169C906F5D4002008BD18B5BA
+:10FAB00000224FF070630092009C641C00949C42F2
+:10FAC0000CD80469002CF7DA2024009244EA811152
+:10FAD00001610099491C0091994201D9032018BD88
+:10FAE00001698906F5D4002018BDD0F8080810F087
+:10FAF000060004D0022803D0062801D00F2070474A
+:10FB000002207047406900F001007047D0F81818D3
+:10FB1000D0F81C08084080B27047D0F81818D0F808
+:10FB20001C080840000C704710B5D0F8102801F0F0
+:10FB30000F0300EB4114D0F83418D4F80809D94069
+:10FB400001F0010142EAC111084010BD00EB411172
+:10FB5000D1F8081BD0F81408084070474169806943
+:10FB6000084070470346084630B5940802F0030188
+:10FB7000002203F5805303E01D68521C40F8045B2B
+:10FB8000A242F9D300290CD01C680023491EDD00D5
+:10FB9000090403F10103090C24FA05F200F8012B12
+:10FBA000F4D130BD70B50446C06801294FF000059E
+:10FBB00020F0C040E06001D079B120E0E06840F082
+:10FBC0000050E0600A20F6F783FA60690A3510F009
+:10FBD000010F10D1C82DF5D30DE0E06840F0804052
+:10FBE000E0600A20F6F774FA60690A3510F0010F38
+:10FBF00001D0C82DF5D3C82D01D0002070BD012043
+:10FC000070BDD0F800284FF4FE6303EA011322F41C
+:10FC1000FE62C0F80028D0F800181943C0F8001898
+:10FC200000207047022A3ED1264A274B0A449A42B6
+:10FC300001D20F2138E0254A254B0A449A4201D2CD
+:10FC40000E2131E0234A244B0A449A4201D20D216D
+:10FC50002AE0224A224B0A449A4201D20C2123E094
+:10FC6000204B214A0B44934201D20B211CE01F4B35
+:10FC70001F4A0B44934201D20A2115E01D4B1E4A34
+:10FC80000B4493420FD31D4B1D4A0B44934201D2A8
+:10FC9000082109E01B4B1C4A1944914201D207215B
+:10FCA00002E0062100E00921C2684FF4705322F4FB
+:10FCB0007052C26003EA8123C1681943C160002009
+:10FCC00070470000405327FF00350C00401E1BFF0B
+:10FCD00040420F0000DC0BFF804F1200808CF9FEC9
+:10FCE00020D6130060B6E5FE60E3160000D3CEFE1A
+:10FCF00040771B00C05BB3FEC091210000CA91FE9B
+:10FD000020753800E05459FEE09C410010B5029C7B
+:10FD100074B900EB0232DB1C00209B0802F5805214
+:10FD200004E000BF51F8044B1460401C9842F9D322
+:10FD3000002010BDFEE703B401984100009850EA8E
+:10FD4000C12018BF04204A0D18BF40F0010040F246
+:10FD5000FF72B2EB515F08BF40F00200012808BFFC
+:10FD6000052002B070474100080218BF04200A0EA7
+:10FD700018BF40F001004FF07F4232EA010108BF96
+:10FD800040F00200012808BF05207047090700283D
+:10FD90004FEA116104DB00F1E02080F800147047A5
+:10FDA00000F00F0000F1E02080F8141D7047000003
+:10FDB00010B510EE104A4FF01A402DED028B00EBFB
+:10FDC0004400B0F1C85F4AD84FF0FC40B0EB440F9C
+:10FDD00022D2B0EEC00ADFED310A30EEC00ADFED0C
+:10FDE000300A20EE208A18EE100A01F0C3FF00EE60
+:10FDF000100A14F0004F1DBF9FED2A1ADFED2A0AEA
+:10FE0000B1EE400A9FED291A08BFF0EE410ADFED7E
+:10FE1000281A20EE210A05E020EE008A9FED251A1F
+:10FE2000DFED250ADFED251A9FED252A70EEC00AC9
+:10FE300020EE080A08EE212ADFED221A48EE021A07
+:10FE40009FED212A08EE212ADFED201A48EE021A42
+:10FE5000BDEC028B40EE610A30EE810A10BD4FF01E
+:10FE6000CC40B0EB440F82BF9FED190ABDEC028B72
+:10FE700010BD4FF07F40B0EB440F05D2BDEC028BBC
+:10FE8000BDE8104000F0DCBD0120F0F760FDBDECE6
+:10FE9000028BBDE8104000F0D9BD00000000803F9B
+:10FEA0000000003F0000494022AA7D3A0000000007
+:10FEB000000000C00000C93F22AAFD3924FE1C3DFD
+:10FEC000C78AD83C1E67383D1B93993DAFAA2A3E8E
+:10FED000DB0FC93F10B54FF00E402DED028BB0EE99
+:10FEE000408A18EE104A00EB4400B0F1506F4AD837
+:10FEF0004FF0FC40B0EB440F22D2B0EEC80ADFED69
+:10FF0000360A30EEC00ADFED350A60EE208A18EEC0
+:10FF1000900A01F02FFF01EE100A14F0004F1DBFF0
+:10FF2000DFED2F0A9FED2F0AB1EE411ADFED2E0A09
+:10FF300008BF9FED2E0ADFED2E1A21EE218A05E083
+:10FF4000DFED2C0A68EE088AB0EE600A9FED2A1AEF
+:10FF5000DFED2A1A30EE080A48EE811A9FED281AC2
+:10FF600008EEA11ADFED271A48EE811A9FED261A36
+:10FF700008EEA11A68EE281ABDEC028B01EE810A88
+:10FF800030EE200A10BD4FF0E440B0EB440F0CD926
+:10FF900018EE100AFFF7E7FE042808BF00F05EFD28
+:10FFA000B0EE480ABDEC028B10BD4FF07F40B0EBC5
+:10FFB000440F07D2B0EE480ABDEC028BBDE81040FA
+:10FFC00000F03EBD0120F0F7C2FCBDEC028BBDE8A5
+:10FFD000104000F03BBD00000000803F0000003FEB
+:10FFE0000000C9BF22AAFDB90000C93F22AAFD39FD
+:10FFF000000000C00000000024FE1C3DC78AD83C61
:020000040801F1
-:100000009FED630ADFED630A9FED630AB0EE481AC5
-:100010000A46B1EE688A80F00041F0EE418A10464F
-:100020000A1A5200B2F1807F34D2484010F0004FDB
-:10003000DFED5A1A9FED5A2A1DBF9FED5A1A70EE36
-:10004000E10A30EE420A9FED581A08BF70EEA10A8D
-:1000500000E040E008BF30EE020AB0EE682A01EE90
-:10006000482A08EE818AC2EE081A15E011F0004F06
-:1000700004BF9FED4E0AF0EE400AD1D010F0004FC1
-:1000800019BFDFED4B0A9FED4B0ADFED4B0A9FEDE9
-:100090004B0AC5E7C8EE881A21EEA11A9FED482A3F
-:1000A000DFED482A41EE022A9FED472A01EE222A7F
-:1000B000DFED462A41EE022A9FED452ABDEC048B76
-:1000C00001EE222A21EE811A01EE020A30EE210A07
-:1000D00030EE200A70BD4FF07F42B2EB400F28BFD8
-:1000E000B2EB410F09D2F0EE480AB0EE680ABDEC5F
-:1000F000048BBDE8704000F026BA40EA01035B00C3
-:1001000008BF41F0FF410BD0B2EB400F08BFB2EB8C
-:10011000410F08D120F0804008EE900A21F0804184
-:1001200008EE101A18E7B2EB400F12BF5FEA410366
-:1001300040F0FF4001F000413FF40EAFB2EB410F41
-:1001400012BF5FEA400200F0004041F0FF413FF47F
-:1001500003AF4A0092EA40033FF5FEAE002AACBF6F
-:100160009FED1C0A9FED1C0A68EE808A28EE008A2B
-:1001700018EE900A18EE101AEEE60000DB0FC9BF69
-:10018000DB0FC93FDB0F4940DB0F49C00000C9BF8F
-:1001900022AAFDB90000C93F22AAFD390060ED3E48
-:1001A000C30ACE37000000BF0000003F000000007F
-:1001B000000049C022AA7DBA0000494022AA7D3A27
-:1001C0002DAD65BD8FB8D53D0FB511BE61C84C3E94
-:1001D000A8AAAABE0000804F0000802F10EE101ABF
-:1001E00008B5434A6846B2EB410F26D94FF0E640C6
-:1001F000B0EB410F94BF00204FF0FF30009000980B
-:10020000DFED3C0A002860DB10F0010F46D060EE05
-:10021000000ADFED391A9FED391A10F0020F00EED7
-:10022000E11ADFED371A40EE811A21EEA01AF0EE46
-:10023000400A40EE010A2ED041E0324B21F000424C
-:1002400093423FD911F0004FDFED2F0A20EE201A24
-:10025000DFED2E0A19BF31EE601A71EE200A31EE81
-:10026000201A71EE600ABDEEE01A11EE100A9FED41
-:10027000281A00F0030000EEC10A9FED261A009034
-:1002800000EEC10A9FED241A00EEC10A9FED231A69
-:1002900000EEC10AB3E7F1EE600A10E020EE000ABA
-:1002A0009FED1F1ADFED1F1A10F0020F40EE011A2A
-:1002B0009FED1D1A00EE211A40EE010AEBD1B0EEBF
-:1002C000600A08BD00F052F999E710EE100A4000EC
-:1002D000B0F17F4FF3D307D14FF00100F0F737FBB8
-:1002E000BDE8084000F032B9BDE8084000F028B988
-:1002F000B61F927E0000803F336D4C39DA82083C95
-:10030000A0AA2ABE490E494683F9223F0000004BAD
-:100310000000C93F00A0FD390020A2331A61342C2F
-:10032000B93AB2BACA9F2A3DDDFFFFBE00B510EE52
-:10033000101A2DED028B81B04D4A6846B2EB410F89
-:100340003CD94FF0E640B0EB410F94BF00204FF096
-:10035000FF3000900098B0EE408A00285FDB28EE66
-:10036000080ADFED440A9FED441A00EE201ADFED83
-:10037000430A40EE010A9FED421A00EE201ADFED1B
-:10038000410A10F0010F40EE010A9FED3F1A00EE06
-:10039000201A61EE000AB0EE480A08EE200A02BFF9
-:1003A00001B0BDEC028B00BD9FED381A01B0C1EE6B
-:1003B000000ABDEC028BB0EE600A00BD344B21F0A8
-:1003C0000042934228D911F0004FDFED320A20EEAF
-:1003D000201ADFED310A19BF31EE601A71EE200AE2
-:1003E00031EE201A71EE600ABDEEE01A11EE100A2D
-:1003F0009FED2A1A00F0030000EEC10A9FED281AB3
-:10040000009000EEC10A9FED271A00EEC10A9FED91
-:10041000261A00EEC10A9DE700F0A8F89AE718EE48
-:10042000100A4000B0F17F4F0DD218EE100AFFF70E
-:10043000D4FA042808BF00F091F8B0EE480A01B0E1
-:10044000BDEC028B00BD09D10120F0F780FA01B0AC
-:10045000BDEC028B5DF804EB00F078B801B0B0EEB3
-:10046000480ABDEC028B5DF804EB00F069B80000AF
-:10047000B61F927EBBE9223C0C6D063B8A76CE3CD1
-:10048000ACB5593D35A1083E29AAAA3E000080BF5F
-:10049000490E494683F9223F0000004B0000C93F46
-:1004A00000A0FD390020A2331A61342C491E00EB54
-:1004B000C102B0EE401B92ED000B31F006020DD0F0
-:1004C000491E00EBC102B0EE403B92ED002B31F033
-:1004D0000602B0EE420B03EE010BF1D1022914D05B
-:1004E00004290AD0062918BF704790ED0A2B00EEA8
-:1004F000012B90ED080B02EE010B90ED062B00EEA8
-:10050000012B90ED040B02EE010B90ED022B00EE9F
-:10051000012B90ED000B02EE010B704730EE000B4B
-:10052000704730EE010B70479FED030B20EE000B80
-:1005300070470000000000000000000000000010F4
-:1005400030EE000A704730EE200A7047DFED020AF5
-:1005500080EEA00A70470000000000009FED020A34
-:1005600020EE000A70470000000000102DE9F001A5
-:100570004FF07F42B2EB410F9FBF4FF0FF31016060
-:10058000BDE8F00170474FF0004242EA0123C1F399
-:10059000C752783A551112F01F0C434CCCF120068B
-:1005A0007C44C1F3C752A2F178024FEA621204EB15
-:1005B000820254F8254008BFD2E9015612D055688E
-:1005C00004FA0CF425FA06F73C43976805FA0CF593
-:1005D00027FA06F8D26807FA0CFCF24045EA08054B
-:1005E0004CEA0206A4FB034CA5FB0352A6FB0363E3
-:1005F0001D449D4234BF012600261319334416B111
-:10060000934202D903E0934201D2012200E000228A
-:10061000624402F1200C9206DC0C42EA443200EE05
-:10062000102A5B03DFED210AF8EEC01A00EE103A43
-:100630004FEA9C1C11F0004FB8EE400AC0F800C011
-:1006400020EE201A00EE105ADFED190AB8EE400A2B
-:1006500020EE200A71EE810A70EE800A10EE902AD8
-:1006600002F500626FF30B0200EE902A70EEE11AC1
-:1006700031EEC11ADFED101A30EE411A9FED0D0A6E
-:1006800020EE800A01EE210A9FED0C1A00EE810A8D
-:1006900004BFBDE8F0017047CCF180510160BDE8B6
-:1006A000F001B1EE400A7047942B000000000036C4
-:1006B0000000802C22AAFD29DB0FC92F0000C92FC2
-:1006C00030380A2801D2012070470020704710B549
-:1006D00041EC100BFFF744FA51EC100B10BD10B5B4
-:1006E00014460B4603E013F8011B00F003F8641EE8
-:1006F000F9D210BD034A4140C9B232F8111081EA63
-:1007000010207047542E01082DE9F041040006D056
-:10071000184E306884420AD10020BDE8F081502094
-:1007200080F31188BFF34F8FBFF36F8FFEE701F0A7
-:10073000BDF8776B6569B66B01F0D8F8BD4201D0A2
-:10074000B54201D10220E8E70B48854208D1A06AF2
-:100750000028F7D194F858000128F3D00320DCE7F3
-:1007600005481438854202D00DB10120D5E7042098
-:10077000D3E70000200100209430002070B504462B
-:1007800090F82C000025FD2803D194F82D00EE28C8
-:1007900001D0A06A0EE00E22002004F12C01FFF728
-:1007A0009EFF618F2084814208D0A06AE5622563A4
-:1007B0006563A563401CA561A06270BD94F83820F4
-:1007C00094F82E0002F0070694F93750218F00F0BC
-:1007D0000F03C0F30210C4E901562370C1F3CB012B
-:1007E00060700122B4F931009FED140A01EE100A85
-:1007F000DFED130ADFED131AB8EEC11A21EE001A6D
-:1008000021EE201A84ED041AB4F92F0001EE100A2B
-:10081000B8EEC11A21EE000A84ED030AD4F83300C1
-:10082000C4E9062100EE100AB8EEC00A20EE200A44
-:1008300020EE210A84ED050A70BD00000000803B17
-:10084000D00FC9400000003882B0CDE9000121F08E
-:10085000004001909DED000B02B051EC100B704771
-:1008600000207047F6F7C0F8FCF748F9FBF7ACF941
-:10087000FBF798F8FBF73CF8FBF712FBFBF7AEFA37
-:10088000FBF7DCFAFBF7E8FBFBF7BEFCFBF7F0FC41
-:10089000FBF724FDFBF750FCFBF782FCFBF7E0F8CD
-:1008A000FBF710F9FBF742F9FBF734FBFBF792FB80
-:1008B000FBF75AFAFBF70AFC00F024F9FBF76AF998
-:1008C00000F048F9FEE7000010B504460188FE205C
-:1008D000EE22207600206276C1B10F2901D30F21CC
-:1008E0002180618811B1072901D30720608094ED30
-:1008F000040ADFED510A51489FED511AB5EEC00AC6
-:10090000F1EE10FA04D8C4ED040A07E02080E8E70D
-:1009100010EE101A814201DB84ED041A94ED050AF1
-:10092000B5EEC00AF1EE10FA02D8C4ED050A05E0F2
-:1009300010EE101A814201DB84ED051A414960680E
-:10094000884202D39FED400A04E04049884203DB1D
-:100950009FED3F0A84ED010A3E49A068884202D318
-:100960009FED3D0A04E03D49884203DB9FED3C0AD0
-:1009700084ED020A3B49E068884202D39FED3A0ABF
-:1009800004E03A49884203DB9FED390A84ED030A0B
-:10099000D4ED042ADFED370A9FED370A2278C2EE44
-:1009A000A01AA07EA1789FED351A62F303009FED97
-:1009B000342A61F30610A0760F2261EE801AFDEE54
-:1009C000E11A11EE901AA4F8231004F11801D4EDE5
-:1009D000051AC1EEA02A62EE800AFDEEE00A10EED2
-:1009E000900AA4F82500D4ED030AC0EE811A21EE86
-:1009F000800ABDEEC00A10EE100AC4F81F0094ED84
-:100A0000020AC0EE010A20EE820ABDEEC00A10EE14
-:100A1000100AA4F81D0094ED010A20EE020ABDEEB2
-:100A2000C00A10EE100AA4F81B000020FFF757FEC2
-:100A3000A4F8270010BD000000000000C1CACC418E
-:100A4000C1CACC41E1FAFFC2E1FAFFC2E1FAFF42BA
-:100A5000E1FAFF42000049C4000049C400004944D3
-:100A600000004944C00FC9C8C00FC9C8C00FC94859
-:100A7000C00FC948CDCCCC4100000047D00FC940C1
-:100A80000000804310B5EFF3058111B16FF005044C
-:100A900004E04FF0000408B100F0E0FF204610BD74
-:100AA00038B50546EFF3058010B16FF005040CE092
-:100AB000002401F00BFE291A0090002903DD68468E
-:100AC00000F0F2FF01E06FF00304204638BD0000A3
-:100AD00010B501F0EDFD38B1022804D003480068DC
-:100AE000012800D0002010BD032010BD700100209F
-:100AF000EFF3058008B101F0EFBD01F0E7BD4FF461
-:100B00007A707047EFF3058010B16FF00500704701
-:100B10000449086810B14FF0FF30704701220A60A5
-:100B2000002070477001002010B5EFF3058010B170
-:100B30006FF0050010BD01F0BBFD20B1022804D00C
-:100B40004FF0FF3010BD012010BD01F0C1F80020B2
-:100B500010BD000010B5EFF3058010B16FF0050077
-:100B600010BD08480168012902D04FF0FF3010BDC8
-:100B7000054A002182F8141D0221016001F064F889
-:100B8000002010BD700100200BE000E070B5EFF315
-:100B9000058010B16FF0050413E001F089FD4FF0FE
-:100BA000FF3510B102280BD108E0012401F0BCFE92
-:100BB000012806D001F07CFD10B102E0002400E025
-:100BC0002C46204670BD0000F8B56FF003021D46AC
-:100BD0006FF002064FF00004EFF30583A3B1F0B10C
-:100BE000E9B1E5B9002200926A4601F087FB0128CD
-:100BF00017D10098B0B10C494FF080500860BFF396
-:100C00004F8FBFF36F8F0DE048B141B12A4601F01D
-:100C1000D7FA012806D025B16FF0010402E014468E
-:100C200000E034462046F8BD04ED00E0F8B5144677
-:100C30004FF00005EFF3058212BB08B301B3A4B176
-:100C4000D4E9023263B1502A1AD32269C2B100FB3F
-:100C500001F66769B74213D3009501F024F907E064
-:100C600072B9226962B9626952B9002201F0FAF8D8
-:100C7000050005D00CB1216800E0002100F0B8FEAD
-:100C80002846F8BDF8B56FF003021D466FF0020666
-:100C90004FF00004EFF30583ABB100B3F9B1F5B940
-:100CA0000022009213466A4601F02AFA012818D160
-:100CB0000098B8B10C494FF080500860BFF34F8FD7
-:100CC000BFF36F8F0EE050B149B100232A4601F007
-:100CD00067F9012806D025B16FF0010402E014463F
-:100CE00000E034462046F8BD04ED00E010B5EFF317
-:100CF000058111B16FF0050404E028B100242146FC
-:100D000001F004F9204610BD6FF00304FAE700007B
-:100D10003EB5040001D0002903DA6FF00300019012
-:100D20002BE04FF0FF300190EFF30580D0B10025AC
-:100D3000029502A82B4601220090204601F030FCCB
-:100D40000022204601AB1146009501F029FC0298D3
-:100D500098B10B494FF080500860BFF34F8FBFF33D
-:100D60006F8F0AE000232046012201F0A9FB002238
-:100D7000204601AB114601F0A3FB01983EBD0000E7
-:100D800004ED00E02DE9F84F894605464FEA0206DA
-:100D9000EFF3058010B16FF005041EE0002D02DABC
-:100DA0006FF0030419E05FEA897002D54FF0000884
-:100DB00000E0A8469246002401F088FCE71E834626
-:100DC000002053466A46414601F0F2FC012807D054
-:100DD00016B36FF001040028F2D12046BDE8F88F69
-:100DE00000982C405FEAC97144EA00040BD035EA50
-:100DF0000400F2D056B101F069FCA0EB0B005045A5
-:100E000006D9002006E02542E7D1F3E73C46E4E7B7
-:100E1000AAEB00008246D3E73C46DCE701F042BC87
-:100E20002DE9FF414FEA01034FF00005EFF3058183
-:100E3000039561BB58B34FF080064FF018014FF097
-:100E400000044AB3176807B13C4697691FB1394699
-:100E50007F1E382F02D21779FF0703D0002004B07D
-:100E6000BDE8F081576907B1BE08D2F808C0BCF1EF
-:100E7000000F0DD0D5685C2D18D312693AB137B187
-:100E80008DE806103246214601F0EFFA03900DE09E
-:100E9000D7685FB912694AB903AACDE90012B2B2A4
-:100EA000214601F0B5FA012800D003950398D6E752
-:100EB00070B50546EFF3058010B16FF005040FE043
-:100EC0004DB12846FFF720FC042807D0002428460F
-:100ED00000F030FE04E06FF0030401E06FF0020464
-:100EE000204670BD2DE9F041134C0F460546E668DB
-:100EF0002068001D00F07DFC681C07D137B1216817
-:100F0000BDE8F0410D48091D00F0C4BC206835441F
-:100F1000B5424560216805D2A06B091DBDE8F041CE
-:100F200000F0A0BC606B091D00F09CFCA06A85422B
-:100F300000D2A562BDE8F08120010020943000209D
-:100F40002DE9F041054600F0B1FC2D4C2D4FA06875
-:100F5000401CA060206810B1606930B32BE02560B0
-:100F6000A068012827D1002606EB860007EB800049
-:100F700000F06AFC761C382EF6D3234800F064FC9F
-:100F80002148143000F060FC1F48283000F05CFC61
-:100F90001D483C3000F058FC1B48503000F054FC19
-:100FA000194860631430A06305E0E86A2168C96AE3
-:100FB000814200D82560606A401C60626864E86A0B
-:100FC0002169884200D9206100EB8000291D07EBD0
-:100FD000800000F05FFC00F089FC606900280CD004
-:100FE0002068E96AC06A884207D208494FF08050F9
-:100FF0000860BFF34F8FBFF36F8FBDE8F081000033
-:1010000020010020E42B00204430002004ED00E00B
-:1010100038B500F04BFC104C2068C8B90F4800F000
-:1010200013FC0E48143000F00FFC0C490020E16066
-:1010300014312161A1F582730090A1F1B402102155
-:101040000A2000F030FF206010B105A100F0D0FCB4
-:10105000BDE8384000F04ABC5C0100209831002017
-:10106000546D72510000000030B4026C0B46002A2F
-:101070000BD0D0E902411144C160A14201D3016803
-:10108000C160184630BCEFF767BB30BC70472DE934
-:10109000F041856B1746026C0446002682B1C7B149
-:1010A000E068EFF759FBE168206C2268091AE160FB
-:1010B000914202D2A168081AE060022F16D017E010
-:1010C0002068A8B9A06801F0B9FB06460020A0601E
-:1010D0000EE06068EFF740FBD4E90101226C104498
-:1010E0006060884204D32068606001E005B16D1E35
-:1010F0006D1CA5633046BDE8F08110B5044690F83C
-:10110000590058B101280CD002280FD0502080F38C
-:101110001188BFF34F8FBFF36F8FFEE7206B00F096
-:10112000F9FB2046BDE8104000F0F4BB10BD000004
-:1011300011484FF4C04110B5420706D00E49C01DFA
-:1011400020F00700411AC1F5C0410C4C00230144B6
-:101150000839A4F1180221F00701C4E900030C1AB0
-:1011600011604B600B60C0E9001494604FF00041C7
-:101170005460516110BD0000783800208C010020BF
-:1011800010B5094CA26812B904F10C02A2601268F1
-:1011900053680A461946EFF7A7FBA0684068A060AD
-:1011A000002800D0012010BDAC010020144E4FF0EB
-:1011B0008058144CDFF85090A6F29C4712E000BF14
-:1011C00000F074FBF068C568281D00F012FBA068F1
-:1011D000401EA0606068401E606000F087FB2846EB
-:1011E000FFF78BFF60680028EAD138680128F9D939
-:1011F000C9F80080BFF34F8FBFF36F8FF2E7000095
-:10120000803000202001002004ED00E070B51D4674
-:10121000049C51B1C4F80020C4E90F01012120460B
-:1012200000F074FE84F84C5070BD2460F4E72DE9A2
-:10123000F05F88469A4691001546DDE90B940A9EB8
-:10124000A5228346206BEFF7FEFA206B6FF00301B7
-:1012500001EB8501084420F00707780707D05020EC
-:1012600080F31188BFF34F8FBFF36F8FFEE7B8F1A4
-:10127000000F4FF000050ED00020221818F80010C3
-:1012800082F8341018F8001011B1401C1028F4D363
-:1012900084F8435001E084F83450382E00D33726C8
-:1012A000E662201DC4E9136500F0D9FA04F11800C4
-:1012B00000F0D5FA6565C6F13800A06184F8585091
-:1012C0005246246159463846646200F05BFAB9F12F
-:1012D000000F206001D0C9F80040BDE8F09F000079
-:1012E00030B5114900E011460A688242FBD34B68D1
-:1012F0005C18844203D14468084623444B60436829
-:101300001D18954209D1084C183C2468A24209D006
-:1013100052681A4442600A6812680260814200D032
-:10132000086030BD0460F9E78C01002070B50D4DF8
-:10133000914241604FF00004006106D88169D21AE1
-:101340008A4206D2011D286907E09A4203D29942D7
-:1013500001D3012403E0011DE86800F083FA204670
-:1013600070BD00005C01002010B5044600F09EFA3C
-:10137000A06B28B15FF0000400F0B8FA204610BD61
-:101380000124F9E730B53C4D89B06BE004980028A2
-:1013900006DA059ADDE9060190470498002861DB2A
-:1013A000069C606910B1201D00F023FA03A800F02C
-:1013B000D5F8024604980A2854D2DFE800F0050563
-:1013C000052D304705052D3094F8280040F0010028
-:1013D00084F82800A06905990B4601442046FFF7D0
-:1013E000A5FF50B3216A2046884794F8280040079B
-:1013F00038D50020009005980023A16942181946AD
-:10140000204601F023FBC0B9502080F31188BFF3C0
-:101410004F8FBFF36F8FFEE794F828001EE094F81B
-:10142000280040F0010084F828000598A06128B148
-:10143000811813462046FFF779FF13E0502080F310
-:101440001188BFF34F8FBFF36F8FFEE794F828002A
-:10145000810703D4204600F05DFA03E020F001008C
-:1014600084F828002868002204A900F0A9FE0028BA
-:101470008CD109B030BD00005C0100202DE9FC4199
-:101480000F46054600F024FC01A800F067F804466A
-:10149000019818B101F048FABDE8FC81254EAFB1C2
-:1014A00030690068D0B300273068291B3A4600F045
-:1014B000B3FA01F039FA0028EED11F494FF08050FD
-:1014C0000860BFF34F8FBFF36F8FE5E7A542EBD8FE
-:1014D00001F02AFAF0682746C068C468201D00F0B1
-:1014E00088F994F82800410719D5A0692B463A4697
-:1014F00041192046FFF71AFFA8B100202A460346EB
-:1015000001460090204601F0A1FA60B9502080F316
-:101510001188BFF34F8FBFF36F8FFEE707E020F016
-:10152000010084F82800216A20468847B4E7012793
-:10153000BAE700005C01002004ED00E00648416BC2
-:10154000096829B1416BC968C968496881627047F7
-:101550004FF0FF31FAE700002001002070B505468A
-:1015600001F0B4F8064E0446B068844203D200F09D
-:1015700009F8012000E0002028602046B46070BD1A
-:101580005C010020F8B5194D20E0C068C468066809
-:10159000201D00F02EF9216A2046884794F8280083
-:1015A000400713D5A0693044B04206D92461211DFB
-:1015B0006060E86800F056F908E000203246034613
-:1015C00001460090204601F041FA38B1E868016810
-:1015D0000029DAD12969C5E90310F8BD502080F34C
-:1015E0001188BFF34F8FBFF36F8FFEE75C010020C0
-:1015F00008484068401C4FF0500080F3118804D028
-:10160000BFF34F8FBFF36F8FFEE7BFF34F8FBFF373
-:101610006F8FFEE794010020074CE068016841B13C
-:10162000C0680021D0F80000FFF728FFFFF7AAFEEE
-:10163000F3E701210020F7E75C0100202DE9F041EC
-:10164000044600F033F994F9455004F1240609E00A
-:10165000606A48B1304601F02FF908B100F0BAFADB
-:101660006D1E6DB2002DF3DC4FF0FF3684F845603F
-:1016700000F03CF900F01AF994F9445004F1100715
-:1016800009E0206948B1384601F016F908B100F0C8
-:10169000A1FA6D1E6DB2002DF3DC84F84460BDE844
-:1016A000F04100F023B900002DE9F0410027044685
-:1016B00000F00EFB324E306808B9FFF739FD706953
-:1016C00004424ED1C4B3083460070ED004F00700C2
-:1016D000C0F108000444600707D0502080F311884F
-:1016E000BFF34F8FBFF36F8FFEE72CB37068844258
-:1016F00037D82348183001460D6801E028460D46CA
-:101700006968A14202D229680029F7D131688D4267
-:1017100027D007682968016008376868011B10290D
-:101720000FD92819420708D0502080F31188BFF341
-:101730004F8FBFF36F8FFEE713E041606C60FFF7E0
-:10174000CFFD69687068401A7060B268904200D23C
-:10175000B060002072691143C5E90001F068401CC7
-:10176000F06001F0E1F8780707D0502080F311888D
-:10177000BFF34F8FBFF36F8FFEE73846BDE8F081B0
-:101780007401002070B5041F094E231F4FF08075AF
-:1017900021F0010125601C1F1960A0F120010B1F21
-:1017A000266044380A606FF002051D6070BD0000BD
-:1017B000F115010810B500EE100A2DED028BB1EE07
-:1017C000C08A18EE100A20F00040C0F1FF40C00FA0
-:1017D0000AD010EE100A20F00040C0F1FF40C00F08
-:1017E00004BF0120EFF7B3F818EE100ABDEC028B2E
-:1017F00010BDD0E9013201699A60D0E901235A6035
-:101800004A68824201D182684A6000220261086807
-:10181000401E08600868704710B5044C80230460BF
-:1018200004F15C000860136010BD0000C0310020AE
-:1018300010B5044C4FF48073046004F15C00086040
-:10184000136010BD1C3400204FF0FF3300F108017D
-:101850000022C0E901130260C160016170470021EC
-:101860000161704730B50B685A1C02D000F10802C4
-:1018700002E0026904E02246546825689D42FAD9D4
-:1018800053684B6099608A60516008610168491C27
-:10189000016030BD42684A6093688B60936859600C
-:1018A000916008610168491C01607047502080F315
-:1018B0001188BFF34F8FBFF36F8F0A494868401CF0
-:1018C000486001280CD10848006810F0FF0F07D0CD
-:1018D000502080F31188BFF34F8FBFF36F8FFEE767
-:1018E000704700009401002004ED00E008494868BA
-:1018F00028B1401E486001D180F311887047502004
-:1019000080F31188BFF34F8FBFF36F8FFEE70000A6
-:101910009401002070B500282AD0164DA0F10804CB
-:1019200061686869014207D1502080F31188BFF3D4
-:101930004F8FBFF36F8FFEE722683AB1502080F3DC
-:101940001188BFF34F8FBFF36F8FFEE78143616054
-:1019500000F0BEF960686968084468602046FFF7D7
-:10196000BFFC2869401C2861BDE8704000F0DCBF66
-:1019700070BD0000740100204FF0E02000210161E3
-:101980004FF47A728161072303490968B1FBF2F1D0
-:10199000491E4161036170478800002010B5EEF7D1
-:1019A000B7FD114910280ED300F1E0200A7890F815
-:1019B000F003904207D2502080F31188BFF34F8F7D
-:1019C000BFF36F8FFEE709488968006800F4E060A4
-:1019D000884207D9502080F31188BFF34F8FBFF39F
-:1019E0006F8FFEE710BD0000940100200CED00E0B9
-:1019F000084B5FF0000210B553F832401CB1521C86
-:101A0000082AF9D310BD03EBC20443F8321060601A
-:101A100010BD0000A42B002070B515460E460446EC
-:101A2000FFF744FF94F944100020491C01D184F8C9
-:101A3000440094F94510491C01D184F84500FFF792
-:101A400055FFA06B28B904F124002A46314600F066
-:101A5000DFF82046BDE87040FFF7F0BD020010B58A
-:101A600014D00F48006B38B1502080F31188BFF3B9
-:101A70004F8FBFF36F8FFEE700F02AF90021104669
-:101A8000FFF730FA00F050FF002807D105494FF06A
-:101A900080500860BFF34F8FBFF36F8F10BD000001
-:101AA0002001002004ED00E070B504000D460BD0CD
-:101AB00095B11E4A106BB8B1502080F31188BFF366
-:101AC0004F8FBFF36F8FFEE7502080F31188BFF375
-:101AD0004F8FBFF36F8FFEE7502080F31188BFF365
-:101AE0004F8FBFF36F8FFEE700F0F2F82368D268E4
-:101AF0005919934204D98B420AD9914202D807E07E
-:101B00008B42FAD9881A21600021FFF7EBF900E037
-:101B1000216000F009FF002807D105494FF08050EF
-:101B20000860BFF34F8FBFF36F8F70BD200100209F
-:101B300004ED00E070B50546FFF7B8FE1E4C05B990
-:101B40002568281DFFF755FEA86A18B105F1180091
-:101B5000FFF74FFE606A401C60622068854207D133
-:101B60001648291DFFF796FE6068401C606007E07C
-:101B7000A068401EA0602846FFF7BFFAFFF7DEFC12
-:101B8000FFF7B4FE6069002814D02068854211D1A7
-:101B9000206B38B1502080F31188BFF34F8FBFF313
-:101BA0006F8FFEE706494FF080500860BFF34F8FFC
-:101BB000BFF36F8F70BD0000200100208030002037
-:101BC00004ED00E002490A6A0260C968416070479A
-:101BD0002001002001490120C86170472001002038
-:101BE00010B50C4650B1094909681831FFF73AFEA3
-:101BF0002046BDE810400121FFF774B9502080F362
-:101C00001188BFF34F8FBFF36F8FFEE720010020D5
-:101C100070B514460D4668B10A4909681831FFF7D6
-:101C200039FE0CB14FF0FF3521462846BDE8704023
-:101C3000FFF758B9502080F31188BFF34F8FBFF3DF
-:101C40006F8FFEE72001002030B587B0002405AA81
-:101C500004A9039403A80494FFF7DEFDDDE9030162
-:101C600000940023CDE90110174815A1059A00F052
-:101C7000FCFB164D0028E8621FD000F0B7FE0128DB
-:101C800009D0401C19D1502080F31188BFF34F8F29
-:101C9000BFF36F8FFEE7502080F31188BFF34F8FA3
-:101CA000BFF36F8F01214FF0FF30A8626961EC60D4
-:101CB00007B0BDE8304000F045B807B030BD0000C7
-:101CC00049444C4500000000AD11010820010020EE
-:101CD0000248016B491C016370470000200100208D
-:101CE000164810B5016B11B10121C16110BD002171
-:101CF000C161134A016901E0B9B1491E01EB8103D9
-:101D000052F82330002BF7D001EB810302EB830262
-:101D100002F1080453685B685360A34201D15B6819
-:101D20005360DA680260016110BD502080F31188B1
-:101D3000BFF34F8FBFF36F8FFEE70000200100203D
-:101D4000E42B002037481CB5374902688A4207D186
-:101D5000502080F31188BFF34F8FBFF36F8FFEE7E2
-:101D600031490068491E884207D1502080F311880C
-:101D7000BFF34F8FBFF36F8FFEE72C49FF200A7828
-:101D80000192087008788DF800009DF800209DF8F9
-:101D9000000002F0F002824207D0502080F3118848
-:101DA000BFF34F8FBFF36F8FFEE79DF80020072032
-:101DB0001F4C02F050022270A06005E09DF8002048
-:101DC00052008DF80020401E9DF800201206F5D428
-:101DD0000328A06007D0502080F31188BFF34F8FF5
-:101DE000BFF36F8FFEE74FF44070A060019808705A
-:101DF0000C482030016841F470010160016841F035
-:101E000070410160FFF7B8FD00206060EEF748FB0D
-:101E10000848016841F040410160EEF72DFB0020C9
-:101E20001CBD000000ED00E071C20F4100E400E0C5
-:101E30009401002034EF00E0502010B580F31188A9
-:101E4000BFF34F8FBFF36F8F00F04EFC18B1044902
-:101E50004FF080500860002080F3118810BD000012
-:101E600004ED00E0F8B5050017460E4613D005FB5B
-:101E700006F05030FFF718FC04000AD0002084F868
-:101E8000460004F150023B46314628460094FFF7D5
-:101E9000BDF92046F8BD502080F31188BFF34F8F65
-:101EA000BFF36F8FFEE7F8B5069D18B153B1CAB105
-:101EB00081B120E0502080F31188BFF34F8FBFF332
-:101EC0006F8FFEE7502080F31188BFF34F8FBFF371
-:101ED0006F8FFEE7502080F31188BFF34F8FBFF361
-:101EE0006F8FFEE739B1502080F31188BFF34F8F19
-:101EF000BFF36F8FFEE750241C46012683F846602F
-:101F000000932B46FFF782F92046F8BD2DE9F047F4
-:101F100004008A4629D0FFF7C9FC21680025D4E9CE
-:101F20000F23D4F840C004F1100810460E46401E9E
-:101F30004FF0FF3902FB031200FB0C10BAF1000F47
-:101F4000A563666084F8449084F84590C4E9022053
-:101F500013D04046FFF778FC04F12400FFF774FC2F
-:101F6000FFF7C4FC0120BDE8F087502080F3118802
-:101F7000BFF34F8FBFF36F8FFEE720690028EFD0CC
-:101F8000404600F099FC0028EAD004494FF0805008
-:101F90000860BFF34F8FBFF36F8FE1E704ED00E000
-:101FA0002DE9FF4704001D4682B08A464FF0000825
-:101FB00003D0BAF1000F08D011E0502080F311884F
-:101FC000BFF34F8FBFF36F8FFEE7206C38B1502007
-:101FD00080F31188BFF34F8FBFF36F8FFEE7022DA1
-:101FE0000AD1E06B012807D0502080F31188BFF39D
-:101FF0004F8FBFF36F8FFEE700F05AFB3F4F4FF05C
-:1020000080564FF0000948B9049838B1502080F349
-:102010001188BFF34F8FBFF36F8FFEE7FFF746FCCA
-:10202000A06BE16B884207D3022D05D00498D0B194
-:10203000B8F1000F1AD01EE02A4651462046FFF79D
-:1020400026F8616A19B104F1240000F035FC20B1D2
-:102050003E60BFF34F8FBFF36F8FFFF747FC012048
-:1020600006B0BDE8F087FFF741FC22E06846FFF7C5
-:10207000A9FD4FF00108FFF739FCFFF729FEFFF734
-:1020800015FC94F94400401C01D184F8449094F963
-:102090004500401C01D184F84590FFF727FC04A9B6
-:1020A000684600F079F930B12046FFF7C7FA00F032
-:1020B0003BFC0020D4E7FFF7F9FBA06BE16B884203
-:1020C00013D1FFF713FC049904F11000FFF788FD0A
-:1020D0002046FFF7B3FA00F027FC00289ED13E60AF
-:1020E000BFF34F8FBFF36F8F98E7FFF7FFFB2046DB
-:1020F000FFF7A4FA00F018FC90E7000004ED00E000
-:102100002DE9F04704001F469046894603D0B9F1F7
-:10211000000F08D011E0502080F31188BFF34F8FDB
-:10212000BFF36F8FFEE7206C38B1502080F3118829
-:10213000BFF34F8FBFF36F8FFEE7022F0AD1E06B23
-:10214000012807D0502080F31188BFF34F8FBFF3D1
-:102150006F8FFEE7FFF722FC5020EFF3118680F32C
-:102160001188BFF34F8FBFF36F8FA06BE16B884275
-:1021700006D3022F04D0002086F31188BDE8F08733
-:1021800094F94550A06B3A4649462046FEF77FFF3A
-:10219000681C04D06D1C84F845500120ECE7606A8F
-:1021A0000028FAD004F1240000F086FB0028F4D0C7
-:1021B000B8F1000FF1D00121C8F80010EDE70000E0
-:1021C0002DE9F74704008A4683B04FF0000603D09C
-:1021D000BAF1000F08D011E0502080F31188BFF34E
-:1021E0004F8FBFF36F8FFEE7206C38B1502080F324
-:1021F0001188BFF34F8FBFF36F8FFEE700F058FADF
-:10220000DFF8F4804FF080574FF0000948B9059887
-:1022100038B1502080F31188BFF34F8FBFF36F8F19
-:10222000FEE7FFF743FBA56BC5B151462046FEF71D
-:102230001BFF6D1EA563206950B104F1100000F072
-:102240003BFB28B1C8F80070BFF34F8FBFF36F8F0F
-:10225000FFF74CFB012006B0BDE8F087059808B1F8
-:102260001EB106E0FFF742FB27E06846FFF7AAFC35
-:102270000126FFF73BFBFFF72BFDFFF717FB94F958
-:102280004400401C01D184F8449094F94500401C5E
-:1022900001D184F84590FFF729FB05A9684600F0B5
-:1022A0007BF8002820460AD0FFF7C8F900F03CFB75
-:1022B0002046FFF759F80028B3D00020CBE7FFF7FE
-:1022C00053F890B1059904F12400FFF789FC2046EA
-:1022D000FFF7B4F900F028FB0028A2D1C8F800707D
-:1022E000BFF34F8FBFF36F8F9BE72046FFF7A6F931
-:1022F00000F01AFB95E7000004ED00E02DE9F0473F
-:1023000004009046894603D0B9F1000F08D011E0CF
+:100000001E67383D1B93993DAFAA2A3E00000000B1
+:1000100070B565482DED020B2DED048B059D25F087
+:100020000044A04218DC6148844202DC0AD10498F2
+:1000300040B19DED040BBDEC048B02B0BDE87040F7
+:1000400000F0EBBC002DCCBF9FED590B9FED5A0B80
+:10005000BDEC048B02B070BD5948A04215DD594873
+:10006000A042D8BF4FF0FF3455DD9DED040B51EC9D
+:10007000100BFFF760FE042808BF00F0D5FC9DEDD3
+:10008000040BBDEC048B02B070BD9DED040B51EC74
+:10009000100B00F059FECDE904014B489FED4C0BCD
+:1000A000A0421CDD4C48A0420BDD9DED042B00243A
+:1000B0009FED4B1B12EE010B32EE011B80EE012B6C
+:1000C00027E09DED041B9DED042B012431EE401B28
+:1000D00032EE000B81EE002B8DED042B1BE042482D
+:1000E000A0420FDD9DED042B02249FED411B9DEDF1
+:1000F000043B32EE412B03EE010B82EE001B8DED33
+:10010000041B08E09DED040B9FED3B1B032481EED7
+:10011000002B8DED042B9DED040B3948062120EEBC
+:10012000009B29EE098BB0EE480B784400F03DFCB3
+:1001300020EE099B3348B0EE480B0521784400F0CF
+:1001400034FC20EE080B002C0BDA9DED042B39EE6D
+:10015000001B9DED040BBDEC048B02B002EE410BC5
+:1001600070BD2948784439EE000B00EBC4009DEDCA
+:10017000042B90ED001B254812EE001B9DED040B97
+:1001800031EE400B784400EBC400002D90ED001BD5
+:1001900031EE400BB8BFB1EE400BBDEC048B02B0AA
+:1001A00070BD000000000000000010440000F07F5F
+:1001B000182D4454FB21F93F182D4454FB21F9BF5D
+:1001C0000000DC3F0000203E0000F33F0000000084
+:1001D000000000000000F03F0000E63F00000000CB
+:1001E000000000000000004000800340000000000C
+:1001F000000000000000F83F000000000000F0BF19
+:10020000823500004835000000350000C034000091
+:1002100070B5614E2DED040B2DED048B82B0DDF831
+:1002200024C0DDE907235C422CF000411C4341EA75
+:10023000D474069D22F00040B44205D86C422C4391
+:1002400040EAD474B4420BD99DED081B9DED060B1A
+:1002500002B0BDEC048B04B0BDE8704000F0E0BB20
+:10026000ACF14054A4F17F641C430BD0022404EA97
+:10027000AC7444EAD27405439FED498B9FED4A2B41
+:100280000DD016E09DED060B51EC100B00F09FFC1D
+:1002900041EC100B02B0BDEC048B04B070BD002C1F
+:1002A00014BF012C9DED060BF4D0022C2ED0032C94
+:1002B0002FD00B439FED3E1B9FED3F0B0AD0B14269
+:1002C0001DD1B04209D121F0804120F08040099138
+:1002D000079014E0002ADDDA15E0394B7B44002C4E
+:1002E00008BF93ED000BD5D0012C04BF93ED000B9C
+:1002F000B1EE400BCED0022C08D0032C09D0B04276
+:100300000AD1002AC6DAB0EE410BC3E7B0EE480BC3
+:10031000C0E7B0EE420BBDE7401A00159FED2A9BE7
+:100320003C28C8BF8DED000B15DCBCF1000FBCBF35
+:1003300010F13C0F8DED009B0DDB9DED061B9DED3F
+:10034000082B81EE020B51EC100B00F0FDFC00F0CD
+:100350003EFCCDE9000194B1012C0CD09DED001BB9
+:100360009FED1B0B022C31EE400B0CBF38EE400B07
+:1003700030EE480B8EE7019880F0004001909DED33
+:10038000000BB4EE490BF1EE10FA04BF0220F0F7B7
+:10039000DEFA9DED000B7DE70000F07F000000001D
+:1003A000182D4454FB210940182D4454FB2109C049
+:1003B000182D4454FB21F9BF182D4454FB21F93F5B
+:1003C00000340000000000000000000000000000F9
+:1003D000075C143326A6A13C70B54FF068422DEDA2
+:1003E000048BF0EE408A18EE900AB0EE608A18EEA8
+:1003F000101A02EB4003B3F1654F3CBF02EB410220
+:10040000B2F1654F7DD200BFC0F3C753C1F3C752ED
+:100410009A1A1B2A09DD10F0004F14BF9FED830AC2
+:100420009FED830ABDEC048B70BD12F11A0F36DA12
+:1004300011F0004F09D010F0004F0CBF9FED7D0A66
+:100440009FED7D0ABDEC048B70BD88EE889A19EE95
+:10045000100AFFF788FC042808BF00F0FFFA18EE26
+:10046000900AFFF780FC054618EE100AFFF77BFCA8
+:10047000044619EE100AFFF776FC042D18BF052D6F
+:1004800008D1042C18BF052C04D1002804BF022079
+:10049000F0F75DFAB0EE490ABDEC048B70BD420086
+:1004A000B2EB410F3AD910F0004F19BFDFED630AEC
+:1004B0009FED630ADFED630A9FED630AB0EE481A11
+:1004C0000A46B1EE688A80F00041F0EE418A10469B
+:1004D0000A1A5200B2F1807F34D2484010F0004F27
+:1004E000DFED5A1A9FED5A2A1DBF9FED5A1A70EE82
+:1004F000E10A30EE420A9FED581A08BF70EEA10AD9
+:1005000000E040E008BF30EE020AB0EE682A01EEDB
+:10051000482A08EE818AC2EE081A15E011F0004F51
+:1005200004BF9FED4E0AF0EE400AD1D010F0004F0C
+:1005300019BFDFED4B0A9FED4B0ADFED4B0A9FED34
+:100540004B0AC5E7C8EE881A21EEA11A9FED482A8A
+:10055000DFED482A41EE022A9FED472A01EE222ACA
+:10056000DFED462A41EE022A9FED452ABDEC048BC1
+:1005700001EE222A21EE811A01EE020A30EE210A52
+:1005800030EE200A70BD4FF07F42B2EB400F28BF23
+:10059000B2EB410F09D2F0EE480AB0EE680ABDECAA
+:1005A000048BBDE8704000F04EBA40EA01035B00E6
+:1005B00008BF41F0FF410BD0B2EB400F08BFB2EBD8
+:1005C000410F08D120F0804008EE900A21F08041D0
+:1005D00008EE101A18E7B2EB400F12BF5FEA4103B2
+:1005E00040F0FF4001F000413FF40EAFB2EB410F8D
+:1005F00012BF5FEA400200F0004041F0FF413FF4CB
+:1006000003AF4A0092EA40033FF5FEAE002AACBFBA
+:100610009FED1C0A9FED1C0A68EE808A28EE008A76
+:1006200018EE900A18EE101AEEE60000DB0FC9BFB4
+:10063000DB0FC93FDB0F4940DB0F49C00000C9BFDA
+:1006400022AAFDB90000C93F22AAFD390060ED3E93
+:10065000C30ACE37000000BF0000003F00000000CA
+:10066000000049C022AA7DBA0000494022AA7D3A72
+:100670002DAD65BD8FB8D53D0FB511BE61C84C3EDF
+:10068000A8AAAABE0000804F0000802F10EE101A0A
+:1006900008B5434A6846B2EB410F26D94FF0E64011
+:1006A000B0EB410F94BF00204FF0FF300090009856
+:1006B000DFED3C0A002860DB10F0010F46D060EE51
+:1006C000000ADFED391A9FED391A10F0020F00EE23
+:1006D000E11ADFED371A40EE811A21EEA01AF0EE92
+:1006E000400A40EE010A2ED041E0324B21F0004298
+:1006F00093423FD911F0004FDFED2F0A20EE201A70
+:10070000DFED2E0A19BF31EE601A71EE200A31EECC
+:10071000201A71EE600ABDEEE01A11EE100A9FED8C
+:10072000281A00F0030000EEC10A9FED261A00907F
+:1007300000EEC10A9FED241A00EEC10A9FED231AB4
+:1007400000EEC10AB3E7F1EE600A10E020EE000A05
+:100750009FED1F1ADFED1F1A10F0020F40EE011A75
+:100760009FED1D1A00EE211A40EE010AEBD1B0EE0A
+:10077000600A08BD00F07AF999E710EE100A40000F
+:10078000B0F17F4FF3D307D14FF00100F0F7DFF85E
+:10079000BDE8084000F05AB9BDE8084000F050B983
+:1007A000B61F927E0000803F336D4C39DA82083CE0
+:1007B000A0AA2ABE490E494683F9223F0000004BF9
+:1007C0000000C93F00A0FD390020A2331A61342C7B
+:1007D000B93AB2BACA9F2A3DDDFFFFBE00B510EE9E
+:1007E000101A2DED028B81B0524A6846B2EB410FD0
+:1007F0002ED94FF0E640B0EB410F94BF00204FF0F0
+:10080000FF3000900098B0EE408A00286ADB10F0BC
+:10081000010F4BD068EE080A9FED471A9FED470A7B
+:1008200000EE810A9FED461A00EE801A9FED450A00
+:1008300010F0020F00EE810A02BF01B0BDEC028B86
+:1008400000BD00BF01B0B1EE400ABDEC028B00BD9F
+:100850003D4B21F00042934241D911F0004FDFEDB2
+:100860003B0A20EE201ADFED3A0A19BF31EE601A7A
+:1008700071EE200A31EE201A71EE600ABDEEE01A28
+:1008800011EE100A9FED331A00F0030000EEC10ACA
+:100890009FED311A009000EEC10A9FED301A00EE74
+:1008A000C10A9FED2F1A00EEC10AABE728EE080A35
+:1008B0009FED2C1ADFED2C0A10F0020F40EE410ADA
+:1008C0009FED2A1A00EE201A61EE000AB0EE480AE7
+:1008D00008EE200AB6D101B0BDEC028B00BD00F0DD
+:1008E000C5F88FE718EE100A4000B0F17F4F0DD227
+:1008F00018EE100AFFF737FA042808BF00F0AEF828
+:10090000B0EE480A01B0BDEC028B00BD09D1012058
+:10091000F0F71DF801B0BDEC028B5DF804EB00F0C0
+:1009200095B801B0B0EE480ABDEC028B5DF804EB5F
+:1009300000F086B8B61F927EB93AB2BACA9F2A3D75
+:10094000DDFFFFBE0000803F490E494683F9223F8C
+:100950000000004B0000C93F00A0FD390020A23379
+:100960001A61342C336D4C39DA82083CA0AA2ABEB5
+:1009700010B52DED028BB1EEC08A18EE100A20F0F2
+:100980000040C0F1FF40C00F0AD010EE100A20F066
+:100990000040C0F1FF40C00F04BF0120EFF7D7FFB8
+:1009A000B0EE480ABDEC028B10BD491E00EBC1023F
+:1009B000B0EE401B92ED000B31F006020DD0491E47
+:1009C00000EBC102B0EE403B92ED002B31F006028D
+:1009D000B0EE420B03EE010BF1D1022914D0042931
+:1009E0000AD0062918BF704790ED0A2B00EE012BA4
+:1009F00090ED080B02EE010B90ED062B00EE012BA3
+:100A000090ED040B02EE010B90ED022B00EE012B9A
+:100A100090ED000B02EE010B704730EE000B7047BB
+:100A200030EE010B704700009FED030B20EE000B32
+:100A300070470000000000000000000000000010EF
+:100A400030EE000A704730EE200A7047DFED020AF0
+:100A500080EEA00A70470000000000009FED020A2F
+:100A600020EE000A70470000000000102DE9F001A0
+:100A70004FF07F42B2EB410F9FBF4FF0FF3101605B
+:100A8000BDE8F00170474FF0004242EA0123C1F394
+:100A9000C752783A551112F01F0C434CCCF1200686
+:100AA0007C44C1F3C752A2F178024FEA621204EB10
+:100AB000820254F8254008BFD2E9015612D0556889
+:100AC00004FA0CF425FA06F73C43976805FA0CF58E
+:100AD00027FA06F8D26807FA0CFCF24045EA080546
+:100AE0004CEA0206A4FB034CA5FB0352A6FB0363DE
+:100AF0001D449D4234BF012600261319334416B10C
+:100B0000934202D903E0934201D2012200E0002285
+:100B1000624402F1200C9206DC0C42EA443200EE00
+:100B2000102A5B03DFED210AF8EEC01A00EE103A3E
+:100B30004FEA9C1C11F0004FB8EE400AC0F800C00C
+:100B400020EE201A00EE105ADFED190AB8EE400A26
+:100B500020EE200A71EE810A70EE800A10EE902AD3
+:100B600002F500626FF30B0200EE902A70EEE11ABC
+:100B700031EEC11ADFED101A30EE411A9FED0D0A69
+:100B800020EE800A01EE210A9FED0C1A00EE810A88
+:100B900004BFBDE8F0017047CCF180510160BDE8B1
+:100BA000F001B1EE400A7047442C0000000000360E
+:100BB0000000802C22AAFD29DB0FC92F0000C92FBD
+:100BC00030380A2801D2012070470020704710B544
+:100BD00041EC100BFFF71CFA51EC100B10BD10B5D7
+:100BE00014460B4603E013F8011B00F003F8641EE3
+:100BF000F9D210BD034A4140C9B232F8111081EA5E
+:100C000010207047003401082DE9F041040006D09F
+:100C1000184E306884420AD10020BDE8F08150208F
+:100C200080F31188BFF34F8FBFF36F8FFEE701F0A2
+:100C30001DF9776B6569B66B01F038F9BD4201D0DB
+:100C4000B54201D10220E8E70B48854208D1A06AED
+:100C50000028F7D194F858000128F3D00320DCE7EE
+:100C600005481438854202D00DB10120D5E7042093
+:100C7000D3E70000200100207832002070B5044640
+:100C800090F82C000025FD2803D194F82D00EE28C3
+:100C900001D0A06A0EE00E22002004F12C01FFF723
+:100CA0009EFF618F2084814208D0A06AE56225639F
+:100CB0006563A563401CA561A06270BD94F83820EF
+:100CC00094F82E0002F0070694F93750218F00F0B7
+:100CD0000F03C0F30210C4E901562370C1F3CB0126
+:100CE00060700122B4F931009FED140A01EE100A80
+:100CF000DFED130ADFED131AB8EEC11A21EE001A68
+:100D000021EE201A84ED041AB4F92F0001EE100A26
+:100D1000B8EEC11A21EE000A84ED030AD4F83300BC
+:100D2000C4E9062100EE100AB8EEC00A20EE200A3F
+:100D300020EE210A84ED050A70BD00000000803B12
+:100D4000D00FC9400000003882B0CDE9000121F089
+:100D5000004001909DED000B02B051EC100B70476C
+:100D600000207047F5F7B8FEFCF73EF8FBF724F8D3
+:100D7000FAF7F8FEFAF79CFEFBF78CF9FBF726F979
+:100D8000FBF754F9FBF762FAFBF738FBFBF76AFB5A
+:100D9000FBF79EFBFBF7CAFAFBF7FCFAFAF758FFE2
+:100DA000FAF788FFFAF7BAFFFBF7AEF9FBF70CFA90
+:100DB000FBF7D2F8FBF784FA00F024F9FAF7E2FF28
+:100DC00000F048F9FEE7000010B504460188FE2057
+:100DD000EE22207600206276C1B10F2901D30F21C7
+:100DE0002180618811B1072901D30720608094ED2B
+:100DF000040ADFED510A51489FED511AB5EEC00AC1
+:100E0000F1EE10FA04D8C4ED040A07E02080E8E708
+:100E100010EE101A814201DB84ED041A94ED050AEC
+:100E2000B5EEC00AF1EE10FA02D8C4ED050A05E0ED
+:100E300010EE101A814201DB84ED051A4149606809
+:100E4000884202D39FED400A04E04049884203DB18
+:100E50009FED3F0A84ED010A3E49A068884202D313
+:100E60009FED3D0A04E03D49884203DB9FED3C0ACB
+:100E700084ED020A3B49E068884202D39FED3A0ABA
+:100E800004E03A49884203DB9FED390A84ED030A06
+:100E9000D4ED042ADFED370A9FED370A2278C2EE3F
+:100EA000A01AA07EA1789FED351A62F303009FED92
+:100EB000342A61F30610A0760F2261EE801AFDEE4F
+:100EC000E11A11EE901AA4F8231004F11801D4EDE0
+:100ED000051AC1EEA02A62EE800AFDEEE00A10EECD
+:100EE000900AA4F82500D4ED030AC0EE811A21EE81
+:100EF000800ABDEEC00A10EE100AC4F81F0094ED7F
+:100F0000020AC0EE010A20EE820ABDEEC00A10EE0F
+:100F1000100AA4F81D0094ED010A20EE020ABDEEAD
+:100F2000C00A10EE100AA4F81B000020FFF757FEBD
+:100F3000A4F8270010BD000000000000C1CACC4189
+:100F4000C1CACC41E1FAFFC2E1FAFFC2E1FAFF42B5
+:100F5000E1FAFF42000049C4000049C400004944CE
+:100F600000004944C00FC9C8C00FC9C8C00FC94854
+:100F7000C00FC948CDCCCC4100000047D00FC940BC
+:100F80000000804310B5EFF3058111B16FF0050447
+:100F900004E04FF0000408B101F040F8204610BD15
+:100FA00038B50546EFF3058010B16FF005040CE08D
+:100FB000002401F06BFE291A0090002903DD684629
+:100FC00001F052F801E06FF00304204638BD000044
+:100FD00010B501F04DFE38B1022804D00348006876
+:100FE000012800D0002010BD032010BD700100209A
+:100FF000EFF3058008B101F04FBE01F047BE4FF49A
+:101000007A707047EFF3058010B16FF005007047FC
+:101010000449086810B14FF0FF30704701220A60A0
+:10102000002070477001002010B5EFF3058010B16B
+:101030006FF0050010BD01F01BFE20B1022804D0A6
+:101040004FF0FF3010BD012010BD01F021F900204C
+:1010500010BD000010B5EFF3058010B16FF0050072
+:1010600010BD08480168012902D04FF0FF3010BDC3
+:10107000054A002182F8141D0221016001F0C4F824
+:10108000002010BD700100200BE000E070B5EFF310
+:10109000058010B16FF0050413E001F0E9FD4FF099
+:1010A000FF3510B102280BD108E0012401F01CFF2C
+:1010B000012806D001F0DCFD10B102E0002400E0C0
+:1010C0002C46204670BD0000F8B56FF003021D46A7
+:1010D0006FF002064FF00004EFF30583A3B1F0B107
+:1010E000E9B1E5B9002200926A4601F0E7FB012868
+:1010F00017D10098B0B10C494FF080500860BFF391
+:101100004F8FBFF36F8F0DE048B141B12A4601F018
+:1011100037FB012806D025B16FF0010402E0144628
+:1011200000E034462046F8BD04ED00E0F8B5144672
+:101130004FF00005EFF3058212BB08B301B3A4B171
+:10114000D4E9023263B1502A1AD32269C2B100FB3A
+:1011500001F66769B74213D3009501F084F907E0FF
+:1011600072B9226962B9626952B9002201F05AF972
+:10117000050005D00CB1216800E0002100F018FF47
+:101180002846F8BDF8B56FF003021D466FF0020661
+:101190004FF00004EFF30583ABB100B3F9B1F5B93B
+:1011A0000022009213466A4601F08AFA012818D1FB
+:1011B0000098B8B10C494FF080500860BFF34F8FD2
+:1011C000BFF36F8F0EE050B149B100232A4601F002
+:1011D000C7F9012806D025B16FF0010402E01446DA
+:1011E00000E034462046F8BD04ED00E010B5EFF312
+:1011F000058111B16FF0050404E028B100242146F7
+:1012000001F064F9204610BD6FF00304FAE7000016
+:101210003EB5040001D0002903DA6FF0030001900D
+:101220002BE04FF0FF300190EFF30580D0B10025A7
+:10123000029502A82B4601220090204601F090FC66
+:101240000022204601AB1146009501F089FC02986E
+:1012500098B10B494FF080500860BFF34F8FBFF338
+:101260006F8F0AE000232046012201F009FC0022D2
+:10127000204601AB114601F003FC01983EBD000081
+:1012800004ED00E02DE9F84F894605464FEA0206D5
+:10129000EFF3058010B16FF005041EE0002D02DAB7
+:1012A0006FF0030419E05FEA897002D54FF000087F
+:1012B00000E0A8469246002401F0E8FCE71E8346C1
+:1012C000002053466A46414601F052FD012807D0EE
+:1012D00016B36FF001040028F2D12046BDE8F88F64
+:1012E00000982C405FEAC97144EA00040BD035EA4B
+:1012F0000400F2D056B101F0C9FCA0EB0B00504540
+:1013000006D9002006E02542E7D1F3E73C46E4E7B2
+:10131000AAEB00008246D3E73C46DCE701F0A2BC22
+:101320002DE9FF414FEA01034FF00005EFF305817E
+:10133000039561BB58B34FF080064FF018014FF092
+:1013400000044AB3176807B13C4697691FB1394694
+:101350007F1E382F02D21779FF0703D0002004B078
+:10136000BDE8F081576907B1BE08D2F808C0BCF1EA
+:10137000000F0DD0D5685C2D18D312693AB137B182
+:101380008DE806103246214601F04FFB03900DE038
+:10139000D7685FB912694AB903AACDE90012B2B29F
+:1013A000214601F015FB012800D003950398D6E7EC
+:1013B00070B50546EFF3058010B16FF005040FE03E
+:1013C0004DB12846FFF720FC042807D0002428460A
+:1013D00000F090FE04E06FF0030401E06FF00204FF
+:1013E000204670BD2DE9F041134C0F460546E668D6
+:1013F0002068001D00F0DDFC681C07D137B12168B2
+:10140000BDE8F0410D48091D00F024BD20683544B9
+:10141000B5424560216805D2A06B091DBDE8F041C9
+:1014200000F000BD606B091D00F0FCFCA06A854265
+:1014300000D2A562BDE8F0812001002078320020B2
+:101440002DE9F041054600F011FD2D4C2D4FA0680F
+:10145000401CA060206810B1606930B32BE02560AB
+:10146000A068012827D1002606EB860007EB800044
+:1014700000F0CAFC761C382EF6D3234800F0C4FCDA
+:101480002148143000F0C0FC1F48283000F0BCFC9C
+:101490001D483C3000F0B8FC1B48503000F0B4FC54
+:1014A000194860631430A06305E0E86A2168C96ADE
+:1014B000814200D82560606A401C60626864E86A06
+:1014C0002169884200D9206100EB8000291D07EBCB
+:1014D000800000F0BFFC00F0E9FC606900280CD03F
+:1014E0002068E96AC06A884207D208494FF08050F4
+:1014F0000860BFF34F8FBFF36F8FBDE8F08100002E
+:1015000020010020C82D00202832002004ED00E03A
+:1015100038B500F0ABFC104C2068C8B90F4800F09B
+:1015200073FC0E48143000F06FFC0C490020E160A1
+:1015300014312161A1F582730090A1F1B402102150
+:101540000A2000F090FF206010B105A100F030FDEE
+:10155000BDE8384000F0AABC5C0100207C330020CC
+:10156000546D72510000000030B4026C0B46002A2A
+:101570000BD0D0E902411144C160A14201D30168FE
+:10158000C160184630BCEFF7E7B830BC70472DE9B2
+:10159000F041856B1746026C0446002682B1C7B144
+:1015A000E068EFF7D9F8E168206C2268091AE16079
+:1015B000914202D2A168081AE060022F16D017E00B
+:1015C0002068A8B9A06801F019FC06460020A060B8
+:1015D0000EE06068EFF7C0F8D4E90101226C104416
+:1015E0006060884204D32068606001E005B16D1E30
+:1015F0006D1CA5633046BDE8F08110B5044690F837
+:10160000590058B101280CD002280FD0502080F387
+:101610001188BFF34F8FBFF36F8FFEE7206B00F091
+:1016200059FC2046BDE8104000F054BC10BD00003D
+:1016300011484FF4C04110B5420706D00E49C01DF5
+:1016400020F00700411AC1F5C0410C4C00230144B1
+:101650000839A4F1180221F00701C4E900030C1AAB
+:1016600011604B600B60C0E9001494604FF00041C2
+:101670005460516110BD00005C3A00208C010020D4
+:1016800010B5094CA26812B904F10C02A2601268EC
+:1016900053680A461946EFF727F9A0684068A0602A
+:1016A000002800D0012010BDAC010020144E4FF0E6
+:1016B0008058144CDFF85090A6F29C4712E000BF0F
+:1016C00000F0D4FBF068C568281D00F072FBA0682C
+:1016D000401EA0606068401E606000F0E7FB284686
+:1016E000FFF78BFF60680028EAD138680128F9D934
+:1016F000C9F80080BFF34F8FBFF36F8FF2E7000090
+:10170000643200202001002004ED00E070B51D4689
+:10171000049C51B1C4F80020C4E90F010121204606
+:1017200000F0D4FE84F84C5070BD2460F4E72DE93D
+:10173000F05F88469A4691001546DDE90B940A9EB3
+:10174000A5228346206BEFF77EF8206B6FF0030134
+:1017500001EB8501084420F00707780707D05020E7
+:1017600080F31188BFF34F8FBFF36F8FFEE7B8F19F
+:10177000000F4FF000050ED00020221818F80010BE
+:1017800082F8341018F8001011B1401C1028F4D35E
+:1017900084F8435001E084F83450382E00D33726C3
+:1017A000E662201DC4E9136500F039FB04F118005E
+:1017B00000F035FB6565C6F13800A06184F858502B
+:1017C0005246246159463846646200F05BFAB9F12A
+:1017D000000F206001D0C9F80040BDE8F09F000074
+:1017E00030B5114900E011460A688242FBD34B68CC
+:1017F0005C18844203D14468084623444B60436824
+:101800001D18954209D1084C183C2468A24209D001
+:1018100052681A4442600A6812680260814200D02D
+:10182000086030BD0460F9E78C01002070B50D4DF3
+:10183000914241604FF00004006106D88169D21ADC
+:101840008A4206D2011D286907E09A4203D29942D2
+:1018500001D3012403E0011DE86800F0E3FA20460B
+:1018600070BD00005C01002010B5044600F0FEFAD7
+:10187000A06B28B15FF0000400F018FB204610BDFB
+:101880000124F9E730B53C4D89B06BE0049800289D
+:1018900006DA059ADDE9060190470498002861DB25
+:1018A000069C606910B1201D00F083FA03A800F0C7
+:1018B000D5F8024604980A2854D2DFE800F005055E
+:1018C000052D304705052D3094F8280040F0010023
+:1018D00084F82800A06905990B4601442046FFF7CB
+:1018E000A5FF50B3216A2046884794F82800400796
+:1018F00038D50020009005980023A16942181946A8
+:10190000204601F083FBC0B9502080F31188BFF35B
+:101910004F8FBFF36F8FFEE794F828001EE094F816
+:10192000280040F0010084F828000598A06128B143
+:10193000811813462046FFF779FF13E0502080F30B
+:101940001188BFF34F8FBFF36F8FFEE794F8280025
+:10195000810703D4204600F0BDFA03E020F0010027
+:1019600084F828002868002204A900F009FF002854
+:101970008CD109B030BD00005C0100202DE9FC4194
+:101980000F46054600F084FC01A800F067F8044605
+:10199000019818B101F0A8FABDE8FC81254EAFB15D
+:1019A00030690068D0B300273068291B3A4600F040
+:1019B00013FB01F099FA0028EED11F494FF0805037
+:1019C0000860BFF34F8FBFF36F8FE5E7A542EBD8F9
+:1019D00001F08AFAF0682746C068C468201D00F04C
+:1019E000E8F994F82800410719D5A0692B463A4632
+:1019F00041192046FFF71AFFA8B100202A460346E6
+:101A000001460090204601F001FB60B9502080F3B0
+:101A10001188BFF34F8FBFF36F8FFEE707E020F011
+:101A2000010084F82800216A20468847B4E701278E
+:101A3000BAE700005C01002004ED00E00648416BBD
+:101A4000096829B1416BC968C968496881627047F2
+:101A50004FF0FF31FAE700002001002070B5054685
+:101A600001F014F9064E0446B068844203D200F037
+:101A700009F8012000E0002028602046B46070BD15
+:101A80005C010020F8B5194D20E0C068C468066804
+:101A9000201D00F08EF9216A2046884794F828001E
+:101AA000400713D5A0693044B04206D92461211DF6
+:101AB0006060E86800F0B6F908E0002032460346AE
+:101AC00001460090204601F0A1FA38B1E8680168AB
+:101AD0000029DAD12969C5E90310F8BD502080F347
+:101AE0001188BFF34F8FBFF36F8FFEE75C010020BB
+:101AF00008484068401C4FF0500080F3118804D023
+:101B0000BFF34F8FBFF36F8FFEE7BFF34F8FBFF36E
+:101B10006F8FFEE794010020074CE068016841B137
+:101B2000C0680021D0F80000FFF728FFFFF7AAFEE9
+:101B3000F3E701210020F7E75C0100202DE9F041E7
+:101B4000044600F093F994F9455004F1240609E0A5
+:101B5000606A48B1304601F08FF908B100F01AFB15
+:101B60006D1E6DB2002DF3DC4FF0FF3684F845603A
+:101B700000F09CF900F07AF994F9445004F1100750
+:101B800009E0206948B1384601F076F908B100F063
+:101B900001FB6D1E6DB2002DF3DC84F84460BDE8DE
+:101BA000F04100F083B900002DE9F0410027044620
+:101BB00000F06EFB324E306808B9FFF739FD7069EE
+:101BC00004424ED1C4B3083460070ED004F00700BD
+:101BD000C0F108000444600707D0502080F311884A
+:101BE000BFF34F8FBFF36F8FFEE72CB37068844253
+:101BF00037D82348183001460D6801E028460D46C5
+:101C00006968A14202D229680029F7D131688D4262
+:101C100027D007682968016008376868011B102908
+:101C20000FD92819420708D0502080F31188BFF33C
+:101C30004F8FBFF36F8FFEE713E041606C60FFF7DB
+:101C4000CFFD69687068401A7060B268904200D237
+:101C5000B060002072691143C5E90001F068401CC2
+:101C6000F06001F041F9780707D0502080F3118827
+:101C7000BFF34F8FBFF36F8FFEE73846BDE8F081AB
+:101C80007401002070B5041F094E231F4FF08075AA
+:101C900021F0010125601C1F1960A0F120010B1F1C
+:101CA000266044380A606FF002051D6070BD0000B8
+:101CB000F11A010810B52DED088BF0EE439AB0EE45
+:101CC000628AB0EE42AAB0EE619AF0EE418AB0EEBE
+:101CD00060BAF0EE40AAFEF781FD20EE099AB0EE60
+:101CE0006A0AFEF7D3FC0AEE409AB0EE4B0AFEF702
+:101CF00075FD20EE29AAB0EE4B0AFEF7C7FC09EEEF
+:101D0000808A6AEE280A2AEE090A48EE490A08EE95
+:101D1000280ABDEC088BBDE81040FEF75DBB000053
+:101D200060EE201A10B5B0EEE12A60EE001AB0EEB7
+:101D3000000A40EEA01A62EE000A41EE411A81EE5E
+:101D4000A00A10EE100AB0F17E5F02DDB7EE000AC5
+:101D500006E010EE100A10F1814F01D9BFEE000A23
+:101D6000FEF726F8DFED020A30EE600A10BD000033
+:101D7000DB0F494010B500EE100A2DED028BB1EEDD
+:101D8000C08A18EE100A20F00040C0F1FF40C00FDA
+:101D90000AD010EE100A20F00040C0F1FF40C00F42
+:101DA00004BF0120EEF7D3FD18EE100ABDEC028B44
+:101DB00010BDD0E9013201699A60D0E901235A606F
+:101DC0004A68824201D182684A6000220261086842
+:101DD000401E08600868704710B5044C80230460FA
+:101DE00004F15C000860136010BD0000A433002003
+:101DF00010B5044C4FF48073046004F15C0008607B
+:101E0000136010BD003600204FF0FF3300F10801D1
+:101E10000022C0E901130260C16001617047002126
+:101E20000161704730B50B685A1C02D000F10802FE
+:101E300002E0026904E02246546825689D42FAD90E
+:101E400053684B6099608A60516008610168491C61
+:101E5000016030BD42684A6093688B609368596046
+:101E6000916008610168491C01607047502080F34F
+:101E70001188BFF34F8FBFF36F8F0A494868401C2A
+:101E8000486001280CD10848006810F0FF0F07D007
+:101E9000502080F31188BFF34F8FBFF36F8FFEE7A1
+:101EA000704700009401002004ED00E008494868F4
+:101EB00028B1401E486001D180F31188704750203E
+:101EC00080F31188BFF34F8FBFF36F8FFEE70000E1
+:101ED0009401002070B500282AD0164DA0F1080406
+:101EE00061686869014207D1502080F31188BFF30F
+:101EF0004F8FBFF36F8FFEE722683AB1502080F317
+:101F00001188BFF34F8FBFF36F8FFEE7814361608E
+:101F100000F0BEF960686968084468602046FFF711
+:101F20005FFC2869401C2861BDE8704000F0DCBF00
+:101F300070BD0000740100204FF0E020002101611D
+:101F40004FF47A728161072303490968B1FBF2F10A
+:101F5000491E4161036170478800002010B5EEF70B
+:101F6000D7FA114910280ED300F1E0200A7890F832
+:101F7000F003904207D2502080F31188BFF34F8FB7
+:101F8000BFF36F8FFEE709488968006800F4E060DE
+:101F9000884207D9502080F31188BFF34F8FBFF3D9
+:101FA0006F8FFEE710BD0000940100200CED00E0F3
+:101FB000084B5FF0000210B553F832401CB1521CC0
+:101FC000082AF9D310BD03EBC20443F83210606055
+:101FD00010BD0000882D002070B515460E46044641
+:101FE000FFF744FF94F944100020491C01D184F804
+:101FF000440094F94510491C01D184F84500FFF7CD
+:1020000055FFA06B28B904F124002A46314600F0A0
+:10201000DFF82046BDE87040FFF790BD020010B524
+:1020200014D00F48006B38B1502080F31188BFF3F3
+:102030004F8FBFF36F8FFEE700F02AF900211046A3
+:10204000FFF7D0F900F050FF002807D105494FF005
+:1020500080500860BFF34F8FBFF36F8F10BD00003B
+:102060002001002004ED00E070B504000D460BD007
+:1020700095B11E4A106BB8B1502080F31188BFF3A0
+:102080004F8FBFF36F8FFEE7502080F31188BFF3AF
+:102090004F8FBFF36F8FFEE7502080F31188BFF39F
+:1020A0004F8FBFF36F8FFEE700F0F2F82368D2681E
+:1020B0005919934204D98B420AD9914202D807E0B8
+:1020C0008B42FAD9881A21600021FFF78BF900E0D2
+:1020D000216000F009FF002807D105494FF080502A
+:1020E0000860BFF34F8FBFF36F8F70BD20010020DA
+:1020F00004ED00E070B50546FFF7B8FE1E4C05B9CB
+:102100002568281DFFF755FEA86A18B105F11800CB
+:10211000FFF74FFE606A401C60622068854207D16D
+:102120001648291DFFF796FE6068401C606007E0B6
+:10213000A068401EA0602846FFF75FFAFFF77EFC0C
+:10214000FFF7B4FE6069002814D02068854211D1E1
+:10215000206B38B1502080F31188BFF34F8FBFF34D
+:102160006F8FFEE706494FF080500860BFF34F8F36
+:10217000BFF36F8F70BD000020010020643200208B
+:1021800004ED00E002490A6A0260C96841607047D4
+:102190002001002001490120C86170472001002072
+:1021A00010B50C4650B1094909681831FFF73AFEDD
+:1021B0002046BDE810400121FFF714B9502080F3FC
+:1021C0001188BFF34F8FBFF36F8FFEE72001002010
+:1021D00070B514460D4668B10A4909681831FFF711
+:1021E00039FE0CB14FF0FF3521462846BDE870405E
+:1021F000FFF7F8B8502080F31188BFF34F8FBFF37B
+:102200006F8FFEE72001002030B587B0002405AABB
+:1022100004A9039403A80494FFF7DEFDDDE903019C
+:1022200000940023CDE90110174815A1059A00F08C
+:10223000FCFB164D0028E8621FD000F0B7FE012815
+:1022400009D0401C19D1502080F31188BFF34F8F63
+:10225000BFF36F8FFEE7502080F31188BFF34F8FDD
+:10226000BFF36F8F01214FF0FF30A8626961EC600E
+:1022700007B0BDE8304000F045B807B030BD000001
+:1022800049444C4500000000AD1601082001002023
+:102290000248016B491C01637047000020010020C7
+:1022A000164810B5016B11B10121C16110BD0021AB
+:1022B000C161134A016901E0B9B1491E01EB810313
+:1022C00052F82330002BF7D001EB810302EB83029D
+:1022D00002F1080453685B685360A34201D15B6854
+:1022E0005360DA680260016110BD502080F31188EC
+:1022F000BFF34F8FBFF36F8FFEE700002001002078
+:10230000C82D002037481CB5374902688A4207D1DA
:10231000502080F31188BFF34F8FBFF36F8FFEE71C
-:10232000206C38B1502080F31188BFF34F8FBFF37A
-:102330006F8FFEE7FFF732FB5020EFF3118680F33B
-:102340001188BFF34F8FBFF36F8FA76BFFB194F965
-:10235000445049462046FEF787FE681CA7F1010756
-:10236000A76304D06D1C84F84450012010E020695C
-:102370000028FAD004F1100000F09EFA0028F4D0F2
-:10238000B8F1000FF1D00121C8F80010EDE70020EE
-:1023900086F31188BDE8F0872DE9F04105000C4671
-:1023A00012D0CCB1FFF782FA184E2068F268471CB1
-:1023B0006B68A2EB030117D02F68366AB74215D0BD
-:1023C000934213D801251CE0502080F31188BFF3FD
-:1023D0004F8FBFF36F8FFEE7502080F31188BFF35C
-:1023E0004F8FBFF36F8FFEE700250AE0884205D9C3
-:1023F000401A20602846FFF7E5FBF5E70020206043
-:102400000125FFF773FA2846BDE8F081200100207E
-:102410002DE9FF5F994616468A4683469000DDE91E
-:102420000E87FFF741F905001CD05C20FFF73CF94F
-:10243000040014D00020256384F859004B46CDE9F0
-:102440000087CDE90240324651465846FEF7EFFE7E
-:102450002046FEF775FD012004B0BDE8F09F284638
-:10246000FFF758FA4FF0FF30F6E7F0B585B0DDE939
-:102470000B740A9DA7B1DCB15C262763022684F8A1
-:102480005960002703970DF1100C0095CDE901C4A8
-:10249000FEF7CDFE2046FEF753FD049805B0F0BDD3
-:1024A000502080F31188BFF34F8FBFF36F8FFEE78B
-:1024B000502080F31188BFF34F8FBFF36F8FFEE77B
-:1024C0002DE9F0411F4690460D464FF0010690B1B0
-:1024D0000446FFF7EBF90FB1606D3860022294F803
-:1024E000580084F85820B8F1050F19D2DFE808F039
-:1024F000230B0E141200502080F31188BFF34F8F6E
-:10250000BFF36F8FFEE7616D294301E0616D491CE8
-:10251000616510E0022801D065650CE0002634E01A
-:10252000616D491C07D0502080F31188BFF34F8F95
-:10253000BFF36F8FFEE7012827D1201DFFF759F960
-:10254000144DE06A2969884200D9286100EB8000B7
-:10255000114901EB8000211DFFF79CF9A06A38B1F9
-:10256000502080F31188BFF34F8FBFF36F8FFEE7CA
-:102570002868E16AC06A814207D908494FF0805053
-:102580000860BFF34F8FBFF36F8FFFF7AFF930468F
-:10259000BDE8F08120010020E42B002004ED00E0E4
-:1025A0002DE9F04704001F4692460D46DDF82090C5
-:1025B0004FF001081AD0FFF7F1F95020EFF3118620
-:1025C00080F31188BFF34F8FBFF36F8F0FB1606D32
-:1025D0003860022294F8580084F85820BAF1050FA8
-:1025E0001AD2DFE80AF0240B0E141200502080F3F8
-:1025F0001188BFF34F8FBFF36F8FFEE7616D2943E3
-:1026000001E0616D491C616511E0022801D065653A
-:102610000DE04FF000083AE0616D491C07D05020F2
-:1026200080F31188BFF34F8FBFF36F8FFEE7012850
-:102630002DD1A06A38B1502080F31188BFF34F8F9D
-:10264000BFF36F8FFEE7144D286B18B1134804F1E8
-:1026500018010DE0201DFFF7CCF8E06A29698842D7
-:1026600000D9286100EB80000D4901EB8000211D9D
-:10267000FFF710F9E06A2968C96A884207D9B9F1F9
-:10268000000F4FF0010001D0C9F80000E86186F3A7
-:1026900011884046BDE8F087200100206C30002002
-:1026A000E42B002001480068704700002001002052
-:1026B0000548416919B1006B18B10020704701202D
-:1026C0007047022070470000200100200148C068C8
-:1026D000704700002001002010B5FFF75FF90148A6
-:1026E000C06810BD200100202DE9F0412E4C206B68
-:1026F000002728B1A069401CA0613846BDE8F081E0
-:10270000E668761CE66013D1606B006838B1502033
-:1027100080F31188BFF34F8FBFF36F8FFEE7606BBD
-:10272000A16B6163A063206A401C2062FEF706FF74
-:10273000DFF87880A06A864209D3606B0068A0B198
-:10274000606BC068C5686868864211D2A062206864
-:10275000C06A00EB800158F82100012800D9012748
-:10276000E0690028C9D00127C7E74FF0FF30EDE747
-:10277000281DFFF73EF8A86A18B105F11800FFF709
-:1027800038F8E86A2169884200D9206100EB8001AD
-:1027900008EB8100291DFFF77DF82068E96AC06A0F
-:1027A0008142CAD30127C8E720010020E42B002082
-:1027B0002DE9F0411E46154688460746FFF776F894
-:1027C0001C4C206890F85800022814D02068416DF5
-:1027D000B94341652168012081F858005EB10121AB
-:1027E0003046FEF77FFB14494FF080500860BFF37E
-:1027F0004F8FBFF36F8FFFF779F8FFF757F815B1D9
-:102800002068406D2860206890F85800022801D0A8
-:10281000002505E02068416D21EA08014165012598
-:102820002168002081F85800FFF760F82846BDE8CD
-:10283000F08100002001002004ED00E070B50446A6
-:102840004FF0000190B31A4D2868844207D0502001
-:1028500080F31188BFF34F8FBFF36F8FFEE7206DBA
-:1028600038B1E36C401EE26A20659A421ED040B146
-:102870001CE0502080F31188BFF34F8FBFF36F8FA0
-:10288000FEE7201DFEF7B5FFE06CC0F13801A16145
-:10289000E0622969884200D9286100EB800005497F
-:1028A00001EB8000211DFEF7F5FF0121084670BDF8
-:1028B00020010020E42B002070B5C068C46854B12A
-:1028C00004F118000646FEF794FF144D286B50B132
-:1028D0001348314615E0502080F31188BFF34F8F25
-:1028E000BFF36F8FFEE7201DFEF783FFE06A2969C3
-:1028F000884200D9286100EB80000A4901EB800082
-:10290000211DFEF7C7FFE06A2968C96A884203D91A
-:102910000121E961084670BD002070BD2001002042
-:102920006C300020E42B00202DE9F0472C4D286B63
-:102930000024274638B1FEF7B9FF286B401E2863F4
-:10294000286B40B147E0502080F31188BFF34F8FD0
-:10295000BFF36F8FFEE7234E0120A968D9B3A6F518
-:10296000916980463068E0B1F068C46804F11800ED
-:10297000FEF73FFF201DFEF73CFFE06A2969884211
-:1029800000D9286100EB800109EB8100211DFEF7D1
-:1029900081FFE06A2968C96A8842E3D3C5F81C80D0
-:1029A000E0E70CB1FEF7CAFDAC694CB14FEA08068E
-:1029B000FFF79AFE00B1EE61641EF9D10020A86114
-:1029C000E86940B1084901274FF080500860BFF323
-:1029D0004F8FBFF36F8FFEF789FF3846BDE8F08752
-:1029E000200100206C30002004ED00E010B586B01E
-:1029F000FEF70EFB114C2068B8B10020039005AA29
-:102A0000049004A903A8FEF713FFDDE903210220C7
-:102A100000238DE807000C4809A1059AFFF725FD62
-:102A2000606010B106B0012010BD502080F3118805
-:102A3000BFF34F8FBFF36F8FFEE700005C010020F4
-:102A4000546D722053766300191601082DE9FF4179
-:102A50001E46134602004FF000000A9D16D0144C8B
-:102A60002768002F0FD006290292CDE9001317DA4C
-:102A7000FFF71EFE02284FF000030FD0002220684F
-:102A80006946FFF78DFA04B0BDE8F081502080F36D
-:102A90001188BFF34F8FBFF36F8FFEE72A46EEE733
-:102AA0000023324669463846FFF72AFBEBE7000071
-:102AB0005C01002010B500290AD00878002807D052
-:102AC00005487844EEF772FF002801D0002010BDC1
-:102AD0000248784410BD0000EA080000E208000047
-:102AE00010B500290AD00878002807D00548784496
-:102AF000EEF75CFF002801D0002010BD02487844AA
-:102B000010BD0000DA080000D20800004FF040704D
-:102B1000E1EE100A7047EEF756BBEEF78BBC0000F3
-:102B20001432010800000000000000000000000056
-:102B3000000000000002000018000000000000007B
-:102B40000000000000061016000610160001020327
-:102B500004050607080C101418203040000000007F
-:102B60000000000000000000000000000000000065
-:102B7000010000000200000003000000040000004B
-:102B80000000000005000000000000000000000040
-:102B9000000000000600000000000000000000002F
-:102BA0000000000007000000010002000400060011
-:102BB00008000A000C001000200040008000000106
-:102BC00001010103070100000804020408010101DA
-:102BD00000000000010203040102030406070809C3
-:102BE0005032010820320108811101080000000064
-:102BF00000000000000000000000000000000000D5
-:102C000000000000000000000000000000000000C4
-:102C100000000000000000000000000000000000B4
-:102C200000000000000000000000000000000000A4
-:102C30000000000000000000000000000000000094
-:102C40000000000000000000000000000000000084
-:102C50000000000000000000000000000000000074
-:102C60000000000000000000000000000000000064
-:102C70000000000000000000000000000000000054
-:102C80000000000000000000000000000000000044
-:102C90000000000000000000000000000000000034
-:102CA0000000000000000000000000000000000024
-:102CB0000000000000000000000000000000000014
-:102CC0000000000000000000000000000000000004
-:102CD00000000000000000000000000000000000F4
-:102CE00000330108000000000000000000000000A8
-:102CF00000000000000400003000000000000000A0
-:102D0000000000000C33010800000000000000007B
-:102D10000000000000000000000400001800000097
-:102D20000000000000000000103301080000000057
-:102D3000000000000000000000000000000400008F
-:102D40001800000000000000000000001C33010813
-:102D50000000000000000000000000000000000073
-:102D60000004000018000000000000000000000047
-:102D700024330108000000000000000000000000F3
-:102D80000000000000040000180000000000000027
-:102D900000000000283301080000000000000000CF
-:102DA0000000000000000000000400001800000007
-:102DB00000000000000000003033010800000000A7
-:102DC00000000000000000000000000000040000FF
-:102DD000180000000000000000000000343301086B
-:102DE00000000000000000000000000000000000E3
-:102DF00000080000180000000000000000000000B3
-:102E00004033010800000000000000000000000046
-:102E10000000000000080000180000000000000092
-:102E2000000000009A99993E0000803F00000000D9
-:102E3000000000000000803F0000803F0000000014
-:102E400000000000743301085033010861080108D4
-:102E5000000000000000891112239B322446AD5768
-:102E60003665BF74488CC19D5AAFD3BE6CCAE5DBD2
-:102E70007EE9F7F88110080193331A22A5562C47F2
-:102E8000B7753E64C99C408DDBBF52AEEDDA64CBB2
-:102E9000FFF976E802218B30100299132667AF768E
-:102EA0003444BD554AADC3BC588ED19F6EEBE7FA92
-:102EB0007CC8F5D983310A2091121803A7772E66B2
-:102EC000B5543C45CBBD42ACD99E508FEFFB66EA72
-:102ED000FDD874C904428D5316619F702004A91552
-:102EE0003227BB364CCEC5DF5EEDD7FC6888E19952
-:102EF0007AABF3BA85520C4397711E60A114280572
-:102F0000B3373A26CDDE44CFDFFD56ECE998608931
-:102F1000FBBB72AA06638F7214409D512225AB340D
-:102F20003006B9174EEFC7FE5CCCD5DD6AA9E3B811
-:102F3000788AF19B87730E6295501C41A3352A2431
-:102F4000B1163807CFFF46EEDDDC54CDEBB962A8F1
-:102F5000F99A708B088481951AA793B62CC2A5D3D1
-:102F60003EE1B7F04008C919522BDB3A644EED5FE1
-:102F7000766DFF7C899400859BB712A6ADD224C3E1
-:102F8000BFF136E0C1184809D33B5A2AE55E6C4FC1
-:102F9000F77D7E6C0AA583B4188691972EE3A7F27D
-:102FA0003CC0B5D14229CB38500AD91B666FEF7EA1
-:102FB000744CFD5D8BB502A499961087AFF326E2A1
-:102FC000BDD034C1C3394A28D11A580BE77F6E6E81
-:102FD000F55C7C4D0CC685D71EE597F42880A19141
-:102FE0003AA3B3B2444ACD5B5669DF78600CE91D61
-:102FF000722FFB3E8DD604C79FF516E4A990208161
-:10300000BBB332A2C55A4C4BD7795E68E11C680D40
-:10301000F33F7A2E0EE787F61CC495D52AA1A3B0FC
-:103020003882B193466BCF7A5448DD59622DEB3C20
-:10303000700EF91F8FF706E69DD414C5ABB122A020
-:10304000B9923083C77B4E6AD5585C49E33D6A2C00
-:10305000F11E780F00000000000000003031323314
-:1030600034353637383941424344454640305800BC
-:1030700030313233343536373839616263646566EE
-:10308000403078000400000800000000000000024A
-:1030900000010000100000004FBB610567ACDD3F80
-:1030A000182D4454FB21E93F9BF681D20B73EF3F6F
-:1030B000182D4454FB21F93FE2652F227F2B7A3CE7
-:1030C000075C143326A6813CBDCBF07A8807703CA0
-:1030D000075C143326A6913CC4EB98999999C9BF13
-:1030E000711623FEC671BCBF6D9A74AFF2B0B3BF48
-:1030F0009AFDDE522DDEADBF2F6C6A2C44B4A2BF08
-:103100000D5555555555D53FFF8300922449C23F73
-:103110006E204CC5CD45B73F513DD0A0660DB13FA7
-:10312000EB0D76244B7BA93F11DA22E33AAD903FB9
-:103130000000000000000000000000006E83F9A203
-:103140002915444ED15727FCC0DD34F5999562DB33
-:103150004190433CAB6351FE303132333435363726
-:1031600038396162636465667870003031323334B7
-:1031700035363738394142434445465850000000FF
-:1031800002400000000000A0000000000540000018
-:10319000000000C8000000000C4000000000409C3F
-:1031A00000000000194000000020BCBE000000002C
-:1031B00034400000BFC91B8E00000004B540000071
-:1031C000504BCFD06607E2CF010000006C410000F9
-:1031D0003E8251AADFEEA73401000000D942000070
-:1031E000DCB5A0E23A301F97FFFFFFFFB4450000B7
-:1031F000FD25A0C8E9A3C14FFFFFFFFFFF3F00006F
-:103200000000008000000000FF3F00000000008080
-:103210000000000064656661756C745461736B0036
-:103220000D0A68656C703A0D0A204C69737473203E
-:10323000616C6C207468652072656769737465726F
-:10324000656420636F6D6D616E64730D0A0D0A0015
-:1032500068656C7000000000496E636F7272656390
-:103260007420636F6D6D616E6420706172616D6555
-:103270007465722873292E2020456E746572202291
-:1032800068656C702220746F2076696577206120F4
-:103290006C697374206F6620617661696C61626C21
-:1032A0006520636F6D6D616E64732E0D0A0D0A00EB
-:1032B000436F6D6D616E64206E6F74207265636F15
-:1032C000676E697365642E2020456E7465722027D1
-:1032D00068656C702720746F20766965772061209F
-:1032E0006C697374206F6620617661696C61626CD1
-:1032F0006520636F6D6D616E64732E0D0A0D0A009B
-:103300005461736B5F496E69740000007263000062
-:10331000617474695F657374690000007465737427
-:1033200000000000636C69006D6F6E69746F72005D
-:10333000636D64006374726C5F6C6567000000000D
-:103340006374726C5F63686173736973000000007B
-:1033500068746F703A20E698BEE7A4BA4672656555
-:1033600052544F53E4BBBBE58AA1E78AB6E680819D
-:103370005C720A0068746F7000000000D8340108A5
-:1033800000000020DC0200000803000814360108D9
-:10339000000000240C050000080300081436010892
-:1033A000DC02002074050100640300081C0000001A
-:1033B00043000000F8FFFFFF0C0000000E000000BB
-:1033C0000F0000002E00000010010000430000006C
-:1033D000F8FFFFFF00404040404040404040414136
-:1033E00041414140404040404040404040404040DA
-:1033F0004040404040050202020202020202020274
-:103400000202020202202020202020202020200270
-:103410000202020202029090909090901010101000
-:10342000101010101010101010101010101010109C
-:103430000202020202028888888888880808080830
-:1034400008080808080808080808080808080808FC
-:103450000202020240000000000000000000000024
-:10346000000000000000000000000000000000005C
-:10347000000000000000000000000000000000004C
-:10348000000000000000000000000000000000003C
-:10349000000000000000000000000000000000002C
-:1034A000000000000000000000000000000000001C
-:1034B000000000000000000000000000000000000C
-:1034C00000000000000000000000000000000000FC
-:1034D00000000000000000008113FDE514082DE647
-:1034E0001B0839041A55041A75041ADD141A090840
-:1034F0004117040309041201140202021640FCFFE2
-:10350000B82226020102030114050F0C1C0107104A
-:103510001721031A1A0313A1321B089B041A9704DC
-:103520001AC5041AD904193F1182103C90D0030423
-:103530003114810182130A0629532A40241C0902EE
-:10354000436F1125C03209041B01020B1305241619
-:10355000100105240118090104240202052406842F
-:1035600015058203081C100904A5320A2E0705015F
-:103570000240072A81071113E1E014084DDF4C08CF
-:103580004BE2D01ADD0C1399DE1B080F08C11A613B
-:10359000281A21041AA1041A150401781AAA01C1D3
-:1035A00017022B073DB80182200C2BE02B019CE574
-:1035B000CDCCCC3D2B803F146301022839A470FD93
-:1035C0003F3D0A37C0CF7701C285EBB14052B84EBC
-:1035D0004121301442EC519840713D92C054630F28
-:1035E000C248E11A409A990D4133331A423255B01C
-:1035F0003DCDCC4C3E0409220C4D5C8FCA40040BDF
-:10360000224A410CE9AC490401101A20288B80BFE2
-:1036100004E1000001FF01FF01FF01FF01FF0111B3
+:1023200031490068491E884207D1502080F3118846
+:10233000BFF34F8FBFF36F8FFEE72C49FF200A7862
+:102340000192087008788DF800009DF800209DF833
+:10235000000002F0F002824207D0502080F3118882
+:10236000BFF34F8FBFF36F8FFEE79DF8002007206C
+:102370001F4C02F050022270A06005E09DF8002082
+:1023800052008DF80020401E9DF800201206F5D462
+:102390000328A06007D0502080F31188BFF34F8F2F
+:1023A000BFF36F8FFEE74FF44070A0600198087094
+:1023B0000C482030016841F470010160016841F06F
+:1023C00070410160FFF7B8FD00206060EEF768F82B
+:1023D0000848016841F040410160EEF74DF80020E7
+:1023E0001CBD000000ED00E071C20F4100E400E000
+:1023F0009401002034EF00E0502010B580F31188E4
+:10240000BFF34F8FBFF36F8F00F04EFC18B104493C
+:102410004FF080500860002080F3118810BD00004C
+:1024200004ED00E0F8B5050017460E4613D005FB95
+:1024300006F05030FFF7B8FB04000AD0002084F803
+:10244000460004F150023B46314628460094FFF70F
+:102450005DF92046F8BD502080F31188BFF34F8FFF
+:10246000BFF36F8FFEE7F8B5069D18B153B1CAB13F
+:1024700081B120E0502080F31188BFF34F8FBFF36C
+:102480006F8FFEE7502080F31188BFF34F8FBFF3AB
+:102490006F8FFEE7502080F31188BFF34F8FBFF39B
+:1024A0006F8FFEE739B1502080F31188BFF34F8F53
+:1024B000BFF36F8FFEE750241C46012683F8466069
+:1024C00000932B46FFF722F92046F8BD2DE9F0478F
+:1024D00004008A4629D0FFF7C9FC21680025D4E909
+:1024E0000F23D4F840C004F1100810460E46401ED9
+:1024F0004FF0FF3902FB031200FB0C10BAF1000F82
+:10250000A563666084F8449084F84590C4E902208D
+:1025100013D04046FFF778FC04F12400FFF774FC69
+:10252000FFF7C4FC0120BDE8F087502080F311883C
+:10253000BFF34F8FBFF36F8FFEE720690028EFD006
+:10254000404600F099FC0028EAD004494FF0805042
+:102550000860BFF34F8FBFF36F8FE1E704ED00E03A
+:102560002DE9FF4704001D4682B08A464FF000085F
+:1025700003D0BAF1000F08D011E0502080F3118889
+:10258000BFF34F8FBFF36F8FFEE7206C38B1502041
+:1025900080F31188BFF34F8FBFF36F8FFEE7022DDB
+:1025A0000AD1E06B012807D0502080F31188BFF3D7
+:1025B0004F8FBFF36F8FFEE700F05AFB3F4F4FF096
+:1025C00080564FF0000948B9049838B1502080F384
+:1025D0001188BFF34F8FBFF36F8FFEE7FFF746FC05
+:1025E000A06BE16B884207D3022D05D00498D0B1CF
+:1025F000B8F1000F1AD01EE02A4651462046FEF7D9
+:10260000C6FF616A19B104F1240000F035FC20B165
+:102610003E60BFF34F8FBFF36F8FFFF747FC012082
+:1026200006B0BDE8F087FFF741FC22E06846FFF7FF
+:10263000A9FD4FF00108FFF739FCFFF729FEFFF76E
+:1026400015FC94F94400401C01D184F8449094F99D
+:102650004500401C01D184F84590FFF727FC04A9F0
+:10266000684600F079F930B12046FFF767FA00F0CC
+:102670003BFC0020D4E7FFF7F9FBA06BE16B88423D
+:1026800013D1FFF713FC049904F11000FFF788FD44
+:102690002046FFF753FA00F027FC00289ED13E6049
+:1026A000BFF34F8FBFF36F8F98E7FFF7FFFB204615
+:1026B000FFF744FA00F018FC90E7000004ED00E09A
+:1026C0002DE9F04704001F469046894603D0B9F132
+:1026D000000F08D011E0502080F31188BFF34F8F16
+:1026E000BFF36F8FFEE7206C38B1502080F3118864
+:1026F000BFF34F8FBFF36F8FFEE7022F0AD1E06B5E
+:10270000012807D0502080F31188BFF34F8FBFF30B
+:102710006F8FFEE7FFF722FC5020EFF3118680F366
+:102720001188BFF34F8FBFF36F8FA06BE16B8842AF
+:1027300006D3022F04D0002086F31188BDE8F0876D
+:1027400094F94550A06B3A4649462046FEF71FFFD4
+:10275000681C04D06D1C84F845500120ECE7606AC9
+:102760000028FAD004F1240000F086FB0028F4D001
+:10277000B8F1000FF1D00121C8F80010EDE700001A
+:102780002DE9F74704008A4683B04FF0000603D0D6
+:10279000BAF1000F08D011E0502080F31188BFF388
+:1027A0004F8FBFF36F8FFEE7206C38B1502080F35E
+:1027B0001188BFF34F8FBFF36F8FFEE700F058FA19
+:1027C000DFF8F4804FF080574FF0000948B90598C2
+:1027D00038B1502080F31188BFF34F8FBFF36F8F54
+:1027E000FEE7FFF743FBA56BC5B151462046FEF758
+:1027F000BBFE6D1EA563206950B104F1100000F00E
+:102800003BFB28B1C8F80070BFF34F8FBFF36F8F49
+:10281000FFF74CFB012006B0BDE8F087059808B132
+:102820001EB106E0FFF742FB27E06846FFF7AAFC6F
+:102830000126FFF73BFBFFF72BFDFFF717FB94F992
+:102840004400401C01D184F8449094F94500401C98
+:1028500001D184F84590FFF729FB05A9684600F0EF
+:102860007BF8002820460AD0FFF768F900F03CFB0F
+:102870002046FEF7F9FF0028B3D00020CBE7FEF793
+:10288000F3FF90B1059904F12400FFF789FC20467D
+:10289000FFF754F900F028FB0028A2D1C8F8007017
+:1028A000BFF34F8FBFF36F8F9BE72046FFF746F9CB
+:1028B00000F01AFB95E7000004ED00E02DE9F04779
+:1028C00004009046894603D0B9F1000F08D011E00A
+:1028D000502080F31188BFF34F8FBFF36F8FFEE757
+:1028E000206C38B1502080F31188BFF34F8FBFF3B5
+:1028F0006F8FFEE7FFF732FB5020EFF3118680F376
+:102900001188BFF34F8FBFF36F8FA76BFFB194F99F
+:10291000445049462046FEF727FE681CA7F10107F0
+:10292000A76304D06D1C84F84450012010E0206996
+:102930000028FAD004F1100000F09EFA0028F4D02C
+:10294000B8F1000FF1D00121C8F80010EDE7002028
+:1029500086F31188BDE8F0872DE9F04105000C46AB
+:1029600012D0CCB1FFF782FA184E2068F268471CEB
+:102970006B68A2EB030117D02F68366AB74215D0F7
+:10298000934213D801251CE0502080F31188BFF337
+:102990004F8FBFF36F8FFEE7502080F31188BFF396
+:1029A0004F8FBFF36F8FFEE700250AE0884205D9FD
+:1029B000401A20602846FFF7E5FBF5E7002020607D
+:1029C0000125FFF773FA2846BDE8F08120010020B9
+:1029D0002DE9FF5F994616468A4683469000DDE959
+:1029E0000E87FFF7E1F805001CD05C20FFF7DCF84C
+:1029F000040014D00020256384F859004B46CDE92B
+:102A00000087CDE90240324651465846FEF78FFE18
+:102A10002046FEF715FD012004B0BDE8F09F2846D2
+:102A2000FFF758FA4FF0FF30F6E7F0B585B0DDE973
+:102A30000B740A9DA7B1DCB15C262763022684F8DB
+:102A40005960002703970DF1100C0095CDE901C4E2
+:102A5000FEF76DFE2046FEF7F3FC049805B0F0BDCE
+:102A6000502080F31188BFF34F8FBFF36F8FFEE7C5
+:102A7000502080F31188BFF34F8FBFF36F8FFEE7B5
+:102A80002DE9F0411F4690460D464FF0010690B1EA
+:102A90000446FFF7EBF90FB1606D3860022294F83D
+:102AA000580084F85820B8F1050F19D2DFE808F073
+:102AB000230B0E141200502080F31188BFF34F8FA8
+:102AC000BFF36F8FFEE7616D294301E0616D491C23
+:102AD000616510E0022801D065650CE0002634E055
+:102AE000616D491C07D0502080F31188BFF34F8FD0
+:102AF000BFF36F8FFEE7012827D1201DFFF759F99B
+:102B0000144DE06A2969884200D9286100EB8000F1
+:102B1000114901EB8000211DFFF79CF9A06A38B133
+:102B2000502080F31188BFF34F8FBFF36F8FFEE704
+:102B30002868E16AC06A814207D908494FF080508D
+:102B40000860BFF34F8FBFF36F8FFFF7AFF93046C9
+:102B5000BDE8F08120010020C82D002004ED00E038
+:102B60002DE9F04704001F4692460D46DDF82090FF
+:102B70004FF001081AD0FFF7F1F95020EFF311865A
+:102B800080F31188BFF34F8FBFF36F8F0FB1606D6C
+:102B90003860022294F8580084F85820BAF1050FE2
+:102BA0001AD2DFE80AF0240B0E141200502080F332
+:102BB0001188BFF34F8FBFF36F8FFEE7616D29431D
+:102BC00001E0616D491C616511E0022801D0656575
+:102BD0000DE04FF000083AE0616D491C07D050202D
+:102BE00080F31188BFF34F8FBFF36F8FFEE701288B
+:102BF0002DD1A06A38B1502080F31188BFF34F8FD8
+:102C0000BFF36F8FFEE7144D286B18B1134804F122
+:102C100018010DE0201DFFF7CCF8E06A2969884211
+:102C200000D9286100EB80000D4901EB8000211DD7
+:102C3000FFF710F9E06A2968C96A884207D9B9F133
+:102C4000000F4FF0010001D0C9F80000E86186F3E1
+:102C500011884046BDE8F087200100205032002056
+:102C6000C82D0020014800687047000020010020A6
+:102C70000548416919B1006B18B100207047012067
+:102C80007047022070470000200100200148C06802
+:102C9000704700002001002010B5FFF75FF90148E0
+:102CA000C06810BD200100202DE9F0412E4C206BA2
+:102CB000002728B1A069401CA0613846BDE8F0811A
+:102CC000E668761CE66013D1606B006838B150206E
+:102CD00080F31188BFF34F8FBFF36F8FFEE7606BF8
+:102CE000A16B6163A063206A401C2062FEF7A6FE10
+:102CF000DFF87880A06A864209D3606B0068A0B1D3
+:102D0000606BC068C5686868864211D2A06220689E
+:102D1000C06A00EB800158F82100012800D9012782
+:102D2000E0690028C9D00127C7E74FF0FF30EDE781
+:102D3000281DFFF73EF8A86A18B105F11800FFF743
+:102D400038F8E86A2169884200D9206100EB8001E7
+:102D500008EB8100291DFFF77DF82068E96AC06A49
+:102D60008142CAD30127C8E720010020C82D0020D6
+:102D70002DE9F0411E46154688460746FFF776F8CE
+:102D80001C4C206890F85800022814D02068416D2F
+:102D9000B94341652168012081F858005EB10121E5
+:102DA0003046FEF71FFB14494FF080500860BFF318
+:102DB0004F8FBFF36F8FFFF779F8FFF757F815B113
+:102DC0002068406D2860206890F85800022801D0E3
+:102DD000002505E02068416D21EA080141650125D3
+:102DE0002168002081F85800FFF760F82846BDE808
+:102DF000F08100002001002004ED00E070B50446E1
+:102E00004FF0000190B31A4D2868844207D050203B
+:102E100080F31188BFF34F8FBFF36F8FFEE7206DF4
+:102E200038B1E36C401EE26A20659A421ED040B180
+:102E30001CE0502080F31188BFF34F8FBFF36F8FDA
+:102E4000FEE7201DFEF7B5FFE06CC0F13801A1617F
+:102E5000E0622969884200D9286100EB80000549B9
+:102E600001EB8000211DFEF7F5FF0121084670BD32
+:102E700020010020C82D002070B5C068C46854B17E
+:102E800004F118000646FEF794FF144D286B50B16C
+:102E90001348314615E0502080F31188BFF34F8F5F
+:102EA000BFF36F8FFEE7201DFEF783FFE06A2969FD
+:102EB000884200D9286100EB80000A4901EB8000BC
+:102EC000211DFEF7C7FFE06A2968C96A884203D955
+:102ED0000121E961084670BD002070BD200100207D
+:102EE00050320020C82D00202DE9F0472C4D286BD2
+:102EF0000024274638B1FEF7B9FF286B401E28632F
+:102F0000286B40B147E0502080F31188BFF34F8F0A
+:102F1000BFF36F8FFEE7234E0120A968D9B3A6F552
+:102F2000916980463068E0B1F068C46804F1180027
+:102F3000FEF73FFF201DFEF73CFFE06A296988424B
+:102F400000D9286100EB800109EB8100211DFEF70B
+:102F500081FFE06A2968C96A8842E3D3C5F81C800A
+:102F6000E0E70CB1FEF76AFDAC694CB14FEA080628
+:102F7000FFF79AFE00B1EE61641EF9D10020A8614E
+:102F8000E86940B1084901274FF080500860BFF35D
+:102F90004F8FBFF36F8FFEF789FF3846BDE8F0878C
+:102FA000200100205032002004ED00E010B586B072
+:102FB000FEF7AEFA114C2068B8B10020039005AAC4
+:102FC000049004A903A8FEF713FFDDE90321022002
+:102FD00000238DE807000C4809A1059AFFF725FD9D
+:102FE000606010B106B0012010BD502080F3118840
+:102FF000BFF34F8FBFF36F8FFEE700005C0100202F
+:10300000546D722053766300191B01082DE9FF41AE
+:103010001E46134602004FF000000A9D16D0144CC5
+:103020002768002F0FD006290292CDE9001317DA86
+:10303000FFF71EFE02284FF000030FD00022206889
+:103040006946FFF78DFA04B0BDE8F081502080F3A7
+:103050001188BFF34F8FBFF36F8FFEE72A46EEE76D
+:103060000023324669463846FFF72AFBEBE70000AB
+:103070005C01002010B500290AD00878002807D08C
+:1030800005487844EEF792FC002801D0002010BDDE
+:103090000248784410BD0000DA080000D2080000A1
+:1030A00010B500290AD00878002807D005487844D0
+:1030B000EEF77CFC002801D0002010BD02487844C7
+:1030C00010BD0000CA080000C20800004FF04070A8
+:1030D000E1EE100A7047EEF776B8EEF7ABB90000F4
+:1030E000C4370108000000000000000000000000DC
+:1030F00000000000000200001800000000000000B6
+:103100000000000000061016000610160001020361
+:1031100004050607080C10141820304000000000B9
+:10312000000000000000000000000000000000009F
+:103130000100000002000000030000000400000085
+:10314000000000000500000000000000000000007A
+:103150000000000006000000000000000000000069
+:10316000000000000700000001000200040006004B
+:1031700008000A000C001000200040008000000140
+:103180000101010307010000080402040801010114
+:1031900000000000010203040102030406070809FD
+:1031A00000380108D037010881160108000000002E
+:1031B000000000000000000000000000000000000F
+:1031C00000000000000000000000000000000000FF
+:1031D00000000000000000000000000000000000EF
+:1031E00000000000000000000000000000000000DF
+:1031F00000000000000000000000000000000000CF
+:1032000000000000000000000000000000000000BE
+:1032100000000000000000000000000000000000AE
+:10322000000000000000000000000000000000009E
+:10323000000000000000000000000000000000008E
+:10324000000000000000000000000000000000007E
+:10325000000000000000000000000000000000006E
+:10326000000000000000000000000000000000005E
+:10327000000000000000000000000000000000004E
+:10328000000000000000000000000000000000003E
+:10329000000000000000000000000000000000002E
+:1032A0000000000000000000CDCC4CBEB03801088A
+:1032B000000000000000000000000000000000000E
+:1032C00000040000300000000000000000000000CA
+:1032D000BC380108000000000000000000000000F1
+:1032E00000000000000400001800000000000000C2
+:1032F00000000000C03801080000000000000000CD
+:1033000000000000000000000004000018000000A1
+:103310000000000000000000CC38010800000000A0
+:103320000000000000000000000000000004000099
+:10333000180000000000000000000000D438010860
+:10334000000000000000000000000000000000007D
+:103350000004000018000000000000000000000051
+:10336000D838010800000000000000000000000044
+:103370000000000000040000180000000000000031
+:1033800000000000E038010800000000000000001C
+:103390000000000000000000000400001800000011
+:1033A0000000000000000000E438010800000000F8
+:1033B0000000000000000000000000000008000005
+:1033C000180000000000000000000000F0380108B4
+:1033D00000000000000000000000000000000000ED
+:1033E00000080000180000000000000000000000BD
+:1033F0002439010800390108610D010800000000AE
+:103400000000891112239B322446AD573665BF74E4
+:10341000488CC19D5AAFD3BE6CCAE5DB7EE9F7F894
+:103420008110080193331A22A5562C47B7753E64C4
+:10343000C99C408DDBBF52AEEDDA64CBFFF976E874
+:1034400002218B30100299132667AF763444BD55A4
+:103450004AADC3BC588ED19F6EEBE7FA7CC8F5D954
+:1034600083310A2091121803A7772E66B5543C4584
+:10347000CBBD42ACD99E508FEFFB66EAFDD874C934
+:1034800004428D5316619F702004A9153227BB3664
+:103490004CCEC5DF5EEDD7FC6888E1997AABF3BA14
+:1034A00085520C4397711E60A1142805B3373A2644
+:1034B000CDDE44CFDFFD56ECE9986089FBBB72AAF4
+:1034C00006638F7214409D512225AB343006B91724
+:1034D0004EEFC7FE5CCCD5DD6AA9E3B8788AF19BD4
+:1034E00087730E6295501C41A3352A24B116380704
+:1034F000CFFF46EEDDDC54CDEBB962A8F99A708BB4
+:10350000088481951AA793B62CC2A5D33EE1B7F0E3
+:103510004008C919522BDB3A644EED5F766DFF7C93
+:10352000899400859BB712A6ADD224C3BFF136E0C3
+:10353000C1184809D33B5A2AE55E6C4FF77D7E6C73
+:103540000AA583B4188691972EE3A7F23CC0B5D1A3
+:103550004229CB38500AD91B666FEF7E744CFD5D53
+:103560008BB502A499961087AFF326E2BDD034C183
+:10357000C3394A28D11A580BE77F6E6EF55C7C4D33
+:103580000CC685D71EE597F42880A1913AA3B3B263
+:10359000444ACD5B5669DF78600CE91D722FFB3E13
+:1035A0008DD604C79FF516E4A9902081BBB332A243
+:1035B000C55A4C4BD7795E68E11C680DF33F7A2EF3
+:1035C0000EE787F61CC495D52AA1A3B03882B19323
+:1035D000466BCF7A5448DD59622DEB3C700EF91FD3
+:1035E0008FF706E69DD414C5ABB122A0B992308303
+:1035F000C77B4E6AD5585C49E33D6A2CF11E780FB3
+:10360000000000000000000030313233343536371E
+:103610003839414243444546403058003031323316
+:103620003435363738396162636465664030780016
+:10363000040000080000000000000002000100007B
+:1036400010000000000000004FBB610567ACDD3FCB
+:10365000182D4454FB21E93F9BF681D20B73EF3FB9
+:10366000182D4454FB21F93FE2652F227F2B7A3C31
+:10367000075C143326A6813CBDCBF07A8807703CEA
+:10368000075C143326A6913CC4EB98999999C9BF5D
+:10369000711623FEC671BCBF6D9A74AFF2B0B3BF92
+:1036A0009AFDDE522DDEADBF2F6C6A2C44B4A2BF52
+:1036B0000D5555555555D53FFF8300922449C23FBE
+:1036C0006E204CC5CD45B73F513DD0A0660DB13FF2
+:1036D000EB0D76244B7BA93F11DA22E33AAD903F04
+:1036E0000000000000000000000000006E83F9A24E
+:1036F0002915444ED15727FCC0DD34F5999562DB7E
+:103700004190433CAB6351FE303132333435363770
+:103710003839616263646566787000303132333401
+:103720003536373839414243444546585000000049
+:1037300002400000000000A0000000000540000062
+:10374000000000C8000000000C4000000000409C89
+:1037500000000000194000000020BCBE0000000076
+:1037600034400000BFC91B8E00000004B5400000BB
+:10377000504BCFD06607E2CF010000006C41000043
+:103780003E8251AADFEEA73401000000D9420000BA
+:10379000DCB5A0E23A301F97FFFFFFFFB445000001
+:1037A000FD25A0C8E9A3C14FFFFFFFFFFF3F0000B9
+:1037B0000000008000000000FF3F000000000080CB
+:1037C0000000000064656661756C745461736B0081
+:1037D0000D0A68656C703A0D0A204C697374732089
+:1037E000616C6C20746865207265676973746572BA
+:1037F000656420636F6D6D616E64730D0A0D0A0060
+:1038000068656C7000000000496E636F72726563DA
+:103810007420636F6D6D616E6420706172616D659F
+:103820007465722873292E2020456E7465722022DB
+:1038300068656C702220746F20766965772061203E
+:103840006C697374206F6620617661696C61626C6B
+:103850006520636F6D6D616E64732E0D0A0D0A0035
+:10386000436F6D6D616E64206E6F74207265636F5F
+:10387000676E697365642E2020456E74657220271B
+:1038800068656C702720746F2076696577206120E9
+:103890006C697374206F6620617661696C61626C1B
+:1038A0006520636F6D6D616E64732E0D0A0D0A00E5
+:1038B0005461736B5F496E697400000072630000AD
+:1038C000617474695F657374690000007465737472
+:1038D00000000000636C69006D6F6E69746F7200A8
+:1038E000636D64006374726C5F6C65670000000058
+:1038F0006374726C5F6368617373697300000000C6
+:1039000068746F703A20E698BEE7A4BA467265659F
+:1039100052544F53E4BBBBE58AA1E78AB6E68081E7
+:103920005C720A0068746F7000000000883A010839
+:10393000000000205803000008030008F43B0108C1
+:10394000000000244405000008030008F43B0108BF
+:1039500058030020B8070100640300081C000000A1
+:1039600043000000F8FFFFFF0C0000000E00000005
+:103970000F0000002E0000001001000043000000B6
+:10398000F8FFFFFF00404040404040404040414180
+:103990004141414040404040404040404040404024
+:1039A00040404040400502020202020202020202BE
+:1039B00002020202022020202020202020202002BB
+:1039C000020202020202909090909090101010104B
+:1039D00010101010101010101010101010101010E7
+:1039E000020202020202888888888888080808087B
+:1039F0000808080808080808080808080808080847
+:103A0000020202024000000000000000000000006E
+:103A100000000000000000000000000000000000A6
+:103A20000000000000000000000000000000000096
+:103A30000000000000000000000000000000000086
+:103A40000000000000000000000000000000000076
+:103A50000000000000000000000000000000000066
+:103A60000000000000000000000000000000000056
+:103A70000000000000000000000000000000000046
+:103A80000000000000000000811389E91B08B90450
+:103A90001AC5041AE1041301EA1B0869081A9504FF
+:103AA0004117040309041201140202021640FCFF2C
+:103AB000B82226020102030114050F0C1C01071095
+:103AC0001721031A1A0313A9321B08A3041A9F040F
+:103AD0001ACD041AE104193F1182103C90D003045E
+:103AE0003114810182130A0629532A40241C090239
+:103AF000436F1125C03209041B01020B1305241664
+:103B00001001052401180901042402020524068479
+:103B100015058203081C100904A5320A2E070501A9
+:103B20000240072A810711136DE41408D9E24C08FA
+:103B3000D7E5D01369E31B0825101A9B04C11AEDC1
+:103B4000181AAD041A2D301AA10801781AAA01C159
+:103B500017022B073DB80182200C37A031019CE5EC
+:103B6000CDCCCC3D2B803F1463010225295C0F3E58
+:103B7000482F40C00E8CF8C1D7A3A840295C17413C
+:103B8000E8C01F42C3F59040713D8AC09377FEC1E3
+:103B90007B142E4066662E418C311A425C8FCA40DF
+:103BA000040B224A410C6D333333BF78290C256650
+:103BB0006626C00B1920C0181A3F0C1A400C2A4068
+:103BC0000C59240A16BF1828093255B03DCDCC4CEB
+:103BD0003E041CC3F548045AA8F01A80243904197D
+:103BE000687904691009120859040110CB20414476
+:103BF000A172010001FF01FF01FF01FF01FF014967
:04000005080002CD20
:00000001FF
diff --git a/User/bsp/uart.c b/User/bsp/uart.c
index 23f8b1e..306dee5 100644
--- a/User/bsp/uart.c
+++ b/User/bsp/uart.c
@@ -16,6 +16,8 @@ static BSP_UART_t UART_Get(UART_HandleTypeDef *huart) {
if (huart->Instance == USART3)
return BSP_UART_RIGHT_LEG;
if (huart->Instance == USART10)
+ return BSP_UART_IMU_N100;
+ if (huart->Instance == UART7)
return BSP_UART_AI;
// else if (huart->Instance == USARTX)
// return BSP_UART_XXX;
@@ -114,6 +116,8 @@ UART_HandleTypeDef *BSP_UART_GetHandle(BSP_UART_t uart) {
case BSP_UART_RIGHT_LEG:
return &huart3;
case BSP_UART_AI:
+ return &huart7;
+ case BSP_UART_IMU_N100:
return &huart10;
// case BSP_UART_XXX:
// return &huartX;
diff --git a/User/bsp/uart.h b/User/bsp/uart.h
index 0b51df2..014f00a 100644
--- a/User/bsp/uart.h
+++ b/User/bsp/uart.h
@@ -20,6 +20,7 @@ typedef enum {
BSP_UART_DR16,
BSP_UART_LEFT_LEG,
BSP_UART_RIGHT_LEG,
+ BSP_UART_IMU_N100,
BSP_UART_AI,
/*BSP_UART_XXX*/
BSP_UART_NUM,
diff --git a/User/component/cmd.c b/User/component/cmd.c
index 9d1898b..5728d8f 100644
--- a/User/component/cmd.c
+++ b/User/component/cmd.c
@@ -53,8 +53,8 @@ static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd, float dt_sec) {
break;
}
/* 将操纵杆的对应值转换为底盘的控制向量和云台变化的欧拉角 */
- cmd->chassis.ctrl_vec.vx = rc->ch_l_x;
- cmd->chassis.ctrl_vec.vy = rc->ch_l_y;
+ cmd->chassis.ctrl_vec.vx = rc->ch_l_y;
+ cmd->chassis.ctrl_vec.vy = rc->ch_l_x;
cmd->chassis.ctrl_vec.wz = rc->ch_r_x;
cmd->chassis.delta_hight = rc->ch_res;
diff --git a/User/component/crc16.c b/User/component/crc16.c
new file mode 100644
index 0000000..01cb26f
--- /dev/null
+++ b/User/component/crc16.c
@@ -0,0 +1,35 @@
+/*
+ N100陀螺仪包头crc16校验
+*/
+
+#include
+
+// CRC16 查找表(多项式 0x1021,初始值 0x0000)
+static const uint16_t CRC16Table[256] = {
+ 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
+ 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
+ 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
+ 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
+ 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
+ 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
+ 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
+ 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
+ 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
+ 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
+ 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
+ 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
+ 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
+ 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
+ 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
+ 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
+};
+
+// 计算 CRC16 校验值
+uint16_t crc16_calc(const uint8_t *data, uint8_t len) {
+ uint16_t crc = 0x0000;
+ for (uint8_t i = 0; i < len; i++) {
+ uint8_t index = (crc >> 8) ^ data[i];
+ crc = (crc << 8) ^ CRC16Table[index];
+ }
+ return crc;
+}
\ No newline at end of file
diff --git a/User/component/crc16.h b/User/component/crc16.h
new file mode 100644
index 0000000..3f1a8e0
--- /dev/null
+++ b/User/component/crc16.h
@@ -0,0 +1,17 @@
+/*
+ N100陀螺仪包头crc16校验
+*/
+
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+
+uint16_t crc16_calc(const uint8_t *data, uint8_t len);
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/User/component/crc8.c b/User/component/crc8.c
new file mode 100644
index 0000000..9deabac
--- /dev/null
+++ b/User/component/crc8.c
@@ -0,0 +1,33 @@
+/*
+ N100陀螺仪包头crc8校验
+*/
+#include
+#include "crc8.h"
+// CRC8 查找表(多项式 0x07,初始值 0x00)
+static const uint8_t CRC8Table[256] = {
+ 0x00, 0x5E, 0xBC, 0xE2, 0x61, 0x3F, 0xDD, 0x83, 0xC2, 0x9C, 0x7E, 0x20, 0xA3, 0xFD, 0x1F, 0x41,
+ 0x9D, 0xC3, 0x21, 0x7F, 0xFC, 0xA2, 0x40, 0x1E, 0x5F, 0x01, 0xE3, 0xBD, 0x3E, 0x60, 0x82, 0xDC,
+ 0x23, 0x7D, 0x9F, 0xC1, 0x42, 0x1C, 0xFE, 0xA0, 0xE1, 0xBF, 0x5D, 0x03, 0x80, 0xDE, 0x3C, 0x62,
+ 0xBE, 0xE0, 0x02, 0x5C, 0xDF, 0x81, 0x63, 0x3D, 0x7C, 0x22, 0xC0, 0x9E, 0x1D, 0x43, 0xA1, 0xFF,
+ 0x46, 0x18, 0xFA, 0xA4, 0x27, 0x79, 0x9B, 0xC5, 0x84, 0xDA, 0x38, 0x66, 0xE5, 0xBB, 0x59, 0x07,
+ 0xDB, 0x85, 0x67, 0x39, 0xBA, 0xE4, 0x06, 0x58, 0x19, 0x47, 0xA5, 0xFB, 0x78, 0x26, 0xC4, 0x9A,
+ 0x65, 0x3B, 0xD9, 0x87, 0x04, 0x5A, 0xB8, 0xE6, 0xA7, 0xF9, 0x1B, 0x45, 0xC6, 0x98, 0x7A, 0x24,
+ 0xF8, 0xA6, 0x44, 0x1A, 0x99, 0xC7, 0x25, 0x7B, 0x3A, 0x64, 0x86, 0xD8, 0x5B, 0x05, 0xE7, 0xB9,
+ 0x8C, 0xD2, 0x30, 0x6E, 0xED, 0xB3, 0x51, 0x0F, 0x4E, 0x10, 0xF2, 0xAC, 0x2F, 0x71, 0x93, 0xCD,
+ 0x11, 0x4F, 0xAD, 0xF3, 0x70, 0x2E, 0xCC, 0x92, 0xD3, 0x8D, 0x6F, 0x31, 0xB2, 0xEC, 0x0E, 0x50,
+ 0xAF, 0xF1, 0x13, 0x4D, 0xCE, 0x90, 0x72, 0x2C, 0x6D, 0x33, 0xD1, 0x8F, 0x0C, 0x52, 0xB0, 0xEE,
+ 0x32, 0x6C, 0x8E, 0xD0, 0x53, 0x0D, 0xEF, 0xB1, 0xF0, 0xAE, 0x4C, 0x12, 0x91, 0xCF, 0x2D, 0x73,
+ 0xCA, 0x94, 0x76, 0x28, 0xAB, 0xF5, 0x17, 0x49, 0x08, 0x56, 0xB4, 0xEA, 0x69, 0x37, 0xD5, 0x8B,
+ 0x57, 0x09, 0xEB, 0xB5, 0x36, 0x68, 0x8A, 0xD4, 0x95, 0xCB, 0x29, 0x77, 0xF4, 0xAA, 0x48, 0x16,
+ 0xE9, 0xB7, 0x55, 0x0B, 0x88, 0xD6, 0x34, 0x6A, 0x2B, 0x75, 0x97, 0xC9, 0x4A, 0x14, 0xF6, 0xA8,
+ 0x74, 0x2A, 0xC8, 0x96, 0x15, 0x4B, 0xA9, 0xF7, 0xB6, 0xE8, 0x0A, 0x54, 0xD7, 0x89, 0x6B, 0x35,
+};
+
+// 计算 CRC8 校验值
+uint8_t crc8_calc(const uint8_t *data, uint8_t len) {
+ uint8_t crc = 0x00;
+ for (uint8_t i = 0; i < len; i++) {
+ crc = CRC8Table[crc ^ data[i]];
+ }
+ return crc;
+}
\ No newline at end of file
diff --git a/User/component/crc8.h b/User/component/crc8.h
new file mode 100644
index 0000000..d398d7a
--- /dev/null
+++ b/User/component/crc8.h
@@ -0,0 +1,17 @@
+/*
+ N100陀螺仪包头crc8校验
+*/
+
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+
+uint8_t crc8_calc(const uint8_t *data, uint8_t len);
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/User/component/kinematics.c b/User/component/kinematics.c
index f2a50db..c281802 100644
--- a/User/component/kinematics.c
+++ b/User/component/kinematics.c
@@ -3,9 +3,35 @@
*/
#include "filter.h"
-
+#include
#include "kinematics.h"
+static float q1_ik(float py, float pz, float l1) {
+ float q1;
+ float L = sqrtf(py*py + pz*pz - l1*l1);
+ q1 = atan2f(pz*l1 + py*L, py*l1 - pz*L);
+ return q1;
+}
+
+static float q3_ik(float b3z, float b4z, float b) {
+ float q3, temp;
+ temp = (b3z*b3z + b4z*b4z - b*b) / (2.0f * fabsf(b3z * b4z));
+ if (temp > 1.0f) temp = 1.0f;
+ if (temp < -1.0f) temp = -1.0f;
+ q3 = acosf(temp);
+ q3 = -(M_PI - q3);
+ return q3;
+}
+
+static float q2_ik(float q1, float q3, float px, float py, float pz, float b3z, float b4z) {
+ float a1 = py * sinf(q1) - pz * cosf(q1);
+ float a2 = px;
+ float m1 = b4z * sinf(q3);
+ float m2 = b3z + b4z * cosf(q3);
+ float q2 = atan2f(m1 * a1 + m2 * a2, m1 * a2 - m2 * a1);
+ return q2;
+}
+
int8_t Kinematics_RealFeedback(Kinematics_JointData_t *real, const Kinematics_JointData_t *in, float ratio, float joint_zero){
real->Pos = (in->Pos-joint_zero) / ratio;
@@ -23,27 +49,30 @@ int8_t Kinematics_RealOutput(const Kinematics_JointCMD_t *real, Kinematics_Joint
return 0;
}
-/**
- * @brief 单腿正运动学
- * @param theta[3] 关节角度数组(单位:弧度):[hip, thigh, calf]
- * @param leg_params 单腿机械参数(长度)
- * @param foot_out 足端位置输出 [x, y, z](单位:米)
- */
-// void Leg_ForwardKinematics(const float theta[3], const joint_params *leg_params, float foot_out[3]) {
-// float l1 = leg_params->named.lf_hip; // 髋关节到大腿长度
-// float l2 = leg_params->named.lf_thigh; // 大腿长度
-// float l3 = leg_params->named.lf_calf; // 小腿长度
+void Kinematics_ForwardKinematics(const float theta_in[3], const Kinematics_LinkLength_t *leg_params, float foot_out[3], Kinematics_Sign_t *sign) {
+ float l1 = leg_params->hip * sign->hip;
+ float l2 = -leg_params->thigh;
+ float l3 = -leg_params->calf;
-// float t1 = theta[0]; // 髋关节侧摆(绕y轴)
-// float t2 = theta[1]; // 髋关节前后
-// float t3 = theta[2]; // 膝关节
+ float q1 = theta_in[0];
+ float q2 = theta_in[1] * sign->thigh;
+ float q3 = theta_in[2] * sign->calf;
-// // 末端位置
-// float leg_proj = l2 * cosf(t2) + l3 * cosf(t2 + t3);
-// foot_out[0] = cosf(t1) * leg_proj + l1 * cosf(t1); // x
-// foot_out[1] = sinf(t1) * leg_proj + l1 * sinf(t1); // y
-// foot_out[2] = l2 * sinf(t2) + l3 * sinf(t2 + t3); // z
-// }
+ float s1 = sinf(q1);
+ float s2 = sinf(q2);
+ float s3 = sinf(q3);
+
+ float c1 = cosf(q1);
+ float c2 = cosf(q2);
+ float c3 = cosf(q3);
+
+ float c23 = c2 * c3 - s2 * s3;
+ float s23 = s2 * c3 + c2 * s3;
+
+ foot_out[0] = l3 * s23 + l2 * s2;
+ foot_out[1] = -l3 * s1 * c23 + l1 * c1 - l2 * c2 * s1;
+ foot_out[2] = l3 * c1 * c23 + l1 * s1 + l2 * c1 * c2;
+}
/**
* @brief 单腿逆运动学
@@ -52,34 +81,28 @@ int8_t Kinematics_RealOutput(const Kinematics_JointCMD_t *real, Kinematics_Joint
* @param theta_out 关节角度输出数组(单位:弧度):[hip, thigh, calf]
* @return 0成功,-1目标不可达
*/
-// int Leg_InverseKinematics(const float foot_in[3], const joint_params *leg_params, float theta_out[3]) {
-// float l1 = leg_params->named.lf_hip;
-// float l2 = leg_params->named.lf_thigh;
-// float l3 = leg_params->named.lf_calf;
+int8_t Kinematics_InverseKinematics(const float foot_in[3], const Kinematics_LinkLength_t *leg_params, float theta_out[3], Kinematics_Sign_t *sign) {
+ float px = foot_in[0];
+ float py = foot_in[1];
+ float pz = foot_in[2];
-// float x = foot_in[0];
-// float y = foot_in[1];
-// float z = foot_in[2];
+ float b2y = leg_params->hip * sign->hip;
+ float b3z = -leg_params->thigh;
+ float b4z = -leg_params->calf;
+ float a = leg_params->hip;
+ float c = sqrtf(px*px + py*py + pz*pz);
+ float b = sqrtf(c*c - a*a);
-// // 1. 先算髋关节侧摆角(绕y轴)
-// float r = sqrtf(x * x + y * y);
-// float t1 = atan2f(y, x); // 髋关节侧摆角:使用 atan2f,计
+ // 检查可达性
+ if (b != b) return -1; // NaN
+ if (b > fabsf(b3z) + fabsf(b4z)) return -1;
-// // 2. 去掉髋关节侧摆影响,得到在sagittal平面上的投影
-// float xp = r - l1;
-// float zp = z;
+ float q1 = q1_ik(py, pz, b2y);
+ float q3 = q3_ik(b3z, b4z, b);
+ float q2 = q2_ik(q1, q3, px, py, pz, b3z, b4z);
-// // 3. 逆解余下两个关节
-// float D = (xp * xp + zp * zp - l2 * l2 - l3 * l3) / (2 * l2 * l3);
-// if (D < -1.0f || D > 1.0f) return -1; // 不可达
-
-// float t3 = atan2f(-sqrtf(1 - D * D), D); // 膝关节
-// float k1 = l2 + l3 * cosf(t3);
-// float k2 = l3 * sinf(t3);
-// float t2 = atan2f(zp, xp) - atan2f(k2, k1);
-
-// theta_out[0] = t1;
-// theta_out[1] = t2;
-// theta_out[2] = t3;
-// return 0;
-// }
\ No newline at end of file
+ theta_out[0] = q1;
+ theta_out[1] = q2 * sign->thigh;
+ theta_out[2] = q3 * sign->calf;
+ return 0;
+}
diff --git a/User/component/kinematics.h b/User/component/kinematics.h
index f28b0c1..5b01a65 100644
--- a/User/component/kinematics.h
+++ b/User/component/kinematics.h
@@ -24,6 +24,24 @@ typedef struct {
float K_W; // 关节速度系数(0-25.599)
} Kinematics_JointCMD_t;
+typedef struct {
+ float hip; // 髋关节长度(m)
+ float thigh; // 大腿长度(m)
+ float calf; // 小腿长度(m)
+} Kinematics_LinkLength_t;
+
+typedef struct {
+ float x;
+ float y;
+ float z;
+} Kinematics_LegOffset_t;
+
+typedef struct {
+ float hip;
+ float thigh;
+ float calf;
+} Kinematics_Sign_t;
+
/**
* @brief 计算实际反馈
@@ -44,6 +62,25 @@ int8_t Kinematics_RealFeedback(Kinematics_JointData_t *real, const Kinematics_Jo
int8_t Kinematics_RealOutput(const Kinematics_JointCMD_t *real, Kinematics_JointCMD_t *out, float ratio, float joint_zero);
+/**
+ * @brief 单腿正运动学
+ * @param theta_in 关节角度输入数组(单位:弧度):[hip, thigh, calf]
+ * @param leg_params 单腿机械参数(长度)
+ * @param foot_out 足端位置输出 [x, y, z](单位:米)
+ * @param side_sign 侧向标志(左前/左后为-1,右前/右后为1)
+ */
+void Kinematics_ForwardKinematics(const float theta_in[3], const Kinematics_LinkLength_t *leg_params, float foot_out[3], Kinematics_Sign_t *sign);
+
+/**
+ * @brief 单腿逆运动学
+ * @param foot_in 足端目标位置 [x, y, z](单位:米)
+ * @param leg_params 单腿机械参数(长度)
+ * @param theta_out 关节角度输出数组(单位:弧度):[hip, thigh, calf]
+ * @param side_sign 侧向标志(左前/左后为-1,右前/右后为1)
+ * @return 0成功,-1目标不可达
+ */
+int8_t Kinematics_InverseKinematics(const float foot_in[3], const Kinematics_LinkLength_t *leg_params, float theta_out[3], Kinematics_Sign_t *sign);
+
#ifdef __cplusplus
}
diff --git a/User/component/limiter.c b/User/component/limiter.c
new file mode 100644
index 0000000..d86d45f
--- /dev/null
+++ b/User/component/limiter.c
@@ -0,0 +1,27 @@
+/*
+ 限制器
+*/
+
+#include "limiter.h"
+
+#include
+#include
+
+#include "component/user_math.h"
+
+int8_t Limit_ChassicOutput(const float feedback_pos ,float *out_pos, float max_speed, float max_angle, float min_angle){
+
+ // 限制位置变化速度
+ if (*out_pos - feedback_pos > max_speed) {
+ *out_pos = feedback_pos + max_speed;
+ } else if (*out_pos - feedback_pos < -max_speed) {
+ *out_pos = feedback_pos - max_speed;
+ }
+ // 限制角度范围
+ if (*out_pos > max_angle) {
+ *out_pos = max_angle;
+ } else if (*out_pos < min_angle) {
+ *out_pos = min_angle;
+ }
+ return 0; // 成功
+}
\ No newline at end of file
diff --git a/User/component/limiter.h b/User/component/limiter.h
new file mode 100644
index 0000000..c584ff1
--- /dev/null
+++ b/User/component/limiter.h
@@ -0,0 +1,20 @@
+/*
+ 限制器
+*/
+
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+#include
+
+
+int8_t Limit_ChassicOutput(const float feedback_pos ,float *out_pos,
+ float max_speed, float max_angle, float min_angle);
+
+#ifdef __cplusplus
+}
+#endif
\ No newline at end of file
diff --git a/User/component/unitreeLeg.cpp b/User/component/unitreeLeg.cpp
new file mode 100755
index 0000000..3c5f443
--- /dev/null
+++ b/User/component/unitreeLeg.cpp
@@ -0,0 +1,175 @@
+/**********************************************************************
+ Copyright (c) 2020-2023, Unitree Robotics.Co.Ltd. All rights reserved.
+***********************************************************************/
+#include "common/unitreeLeg.h"
+#include
+
+
+/************************/
+/*******QuadrupedLeg*****/
+/************************/
+QuadrupedLeg::QuadrupedLeg(int legID, float abadLinkLength, float hipLinkLength,
+ float kneeLinkLength, Vec3 pHip2B)
+ :_abadLinkLength(abadLinkLength),
+ _hipLinkLength(hipLinkLength),
+ _kneeLinkLength(kneeLinkLength),
+ _pHip2B(pHip2B){
+ if (legID == 0 || legID == 2)
+ _sideSign = -1;
+ else if (legID == 1 || legID == 3)
+ _sideSign = 1;
+ else{
+ std::cout << "Leg ID incorrect!" << std::endl;
+ exit(-1);
+ }
+}
+
+// Forward Kinematics
+Vec3 QuadrupedLeg::calcPEe2H(Vec3 q){
+ float l1 = _sideSign * _abadLinkLength;
+ float l2 = -_hipLinkLength;
+ float l3 = -_kneeLinkLength;
+
+ float s1 = std::sin(q(0));
+ float s2 = std::sin(q(1));
+ float s3 = std::sin(q(2));
+
+ float c1 = std::cos(q(0));
+ float c2 = std::cos(q(1));
+ float c3 = std::cos(q(2));
+
+ float c23 = c2 * c3 - s2 * s3;
+ float s23 = s2 * c3 + c2 * s3;
+
+ Vec3 pEe2H;
+
+ pEe2H(0) = l3 * s23 + l2 * s2;
+ pEe2H(1) = -l3 * s1 * c23 + l1 * c1 - l2 * c2 * s1;
+ pEe2H(2) = l3 * c1 * c23 + l1 * s1 + l2 * c1 * c2;
+
+ return pEe2H;
+}
+
+// Forward Kinematics
+Vec3 QuadrupedLeg::calcPEe2B(Vec3 q){
+ return _pHip2B + calcPEe2H(q);
+}
+
+// Derivative Forward Kinematics
+Vec3 QuadrupedLeg::calcVEe(Vec3 q, Vec3 qd){
+ return calcJaco(q) * qd;
+}
+
+// Inverse Kinematics
+Vec3 QuadrupedLeg::calcQ(Vec3 pEe, FrameType frame){
+ Vec3 pEe2H;
+ if(frame == FrameType::HIP)
+ pEe2H = pEe;
+ else if(frame == FrameType::BODY)
+ pEe2H = pEe - _pHip2B;
+ else{
+ std::cout << "[ERROR] The frame of QuadrupedLeg::calcQ can only be HIP or BODY!" << std::endl;
+ exit(-1);
+ }
+
+ float q1, q2, q3;
+ Vec3 qResult;
+ float px, py, pz;
+ float b2y, b3z, b4z, a, b, c;
+
+ px = pEe2H(0);
+ py = pEe2H(1);
+ pz = pEe2H(2);
+
+ b2y = _abadLinkLength * _sideSign;
+ b3z = -_hipLinkLength;
+ b4z = -_kneeLinkLength;
+ a = _abadLinkLength;
+ c = sqrt(pow(px, 2) + pow(py, 2) + pow(pz, 2)); // whole length
+ b = sqrt(pow(c, 2) - pow(a, 2)); // distance between shoulder and footpoint
+
+ q1 = q1_ik(py, pz, b2y);
+ q3 = q3_ik(b3z, b4z, b);
+ q2 = q2_ik(q1, q3, px, py, pz, b3z, b4z);
+
+ qResult(0) = q1;
+ qResult(1) = q2;
+ qResult(2) = q3;
+
+ return qResult;
+}
+
+// Derivative Inverse Kinematics
+Vec3 QuadrupedLeg::calcQd(Vec3 q, Vec3 vEe){
+ return calcJaco(q).inverse() * vEe;
+}
+
+// Derivative Inverse Kinematics
+Vec3 QuadrupedLeg::calcQd(Vec3 pEe, Vec3 vEe, FrameType frame){
+ Vec3 q = calcQ(pEe, frame);
+ return calcJaco(q).inverse() * vEe;
+}
+
+// Inverse Dynamics
+Vec3 QuadrupedLeg::calcTau(Vec3 q, Vec3 force){
+ return calcJaco(q).transpose() * force;
+}
+
+// Jacobian Matrix
+Mat3 QuadrupedLeg::calcJaco(Vec3 q){
+ Mat3 jaco;
+
+ float l1 = _abadLinkLength * _sideSign;
+ float l2 = -_hipLinkLength;
+ float l3 = -_kneeLinkLength;
+
+ float s1 = std::sin(q(0));
+ float s2 = std::sin(q(1));
+ float s3 = std::sin(q(2));
+
+ float c1 = std::cos(q(0));
+ float c2 = std::cos(q(1));
+ float c3 = std::cos(q(2));
+
+ float c23 = c2 * c3 - s2 * s3;
+ float s23 = s2 * c3 + c2 * s3;
+ jaco(0, 0) = 0;
+ jaco(1, 0) = -l3 * c1 * c23 - l2 * c1 * c2 - l1 * s1;
+ jaco(2, 0) = -l3 * s1 * c23 - l2 * c2 * s1 + l1 * c1;
+ jaco(0, 1) = l3 * c23 + l2 * c2;
+ jaco(1, 1) = l3 * s1 * s23 + l2 * s1 * s2;
+ jaco(2, 1) = -l3 * c1 * s23 - l2 * c1 * s2;
+ jaco(0, 2) = l3 * c23;
+ jaco(1, 2) = l3 * s1 * s23;
+ jaco(2, 2) = -l3 * c1 * s23;
+
+ return jaco;
+}
+
+float QuadrupedLeg::q1_ik(float py, float pz, float l1){
+ float q1;
+ float L = sqrt(pow(py,2)+pow(pz,2)-pow(l1,2));
+ q1 = atan2(pz*l1+py*L, py*l1-pz*L);
+ return q1;
+}
+
+float QuadrupedLeg::q3_ik(float b3z, float b4z, float b){
+ float q3, temp;
+ temp = (pow(b3z, 2) + pow(b4z, 2) - pow(b, 2))/(2*fabs(b3z*b4z));
+ if(temp>1) temp = 1;
+ if(temp<-1) temp = -1;
+ q3 = acos(temp);
+ q3 = -(M_PI - q3); //0~180
+ return q3;
+}
+
+float QuadrupedLeg::q2_ik(float q1, float q3, float px, float py, float pz, float b3z, float b4z){
+ float q2, a1, a2, m1, m2;
+
+ a1 = py*sin(q1) - pz*cos(q1);
+ a2 = px;
+ m1 = b4z*sin(q3);
+ m2 = b3z + b4z*cos(q3);
+ q2 = atan2(m1*a1+m2*a2, m1*a2-m2*a1);
+ return q2;
+}
diff --git a/User/component/user_math.c b/User/component/user_math.c
index 1fceac2..b483048 100644
--- a/User/component/user_math.c
+++ b/User/component/user_math.c
@@ -130,3 +130,4 @@ void VerifyFailed(const char *file, uint32_t line) {
__NOP();
}
}
+
diff --git a/User/device/ai.c b/User/device/ai.c
new file mode 100644
index 0000000..6ee1e3e
--- /dev/null
+++ b/User/device/ai.c
@@ -0,0 +1,152 @@
+/*
+AI
+*/
+
+/* Includes ----------------------------------------------------------------- */
+#include "ai.h"
+
+#include
+
+#include "bsp\delay.h"
+#include "bsp\uart.h"
+#include "component\crc16.h"
+#include "component\crc8.h"
+#include "component\user_math.h"
+#include "component\filter.h"
+
+
+/* Private define ----------------------------------------------------------- */
+#define AI_LEN_RX_BUFF (sizeof(Protocol_DownPackage_t))
+
+/* Private macro ------------------------------------------------------------ */
+/* Private typedef ---------------------------------------------------------- */
+/* Private variables -------------------------------------------------------- */
+static volatile uint32_t drop_message = 0;
+
+static uint8_t rxbuf[AI_LEN_RX_BUFF];
+
+static bool inited = false;
+
+static osThreadId_t thread_alert;
+
+/* Private function -------------------------------------------------------- */
+
+static void Ai_RxCpltCallback(void) {
+ osThreadFlagsSet(thread_alert, SIGNAL_AI_RAW_REDY);
+}
+
+static void Ai_IdleLineCallback(void) {
+ osThreadFlagsSet(thread_alert, SIGNAL_AI_RAW_REDY);
+}
+
+/* Exported functions ------------------------------------------------------- */
+int8_t AI_Init(AI_t *ai) {
+ UNUSED(ai);
+ ASSERT(ai);
+ if (inited) return DEVICE_ERR_INITED;
+ VERIFY((thread_alert = osThreadGetId()) != NULL);
+
+ BSP_UART_RegisterCallback(BSP_UART_AI, BSP_UART_RX_CPLT_CB,
+ Ai_RxCpltCallback);
+ BSP_UART_RegisterCallback(BSP_UART_AI, BSP_UART_IDLE_LINE_CB,
+ Ai_IdleLineCallback);
+
+ inited = true;
+ return 0;
+}
+
+int8_t AI_Restart(void) {
+ __HAL_UART_DISABLE(BSP_UART_GetHandle(BSP_UART_AI));
+ __HAL_UART_ENABLE(BSP_UART_GetHandle(BSP_UART_AI));
+ return DEVICE_OK;
+}
+
+int8_t AI_StartReceiving(AI_t *ai) {
+ UNUSED(ai);
+ if (HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_AI), rxbuf,
+ AI_LEN_RX_BUFF) == HAL_OK)
+ return DEVICE_OK;
+ return DEVICE_ERR;
+}
+
+bool AI_WaitDmaCplt(void) {
+ return (osThreadFlagsWait(SIGNAL_AI_RAW_REDY, osFlagsWaitAll, 0) ==
+ SIGNAL_AI_RAW_REDY);
+}
+
+int8_t AI_ParseHost(AI_t *ai) {
+ if (!CRC16_Verify((const uint8_t *)&(rxbuf), sizeof(ai->from_host)))
+ goto error;
+ ai->ai_online = true;
+ memcpy(&(ai->from_host), rxbuf, sizeof(ai->from_host));
+ memset(rxbuf, 0, AI_LEN_RX_BUFF);
+ return DEVICE_OK;
+
+error:
+ drop_message++;
+ return DEVICE_ERR;
+}
+
+void AI_PackCmd(AI_t *ai, CMD_Host_t *cmd_host) {
+ cmd_host->gimbal_delta.yaw = ai->from_host.data.gimbal.yaw;
+ cmd_host->gimbal_delta.pit = ai->from_host.data.gimbal.pit;
+ cmd_host->fire = (ai->from_host.data.notice & AI_NOTICE_FIRE);
+ cmd_host->chassis_move_vec.vx = ai->from_host.data.chassis_move_vec.vx;
+ cmd_host->chassis_move_vec.vy = ai->from_host.data.chassis_move_vec.vy;
+ cmd_host->chassis_move_vec.wz = ai->from_host.data.chassis_move_vec.wz;
+}
+
+int8_t AI_HandleOffline(AI_t *ai, CMD_Host_t *cmd_host) {
+ if (ai == NULL) return DEVICE_ERR_NULL;
+ if (cmd_host == NULL) return DEVICE_ERR_NULL;
+ ai->ai_online = false;
+ memset(&(ai->from_host), 0, sizeof(ai->from_host));
+ memset(cmd_host, 0, sizeof(*cmd_host));
+ return 0;
+}
+
+int8_t AI_PackMCU(AI_t *ai, const AHRS_Quaternion_t *quat) {
+ ai->to_host.mcu.id = AI_ID_MCU;
+ memcpy((void *)&(ai->to_host.mcu.package.data.quat), (const void *)quat,
+ sizeof(*quat));
+ ai->to_host.mcu.package.data.notice = 0;
+ if (ai->status == AI_STATUS_AUTOAIM)
+ ai->to_host.mcu.package.data.notice |= AI_NOTICE_AUTOAIM;
+ else if (ai->status == AI_STATUS_HITSWITCH)
+ ai->to_host.mcu.package.data.notice |= AI_NOTICE_HITBUFF;
+ else if (ai->status == AI_STATUS_AUTOMATIC)
+ ai->to_host.mcu.package.data.notice |= AI_NOTICE_AUTOMATIC;
+
+ ai->to_host.mcu.package.crc16 = CRC16_Calc(
+ (const uint8_t *)&(ai->to_host.mcu.package),
+ sizeof(ai->to_host.mcu.package) - sizeof(uint16_t), CRC16_INIT);
+ return DEVICE_OK;
+}
+
+int8_t AI_PackRef(AI_t *ai, const Referee_ForAI_t *ref) {
+ (void)ref;
+ ai->to_host.ref.id = AI_ID_REF;
+ ai->to_host.ref.package.crc16 = CRC16_Calc(
+ (const uint8_t *)&(ai->to_host.ref.package),
+ sizeof(ai->to_host.ref.package) - sizeof(uint16_t), CRC16_INIT);
+ return DEVICE_OK;
+}
+
+int8_t AI_StartSend(AI_t *ai, bool ref_update) {
+ if (ref_update) {
+ if (HAL_UART_Transmit_DMA(
+ BSP_UART_GetHandle(BSP_UART_AI), (uint8_t *)&(ai->to_host),
+ sizeof(ai->to_host.ref) + sizeof(ai->to_host.mcu)) == HAL_OK)
+ return DEVICE_OK;
+ else
+ return DEVICE_ERR;
+ } else {
+ if (HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_AI),
+ (uint8_t *)&(ai->to_host.mcu),
+ sizeof(ai->to_host.mcu)) == HAL_OK)
+ return DEVICE_OK;
+ else
+ return DEVICE_ERR;
+ }
+}
+
diff --git a/User/device/ai.h b/User/device/ai.h
new file mode 100644
index 0000000..4434da3
--- /dev/null
+++ b/User/device/ai.h
@@ -0,0 +1,69 @@
+/*
+ AI
+*/
+
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ----------------------------------------------------------------- */
+#include
+#include
+#include
+
+#include "component\ahrs.h"
+#include "component\cmd.h"
+#include "component\user_math.h"
+#include "component\filter.h"
+#include "device\device.h"
+#include "device\referee.h"
+#include "protocol.h"
+
+/* Exported constants ------------------------------------------------------- */
+/* Exported macro ----------------------------------------------------------- */
+/* Exported types ----------------------------------------------------------- */
+
+typedef struct __packed {
+ uint8_t id;
+ Protocol_UpPackageReferee_t package;
+} AI_UpPackageReferee_t;
+
+typedef struct __packed {
+ uint8_t id;
+ Protocol_UpPackageMCU_t package;
+} AI_UpPackageMCU_t;
+
+typedef struct __packed {
+ osThreadId_t thread_alert;
+
+ Protocol_DownPackage_t from_host;
+
+ struct {
+ AI_UpPackageReferee_t ref;
+ AI_UpPackageMCU_t mcu;
+ } to_host;
+
+ CMD_AI_Status_t status;
+ bool ai_online;
+} AI_t;
+
+/* Exported functions prototypes -------------------------------------------- */
+int8_t AI_Init(AI_t *ai);
+int8_t AI_Restart(void);
+
+int8_t AI_StartReceiving(AI_t *ai);
+bool AI_WaitDmaCplt(void);
+int8_t AI_ParseHost(AI_t *ai);
+int8_t AI_HandleOffline(AI_t *ai, CMD_Host_t *cmd_host);
+int8_t AI_PackMCU(AI_t *ai, const AHRS_Quaternion_t *quat);
+int8_t AI_PackRef(AI_t *ai, const Referee_ForAI_t *ref);
+int8_t AI_StartSend(AI_t *ai, bool option);
+void AI_PackCmd(AI_t *ai, CMD_Host_t *cmd_host);
+#ifdef __cplusplus
+}
+#endif
+
+
+
diff --git a/User/device/bmi088.c b/User/device/bmi088.c
index e82cadf..b1f0736 100644
--- a/User/device/bmi088.c
+++ b/User/device/bmi088.c
@@ -365,5 +365,6 @@ int8_t BMI088_ParseGyro(BMI088_t *bmi088) {
float BMI088_GetUpdateFreq(BMI088_t *bmi088) {
(void)bmi088;
- return 400.0f;
+ return 200.0f;
}
+
diff --git a/User/device/device.h b/User/device/device.h
index f11fa6d..db37a9e 100644
--- a/User/device/device.h
+++ b/User/device/device.h
@@ -19,19 +19,12 @@ extern "C" {
#define SIGNAL_BMI088_GYRO_RAW_REDY (1u << 2)
#define SIGNAL_BMI088_ACCL_RAW_REDY (1u << 3)
-#define SIGNAL_DR16_RAW_REDY (1u << 4)
+#define SIGNAL_N100_NEW_DATA (1u << 4)
+#define SIGNAL_DR16_RAW_REDY (1u << 5)
-#define SIGNAL_GO_MOTOR_RECV (1u << 5)
+#define SIGNAL_GO_MOTOR_RECV (1u << 6)
-
-#define SIGNAL_IST8310_MAGN_NEW_DATA (1u << 8)
-#define SIGNAL_IST8310_MAGN_RAW_REDY (1u << 9)
-
-#define SIGNAL_REFEREE_RAW_REDY (1u << 10)
-#define SIGNAL_REFEREE_FAST_REFRESH_UI (1u << 11)
-#define SIGNAL_REFEREE_SLOW_REFRESH_UI (1u << 12)
-
#define SIGNAL_AI_RAW_REDY (1u << 14)
#ifdef __cplusplus
diff --git a/User/device/go copy.c b/User/device/go copy.c
deleted file mode 100644
index 50d8f7b..0000000
--- a/User/device/go copy.c
+++ /dev/null
@@ -1,118 +0,0 @@
-/*
- 四足机器人12个关节驱动
-*/
-
-/* Includes ----------------------------------------------------------------- */
-#include "bsp/uart.h"
-#include "go.h"
-
-#include
-#include
-
-
-#include "component/user_math.h"
-
-#include "cmsis_os2.h"
-
-static osSemaphoreId_t sem_left_rx = NULL;
-static osSemaphoreId_t sem_right_rx = NULL;
-
-/* Private define ----------------------------------------------------------- */
-
-
-/* Private macro ------------------------------------------------------------ */
-/* Private typedef ---------------------------------------------------------- */
-/* Private variables -------------------------------------------------------- */
-// static RIS_MotorData_t raw_left __attribute__ ((section(".AXI_SRAM")));
-static uint8_t raw_left_buff[16] __attribute__ ((section(".AXI_SRAM")));
-static uint8_t raw_right_buff[16] __attribute__ ((section(".AXI_SRAM")));
-// static RIS_MotorData_t raw_right __attribute__ ((section(".AXI_SRAM")));
-static MotorCmd_t motor_cmd __attribute__ ((section(".AXI_SRAM")));
-
-static osThreadId_t thread_alert;
-static GO_t *go_rx;
-static bool inited = false;
-
-/* Private function -------------------------------------------------------- */
-
-// static void GO_LeftRxCpltCallback(void) {
-// osMessageQueuePut(go_rx->msgq_raw, &raw_left_buff, 0, 0);
-// osSemaphoreRelease(sem_left_rx); // 通知接收完成
- // memset(raw_left_buff, 0, sizeof(raw_left_buff)); // 清空缓存区
- // HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_LEFT_LEG),
- // (uint8_t *)&raw_left, sizeof(RIS_MotorData_t));
-// }
-// static void GO_RightRxCpltCallback(void) {
-// osMessageQueuePut(go_rx->msgq_raw, &raw_right_buff, 0, 0);
-// osSemaphoreRelease(sem_right_rx); // 通知接收完成
- // memset(raw_right_buff, 0, sizeof(raw_right_buff)); // 清空缓存区
- // HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_RIGHT_LEG),
- // (uint8_t *)&raw_right, sizeof(RIS_MotorData_t));
-// }
-
-/* Exported functions ------------------------------------------------------- */
-
-int8_t GO_Init(GO_t *go, const GO_UART_Params_t *param){
- if (go == NULL) return DEVICE_ERR_NULL;
- if (inited) return DEVICE_ERR_INITED;
- if ((thread_alert = osThreadGetId()) == NULL) return DEVICE_ERR_NULL;
-
- go_rx->msgq_raw = osMessageQueueNew(36, 16u, NULL);
-
- go->param = param;
- sem_left_rx = osSemaphoreNew(1, 0, NULL);
- sem_right_rx = osSemaphoreNew(1, 0, NULL);
- // BSP_UART_RegisterCallback(BSP_UART_LEFT_LEG, BSP_UART_RX_CPLT_CB,
- // GO_LeftRxCpltCallback);
- // BSP_UART_RegisterCallback(BSP_UART_RIGHT_LEG, BSP_UART_RX_CPLT_CB,
- // GO_RightRxCpltCallback);
-
- inited = true;
- return DEVICE_OK;
-}
-
-int8_t GO_Motor_Control(GO_MotorOutput_t *output, GO_t *go){
- if (go == NULL) return DEVICE_ERR_NULL;
- if (output == NULL) return DEVICE_ERR_NULL;
- memset(raw_right_buff, 0, sizeof(raw_right_buff));
- memset(raw_left_buff, 0, sizeof(raw_left_buff));
- // HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_LEFT_LEG),
- // (uint8_t *)&raw_left_buff, 16);
- // HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_RIGHT_LEG),
- // (uint8_t *)&raw_right_buff, 16);
-
- for (uint8_t i = 0; i < GO_MOTOR_NUM; i++) {
- motor_cmd.id = i;
- motor_cmd.mode = GO_MOTOR_MODE_FOC;
- motor_cmd.T = output->as_array[i].tor_des;
- motor_cmd.W = output->as_array[i].spd_des;
- motor_cmd.Pos = output->as_array[i].pos_des;
- motor_cmd.K_P = output->as_array[i].k_pos;
- motor_cmd.K_W = output->as_array[i].k_spd;
-
- modify_data(&motor_cmd);
-
- if (i <= GO_MOTOR_LF_CALF || (i >= GO_MOTOR_LR_HIP && i <= GO_MOTOR_LR_CALF)) {
- HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_LEFT_LEG),
- (uint8_t *)&motor_cmd.motor_send_data,
- sizeof(RIS_ControlData_t));
-
- HAL_UART_Receive(BSP_UART_GetHandle(BSP_UART_LEFT_LEG),
- (uint8_t *)&raw_left_buff, 16, 5);
- } else {
- HAL_UART_Transmit_DMA(BSP_UART_GetHandle(BSP_UART_RIGHT_LEG),
- (uint8_t *)&motor_cmd.motor_send_data,
- sizeof(RIS_ControlData_t));
-
- HAL_UART_Receive(BSP_UART_GetHandle(BSP_UART_RIGHT_LEG),
- (uint8_t *)&raw_right_buff, 16, 5);
- }
-
- }
- return DEVICE_OK;
-}
-
-int8_t GO_StoreMsg(GO_t *go, RIS_MotorData_t *go_rx){
-
- return DEVICE_OK;
-}
diff --git a/User/device/go.c b/User/device/go.c
index a339118..586e224 100644
--- a/User/device/go.c
+++ b/User/device/go.c
@@ -47,6 +47,7 @@ int8_t GO_Motor_Control(GO_t *go){
go->motor.output.id[i].mode = GO_MOTOR_MODE_FOC; // 设置电机模式
modify_data(&go->motor.output.id[i]);
if (i < GO_MOTOR_NUM / 4 || i >= GO_MOTOR_NUM/2 && i < GO_MOTOR_NUM * 3 / 4) {
+ // if (i < GO_MOTOR_NUM / 4) {
HAL_UART_Transmit(BSP_UART_GetHandle(go->uart_param->left_leg),
(uint8_t *)&go->motor.output.id[i].motor_send_data,
sizeof(go->motor.output.id[i].motor_send_data), 1);
diff --git a/User/device/n100.c b/User/device/n100.c
new file mode 100644
index 0000000..4d9cb1f
--- /dev/null
+++ b/User/device/n100.c
@@ -0,0 +1,156 @@
+/*
+ N100 陀螺仪数据
+*/
+
+/* Includes ----------------------------------------------------------------- */
+#include "n100.h"
+
+#include
+#include "device/device.h"
+
+#include "bsp/uart.h"
+#include "component/user_math.h"
+#include "component/crc8.h"
+#include "component/crc16.h"
+/* Private define ----------------------------------------------------------- */
+#define RX_BUFF_SIZE 56
+#define N100_BAG_HEAD 0xFC
+#define N100_BAG_END 0xFD
+// #define RX_BUFF_SIZE (sizeof(N100_AHRS_t))
+/* Private macro ------------------------------------------------------------ */
+/* Private typedef ---------------------------------------------------------- */
+/* Private variables -------------------------------------------------------- */
+static volatile uint32_t drop_message = 0;
+
+static uint8_t rxbuf[RX_BUFF_SIZE] __attribute__ ((section(".AXI_SRAM")));
+
+// static N100_AHRS_t rxbuf __attribute__((section(".AXI_SRAM")));
+
+static bool inited = false;
+
+static osThreadId_t thread_alert;
+
+/* Private function -------------------------------------------------------- */
+
+static void N100_RxCpltCallback(void) {
+ osThreadFlagsSet(thread_alert, SIGNAL_N100_NEW_DATA);
+}
+
+static void N100_ErrorCallback(void) {
+ N100_Restart();
+}
+
+static void N100_Decode(N100_t *n100, const uint8_t *rxbuf) {
+ if (n100 == NULL || rxbuf == NULL) return;
+
+ size_t offset = 0;
+
+ // header
+ n100->rx_raw.header.head = rxbuf[offset++];
+ n100->rx_raw.header.cmd = rxbuf[offset++];
+ n100->rx_raw.header.len = rxbuf[offset++];
+ n100->rx_raw.header.count = rxbuf[offset++];
+ n100->rx_raw.header.crc8 = rxbuf[offset++];
+
+ // data.crc16
+ n100->rx_raw.data.crc16 = (uint16_t)(rxbuf[offset] | (rxbuf[offset+1] << 8));
+ offset += 2;
+
+ //都是float32
+ memcpy(&n100->rx_raw.data.gyro.x, rxbuf + offset, 4);
+ offset += 4;
+ memcpy(&n100->rx_raw.data.gyro.y, rxbuf + offset, 4);
+ offset += 4;
+ memcpy(&n100->rx_raw.data.gyro.z, rxbuf + offset, 4);
+ offset += 4;
+
+ memcpy(&n100->rx_raw.data.eulr.rol, rxbuf + offset, 4);
+ offset += 4;
+ memcpy(&n100->rx_raw.data.eulr.pit, rxbuf + offset, 4);
+ offset += 4;
+ memcpy(&n100->rx_raw.data.eulr.yaw, rxbuf + offset, 4);
+ offset += 4;
+ // data.quat
+ memcpy(&n100->rx_raw.data.quat, rxbuf + offset, sizeof(AHRS_Quaternion_t));
+ offset += sizeof(AHRS_Quaternion_t);
+
+ // data.time
+ memcpy(&n100->rx_raw.data.time, rxbuf + offset, sizeof(int64_t));
+ offset += sizeof(int64_t);
+
+ // end
+ n100->rx_raw.end = rxbuf[offset];
+}
+
+// 直接对原始数据 rxbuf 校验
+static bool N100_Verify(const uint8_t *rxbuf) {
+ if (rxbuf == NULL) return false;
+ // 检查包头包尾
+ if (rxbuf[0] != N100_BAG_HEAD || rxbuf[RX_BUFF_SIZE - 1] != N100_BAG_END) {
+ drop_message++;
+ return false;
+ }
+ // // CRC8 校验(包头4字节)
+ // if (rxbuf[4] != crc8_calc(rxbuf, 4)) {
+ // drop_message++;
+ // return false;
+ // }
+ // // CRC16 校验(数据段,从第7字节开始,长度为RX_BUFF_SIZE-8)
+ // uint16_t crc16 = (uint16_t)(rxbuf[5] | (rxbuf[6] << 8));
+ // if (crc16 != crc16_calc(rxbuf + 7, RX_BUFF_SIZE - 8)) {
+ // drop_message++;
+ // return false;
+ // }
+ return true;
+}
+
+/* Exported functions ------------------------------------------------------- */
+int8_t N100_Init(N100_t *n100){
+ ASSERT(n100);
+ if (inited) return DEVICE_ERR_INITED;
+ if ((thread_alert = osThreadGetId()) == NULL) return DEVICE_ERR_NULL;
+
+ BSP_UART_RegisterCallback(BSP_UART_IMU_N100, BSP_UART_RX_CPLT_CB, N100_RxCpltCallback);
+ BSP_UART_RegisterCallback(BSP_UART_IMU_N100, BSP_UART_ERROR_CB, N100_ErrorCallback);
+ inited = true;
+ return DEVICE_OK;
+}
+
+int8_t N100_Restart(void) {
+ __HAL_UART_DISABLE(BSP_UART_GetHandle(BSP_UART_IMU_N100));
+ __HAL_UART_ENABLE(BSP_UART_GetHandle(BSP_UART_IMU_N100));
+ return DEVICE_OK;
+}
+
+int8_t N100_StartReceiving(N100_t *n100) {
+ if (HAL_UART_Receive_DMA(BSP_UART_GetHandle(BSP_UART_IMU_N100), rxbuf, RX_BUFF_SIZE) != HAL_OK)
+ return DEVICE_ERR;
+ return DEVICE_OK;
+}
+
+bool N100_WaitDmaCplt(void) {
+ return (osThreadFlagsWait(SIGNAL_N100_NEW_DATA, osFlagsWaitAll, 200) ==
+ SIGNAL_N100_NEW_DATA);
+}
+
+int8_t N100_ParseData (N100_t *n100) {
+ if (n100 == NULL) return DEVICE_ERR_NULL;
+ // 先校验原始数据
+ if (!N100_Verify(rxbuf)) {
+ return DEVICE_ERR;
+ }
+ // 校验通过后再解码
+ N100_Decode(n100, rxbuf);
+ n100->eulr = n100->rx_raw.data.eulr;
+ n100->gyro = n100->rx_raw.data.gyro;
+ n100->quat = n100->rx_raw.data.quat;
+
+ return DEVICE_OK;
+}
+
+int8_t N100_HandleOffline(N100_t *n100) {
+ if (n100 == NULL) return DEVICE_ERR_NULL;
+ /*清空n100结构体*/
+ memset(n100, 0, sizeof(*n100));
+ return DEVICE_OK;
+}
\ No newline at end of file
diff --git a/User/device/n100.h b/User/device/n100.h
new file mode 100644
index 0000000..e71728c
--- /dev/null
+++ b/User/device/n100.h
@@ -0,0 +1,63 @@
+/*
+ N100 陀螺仪数据
+*/
+
+#pragma once
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ----------------------------------------------------------------- */
+#include
+#include
+#include
+
+#include "component/ahrs.h"
+
+/* Exported constants ------------------------------------------------------- */
+/* Exported macro ----------------------------------------------------------- */
+/* Exported types ----------------------------------------------------------- */
+
+typedef struct {
+ struct {
+ uint8_t head;
+ uint8_t cmd;
+ uint8_t len;
+ uint8_t count;
+ uint8_t crc8;
+ } header; /* 数据包头部 */
+ struct {
+ uint16_t crc16;
+ AHRS_Gyro_t gyro; /* 陀螺仪数据 */
+ AHRS_Eulr_t eulr; /* 欧拉角数据 */
+ AHRS_Quaternion_t quat; /* 四元数数据 */
+ int64_t time; /* 时间戳 */
+ } data; /* 数据包内容 */
+ uint8_t end;
+} N100_AHRS_t;
+
+
+typedef struct {
+ osThreadId_t thread_alert;
+ N100_AHRS_t rx_raw;
+ AHRS_Gyro_t gyro; /* 陀螺仪数据 */
+ AHRS_Eulr_t eulr; /* 欧拉角数据 */
+ AHRS_Quaternion_t quat; /* 四元数数据 */
+} N100_t;
+
+/* Exported functions prototypes -------------------------------------------- */
+int8_t N100_Init(N100_t *n100);
+int8_t N100_Restart(void);
+
+int8_t N100_StartReceiving(N100_t *n100);
+bool N100_WaitDmaCplt(void);
+int8_t N100_ParseData (N100_t *n100);
+int8_t N100_HandleOffline(N100_t *n100);
+
+#ifdef __cplusplus
+}
+#endif
+
+
+
diff --git a/User/module/chassis.c b/User/module/chassis.c
index 69c80c6..a376412 100644
--- a/User/module/chassis.c
+++ b/User/module/chassis.c
@@ -10,12 +10,13 @@
#include "cmsis_os2.h"
// #include "component/limiter.h"
#include "device/go.h"
-
+#include "component/limiter.h"
/* Private typedef ---------------------------------------------------------- */
/* Private define ----------------------------------------------------------- */
/*底盘默认高度*/
#define CHASSIS_DEFAULT_HEIGHT (0.2f) /* 底盘默认高度,单位:米 */
+#define CHASSIS_MAX_SPEED (0.03f)
/* Private macro ------------------------------------------------------------ */
@@ -151,6 +152,7 @@ int8_t Chassis_Control(Chassis_t *c, const CMD_ChassisCmd_t *c_cmd, uint32_t now
// c->output.id[i] = damping_torque; /* 设置阻尼力矩 */
c->output.id[i] = position_mode; /* 设置位置模式 */
}
+
// c->output.named.lf_thigh.Pos = 1.0f; /* 左前腿大腿位置 */
// c->output.named.lf_calf.Pos = 2.0f; /* 左前腿小腿位置 */
// c->output.named.rf_thigh.Pos = -1.0f; /* 右前腿大腿位置 */
@@ -171,6 +173,11 @@ int8_t Chassis_Control(Chassis_t *c, const CMD_ChassisCmd_t *c_cmd, uint32_t now
}
break;
}
+ c->output.named.lf_hip.Pos = 0.0f; /* 左前腿髋关节位置 */
+ c->output.named.lr_hip.Pos = 0.0f; /* 左后腿髋关节位置 */
+ c->output.named.rf_hip.Pos = 0.0f; /* 右前腿髋关节位置 */
+ c->output.named.rr_hip.Pos = 0.0f; /* 右后腿髋关节位置 */
+
c->height = c->height + c_cmd->delta_hight * c->dt; /* 更新底盘高度 */
c->output.named.lf_thigh.Pos = c->height * 5;
c->output.named.lf_calf.Pos = c->height * 10;
@@ -181,8 +188,35 @@ int8_t Chassis_Control(Chassis_t *c, const CMD_ChassisCmd_t *c_cmd, uint32_t now
c->output.named.rr_thigh.Pos = -c->height * 5;
c->output.named.rr_calf.Pos = -c->height * 10;
chassis_mode_states = CHASSIS_MODE_RECOVER; /* 更新状态 */
+
+ for (uint8_t i = 0; i < 4; i++) {
+ float target_pose[3] = {0.0,0.0,-0.2}; /* 目标位置 */
+ float angle_pose[3];
+ Kinematics_InverseKinematics(target_pose, &c->param->mech_param.length, angle_pose, &c->param->mech_param.sign.leg[i]); /* 逆运动学计算 */
+ c->output.id[i * 3].Pos = angle_pose[0]; /* 髋关节位置 */
+ c->output.id[i * 3 + 1].Pos = angle_pose[1]; /* 大腿位置 */
+ c->output.id[i * 3 + 2].Pos = angle_pose[2]; /* 小腿位置 */
+ }
+ // float target_pose[3] = {c_cmd->ctrl_vec.vx/10.0f, c_cmd->ctrl_vec.vy/10.0f, -0.2f}; /* 目标位置 */
+ // float target_pose[3] = {0.0,0.0,-0.2}; /* 目标位置 */
+ // float angle_pose[3];
+ // Kinematics_InverseKinematics(target_pose, &c->param->mech_param.length, angle_pose, &c->param->mech_param.sign.leg[0]); /* 逆运动学计算 */
+ // c->output.named.lf_hip.Pos = angle_pose[0]; /* 左前腿髋关节位置 */
+ // c->output.named.lf_thigh.Pos = angle_pose[1]; /* 左前腿大腿位置 */
+ // c->output.named.lf_calf.Pos = angle_pose[2]; /* 左前腿小腿位置 */
+
break;
}
+
+ // Limit_ChassicOutput(&c->feedback, &c->output, 0.5, 0.0, 0.0);
+ for (uint8_t i = 0; i < GO_MOTOR_NUM; i++) {
+ /* 限制输出 */
+ Limit_ChassicOutput(c->feedback.id[i].Pos, &c->output.id[i].Pos,
+ c->param->mech_param.ratio.id[i] * CHASSIS_MAX_SPEED,
+ c->param->mech_param.limit.max.id[i],
+ c->param->mech_param.limit.min.id[i]);
+ }
+
}
void Chassis_DumpOutput(const Chassis_t *c, GO_ChassisCMD_t *out){
diff --git a/User/module/chassis.h b/User/module/chassis.h
index c28e925..2b35bb9 100644
--- a/User/module/chassis.h
+++ b/User/module/chassis.h
@@ -11,6 +11,7 @@ extern "C" {
/* Includes ----------------------------------------------------------------- */
#include "component/cmd.h"
#include "component/filter.h"
+#include "component/kinematics.h"
#include "component/pid.h"
#include "device/go.h"
@@ -30,6 +31,13 @@ typedef enum {
CHASSIS_TYPE_QUADRUPED, /* 四足机器人 */
} Chassis_Type_t;
+typedef enum {
+ IMU_BOARD_BMI088,
+ IMU_WHEELREC_N100,
+ IMU_NUM,
+ IMU_ERROR,
+} Chassis_ImuType_t;
+
// typedef union {
// float id[GO_MOTOR_NUM]; /* 零点角度,单位:弧度 */
// struct {
@@ -66,46 +74,32 @@ typedef union {
} named;
} joint_params;
-// /*关节减速比*/
-// typedef union {
-// float id[GO_MOTOR_NUM];
-// struct{
-// float lf_hip; /* 左前腿髋关节长度,单位:米 */
-// float lf_thigh; /* 左前腿大腿长度,单位:米 */
-// float lf_calf; /* 左前腿小腿长度,单位:米 */
-// float rf_hip; /* 右前腿髋关节长度,单位:米 */
-// float rf_thigh; /* 右前腿大腿长度,单位:米 */
-// float rf_calf; /* 右前腿小腿长度,单位:米 */
-// float lr_hip; /* 左后腿髋关节长度,单位:米 */
-// float lr_thigh; /* 左后腿大腿长度,单位:米 */
-// float lr_calf; /* 左后腿小腿长度,单位:米 */
-// float rr_hip; /* 右后腿髋关节长度,单位:米 */
-// float rr_thigh; /* 右后腿大腿长度,单位:米 */
-// float rr_calf; /* 右后腿小腿长度,单位:米 */
-// } named;
-// } joint_ratio;
+typedef struct {
+ joint_params min;
+ joint_params max; /* 关节的最小和最大角度,单位:弧度 */
+} joint_limits;
-
-
- // struct {
- // float x; /* 机械中心X坐标,单位:米 */
- // float y; /* 机械中心Y坐标,单位:米 */
- // float z; /* 机械中心Z坐标,单位:米 */
- // } mech_center; /* 机械中心位置 */
+typedef union {
+ Kinematics_Sign_t leg[GO_MOTOR_NUM/3];
+ struct {
+ Kinematics_Sign_t lf; /* 左前腿 */
+ Kinematics_Sign_t rf; /* 右前腿 */
+ Kinematics_Sign_t lr; /* 左后腿 */
+ Kinematics_Sign_t rr; /* 右后腿 */
+ } named;
+} Kinematics_DirectionSign_t;
-
- // typedef struct {
- // /*三个关节距离*/
typedef struct{
joint_params zero_point; /* 零点角度,单位:弧度 */
- joint_params length; /* 关节长度,单位:米 */
+
+ // joint_params length; /* 关节长度,单位:米 */
+
joint_params ratio; /* 关节减速比 */
- struct {
- float x; /* 机械中心X坐标,单位:米 */
- float y; /* 机械中心Y坐标,单位:米 */
- float z; /* 机械中心Z坐标,单位:米 */
- } mech_center; /* 机械中心位置 */
+ joint_limits limit; /* 关节的最小和最大角度,单位:弧度 */
+ Kinematics_LinkLength_t length; /* 关节长度,单位:米 */
+ Kinematics_LegOffset_t offset; /* 关节偏移,单位:米 */
+ Kinematics_DirectionSign_t sign; /* 关节侧向标志(左前/左后为-1,右前/右后为1) */
}Chassis_Mech_Params_t;
diff --git a/User/module/config.c b/User/module/config.c
deleted file mode 100644
index de5d622..0000000
--- a/User/module/config.c
+++ /dev/null
@@ -1,116 +0,0 @@
-/*
- * 配置相关
- */
-
-#include "config.h"
-
-#include
-#include
-
-#include "bsp/flash.h"
-
-#define CONFIG_BASE_ADDRESS (ADDR_FLASH_SECTOR_11)
-
-Config_t param_default = {
-
- .uart = {
- .left_leg = BSP_UART_LEFT_LEG,
- .right_leg = BSP_UART_RIGHT_LEG,
- },
- .cali = {
- .bmi088 = {
- .gyro_offset = {0.0f, 0.0f, 0.0f},
- },
- },
- .chassis = {
- .type = CHASSIS_TYPE_QUADRUPED,
-
- .torque_pid_param = {
- .k = 1.0f, /* 控制器增益 */
- .p = 1.0f, /* 比例项增益 */
- .i = 0.0f, /* 积分项增益 */
- .d = 0.0f, /* 微分项增益 */
- .i_limit = 0.0f, /* 积分项上限 */
- .out_limit = 0.0f, /* 输出绝对值限制 */
- .d_cutoff_freq = 10.0f, /* D项低通截止频率 */
- .range = -1.0f, /* 计算循环误差时使用,大于0时启用 */
- },
-
- .low_pass_cutoff_freq = {
- .in = -1.0f,
- .out = -1.0f,
- },
-
- .mech_param = {
- .length = {
- .named = {
- .lf_hip = 0.0861f, /* 左前腿髋关节长度,单位:米 */
- .lf_thigh = 0.20f, /* 左前腿大腿长度,单位:米 */
- .lf_calf = 0.20f, /* 左前腿小腿长度,单位:米 */
- .rf_hip = 0.0861f, /* 右前腿髋关节长度,单位:米 */
- .rf_thigh = 0.20f, /* 右前腿大腿长度,单位:米 */
- .rf_calf = 0.20f, /* 右前腿小腿长度,单位:米 */
- .lr_hip = 0.0861f, /* 左后腿髋关节长度,单位:米 */
- .lr_thigh = 0.20f, /* 左后腿大腿长度,单位:米 */
- .lr_calf = 0.20f, /* 左后腿小腿长度,单位:米 */
- .rr_hip = 0.0861f, /* 右后腿髋关节长度,单位:米 */
- .rr_thigh = 0.20f, /* 右后腿大腿长度,单位:米 */
- .rr_calf = 0.20f, /* 右后腿小腿长度,单位:米 */
- }
- },
- .zero_point = {
- .named = {
- .lf_hip = 1.98f, /* 左前腿髋关节零点角度,单位:弧度 */
- .lf_thigh = -2.86f, /* 左前腿大腿零点角度,单位:弧度 */
- .lf_calf = -32.367f, /* 左前腿小腿零点角度,单位:弧度 */
- .rf_hip = 5.56f, /* 右前腿髋关节零点角度,单位:弧度 */
- .rf_thigh = 12.92f, /* 右前腿大腿零点角度,单位:弧度 */
- .rf_calf = 37.047f, /* 右前腿小腿零点角度,单位:弧度 */
- .lr_hip = 4.76f, /* 左后腿髋关节零点角度,单位:弧度 */
- .lr_thigh = -4.57f, /* 左后腿大腿零点角度,单位:弧度 */
- .lr_calf = -35.847f, /* 左后腿小腿零点角度,单位:弧度 */
- .rr_hip = 2.42f, /* 右后腿髋关节零点角度,单位:弧度 */
- .rr_thigh = 8.85f, /* 右后腿大腿零点角度,单位:弧度 */
- .rr_calf = 38.55f, /* 右后腿小腿零点角度,单位:弧度 */
- }
- },
- .ratio = {
- .named = {
- .lf_hip = 6.33f, /* 左前腿髋关节减速比 */
- .lf_thigh = 6.33f, /* 左前腿大腿减速比 */
- .lf_calf = 12.66f, /* 左前腿小腿减速比 */
- .rf_hip = 6.33f, /* 右前腿髋关节减速比 */
- .rf_thigh = 6.33f, /* 右前腿大腿减速比 */
- .rf_calf = 12.66f, /* 右前腿小腿减速比 */
- .lr_hip = 6.33f, /* 左后腿髋关节减速比 */
- .lr_thigh = 6.33f, /* 左后腿大腿减速比 */
- .lr_calf = 12.66f, /* 左后腿小腿减速比 */
- .rr_hip = 6.33f, /* 右后腿髋关节减速比 */
- .rr_thigh = 6.33f, /* 右后腿大腿减速比 */
- .rr_calf = 12.66f, /* 右后腿小腿减速比 */
- }
- },
- .mech_center = {
- .x = 0.0f, /* 机械中心X坐标,单位:米 */
- .y = 0.0f, /* 机械中心Y坐标,单位:米 */
- .z = 0.0f, /* 机械中心Z坐标,单位:米 */
- }, /* 机械中心位置 */
-
- },
-
-
- },
-}; /* param_default */
-
-
-
-/**
- * \brief 获取配置信息
- *
- * \param cfg 配置信息
- */
-void Config_Get(Config_t *cfg) {
- //直接把param_default传进去
- if (cfg == NULL) return; // 检查参数是否为NULL
- memcpy(cfg, ¶m_default, sizeof(Config_t)); // 复制默认配置到cfg
-}
diff --git a/User/module/config.h b/User/module/config.h
index a813e63..a15272d 100644
--- a/User/module/config.h
+++ b/User/module/config.h
@@ -37,7 +37,8 @@ typedef struct {
struct {
BMI088_Cali_t bmi088;
} cali; /* 校准 */
-
+ Chassis_ImuType_t chassis_imu_type; /* 底盘IMU类型 */
+
} Config_t;
/**
diff --git a/User/task/atti_esti.c b/User/task/atti_esti.c
index 8558fcb..4d8b66d 100644
--- a/User/task/atti_esti.c
+++ b/User/task/atti_esti.c
@@ -7,9 +7,11 @@
#include "task/user_task.h"
/* USER INCLUDE BEGIN*/
#include "bsp/pwm.h"
+#include "bsp/gpio.h"
#include "component/ahrs.h"
#include "component/pid.h"
#include "device/bmi088.h"
+#include "device/n100.h"
#include "task/user_task.h"
/* USER INCLUDE END*/
@@ -19,6 +21,8 @@
/* Private variables -------------------------------------------------------- */
/* USER STRUCT BEGIN*/
BMI088_t bmi088;
+N100_t n100;
+
BMI088_Cali_t bmi088_cali = {
.gyro_offset = {0.0f, 0.0f, 0.0f},
}; /* BMI088校准数据 */
@@ -48,44 +52,81 @@ void Task_atti_esti(void *argument) {
osDelay(ATTI_ESTI_INIT_DELAY); /* 延时一段时间再开启任务 */
/* USER CODE INIT BEGIN*/
- BMI088_Init(&bmi088, &bmi088_cali); /* 初始化BMI088传感器 */
- AHRS_Init(&gimbal_ahrs, &mage, BMI088_GetUpdateFreq(&bmi088)); /* 初始化姿态解算算法 */
- /* 初始化IMU温度控制PID,防止温漂 */
- PID_Init(&imu_temp_ctrl_pid, KPID_MODE_NO_D,
- 1.0f / BMI088_GetUpdateFreq(&bmi088), &imu_temp_ctrl_pid_param);
- // BSP_PWM_Start(BSP_PWM_IMU_HEAT);
+ switch (task_runtime.config.chassis_imu_type) {
+ case IMU_BOARD_BMI088:
+ BMI088_Init(&bmi088, &bmi088_cali); /* 初始化BMI088传感器 */
+ AHRS_Init(&gimbal_ahrs, &mage, BMI088_GetUpdateFreq(&bmi088)); /* 初始化姿态解算算法 */
+ /* 初始化IMU温度控制PID,防止温漂 */
+ // PID_Init(&imu_temp_ctrl_pid, KPID_MODE_NO_D,
+ // 1.0f / BMI088_GetUpdateFreq(&bmi088), &imu_temp_ctrl_pid_param);
+ // BSP_PWM_Start(BSP_PWM_IMU_HEAT);
+ break;
+ case IMU_WHEELREC_N100:
+ N100_Init(&n100);
+ BSP_GPIO_SetPin(BSP_GPIO_5V_EN, BSP_GPIO_ON); /* 打开5V电源 */
+ break;
+ default:
+ break;
+ }
/* USER CODE INIT END*/
while (1) {
/* USER CODE BEGIN */
- /* 等待IMU新数据 */
- BMI088_WaitNew();
+ switch (task_runtime.config.chassis_imu_type) {
+ case IMU_BOARD_BMI088:
+ /* 等待IMU新数据 */
+ BMI088_WaitNew();
+ /* 开始数据接收DMA,加速度计和陀螺仪共用同一个SPI接口,
+ * 一次只能开启一个DMA
+ */
+ BMI088_AcclStartDmaRecv();
+ BMI088_AcclWaitDmaCplt();
- /* 开始数据接收DMA,加速度计和陀螺仪共用同一个SPI接口,
- * 一次只能开启一个DMA
- */
- BMI088_AcclStartDmaRecv();
- BMI088_AcclWaitDmaCplt();
+ BMI088_GyroStartDmaRecv();
+ BMI088_GyroWaitDmaCplt();
- BMI088_GyroStartDmaRecv();
- BMI088_GyroWaitDmaCplt();
+ /* 锁住RTOS内核防止数据解析过程中断,造成错误 */
+ osKernelLock();
+ /* 接收完所有数据后,把数据从原始字节加工成方便计算的数据 */
+ BMI088_ParseAccl(&bmi088);
+ BMI088_ParseGyro(&bmi088);
+
+ /* 根据设备接收到的数据进行姿态解析 */
+ AHRS_Update(&gimbal_ahrs, &bmi088.accl, &bmi088.gyro, &mage);
+
+ /* 根据解析出来的四元数计算欧拉角 */
+ AHRS_GetEulr(&eulr_to_send, &gimbal_ahrs);
+ osKernelUnlock();
+ /* 将欧拉角数据放入消息队列 */
+ osMessageQueueReset(task_runtime.msgq.body.eulr_imu);
+ osMessageQueuePut(task_runtime.msgq.body.eulr_imu, &eulr_to_send, 0, 0); /* 将欧拉角数据放入消息队列 */
+
+ /* PID控制IMU温度,PWM输出 */
+ // BSP_PWM_Set(BSP_PWM_IMU_HEAT,
+ // PID_Calc(&imu_temp_ctrl_pid, 40.0f, bmi088.temp, 0.0f, 0.01f));
+ break;
+ case IMU_WHEELREC_N100:
+ N100_StartReceiving(&n100);
+ if (N100_WaitDmaCplt()) {
+ osKernelLock();
+ N100_ParseData(&n100);
+ osKernelUnlock();
+ } else {
+ N100_HandleOffline(&n100);
+ }
+ osMessageQueueReset(task_runtime.msgq.body.eulr_imu); /* 重置消息队列 */
+ osMessageQueuePut(task_runtime.msgq.body.eulr_imu, &n100.eulr, 0, 0); /* 将欧拉角数据放入消息队列 */
+
+ break;
+ default:
+
+ break;
+
+ }
- /* 锁住RTOS内核防止数据解析过程中断,造成错误 */
- osKernelLock();
- /* 接收完所有数据后,把数据从原始字节加工成方便计算的数据 */
- BMI088_ParseAccl(&bmi088);
- BMI088_ParseGyro(&bmi088);
- /* 根据设备接收到的数据进行姿态解析 */
- AHRS_Update(&gimbal_ahrs, &bmi088.accl, &bmi088.gyro, &mage);
- /* 根据解析出来的四元数计算欧拉角 */
- AHRS_GetEulr(&eulr_to_send, &gimbal_ahrs);
- osKernelUnlock();
- /* PID控制IMU温度,PWM输出 */
- // BSP_PWM_Set(BSP_PWM_IMU_HEAT,
- // PID_Calc(&imu_temp_ctrl_pid, 40.0f, bmi088.temp, 0.0f, 0.01f));
/* USER CODE END */
}
diff --git a/User/task/config.yaml b/User/task/config.yaml
index c2094b2..43a7c64 100644
--- a/User/task/config.yaml
+++ b/User/task/config.yaml
@@ -37,14 +37,14 @@
function: Task_cmd
name: cmd
stack: 256
-- delay: 0
+- delay: 200
description: 四足控制
freq_control: true
frequency: 800
function: Task_ctrl_leg
name: ctrl_leg
stack: 512
-- delay: 0
+- delay: 200
description: 底盘控制,接受反馈和命令,计算输出给到两测腿控制
freq_control: true
frequency: 500
diff --git a/User/task/ctrl_leg.c b/User/task/ctrl_leg.c
index 684e586..4851d0f 100644
--- a/User/task/ctrl_leg.c
+++ b/User/task/ctrl_leg.c
@@ -40,9 +40,7 @@ void Task_ctrl_leg(void *argument) {
uint32_t tick = osKernelGetTickCount(); /* 控制任务运行频率的计时 */
while (1) {
tick += delay_tick; /* 计算下一个唤醒时刻 */
-
/* USER CODE BEGIN */
- // osMessageQueueGet(task_runtime.msgq.chassis.output, &cmd, NULL, 0); /* 从消息队列中获取底盘控制命令 */
if (osMessageQueueGet(task_runtime.msgq.chassis.output, &go_cmd, NULL, 0) == osOK) { /* 从消息队列中获取底盘控制命令 */
GO_ParseCmd(&go, &go_cmd); /* 解析底盘控制命令 */
}
diff --git a/User/task/init.c b/User/task/init.c
index 82d2981..f5c28ac 100644
--- a/User/task/init.c
+++ b/User/task/init.c
@@ -45,6 +45,7 @@ void Task_Init(void *argument) {
task_runtime.msgq.cmd.chassis = osMessageQueueNew(2u, sizeof(CMD_ChassisCmd_t), NULL);
task_runtime.msgq.chassis.feefback = osMessageQueueNew(2u, sizeof(GO_ChassisFeedback_t), NULL);
task_runtime.msgq.chassis.output = osMessageQueueNew(2u, sizeof(GO_ChassisCMD_t), NULL);
+ task_runtime.msgq.body.eulr_imu = osMessageQueueNew(2u, sizeof(AHRS_Eulr_t), NULL);
/* USER MESSAGE END */
osKernelUnlock(); // 解锁内核
diff --git a/User/task/user_task.h b/User/task/user_task.h
index c55a80c..8f9bdba 100644
--- a/User/task/user_task.h
+++ b/User/task/user_task.h
@@ -16,7 +16,7 @@ extern "C" {
#define TEST_FREQ (1000)
#define MONITOR_FREQ (100)
#define CMD_FREQ (500)
-#define CTRL_LEG_FREQ (500)
+#define CTRL_LEG_FREQ (800)
#define CTRL_CHASSIS_FREQ (500)
/* 任务初始化延时ms */
@@ -27,8 +27,8 @@ extern "C" {
#define CLI_INIT_DELAY (0)
#define MONITOR_INIT_DELAY (0)
#define CMD_INIT_DELAY (0)
-#define CTRL_LEG_INIT_DELAY (0)
-#define CTRL_CHASSIS_INIT_DELAY (0)
+#define CTRL_LEG_INIT_DELAY (200)
+#define CTRL_CHASSIS_INIT_DELAY (200)
/* Exported defines --------------------------------------------------------- */
/* Exported macro ----------------------------------------------------------- */
@@ -51,6 +51,10 @@ typedef struct {
/* USER MESSAGE BEGIN */
struct {
// osMessageQueueId_t user_msg; /* 用户自定义任务消息队列 */
+
+ struct {
+ osMessageQueueId_t eulr_imu;
+ } body;
struct {
struct {
osMessageQueueId_t rc; /* 原始数据消息队列 */
diff --git a/Utils/Kinematics.m b/Utils/Kinematics.m
new file mode 100644
index 0000000..f3104d9
--- /dev/null
+++ b/Utils/Kinematics.m
@@ -0,0 +1,221 @@
+function quadruped_leg_visualization()
+ % 四足机器人单腿运动学可视化
+
+ % 清除之前的图形
+ close all;
+ clc;
+
+ % 定义腿部参数 (单位: 米)
+ leg_params.upper_leg_length = 0.15;
+ leg_params.lower_leg_length = 0.15;
+ leg_params.hip_offset_x = 0.05;
+ leg_params.hip_offset_z = -0.02;
+ leg_params.hip_yaw_offset = 0.01;
+ leg_params.knee_sign = 1; % 1或-1,取决于机械设计
+
+ % 目标位置 (在髋关节坐标系中)
+ target_pos = [0.2, 0.1, -0.25]; % x, y, z
+
+ % 计算逆运动学 (右腿hip_yaw_sign=1,左腿=-1)
+ joint_angles = leg_inverse_kinematics(target_pos, leg_params, 1);
+
+ % 显示计算结果
+ disp('关节角度 (弧度):');
+ disp(['髋关节偏航 (hip yaw): ', num2str(joint_angles(1)), ' rad']);
+ disp(['髋关节滚动 (hip roll): ', num2str(joint_angles(2)), ' rad']);
+ disp(['髋关节俯仰 (hip pitch): ', num2str(joint_angles(3)), ' rad']);
+ disp(['膝关节 (knee): ', num2str(joint_angles(4)), ' rad']);
+
+ disp('关节角度 (度):');
+ disp(['髋关节偏航 (hip yaw): ', num2str(rad2deg(joint_angles(1))), '°']);
+ disp(['髋关节滚动 (hip roll): ', num2str(rad2deg(joint_angles(2))), '°']);
+ disp(['髋关节俯仰 (hip pitch): ', num2str(rad2deg(joint_angles(3))), '°']);
+ disp(['膝关节 (knee): ', num2str(rad2deg(joint_angles(4))), '°']);
+
+ % 可视化腿部
+ visualize_leg(joint_angles, leg_params, target_pos);
+end
+
+function joint_angles = leg_inverse_kinematics(target_pos, leg_params, hip_yaw_sign)
+ % 逆运动学计算函数
+
+ % 从参数字典中提取参数
+ L1 = leg_params.upper_leg_length;
+ L2 = leg_params.lower_leg_length;
+ offset_x = leg_params.hip_offset_x;
+ offset_z = leg_params.hip_offset_z;
+ yaw_offset = leg_params.hip_yaw_offset;
+ knee_sign = leg_params.knee_sign;
+
+ % 第一步:计算髋关节偏航角 (hip yaw)
+ x = target_pos(1);
+ y = target_pos(2);
+ z = target_pos(3);
+
+ x = x - offset_x;
+ z = z - offset_z;
+
+ % 使用迭代法处理yaw offset
+ theta_yaw = atan2(hip_yaw_sign * y, x);
+ for i = 1:3
+ % 计算yaw旋转后的位置
+ x_rot = x * cos(theta_yaw) + hip_yaw_sign * y * sin(theta_yaw);
+ y_rot = -x * sin(theta_yaw) + hip_yaw_sign * y * cos(theta_yaw);
+
+ % 考虑yaw offset
+ x_rot = x_rot - yaw_offset * (1 - cos(theta_yaw));
+ y_rot = y_rot + yaw_offset * sin(theta_yaw);
+
+ theta_yaw = atan2(hip_yaw_sign * y_rot, x_rot);
+ end
+
+ % 第二步:计算髋关节滚转角 (hip roll) 和俯仰角 (hip pitch)
+ x_rot = x * cos(theta_yaw) + hip_yaw_sign * y * sin(theta_yaw) - yaw_offset;
+ z_rot = z;
+
+ % 计算髋关节滚转角
+ L = sqrt(x_rot^2 + z_rot^2);
+ theta_roll = atan2(z_rot, x_rot);
+
+ % 计算髋关节俯仰角和膝关节角度
+ D = (L^2 - L1^2 - L2^2) / (2 * L1 * L2);
+ D = max(min(D, 1.0), -1.0); % 确保数值在有效范围内
+
+ theta_knee = knee_sign * acos(D);
+
+ alpha = atan2(L2 * sin(theta_knee), L1 + L2 * cos(theta_knee));
+ theta_pitch = alpha + theta_roll;
+
+ % 返回关节角度 (hip_yaw, hip_roll, hip_pitch, knee)
+ joint_angles = [theta_yaw, theta_roll, theta_pitch, theta_knee];
+end
+
+function visualize_leg(joint_angles, leg_params, target_pos)
+ % 可视化腿部运动学
+
+ % 提取参数
+ L1 = leg_params.upper_leg_length;
+ L2 = leg_params.lower_leg_length;
+ offset_x = leg_params.hip_offset_x;
+ offset_z = leg_params.hip_offset_z;
+ yaw_offset = leg_params.hip_yaw_offset;
+
+ % 提取关节角度
+ theta_yaw = joint_angles(1);
+ theta_roll = joint_angles(2);
+ theta_pitch = joint_angles(3);
+ theta_knee = joint_angles(4);
+
+ % 创建图形窗口
+ figure('Name', '四足机器人单腿运动学可视化', 'NumberTitle', 'off', 'Position', [100, 100, 1200, 800]);
+
+ % 1. 3D视图
+ subplot(2,2,[1,3]);
+ hold on;
+ grid on;
+ axis equal;
+ view(3);
+ xlabel('X (m)');
+ ylabel('Y (m)');
+ zlabel('Z (m)');
+ title('3D视图');
+
+ % 绘制坐标系
+ plot3([0, 0.1], [0, 0], [0, 0], 'r', 'LineWidth', 2); % X轴
+ plot3([0, 0], [0, 0.1], [0, 0], 'g', 'LineWidth', 2); % Y轴
+ plot3([0, 0], [0, 0], [0, 0.1], 'b', 'LineWidth', 2); % Z轴
+
+ % 计算关节位置
+ % 髋关节位置 (考虑了offset)
+ hip_pos = [offset_x, 0, offset_z];
+
+ % 应用yaw旋转
+ R_yaw = [cos(theta_yaw), -sin(theta_yaw), 0;
+ sin(theta_yaw), cos(theta_yaw), 0;
+ 0, 0, 1];
+
+ % 应用roll旋转 (在yaw旋转后的坐标系中)
+ R_roll = [cos(theta_roll), 0, sin(theta_roll);
+ 0, 1, 0;
+ -sin(theta_roll), 0, cos(theta_roll)];
+
+ % 应用pitch旋转
+ R_pitch = [1, 0, 0;
+ 0, cos(theta_pitch), -sin(theta_pitch);
+ 0, sin(theta_pitch), cos(theta_pitch)];
+
+ % 计算大腿末端位置
+ upper_leg_end = hip_pos + (R_yaw * R_roll * R_pitch * [L1; 0; 0])';
+
+ % 计算小腿末端位置
+ R_knee = [1, 0, 0;
+ 0, cos(theta_knee), -sin(theta_knee);
+ 0, sin(theta_knee), cos(theta_knee)];
+
+ lower_leg_end = upper_leg_end + (R_yaw * R_roll * R_pitch * R_knee * [L2; 0; 0])';
+
+ % 绘制连杆
+ plot3([hip_pos(1), upper_leg_end(1)], ...
+ [hip_pos(2), upper_leg_end(2)], ...
+ [hip_pos(3), upper_leg_end(3)], 'b-o', 'LineWidth', 3, 'MarkerSize', 8);
+
+ plot3([upper_leg_end(1), lower_leg_end(1)], ...
+ [upper_leg_end(2), lower_leg_end(2)], ...
+ [upper_leg_end(3), lower_leg_end(3)], 'r-o', 'LineWidth', 3, 'MarkerSize', 8);
+
+ % 绘制目标位置
+ plot3(target_pos(1), target_pos(2), target_pos(3), 'g*', 'MarkerSize', 15);
+
+ % 绘制yaw offset
+ plot3([hip_pos(1), hip_pos(1)+yaw_offset*sin(theta_yaw)], ...
+ [0, yaw_offset*cos(theta_yaw)], ...
+ [hip_pos(3), hip_pos(3)], 'm--', 'LineWidth', 2);
+
+ % 设置视图范围
+ axis_range = max([L1+L2, abs(offset_x)+0.1, abs(offset_z)+0.1]);
+ xlim([-axis_range, axis_range]);
+ ylim([-axis_range, axis_range]);
+ zlim([-axis_range, axis_range]);
+
+ % 2. X-Y平面视图
+ subplot(2,2,2);
+ hold on;
+ grid on;
+ axis equal;
+ xlabel('X (m)');
+ ylabel('Y (m)');
+ title('X-Y平面视图');
+
+ plot([0, 0.1], [0, 0], 'r', 'LineWidth', 2); % X轴
+ plot([0, 0], [0, 0.1], 'g', 'LineWidth', 2); % Y轴
+
+ plot([hip_pos(1), upper_leg_end(1)], [hip_pos(2), upper_leg_end(2)], 'b-o', 'LineWidth', 3, 'MarkerSize', 8);
+ plot([upper_leg_end(1), lower_leg_end(1)], [upper_leg_end(2), lower_leg_end(2)], 'r-o', 'LineWidth', 3, 'MarkerSize', 8);
+ plot(target_pos(1), target_pos(2), 'g*', 'MarkerSize', 15);
+ plot([hip_pos(1), hip_pos(1)+yaw_offset*sin(theta_yaw)], [0, yaw_offset*cos(theta_yaw)], 'm--', 'LineWidth', 2);
+
+ xlim([-axis_range, axis_range]);
+ ylim([-axis_range, axis_range]);
+
+ % 3. X-Z平面视图
+ subplot(2,2,4);
+ hold on;
+ grid on;
+ axis equal;
+ xlabel('X (m)');
+ ylabel('Z (m)');
+ title('X-Z平面视图');
+
+ plot([0, 0.1], [0, 0], 'r', 'LineWidth', 2); % X轴
+ plot([0, 0], [0, 0.1], 'b', 'LineWidth', 2); % Z轴
+
+ plot([hip_pos(1), upper_leg_end(1)], [hip_pos(3), upper_leg_end(3)], 'b-o', 'LineWidth', 3, 'MarkerSize', 8);
+ plot([upper_leg_end(1), lower_leg_end(1)], [upper_leg_end(3), lower_leg_end(3)], 'r-o', 'LineWidth', 3, 'MarkerSize', 8);
+ plot(target_pos(1), target_pos(3), 'g*', 'MarkerSize', 15);
+
+ xlim([-axis_range, axis_range]);
+ ylim([-axis_range, axis_range]);
+
+ % 添加图例
+ legend({'大腿', '小腿', '目标位置', 'Yaw偏移'}, 'Location', 'best');
+end
\ No newline at end of file
diff --git a/Utils/Kinematics.py b/Utils/Kinematics.py
new file mode 100644
index 0000000..c37dbca
--- /dev/null
+++ b/Utils/Kinematics.py
@@ -0,0 +1,78 @@
+# test_kinematics.py
+
+import numpy as np
+
+def forward_kinematics(theta, link, side_sign):
+ l1 = link['hip'] * side_sign
+ l2 = -link['thigh']
+ l3 = -link['calf']
+ q1, q2, q3 = theta
+
+ s1, s2, s3 = np.sin([q1, q2, q3])
+ c1, c2, c3 = np.cos([q1, q2, q3])
+
+ c23 = c2 * c3 - s2 * s3
+ s23 = s2 * c3 + c2 * s3
+
+ x = l3 * s23 + l2 * s2
+ y = -l3 * s1 * c23 + l1 * c1 - l2 * c2 * s1
+ z = l3 * c1 * c23 + l1 * s1 + l2 * c1 * c2
+ return np.array([x, y, z])
+
+def q1_ik(py, pz, l1):
+ L = np.sqrt(py*py + pz*pz - l1*l1)
+ return np.arctan2(pz*l1 + py*L, py*l1 - pz*L)
+
+def q3_ik(b3z, b4z, b):
+ temp = (b3z**2 + b4z**2 - b**2) / (2.0 * np.abs(b3z * b4z))
+ temp = np.clip(temp, -1.0, 1.0)
+ q3 = np.arccos(temp)
+ return -(np.pi - q3)
+
+def q2_ik(q1, q3, px, py, pz, b3z, b4z):
+ a1 = py * np.sin(q1) - pz * np.cos(q1)
+ a2 = px
+ m1 = b4z * np.sin(q3)
+ m2 = b3z + b4z * np.cos(q3)
+ return np.arctan2(m1 * a1 + m2 * a2, m1 * a2 - m2 * a1)
+
+def inverse_kinematics(foot, link, side_sign):
+ px, py, pz = foot
+ b2y = link['hip'] * side_sign
+ b3z = -link['thigh']
+ b4z = -link['calf']
+ a = link['hip']
+ c = np.sqrt(px*px + py*py + pz*pz)
+ b = np.sqrt(c*c - a*a)
+ if np.isnan(b) or b > abs(b3z) + abs(b4z):
+ return None
+ q1 = q1_ik(py, pz, b2y)
+ q3 = q3_ik(b3z, b4z, b)
+ q2 = q2_ik(q1, q3, px, py, pz, b3z, b4z)
+ return np.array([q1, q2, q3])
+
+# ...existing code...
+
+def test():
+ link = {'hip': 0.05, 'thigh': 0.2, 'calf': 0.2}
+ side_sign = 1 # 左前腿
+
+ # 输入一个目标点
+ foot_target = np.array([0.0, 0.06, -0.2])
+ print("目标足端位置:", foot_target)
+
+ # 逆运动学求解关节角度
+ theta = inverse_kinematics(foot_target, link, side_sign)
+ if theta is None:
+ print("目标点不可达!")
+ return
+ print("逆运动学解(关节角度,单位:弧度):", theta)
+ print("逆运动学解(关节角度,单位:度):", np.degrees(theta))
+
+ # 正运动学验算
+ foot_check = forward_kinematics(theta, link, side_sign)
+ print("正运动学验算足端位置:", foot_check)
+ print("位置误差:", np.abs(foot_target - foot_check))
+
+if __name__ == "__main__":
+ test()