From 61bd188196b70662603bd564cefb8073c82b2222 Mon Sep 17 00:00:00 2001 From: Federica Di Lauro Date: Mon, 20 Jan 2020 13:48:31 +0100 Subject: [PATCH] fix #7 --- docs | 2 +- otto_controller/.mxproject | 18 +- otto_controller/Core/Inc/main.h | 16 +- otto_controller/Core/Inc/motor_controller.h | 10 +- otto_controller/Core/Src/main.cpp | 221 +- otto_controller/Core/Src/stm32f7xx_hal_msp.c | 16 +- otto_controller/Debug/otto_controller.list | 17271 ++++++++-------- otto_controller/otto_controller.ioc | 8 +- utils/pid_tuning/otto_pid_tuning/.mxproject | 18 +- .../otto_pid_tuning/Core/Inc/main.h | 16 +- .../otto_pid_tuning/Core/Src/main.cpp | 217 +- .../Core/Src/stm32f7xx_hal_msp.c | 16 +- .../otto_pid_tuning/otto_pid_tuning.ioc | 8 +- 13 files changed, 8993 insertions(+), 8844 deletions(-) diff --git a/docs b/docs index 5bde98f..b38a5a0 160000 --- a/docs +++ b/docs @@ -1 +1 @@ -Subproject commit 5bde98fe6c28075c3fe976d77bec33087092c03c +Subproject commit b38a5a0bcc78bdea011630ea0b8650af24aba0c1 diff --git a/otto_controller/.mxproject b/otto_controller/.mxproject index 7190dbe..be93599 100644 --- a/otto_controller/.mxproject +++ b/otto_controller/.mxproject @@ -1,17 +1,19 @@ [PreviousGenFiles] AdvancedFolderStructure=true HeaderFileListSize=3 -HeaderFiles#0=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/stm32f7xx_it.h -HeaderFiles#1=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/stm32f7xx_hal_conf.h -HeaderFiles#2=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/main.h +HeaderFiles#0=/home/fdila/Projects/otto/otto_controller/Core/Inc/stm32f7xx_it.h +HeaderFiles#1=/home/fdila/Projects/otto/otto_controller/Core/Inc/stm32f7xx_hal_conf.h +HeaderFiles#2=/home/fdila/Projects/otto/otto_controller/Core/Inc/main.h HeaderFolderListSize=1 -HeaderPath#0=/home/fdila/Projects/otto/otto_controller_source/Core/Inc +HeaderPath#0=/home/fdila/Projects/otto/otto_controller/Core/Inc SourceFileListSize=3 -SourceFiles#0=/home/fdila/Projects/otto/otto_controller_source/Core/Src/stm32f7xx_it.c -SourceFiles#1=/home/fdila/Projects/otto/otto_controller_source/Core/Src/stm32f7xx_hal_msp.c -SourceFiles#2=/home/fdila/Projects/otto/otto_controller_source/Core/Src/main.c +SourceFiles#0=/home/fdila/Projects/otto/otto_controller/Core/Src/stm32f7xx_it.c +SourceFiles#1=/home/fdila/Projects/otto/otto_controller/Core/Src/stm32f7xx_hal_msp.c +SourceFiles#2=/home/fdila/Projects/otto/otto_controller/Core/Src/main.c SourceFolderListSize=1 -SourcePath#0=/home/fdila/Projects/otto/otto_controller_source/Core/Src +SourcePath#0=/home/fdila/Projects/otto/otto_controller/Core/Src +HeaderFiles=; +SourceFiles=; [PreviousLibFiles] LibFiles=Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_cortex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_def.h;Drivers/STM32F7xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_exti.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart_ex.h;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.c;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_cortex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_def.h;Drivers/STM32F7xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_exti.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart_ex.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f767xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/system_stm32f7xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/cmsis_armclang.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm4.h; diff --git a/otto_controller/Core/Inc/main.h b/otto_controller/Core/Inc/main.h index c545cce..6b45ffa 100644 --- a/otto_controller/Core/Inc/main.h +++ b/otto_controller/Core/Inc/main.h @@ -65,14 +65,14 @@ void Error_Handler(void); #define user_button_EXTI_IRQn EXTI15_10_IRQn #define current2_Pin GPIO_PIN_0 #define current2_GPIO_Port GPIOC -#define encoder_sx1_Pin GPIO_PIN_0 -#define encoder_sx1_GPIO_Port GPIOA -#define encoder_sx2_Pin GPIO_PIN_1 -#define encoder_sx2_GPIO_Port GPIOA +#define encoder_dx1_Pin GPIO_PIN_0 +#define encoder_dx1_GPIO_Port GPIOA +#define encoder_dx2_Pin GPIO_PIN_1 +#define encoder_dx2_GPIO_Port GPIOA #define current1_Pin GPIO_PIN_3 #define current1_GPIO_Port GPIOA -#define encoder_dx1_Pin GPIO_PIN_5 -#define encoder_dx1_GPIO_Port GPIOA +#define encoder_sx1_Pin GPIO_PIN_5 +#define encoder_sx1_GPIO_Port GPIOA #define fault2_Pin GPIO_PIN_6 #define fault2_GPIO_Port GPIOA #define dir2_Pin GPIO_PIN_12 @@ -89,8 +89,8 @@ void Error_Handler(void); #define pwm2_GPIO_Port GPIOD #define pwm1_Pin GPIO_PIN_15 #define pwm1_GPIO_Port GPIOD -#define encoder_dx2_Pin GPIO_PIN_3 -#define encoder_dx2_GPIO_Port GPIOB +#define encoder_sx2_Pin GPIO_PIN_3 +#define encoder_sx2_GPIO_Port GPIOB /* USER CODE BEGIN Private defines */ /* USER CODE END Private defines */ diff --git a/otto_controller/Core/Inc/motor_controller.h b/otto_controller/Core/Inc/motor_controller.h index 710edd0..dcd3fc6 100644 --- a/otto_controller/Core/Inc/motor_controller.h +++ b/otto_controller/Core/Inc/motor_controller.h @@ -30,18 +30,18 @@ class MotorController { void set_speed(int duty_cycle) { if (duty_cycle >= 0) { // HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); - HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); if (duty_cycle > 790) __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); else __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - } else { + } else if (duty_cycle < 0) { // HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); - HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); - if (duty_cycle < 790) + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); + if (duty_cycle < -790) __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); else - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); } } diff --git a/otto_controller/Core/Src/main.cpp b/otto_controller/Core/Src/main.cpp index dca4ed5..1a24672 100644 --- a/otto_controller/Core/Src/main.cpp +++ b/otto_controller/Core/Src/main.cpp @@ -58,8 +58,8 @@ UART_HandleTypeDef huart6; /* USER CODE BEGIN PV */ //Odometry -Encoder left_encoder = Encoder(&htim5); -Encoder right_encoder = Encoder(&htim2); +Encoder left_encoder = Encoder(&htim2); +Encoder right_encoder = Encoder(&htim5); Odometry odom = Odometry(left_encoder, right_encoder); float left_velocity; @@ -120,12 +120,14 @@ static void MX_NVIC_Init(void); /* USER CODE END 0 */ /** - * @brief The application entry point. - * @retval int - */ -int main(void) { + * @brief The application entry point. + * @retval int + */ +int main(void) +{ /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ + /* MCU Configuration--------------------------------------------------------*/ @@ -189,51 +191,56 @@ int main(void) { } /** - * @brief System Clock Configuration - * @retval None - */ -void SystemClock_Config(void) { - RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; - RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; /** Configure the main internal regulator output voltage - */ + */ __HAL_RCC_PWR_CLK_ENABLE(); __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); /** Initializes the CPU, AHB and APB busses clocks - */ + */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { Error_Handler(); } /** Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK - | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) + { Error_Handler(); } PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) + { Error_Handler(); } } /** - * @brief NVIC Configuration. - * @retval None - */ -static void MX_NVIC_Init(void) { + * @brief NVIC Configuration. + * @retval None + */ +static void MX_NVIC_Init(void) +{ /* TIM3_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM3_IRQn, 2, 1); HAL_NVIC_EnableIRQ(TIM3_IRQn); @@ -246,18 +253,19 @@ static void MX_NVIC_Init(void) { } /** - * @brief TIM2 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM2_Init(void) { + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) +{ /* USER CODE BEGIN TIM2_Init 0 */ /* USER CODE END TIM2_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_Encoder_InitTypeDef sConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM2_Init 1 */ @@ -277,12 +285,14 @@ static void MX_TIM2_Init(void) { sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM2_Init 2 */ @@ -292,18 +302,19 @@ static void MX_TIM2_Init(void) { } /** - * @brief TIM3 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM3_Init(void) { + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) +{ /* USER CODE BEGIN TIM3_Init 0 */ /* USER CODE END TIM3_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM3_Init 1 */ @@ -314,16 +325,19 @@ static void MX_TIM3_Init(void) { htim3.Init.Period = 159; htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) + { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM3_Init 2 */ @@ -333,19 +347,20 @@ static void MX_TIM3_Init(void) { } /** - * @brief TIM4 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM4_Init(void) { + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) +{ /* USER CODE BEGIN TIM4_Init 0 */ /* USER CODE END TIM4_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - TIM_OC_InitTypeDef sConfigOC = { 0 }; + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_OC_InitTypeDef sConfigOC = {0}; /* USER CODE BEGIN TIM4_Init 1 */ @@ -356,29 +371,35 @@ static void MX_TIM4_Init(void) { htim4.Init.Period = 799; htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) + { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) + { Error_Handler(); } - if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) + { Error_Handler(); } sConfigOC.OCMode = TIM_OCMODE_PWM1; sConfigOC.Pulse = 0; sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) + { Error_Handler(); } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM4_Init 2 */ @@ -389,18 +410,19 @@ static void MX_TIM4_Init(void) { } /** - * @brief TIM5 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM5_Init(void) { + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) +{ /* USER CODE BEGIN TIM5_Init 0 */ /* USER CODE END TIM5_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_Encoder_InitTypeDef sConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM5_Init 1 */ @@ -420,12 +442,14 @@ static void MX_TIM5_Init(void) { sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM5_Init 2 */ @@ -435,17 +459,18 @@ static void MX_TIM5_Init(void) { } /** - * @brief TIM6 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM6_Init(void) { + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) +{ /* USER CODE BEGIN TIM6_Init 0 */ /* USER CODE END TIM6_Init 0 */ - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM6_Init 1 */ @@ -455,12 +480,14 @@ static void MX_TIM6_Init(void) { htim6.Init.CounterMode = TIM_COUNTERMODE_UP; htim6.Init.Period = 799; htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM6_Init 2 */ @@ -470,11 +497,12 @@ static void MX_TIM6_Init(void) { } /** - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) { + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) +{ /* USER CODE BEGIN USART6_Init 0 */ @@ -493,7 +521,8 @@ static void MX_USART6_UART_Init(void) { huart6.Init.OverSampling = UART_OVERSAMPLING_16; huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - if (HAL_UART_Init(&huart6) != HAL_OK) { + if (HAL_UART_Init(&huart6) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN USART6_Init 2 */ @@ -503,12 +532,13 @@ static void MX_USART6_UART_Init(void) { } /** - * @brief GPIO Initialization Function - * @param None - * @retval None - */ -static void MX_GPIO_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; /* GPIO Ports Clock Enable */ __HAL_RCC_GPIOC_CLK_ENABLE(); @@ -519,10 +549,10 @@ static void MX_GPIO_Init(void) { __HAL_RCC_GPIOB_CLK_ENABLE(); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin, GPIO_PIN_RESET); + HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, sleep2_Pin | sleep1_Pin, GPIO_PIN_SET); + HAL_GPIO_WritePin(GPIOF, sleep2_Pin|sleep1_Pin, GPIO_PIN_SET); /*Configure GPIO pin : user_button_Pin */ GPIO_InitStruct.Pin = user_button_Pin; @@ -549,14 +579,14 @@ static void MX_GPIO_Init(void) { HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); /*Configure GPIO pins : dir2_Pin dir1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin; + GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); /*Configure GPIO pins : sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = sleep2_Pin | sleep1_Pin; + GPIO_InitStruct.Pin = sleep2_Pin|sleep1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; @@ -630,10 +660,11 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { /* USER CODE END 4 */ /** - * @brief This function is executed in case of error occurrence. - * @retval None - */ -void Error_Handler(void) { + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) +{ /* USER CODE BEGIN Error_Handler_Debug */ /* User can add his own implementation to report the HAL error return state */ diff --git a/otto_controller/Core/Src/stm32f7xx_hal_msp.c b/otto_controller/Core/Src/stm32f7xx_hal_msp.c index 821e58b..2918b9b 100644 --- a/otto_controller/Core/Src/stm32f7xx_hal_msp.c +++ b/otto_controller/Core/Src/stm32f7xx_hal_msp.c @@ -102,19 +102,19 @@ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ - GPIO_InitStruct.Pin = encoder_dx1_Pin; + GPIO_InitStruct.Pin = encoder_sx1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - HAL_GPIO_Init(encoder_dx1_GPIO_Port, &GPIO_InitStruct); + HAL_GPIO_Init(encoder_sx1_GPIO_Port, &GPIO_InitStruct); - GPIO_InitStruct.Pin = encoder_dx2_Pin; + GPIO_InitStruct.Pin = encoder_sx2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - HAL_GPIO_Init(encoder_dx2_GPIO_Port, &GPIO_InitStruct); + HAL_GPIO_Init(encoder_sx2_GPIO_Port, &GPIO_InitStruct); /* USER CODE BEGIN TIM2_MspInit 1 */ @@ -133,7 +133,7 @@ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) PA0/WKUP ------> TIM5_CH1 PA1 ------> TIM5_CH2 */ - GPIO_InitStruct.Pin = encoder_sx1_Pin|encoder_sx2_Pin; + GPIO_InitStruct.Pin = encoder_dx1_Pin|encoder_dx2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; @@ -238,9 +238,9 @@ void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ - HAL_GPIO_DeInit(encoder_dx1_GPIO_Port, encoder_dx1_Pin); + HAL_GPIO_DeInit(encoder_sx1_GPIO_Port, encoder_sx1_Pin); - HAL_GPIO_DeInit(encoder_dx2_GPIO_Port, encoder_dx2_Pin); + HAL_GPIO_DeInit(encoder_sx2_GPIO_Port, encoder_sx2_Pin); /* USER CODE BEGIN TIM2_MspDeInit 1 */ @@ -258,7 +258,7 @@ void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) PA0/WKUP ------> TIM5_CH1 PA1 ------> TIM5_CH2 */ - HAL_GPIO_DeInit(GPIOA, encoder_sx1_Pin|encoder_sx2_Pin); + HAL_GPIO_DeInit(GPIOA, encoder_dx1_Pin|encoder_dx2_Pin); /* USER CODE BEGIN TIM5_MspDeInit 1 */ diff --git a/otto_controller/Debug/otto_controller.list b/otto_controller/Debug/otto_controller.list index bf0912c..2bfcfdc 100644 --- a/otto_controller/Debug/otto_controller.list +++ b/otto_controller/Debug/otto_controller.list @@ -5,45 +5,45 @@ Sections: Idx Name Size VMA LMA File off Algn 0 .isr_vector 000001f8 08000000 08000000 00010000 2**0 CONTENTS, ALLOC, LOAD, READONLY, DATA - 1 .text 000050d0 080001f8 080001f8 000101f8 2**3 + 1 .text 00005198 080001f8 080001f8 000101f8 2**2 CONTENTS, ALLOC, LOAD, READONLY, CODE - 2 .rodata 00000018 080052c8 080052c8 000152c8 2**2 + 2 .rodata 00000018 08005390 08005390 00015390 2**2 CONTENTS, ALLOC, LOAD, READONLY, DATA - 3 .ARM.extab 00000000 080052e0 080052e0 00020014 2**0 + 3 .ARM.extab 00000000 080053a8 080053a8 00020010 2**0 CONTENTS - 4 .ARM 00000008 080052e0 080052e0 000152e0 2**2 + 4 .ARM 00000008 080053a8 080053a8 000153a8 2**2 CONTENTS, ALLOC, LOAD, READONLY, DATA - 5 .preinit_array 00000000 080052e8 080052e8 00020014 2**0 + 5 .preinit_array 00000000 080053b0 080053b0 00020010 2**0 CONTENTS, ALLOC, LOAD, DATA - 6 .init_array 00000008 080052e8 080052e8 000152e8 2**2 + 6 .init_array 00000008 080053b0 080053b0 000153b0 2**2 CONTENTS, ALLOC, LOAD, DATA - 7 .fini_array 00000004 080052f0 080052f0 000152f0 2**2 + 7 .fini_array 00000004 080053b8 080053b8 000153b8 2**2 CONTENTS, ALLOC, LOAD, DATA - 8 .data 00000014 20000000 080052f4 00020000 2**2 + 8 .data 00000010 20000000 080053bc 00020000 2**2 CONTENTS, ALLOC, LOAD, DATA - 9 .bss 0000038c 20000014 08005308 00020014 2**2 + 9 .bss 0000038c 20000010 080053cc 00020010 2**2 ALLOC - 10 ._user_heap_stack 00000600 200003a0 08005308 000203a0 2**0 + 10 ._user_heap_stack 00000604 2000039c 080053cc 0002039c 2**0 ALLOC - 11 .ARM.attributes 0000002e 00000000 00000000 00020014 2**0 + 11 .ARM.attributes 0000002e 00000000 00000000 00020010 2**0 CONTENTS, READONLY - 12 .debug_info 0000daea 00000000 00000000 00020042 2**0 + 12 .debug_info 0000db30 00000000 00000000 0002003e 2**0 CONTENTS, READONLY, DEBUGGING - 13 .debug_abbrev 00001e6a 00000000 00000000 0002db2c 2**0 + 13 .debug_abbrev 00001e91 00000000 00000000 0002db6e 2**0 CONTENTS, READONLY, DEBUGGING - 14 .debug_aranges 00000d48 00000000 00000000 0002f998 2**3 + 14 .debug_aranges 00000d50 00000000 00000000 0002fa00 2**3 CONTENTS, READONLY, DEBUGGING - 15 .debug_ranges 00000c60 00000000 00000000 000306e0 2**3 + 15 .debug_ranges 00000c68 00000000 00000000 00030750 2**3 CONTENTS, READONLY, DEBUGGING - 16 .debug_macro 000281fd 00000000 00000000 00031340 2**0 + 16 .debug_macro 000281fd 00000000 00000000 000313b8 2**0 CONTENTS, READONLY, DEBUGGING - 17 .debug_line 00009b10 00000000 00000000 0005953d 2**0 + 17 .debug_line 00009ae0 00000000 00000000 000595b5 2**0 CONTENTS, READONLY, DEBUGGING - 18 .debug_str 000f1c8d 00000000 00000000 0006304d 2**0 + 18 .debug_str 000f1cb0 00000000 00000000 00063095 2**0 CONTENTS, READONLY, DEBUGGING - 19 .comment 0000007b 00000000 00000000 00154cda 2**0 + 19 .comment 0000007b 00000000 00000000 00154d45 2**0 CONTENTS, READONLY - 20 .debug_frame 000037cc 00000000 00000000 00154d58 2**2 + 20 .debug_frame 000037f8 00000000 00000000 00154dc0 2**2 CONTENTS, READONLY, DEBUGGING Disassembly of section .text: @@ -60,9 +60,9 @@ Disassembly of section .text: 800020a: 2301 movs r3, #1 800020c: 7023 strb r3, [r4, #0] 800020e: bd10 pop {r4, pc} - 8000210: 20000014 .word 0x20000014 + 8000210: 20000010 .word 0x20000010 8000214: 00000000 .word 0x00000000 - 8000218: 080052b0 .word 0x080052b0 + 8000218: 08005378 .word 0x08005378 0800021c : 800021c: b508 push {r3, lr} @@ -73,8 +73,8 @@ Disassembly of section .text: 8000226: f3af 8000 nop.w 800022a: bd08 pop {r3, pc} 800022c: 00000000 .word 0x00000000 - 8000230: 20000018 .word 0x20000018 - 8000234: 080052b0 .word 0x080052b0 + 8000230: 20000014 .word 0x20000014 + 8000234: 08005378 .word 0x08005378 08000238 <__aeabi_uldivmod>: 8000238: b953 cbnz r3, 8000250 <__aeabi_uldivmod+0x18> @@ -455,7 +455,7 @@ void Encoder::Setup() { 80005ce: 681b ldr r3, [r3, #0] 80005d0: 213c movs r1, #60 ; 0x3c 80005d2: 4618 mov r0, r3 - 80005d4: f002 ff54 bl 8003480 + 80005d4: f002 ffb8 bl 8003548 this->ResetCount(); 80005d8: 6878 ldr r0, [r7, #4] 80005da: f7ff ffc2 bl 8000562 <_ZN7Encoder10ResetCountEv> @@ -464,7 +464,7 @@ void Encoder::Setup() { 80005e0: 2200 movs r2, #0 80005e2: 605a str r2, [r3, #4] this->current_millis_ = HAL_GetTick(); - 80005e4: f001 fa68 bl 8001ab8 + 80005e4: f001 facc bl 8001b80 80005e8: 4602 mov r2, r0 80005ea: 687b ldr r3, [r7, #4] 80005ec: 609a str r2, [r3, #8] @@ -487,7 +487,7 @@ void Encoder::UpdateValues() { 8000602: 687b ldr r3, [r7, #4] 8000604: 605a str r2, [r3, #4] this->current_millis_ = HAL_GetTick(); - 8000606: f001 fa57 bl 8001ab8 + 8000606: f001 fabb bl 8001b80 800060a: 4602 mov r2, r0 800060c: 687b ldr r3, [r7, #4] 800060e: 609a str r2, [r3, #8] @@ -718,12985 +718,13068 @@ float Encoder::GetLinearVelocity() { 80007b0: 695b ldr r3, [r3, #20] 80007b2: 4619 mov r1, r3 80007b4: 4610 mov r0, r2 - 80007b6: f002 fd8d bl 80032d4 + 80007b6: f002 fdf1 bl 800339c } 80007ba: bf00 nop 80007bc: 3708 adds r7, #8 80007be: 46bd mov sp, r7 80007c0: bd80 pop {r7, pc} + ... -080007c2 <_ZN15MotorController9set_speedEi>: +080007c4 <_ZN15MotorController9set_speedEi>: void set_speed(int duty_cycle) { - 80007c2: b580 push {r7, lr} - 80007c4: b082 sub sp, #8 - 80007c6: af00 add r7, sp, #0 - 80007c8: 6078 str r0, [r7, #4] - 80007ca: 6039 str r1, [r7, #0] + 80007c4: b580 push {r7, lr} + 80007c6: b082 sub sp, #8 + 80007c8: af00 add r7, sp, #0 + 80007ca: 6078 str r0, [r7, #4] + 80007cc: 6039 str r1, [r7, #0] if (duty_cycle >= 0) { - 80007cc: 683b ldr r3, [r7, #0] - 80007ce: 2b00 cmp r3, #0 - 80007d0: f2c0 8083 blt.w 80008da <_ZN15MotorController9set_speedEi+0x118> + 80007ce: 683b ldr r3, [r7, #0] + 80007d0: 2b00 cmp r3, #0 + 80007d2: f2c0 8083 blt.w 80008dc <_ZN15MotorController9set_speedEi+0x118> // HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); - HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); - 80007d4: 687b ldr r3, [r7, #4] - 80007d6: 6898 ldr r0, [r3, #8] - 80007d8: 687b ldr r3, [r7, #4] - 80007da: 899b ldrh r3, [r3, #12] - 80007dc: 2200 movs r2, #0 - 80007de: 4619 mov r1, r3 - 80007e0: f001 fc54 bl 800208c + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); + 80007d6: 687b ldr r3, [r7, #4] + 80007d8: 6898 ldr r0, [r3, #8] + 80007da: 687b ldr r3, [r7, #4] + 80007dc: 899b ldrh r3, [r3, #12] + 80007de: 2201 movs r2, #1 + 80007e0: 4619 mov r1, r3 + 80007e2: f001 fcb7 bl 8002154 if (duty_cycle > 790) - 80007e4: 683b ldr r3, [r7, #0] - 80007e6: f240 3216 movw r2, #790 ; 0x316 - 80007ea: 4293 cmp r3, r2 - 80007ec: dd3d ble.n 800086a <_ZN15MotorController9set_speedEi+0xa8> + 80007e6: 683b ldr r3, [r7, #0] + 80007e8: f240 3216 movw r2, #790 ; 0x316 + 80007ec: 4293 cmp r3, r2 + 80007ee: dd3d ble.n 800086c <_ZN15MotorController9set_speedEi+0xa8> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 80007ee: 687b ldr r3, [r7, #4] - 80007f0: 695b ldr r3, [r3, #20] - 80007f2: 2b00 cmp r3, #0 - 80007f4: d106 bne.n 8000804 <_ZN15MotorController9set_speedEi+0x42> - 80007f6: 687b ldr r3, [r7, #4] - 80007f8: 691b ldr r3, [r3, #16] - 80007fa: 681b ldr r3, [r3, #0] - 80007fc: f240 3216 movw r2, #790 ; 0x316 - 8000800: 635a str r2, [r3, #52] ; 0x34 + 80007f0: 687b ldr r3, [r7, #4] + 80007f2: 695b ldr r3, [r3, #20] + 80007f4: 2b00 cmp r3, #0 + 80007f6: d106 bne.n 8000806 <_ZN15MotorController9set_speedEi+0x42> + 80007f8: 687b ldr r3, [r7, #4] + 80007fa: 691b ldr r3, [r3, #16] + 80007fc: 681b ldr r3, [r3, #0] + 80007fe: f240 3216 movw r2, #790 ; 0x316 + 8000802: 635a str r2, [r3, #52] ; 0x34 __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); else - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); } } - 8000802: e0f2 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000804: e0f5 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000804: 687b ldr r3, [r7, #4] - 8000806: 695b ldr r3, [r3, #20] - 8000808: 2b04 cmp r3, #4 - 800080a: d106 bne.n 800081a <_ZN15MotorController9set_speedEi+0x58> - 800080c: 687b ldr r3, [r7, #4] - 800080e: 691b ldr r3, [r3, #16] - 8000810: 681b ldr r3, [r3, #0] - 8000812: f240 3216 movw r2, #790 ; 0x316 - 8000816: 639a str r2, [r3, #56] ; 0x38 - } - 8000818: e0e7 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000806: 687b ldr r3, [r7, #4] + 8000808: 695b ldr r3, [r3, #20] + 800080a: 2b04 cmp r3, #4 + 800080c: d106 bne.n 800081c <_ZN15MotorController9set_speedEi+0x58> + 800080e: 687b ldr r3, [r7, #4] + 8000810: 691b ldr r3, [r3, #16] + 8000812: 681b ldr r3, [r3, #0] + 8000814: f240 3216 movw r2, #790 ; 0x316 + 8000818: 639a str r2, [r3, #56] ; 0x38 + } + 800081a: e0ea b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800081a: 687b ldr r3, [r7, #4] - 800081c: 695b ldr r3, [r3, #20] - 800081e: 2b08 cmp r3, #8 - 8000820: d106 bne.n 8000830 <_ZN15MotorController9set_speedEi+0x6e> - 8000822: 687b ldr r3, [r7, #4] - 8000824: 691b ldr r3, [r3, #16] - 8000826: 681b ldr r3, [r3, #0] - 8000828: f240 3216 movw r2, #790 ; 0x316 - 800082c: 63da str r2, [r3, #60] ; 0x3c - } - 800082e: e0dc b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 800081c: 687b ldr r3, [r7, #4] + 800081e: 695b ldr r3, [r3, #20] + 8000820: 2b08 cmp r3, #8 + 8000822: d106 bne.n 8000832 <_ZN15MotorController9set_speedEi+0x6e> + 8000824: 687b ldr r3, [r7, #4] + 8000826: 691b ldr r3, [r3, #16] + 8000828: 681b ldr r3, [r3, #0] + 800082a: f240 3216 movw r2, #790 ; 0x316 + 800082e: 63da str r2, [r3, #60] ; 0x3c + } + 8000830: e0df b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000830: 687b ldr r3, [r7, #4] - 8000832: 695b ldr r3, [r3, #20] - 8000834: 2b0c cmp r3, #12 - 8000836: d106 bne.n 8000846 <_ZN15MotorController9set_speedEi+0x84> - 8000838: 687b ldr r3, [r7, #4] - 800083a: 691b ldr r3, [r3, #16] - 800083c: 681b ldr r3, [r3, #0] - 800083e: f240 3216 movw r2, #790 ; 0x316 - 8000842: 641a str r2, [r3, #64] ; 0x40 - } - 8000844: e0d1 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000832: 687b ldr r3, [r7, #4] + 8000834: 695b ldr r3, [r3, #20] + 8000836: 2b0c cmp r3, #12 + 8000838: d106 bne.n 8000848 <_ZN15MotorController9set_speedEi+0x84> + 800083a: 687b ldr r3, [r7, #4] + 800083c: 691b ldr r3, [r3, #16] + 800083e: 681b ldr r3, [r3, #0] + 8000840: f240 3216 movw r2, #790 ; 0x316 + 8000844: 641a str r2, [r3, #64] ; 0x40 + } + 8000846: e0d4 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000846: 687b ldr r3, [r7, #4] - 8000848: 695b ldr r3, [r3, #20] - 800084a: 2b10 cmp r3, #16 - 800084c: d106 bne.n 800085c <_ZN15MotorController9set_speedEi+0x9a> - 800084e: 687b ldr r3, [r7, #4] - 8000850: 691b ldr r3, [r3, #16] - 8000852: 681b ldr r3, [r3, #0] - 8000854: f240 3216 movw r2, #790 ; 0x316 - 8000858: 659a str r2, [r3, #88] ; 0x58 - } - 800085a: e0c6 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000848: 687b ldr r3, [r7, #4] + 800084a: 695b ldr r3, [r3, #20] + 800084c: 2b10 cmp r3, #16 + 800084e: d106 bne.n 800085e <_ZN15MotorController9set_speedEi+0x9a> + 8000850: 687b ldr r3, [r7, #4] + 8000852: 691b ldr r3, [r3, #16] + 8000854: 681b ldr r3, [r3, #0] + 8000856: f240 3216 movw r2, #790 ; 0x316 + 800085a: 659a str r2, [r3, #88] ; 0x58 + } + 800085c: e0c9 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800085c: 687b ldr r3, [r7, #4] - 800085e: 691b ldr r3, [r3, #16] - 8000860: 681b ldr r3, [r3, #0] - 8000862: f240 3216 movw r2, #790 ; 0x316 - 8000866: 65da str r2, [r3, #92] ; 0x5c + 800085e: 687b ldr r3, [r7, #4] + 8000860: 691b ldr r3, [r3, #16] + 8000862: 681b ldr r3, [r3, #0] + 8000864: f240 3216 movw r2, #790 ; 0x316 + 8000868: 65da str r2, [r3, #92] ; 0x5c } - 8000868: e0bf b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 800086a: e0c2 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 800086a: 687b ldr r3, [r7, #4] - 800086c: 695b ldr r3, [r3, #20] - 800086e: 2b00 cmp r3, #0 - 8000870: d105 bne.n 800087e <_ZN15MotorController9set_speedEi+0xbc> - 8000872: 683a ldr r2, [r7, #0] - 8000874: 687b ldr r3, [r7, #4] - 8000876: 691b ldr r3, [r3, #16] - 8000878: 681b ldr r3, [r3, #0] - 800087a: 635a str r2, [r3, #52] ; 0x34 - } - 800087c: e0b5 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 800086c: 687b ldr r3, [r7, #4] + 800086e: 695b ldr r3, [r3, #20] + 8000870: 2b00 cmp r3, #0 + 8000872: d105 bne.n 8000880 <_ZN15MotorController9set_speedEi+0xbc> + 8000874: 683a ldr r2, [r7, #0] + 8000876: 687b ldr r3, [r7, #4] + 8000878: 691b ldr r3, [r3, #16] + 800087a: 681b ldr r3, [r3, #0] + 800087c: 635a str r2, [r3, #52] ; 0x34 + } + 800087e: e0b8 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 800087e: 687b ldr r3, [r7, #4] - 8000880: 695b ldr r3, [r3, #20] - 8000882: 2b04 cmp r3, #4 - 8000884: d105 bne.n 8000892 <_ZN15MotorController9set_speedEi+0xd0> - 8000886: 683a ldr r2, [r7, #0] - 8000888: 687b ldr r3, [r7, #4] - 800088a: 691b ldr r3, [r3, #16] - 800088c: 681b ldr r3, [r3, #0] - 800088e: 639a str r2, [r3, #56] ; 0x38 - } - 8000890: e0ab b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000880: 687b ldr r3, [r7, #4] + 8000882: 695b ldr r3, [r3, #20] + 8000884: 2b04 cmp r3, #4 + 8000886: d105 bne.n 8000894 <_ZN15MotorController9set_speedEi+0xd0> + 8000888: 683a ldr r2, [r7, #0] + 800088a: 687b ldr r3, [r7, #4] + 800088c: 691b ldr r3, [r3, #16] + 800088e: 681b ldr r3, [r3, #0] + 8000890: 639a str r2, [r3, #56] ; 0x38 + } + 8000892: e0ae b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 8000892: 687b ldr r3, [r7, #4] - 8000894: 695b ldr r3, [r3, #20] - 8000896: 2b08 cmp r3, #8 - 8000898: d105 bne.n 80008a6 <_ZN15MotorController9set_speedEi+0xe4> - 800089a: 683a ldr r2, [r7, #0] - 800089c: 687b ldr r3, [r7, #4] - 800089e: 691b ldr r3, [r3, #16] - 80008a0: 681b ldr r3, [r3, #0] - 80008a2: 63da str r2, [r3, #60] ; 0x3c - } - 80008a4: e0a1 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000894: 687b ldr r3, [r7, #4] + 8000896: 695b ldr r3, [r3, #20] + 8000898: 2b08 cmp r3, #8 + 800089a: d105 bne.n 80008a8 <_ZN15MotorController9set_speedEi+0xe4> + 800089c: 683a ldr r2, [r7, #0] + 800089e: 687b ldr r3, [r7, #4] + 80008a0: 691b ldr r3, [r3, #16] + 80008a2: 681b ldr r3, [r3, #0] + 80008a4: 63da str r2, [r3, #60] ; 0x3c + } + 80008a6: e0a4 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008a6: 687b ldr r3, [r7, #4] - 80008a8: 695b ldr r3, [r3, #20] - 80008aa: 2b0c cmp r3, #12 - 80008ac: d105 bne.n 80008ba <_ZN15MotorController9set_speedEi+0xf8> - 80008ae: 683a ldr r2, [r7, #0] - 80008b0: 687b ldr r3, [r7, #4] - 80008b2: 691b ldr r3, [r3, #16] - 80008b4: 681b ldr r3, [r3, #0] - 80008b6: 641a str r2, [r3, #64] ; 0x40 - } - 80008b8: e097 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 80008a8: 687b ldr r3, [r7, #4] + 80008aa: 695b ldr r3, [r3, #20] + 80008ac: 2b0c cmp r3, #12 + 80008ae: d105 bne.n 80008bc <_ZN15MotorController9set_speedEi+0xf8> + 80008b0: 683a ldr r2, [r7, #0] + 80008b2: 687b ldr r3, [r7, #4] + 80008b4: 691b ldr r3, [r3, #16] + 80008b6: 681b ldr r3, [r3, #0] + 80008b8: 641a str r2, [r3, #64] ; 0x40 + } + 80008ba: e09a b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008ba: 687b ldr r3, [r7, #4] - 80008bc: 695b ldr r3, [r3, #20] - 80008be: 2b10 cmp r3, #16 - 80008c0: d105 bne.n 80008ce <_ZN15MotorController9set_speedEi+0x10c> - 80008c2: 683a ldr r2, [r7, #0] - 80008c4: 687b ldr r3, [r7, #4] - 80008c6: 691b ldr r3, [r3, #16] - 80008c8: 681b ldr r3, [r3, #0] - 80008ca: 659a str r2, [r3, #88] ; 0x58 - } - 80008cc: e08d b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 80008bc: 687b ldr r3, [r7, #4] + 80008be: 695b ldr r3, [r3, #20] + 80008c0: 2b10 cmp r3, #16 + 80008c2: d105 bne.n 80008d0 <_ZN15MotorController9set_speedEi+0x10c> + 80008c4: 683a ldr r2, [r7, #0] + 80008c6: 687b ldr r3, [r7, #4] + 80008c8: 691b ldr r3, [r3, #16] + 80008ca: 681b ldr r3, [r3, #0] + 80008cc: 659a str r2, [r3, #88] ; 0x58 + } + 80008ce: e090 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008ce: 683a ldr r2, [r7, #0] - 80008d0: 687b ldr r3, [r7, #4] - 80008d2: 691b ldr r3, [r3, #16] - 80008d4: 681b ldr r3, [r3, #0] - 80008d6: 65da str r2, [r3, #92] ; 0x5c - } - 80008d8: e087 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); - 80008da: 687b ldr r3, [r7, #4] - 80008dc: 6898 ldr r0, [r3, #8] - 80008de: 687b ldr r3, [r7, #4] - 80008e0: 899b ldrh r3, [r3, #12] - 80008e2: 2201 movs r2, #1 - 80008e4: 4619 mov r1, r3 - 80008e6: f001 fbd1 bl 800208c - if (duty_cycle < 790) - 80008ea: 683b ldr r3, [r7, #0] - 80008ec: f240 3215 movw r2, #789 ; 0x315 - 80008f0: 4293 cmp r3, r2 - 80008f2: dc3d bgt.n 8000970 <_ZN15MotorController9set_speedEi+0x1ae> + 80008d0: 683a ldr r2, [r7, #0] + 80008d2: 687b ldr r3, [r7, #4] + 80008d4: 691b ldr r3, [r3, #16] + 80008d6: 681b ldr r3, [r3, #0] + 80008d8: 65da str r2, [r3, #92] ; 0x5c + } + 80008da: e08a b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + } else if (duty_cycle < 0) { + 80008dc: 683b ldr r3, [r7, #0] + 80008de: 2b00 cmp r3, #0 + 80008e0: f280 8087 bge.w 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); + 80008e4: 687b ldr r3, [r7, #4] + 80008e6: 6898 ldr r0, [r3, #8] + 80008e8: 687b ldr r3, [r7, #4] + 80008ea: 899b ldrh r3, [r3, #12] + 80008ec: 2200 movs r2, #0 + 80008ee: 4619 mov r1, r3 + 80008f0: f001 fc30 bl 8002154 + if (duty_cycle < -790) + 80008f4: 683b ldr r3, [r7, #0] + 80008f6: 4a41 ldr r2, [pc, #260] ; (80009fc <_ZN15MotorController9set_speedEi+0x238>) + 80008f8: 4293 cmp r3, r2 + 80008fa: da3d bge.n 8000978 <_ZN15MotorController9set_speedEi+0x1b4> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 80008f4: 687b ldr r3, [r7, #4] - 80008f6: 695b ldr r3, [r3, #20] - 80008f8: 2b00 cmp r3, #0 - 80008fa: d106 bne.n 800090a <_ZN15MotorController9set_speedEi+0x148> 80008fc: 687b ldr r3, [r7, #4] - 80008fe: 691b ldr r3, [r3, #16] - 8000900: 681b ldr r3, [r3, #0] - 8000902: f240 3216 movw r2, #790 ; 0x316 - 8000906: 635a str r2, [r3, #52] ; 0x34 - } - 8000908: e06f b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 80008fe: 695b ldr r3, [r3, #20] + 8000900: 2b00 cmp r3, #0 + 8000902: d106 bne.n 8000912 <_ZN15MotorController9set_speedEi+0x14e> + 8000904: 687b ldr r3, [r7, #4] + 8000906: 691b ldr r3, [r3, #16] + 8000908: 681b ldr r3, [r3, #0] + 800090a: f240 3216 movw r2, #790 ; 0x316 + 800090e: 635a str r2, [r3, #52] ; 0x34 + } + 8000910: e06f b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800090a: 687b ldr r3, [r7, #4] - 800090c: 695b ldr r3, [r3, #20] - 800090e: 2b04 cmp r3, #4 - 8000910: d106 bne.n 8000920 <_ZN15MotorController9set_speedEi+0x15e> 8000912: 687b ldr r3, [r7, #4] - 8000914: 691b ldr r3, [r3, #16] - 8000916: 681b ldr r3, [r3, #0] - 8000918: f240 3216 movw r2, #790 ; 0x316 - 800091c: 639a str r2, [r3, #56] ; 0x38 - } - 800091e: e064 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000914: 695b ldr r3, [r3, #20] + 8000916: 2b04 cmp r3, #4 + 8000918: d106 bne.n 8000928 <_ZN15MotorController9set_speedEi+0x164> + 800091a: 687b ldr r3, [r7, #4] + 800091c: 691b ldr r3, [r3, #16] + 800091e: 681b ldr r3, [r3, #0] + 8000920: f240 3216 movw r2, #790 ; 0x316 + 8000924: 639a str r2, [r3, #56] ; 0x38 + } + 8000926: e064 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000920: 687b ldr r3, [r7, #4] - 8000922: 695b ldr r3, [r3, #20] - 8000924: 2b08 cmp r3, #8 - 8000926: d106 bne.n 8000936 <_ZN15MotorController9set_speedEi+0x174> 8000928: 687b ldr r3, [r7, #4] - 800092a: 691b ldr r3, [r3, #16] - 800092c: 681b ldr r3, [r3, #0] - 800092e: f240 3216 movw r2, #790 ; 0x316 - 8000932: 63da str r2, [r3, #60] ; 0x3c - } - 8000934: e059 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 800092a: 695b ldr r3, [r3, #20] + 800092c: 2b08 cmp r3, #8 + 800092e: d106 bne.n 800093e <_ZN15MotorController9set_speedEi+0x17a> + 8000930: 687b ldr r3, [r7, #4] + 8000932: 691b ldr r3, [r3, #16] + 8000934: 681b ldr r3, [r3, #0] + 8000936: f240 3216 movw r2, #790 ; 0x316 + 800093a: 63da str r2, [r3, #60] ; 0x3c + } + 800093c: e059 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000936: 687b ldr r3, [r7, #4] - 8000938: 695b ldr r3, [r3, #20] - 800093a: 2b0c cmp r3, #12 - 800093c: d106 bne.n 800094c <_ZN15MotorController9set_speedEi+0x18a> 800093e: 687b ldr r3, [r7, #4] - 8000940: 691b ldr r3, [r3, #16] - 8000942: 681b ldr r3, [r3, #0] - 8000944: f240 3216 movw r2, #790 ; 0x316 - 8000948: 641a str r2, [r3, #64] ; 0x40 - } - 800094a: e04e b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000940: 695b ldr r3, [r3, #20] + 8000942: 2b0c cmp r3, #12 + 8000944: d106 bne.n 8000954 <_ZN15MotorController9set_speedEi+0x190> + 8000946: 687b ldr r3, [r7, #4] + 8000948: 691b ldr r3, [r3, #16] + 800094a: 681b ldr r3, [r3, #0] + 800094c: f240 3216 movw r2, #790 ; 0x316 + 8000950: 641a str r2, [r3, #64] ; 0x40 + } + 8000952: e04e b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800094c: 687b ldr r3, [r7, #4] - 800094e: 695b ldr r3, [r3, #20] - 8000950: 2b10 cmp r3, #16 - 8000952: d106 bne.n 8000962 <_ZN15MotorController9set_speedEi+0x1a0> 8000954: 687b ldr r3, [r7, #4] - 8000956: 691b ldr r3, [r3, #16] - 8000958: 681b ldr r3, [r3, #0] - 800095a: f240 3216 movw r2, #790 ; 0x316 - 800095e: 659a str r2, [r3, #88] ; 0x58 - } - 8000960: e043 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> + 8000956: 695b ldr r3, [r3, #20] + 8000958: 2b10 cmp r3, #16 + 800095a: d106 bne.n 800096a <_ZN15MotorController9set_speedEi+0x1a6> + 800095c: 687b ldr r3, [r7, #4] + 800095e: 691b ldr r3, [r3, #16] + 8000960: 681b ldr r3, [r3, #0] + 8000962: f240 3216 movw r2, #790 ; 0x316 + 8000966: 659a str r2, [r3, #88] ; 0x58 + } + 8000968: e043 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000962: 687b ldr r3, [r7, #4] - 8000964: 691b ldr r3, [r3, #16] - 8000966: 681b ldr r3, [r3, #0] - 8000968: f240 3216 movw r2, #790 ; 0x316 - 800096c: 65da str r2, [r3, #92] ; 0x5c - } - 800096e: e03c b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 8000970: 687b ldr r3, [r7, #4] - 8000972: 695b ldr r3, [r3, #20] - 8000974: 2b00 cmp r3, #0 - 8000976: d106 bne.n 8000986 <_ZN15MotorController9set_speedEi+0x1c4> - 8000978: 683b ldr r3, [r7, #0] - 800097a: 425a negs r2, r3 - 800097c: 687b ldr r3, [r7, #4] - 800097e: 691b ldr r3, [r3, #16] - 8000980: 681b ldr r3, [r3, #0] - 8000982: 635a str r2, [r3, #52] ; 0x34 - } - 8000984: e031 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 8000986: 687b ldr r3, [r7, #4] - 8000988: 695b ldr r3, [r3, #20] - 800098a: 2b04 cmp r3, #4 - 800098c: d106 bne.n 800099c <_ZN15MotorController9set_speedEi+0x1da> - 800098e: 683b ldr r3, [r7, #0] - 8000990: 425a negs r2, r3 - 8000992: 687b ldr r3, [r7, #4] - 8000994: 691b ldr r3, [r3, #16] - 8000996: 681b ldr r3, [r3, #0] - 8000998: 639a str r2, [r3, #56] ; 0x38 - } - 800099a: e026 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 800099c: 687b ldr r3, [r7, #4] - 800099e: 695b ldr r3, [r3, #20] - 80009a0: 2b08 cmp r3, #8 - 80009a2: d106 bne.n 80009b2 <_ZN15MotorController9set_speedEi+0x1f0> - 80009a4: 683b ldr r3, [r7, #0] - 80009a6: 425a negs r2, r3 - 80009a8: 687b ldr r3, [r7, #4] - 80009aa: 691b ldr r3, [r3, #16] - 80009ac: 681b ldr r3, [r3, #0] - 80009ae: 63da str r2, [r3, #60] ; 0x3c - } - 80009b0: e01b b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009b2: 687b ldr r3, [r7, #4] - 80009b4: 695b ldr r3, [r3, #20] - 80009b6: 2b0c cmp r3, #12 - 80009b8: d106 bne.n 80009c8 <_ZN15MotorController9set_speedEi+0x206> - 80009ba: 683b ldr r3, [r7, #0] - 80009bc: 425a negs r2, r3 - 80009be: 687b ldr r3, [r7, #4] - 80009c0: 691b ldr r3, [r3, #16] - 80009c2: 681b ldr r3, [r3, #0] - 80009c4: 641a str r2, [r3, #64] ; 0x40 - } - 80009c6: e010 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009c8: 687b ldr r3, [r7, #4] - 80009ca: 695b ldr r3, [r3, #20] - 80009cc: 2b10 cmp r3, #16 - 80009ce: d106 bne.n 80009de <_ZN15MotorController9set_speedEi+0x21c> - 80009d0: 683b ldr r3, [r7, #0] - 80009d2: 425a negs r2, r3 - 80009d4: 687b ldr r3, [r7, #4] - 80009d6: 691b ldr r3, [r3, #16] - 80009d8: 681b ldr r3, [r3, #0] - 80009da: 659a str r2, [r3, #88] ; 0x58 - } - 80009dc: e005 b.n 80009ea <_ZN15MotorController9set_speedEi+0x228> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009de: 683b ldr r3, [r7, #0] - 80009e0: 425a negs r2, r3 - 80009e2: 687b ldr r3, [r7, #4] - 80009e4: 691b ldr r3, [r3, #16] - 80009e6: 681b ldr r3, [r3, #0] - 80009e8: 65da str r2, [r3, #92] ; 0x5c - } - 80009ea: bf00 nop - 80009ec: 3708 adds r7, #8 - 80009ee: 46bd mov sp, r7 - 80009f0: bd80 pop {r7, pc} - -080009f2 <_ZN15MotorController5brakeEv>: - - void brake() { - 80009f2: b480 push {r7} - 80009f4: b083 sub sp, #12 - 80009f6: af00 add r7, sp, #0 - 80009f8: 6078 str r0, [r7, #4] - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 80009fa: 687b ldr r3, [r7, #4] - 80009fc: 695b ldr r3, [r3, #20] - 80009fe: 2b00 cmp r3, #0 - 8000a00: d105 bne.n 8000a0e <_ZN15MotorController5brakeEv+0x1c> - 8000a02: 687b ldr r3, [r7, #4] - 8000a04: 691b ldr r3, [r3, #16] - 8000a06: 681b ldr r3, [r3, #0] - 8000a08: 2200 movs r2, #0 - 8000a0a: 635a str r2, [r3, #52] ; 0x34 - } - 8000a0c: e02c b.n 8000a68 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a0e: 687b ldr r3, [r7, #4] - 8000a10: 695b ldr r3, [r3, #20] - 8000a12: 2b04 cmp r3, #4 - 8000a14: d105 bne.n 8000a22 <_ZN15MotorController5brakeEv+0x30> - 8000a16: 687b ldr r3, [r7, #4] - 8000a18: 691b ldr r3, [r3, #16] - 8000a1a: 681b ldr r3, [r3, #0] - 8000a1c: 2200 movs r2, #0 - 8000a1e: 639a str r2, [r3, #56] ; 0x38 - } - 8000a20: e022 b.n 8000a68 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a22: 687b ldr r3, [r7, #4] - 8000a24: 695b ldr r3, [r3, #20] - 8000a26: 2b08 cmp r3, #8 - 8000a28: d105 bne.n 8000a36 <_ZN15MotorController5brakeEv+0x44> - 8000a2a: 687b ldr r3, [r7, #4] - 8000a2c: 691b ldr r3, [r3, #16] - 8000a2e: 681b ldr r3, [r3, #0] - 8000a30: 2200 movs r2, #0 - 8000a32: 63da str r2, [r3, #60] ; 0x3c - } - 8000a34: e018 b.n 8000a68 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a36: 687b ldr r3, [r7, #4] - 8000a38: 695b ldr r3, [r3, #20] - 8000a3a: 2b0c cmp r3, #12 - 8000a3c: d105 bne.n 8000a4a <_ZN15MotorController5brakeEv+0x58> - 8000a3e: 687b ldr r3, [r7, #4] - 8000a40: 691b ldr r3, [r3, #16] - 8000a42: 681b ldr r3, [r3, #0] - 8000a44: 2200 movs r2, #0 - 8000a46: 641a str r2, [r3, #64] ; 0x40 - } - 8000a48: e00e b.n 8000a68 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a4a: 687b ldr r3, [r7, #4] - 8000a4c: 695b ldr r3, [r3, #20] - 8000a4e: 2b10 cmp r3, #16 - 8000a50: d105 bne.n 8000a5e <_ZN15MotorController5brakeEv+0x6c> - 8000a52: 687b ldr r3, [r7, #4] - 8000a54: 691b ldr r3, [r3, #16] - 8000a56: 681b ldr r3, [r3, #0] - 8000a58: 2200 movs r2, #0 - 8000a5a: 659a str r2, [r3, #88] ; 0x58 - } - 8000a5c: e004 b.n 8000a68 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a5e: 687b ldr r3, [r7, #4] - 8000a60: 691b ldr r3, [r3, #16] - 8000a62: 681b ldr r3, [r3, #0] - 8000a64: 2200 movs r2, #0 - 8000a66: 65da str r2, [r3, #92] ; 0x5c - } - 8000a68: bf00 nop - 8000a6a: 370c adds r7, #12 - 8000a6c: 46bd mov sp, r7 - 8000a6e: f85d 7b04 ldr.w r7, [sp], #4 - 8000a72: 4770 bx lr - -08000a74 <_ZN3PidC1Efff>: + 800096a: 687b ldr r3, [r7, #4] + 800096c: 691b ldr r3, [r3, #16] + 800096e: 681b ldr r3, [r3, #0] + 8000970: f240 3216 movw r2, #790 ; 0x316 + 8000974: 65da str r2, [r3, #92] ; 0x5c + } + 8000976: e03c b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 8000978: 687b ldr r3, [r7, #4] + 800097a: 695b ldr r3, [r3, #20] + 800097c: 2b00 cmp r3, #0 + 800097e: d106 bne.n 800098e <_ZN15MotorController9set_speedEi+0x1ca> + 8000980: 683b ldr r3, [r7, #0] + 8000982: 425a negs r2, r3 + 8000984: 687b ldr r3, [r7, #4] + 8000986: 691b ldr r3, [r3, #16] + 8000988: 681b ldr r3, [r3, #0] + 800098a: 635a str r2, [r3, #52] ; 0x34 + } + 800098c: e031 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 800098e: 687b ldr r3, [r7, #4] + 8000990: 695b ldr r3, [r3, #20] + 8000992: 2b04 cmp r3, #4 + 8000994: d106 bne.n 80009a4 <_ZN15MotorController9set_speedEi+0x1e0> + 8000996: 683b ldr r3, [r7, #0] + 8000998: 425a negs r2, r3 + 800099a: 687b ldr r3, [r7, #4] + 800099c: 691b ldr r3, [r3, #16] + 800099e: 681b ldr r3, [r3, #0] + 80009a0: 639a str r2, [r3, #56] ; 0x38 + } + 80009a2: e026 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 80009a4: 687b ldr r3, [r7, #4] + 80009a6: 695b ldr r3, [r3, #20] + 80009a8: 2b08 cmp r3, #8 + 80009aa: d106 bne.n 80009ba <_ZN15MotorController9set_speedEi+0x1f6> + 80009ac: 683b ldr r3, [r7, #0] + 80009ae: 425a negs r2, r3 + 80009b0: 687b ldr r3, [r7, #4] + 80009b2: 691b ldr r3, [r3, #16] + 80009b4: 681b ldr r3, [r3, #0] + 80009b6: 63da str r2, [r3, #60] ; 0x3c + } + 80009b8: e01b b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 80009ba: 687b ldr r3, [r7, #4] + 80009bc: 695b ldr r3, [r3, #20] + 80009be: 2b0c cmp r3, #12 + 80009c0: d106 bne.n 80009d0 <_ZN15MotorController9set_speedEi+0x20c> + 80009c2: 683b ldr r3, [r7, #0] + 80009c4: 425a negs r2, r3 + 80009c6: 687b ldr r3, [r7, #4] + 80009c8: 691b ldr r3, [r3, #16] + 80009ca: 681b ldr r3, [r3, #0] + 80009cc: 641a str r2, [r3, #64] ; 0x40 + } + 80009ce: e010 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 80009d0: 687b ldr r3, [r7, #4] + 80009d2: 695b ldr r3, [r3, #20] + 80009d4: 2b10 cmp r3, #16 + 80009d6: d106 bne.n 80009e6 <_ZN15MotorController9set_speedEi+0x222> + 80009d8: 683b ldr r3, [r7, #0] + 80009da: 425a negs r2, r3 + 80009dc: 687b ldr r3, [r7, #4] + 80009de: 691b ldr r3, [r3, #16] + 80009e0: 681b ldr r3, [r3, #0] + 80009e2: 659a str r2, [r3, #88] ; 0x58 + } + 80009e4: e005 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 80009e6: 683b ldr r3, [r7, #0] + 80009e8: 425a negs r2, r3 + 80009ea: 687b ldr r3, [r7, #4] + 80009ec: 691b ldr r3, [r3, #16] + 80009ee: 681b ldr r3, [r3, #0] + 80009f0: 65da str r2, [r3, #92] ; 0x5c + } + 80009f2: bf00 nop + 80009f4: 3708 adds r7, #8 + 80009f6: 46bd mov sp, r7 + 80009f8: bd80 pop {r7, pc} + 80009fa: bf00 nop + 80009fc: fffffcea .word 0xfffffcea + +08000a00 <_ZN3PidC1Efff>: float previous_error_; // int min_; // int max_; Pid(float kp, float ki, float kd) { - 8000a74: b480 push {r7} - 8000a76: b087 sub sp, #28 - 8000a78: af00 add r7, sp, #0 - 8000a7a: 60f8 str r0, [r7, #12] - 8000a7c: ed87 0a02 vstr s0, [r7, #8] - 8000a80: edc7 0a01 vstr s1, [r7, #4] - 8000a84: ed87 1a00 vstr s2, [r7] + 8000a00: b480 push {r7} + 8000a02: b087 sub sp, #28 + 8000a04: af00 add r7, sp, #0 + 8000a06: 60f8 str r0, [r7, #12] + 8000a08: ed87 0a02 vstr s0, [r7, #8] + 8000a0c: edc7 0a01 vstr s1, [r7, #4] + 8000a10: ed87 1a00 vstr s2, [r7] this->kp_ = kp; - 8000a88: 68fb ldr r3, [r7, #12] - 8000a8a: 68ba ldr r2, [r7, #8] - 8000a8c: 601a str r2, [r3, #0] + 8000a14: 68fb ldr r3, [r7, #12] + 8000a16: 68ba ldr r2, [r7, #8] + 8000a18: 601a str r2, [r3, #0] this->ki_ = ki; - 8000a8e: 68fb ldr r3, [r7, #12] - 8000a90: 687a ldr r2, [r7, #4] - 8000a92: 605a str r2, [r3, #4] + 8000a1a: 68fb ldr r3, [r7, #12] + 8000a1c: 687a ldr r2, [r7, #4] + 8000a1e: 605a str r2, [r3, #4] this->kd_ = kd; - 8000a94: 68fb ldr r3, [r7, #12] - 8000a96: 683a ldr r2, [r7, #0] - 8000a98: 609a str r2, [r3, #8] + 8000a20: 68fb ldr r3, [r7, #12] + 8000a22: 683a ldr r2, [r7, #0] + 8000a24: 609a str r2, [r3, #8] this->error_ = 0; - 8000a9a: 68fb ldr r3, [r7, #12] - 8000a9c: f04f 0200 mov.w r2, #0 - 8000aa0: 60da str r2, [r3, #12] + 8000a26: 68fb ldr r3, [r7, #12] + 8000a28: f04f 0200 mov.w r2, #0 + 8000a2c: 60da str r2, [r3, #12] this->setpoint_ = 0; - 8000aa2: 68fb ldr r3, [r7, #12] - 8000aa4: f04f 0200 mov.w r2, #0 - 8000aa8: 611a str r2, [r3, #16] + 8000a2e: 68fb ldr r3, [r7, #12] + 8000a30: f04f 0200 mov.w r2, #0 + 8000a34: 611a str r2, [r3, #16] this->previous_error_ = 0; - 8000aaa: 68fb ldr r3, [r7, #12] - 8000aac: f04f 0200 mov.w r2, #0 - 8000ab0: 641a str r2, [r3, #64] ; 0x40 + 8000a36: 68fb ldr r3, [r7, #12] + 8000a38: f04f 0200 mov.w r2, #0 + 8000a3c: 641a str r2, [r3, #64] ; 0x40 this->error_sum_index_ = 0; - 8000ab2: 68fb ldr r3, [r7, #12] - 8000ab4: 2200 movs r2, #0 - 8000ab6: 63da str r2, [r3, #60] ; 0x3c + 8000a3e: 68fb ldr r3, [r7, #12] + 8000a40: 2200 movs r2, #0 + 8000a42: 63da str r2, [r3, #60] ; 0x3c for (int i = 0; i < 10; i++) { - 8000ab8: 2300 movs r3, #0 - 8000aba: 617b str r3, [r7, #20] - 8000abc: 697b ldr r3, [r7, #20] - 8000abe: 2b09 cmp r3, #9 - 8000ac0: dc0c bgt.n 8000adc <_ZN3PidC1Efff+0x68> + 8000a44: 2300 movs r3, #0 + 8000a46: 617b str r3, [r7, #20] + 8000a48: 697b ldr r3, [r7, #20] + 8000a4a: 2b09 cmp r3, #9 + 8000a4c: dc0c bgt.n 8000a68 <_ZN3PidC1Efff+0x68> this->error_sum_array_[i] = 0; - 8000ac2: 68fa ldr r2, [r7, #12] - 8000ac4: 697b ldr r3, [r7, #20] - 8000ac6: 3304 adds r3, #4 - 8000ac8: 009b lsls r3, r3, #2 - 8000aca: 4413 add r3, r2 - 8000acc: 3304 adds r3, #4 - 8000ace: f04f 0200 mov.w r2, #0 - 8000ad2: 601a str r2, [r3, #0] + 8000a4e: 68fa ldr r2, [r7, #12] + 8000a50: 697b ldr r3, [r7, #20] + 8000a52: 3304 adds r3, #4 + 8000a54: 009b lsls r3, r3, #2 + 8000a56: 4413 add r3, r2 + 8000a58: 3304 adds r3, #4 + 8000a5a: f04f 0200 mov.w r2, #0 + 8000a5e: 601a str r2, [r3, #0] for (int i = 0; i < 10; i++) { - 8000ad4: 697b ldr r3, [r7, #20] - 8000ad6: 3301 adds r3, #1 - 8000ad8: 617b str r3, [r7, #20] - 8000ada: e7ef b.n 8000abc <_ZN3PidC1Efff+0x48> + 8000a60: 697b ldr r3, [r7, #20] + 8000a62: 3301 adds r3, #1 + 8000a64: 617b str r3, [r7, #20] + 8000a66: e7ef b.n 8000a48 <_ZN3PidC1Efff+0x48> } } - 8000adc: 68fb ldr r3, [r7, #12] - 8000ade: 4618 mov r0, r3 - 8000ae0: 371c adds r7, #28 - 8000ae2: 46bd mov sp, r7 - 8000ae4: f85d 7b04 ldr.w r7, [sp], #4 - 8000ae8: 4770 bx lr - ... + 8000a68: 68fb ldr r3, [r7, #12] + 8000a6a: 4618 mov r0, r3 + 8000a6c: 371c adds r7, #28 + 8000a6e: 46bd mov sp, r7 + 8000a70: f85d 7b04 ldr.w r7, [sp], #4 + 8000a74: 4770 bx lr + +08000a76 <_ZN3Pid3setEf>: + + void set(float setpoint) { + 8000a76: b480 push {r7} + 8000a78: b083 sub sp, #12 + 8000a7a: af00 add r7, sp, #0 + 8000a7c: 6078 str r0, [r7, #4] + 8000a7e: ed87 0a00 vstr s0, [r7] + this->setpoint_ = setpoint; + 8000a82: 687b ldr r3, [r7, #4] + 8000a84: 683a ldr r2, [r7, #0] + 8000a86: 611a str r2, [r3, #16] + } + 8000a88: bf00 nop + 8000a8a: 370c adds r7, #12 + 8000a8c: 46bd mov sp, r7 + 8000a8e: f85d 7b04 ldr.w r7, [sp], #4 + 8000a92: 4770 bx lr + +08000a94 <_ZN3Pid6updateEf>: + + int update(float measure) { + 8000a94: b480 push {r7} + 8000a96: b087 sub sp, #28 + 8000a98: af00 add r7, sp, #0 + 8000a9a: 6078 str r0, [r7, #4] + 8000a9c: ed87 0a00 vstr s0, [r7] + + this->error_ = this->setpoint_ - measure; + 8000aa0: 687b ldr r3, [r7, #4] + 8000aa2: ed93 7a04 vldr s14, [r3, #16] + 8000aa6: edd7 7a00 vldr s15, [r7] + 8000aaa: ee77 7a67 vsub.f32 s15, s14, s15 + 8000aae: 687b ldr r3, [r7, #4] + 8000ab0: edc3 7a03 vstr s15, [r3, #12] + + //proportional term + float output = this->error_ * this->kp_; + 8000ab4: 687b ldr r3, [r7, #4] + 8000ab6: ed93 7a03 vldr s14, [r3, #12] + 8000aba: 687b ldr r3, [r7, #4] + 8000abc: edd3 7a00 vldr s15, [r3] + 8000ac0: ee67 7a27 vmul.f32 s15, s14, s15 + 8000ac4: edc7 7a03 vstr s15, [r7, #12] + + //integral term + if (this->error_sum_index_ == 10) { + 8000ac8: 687b ldr r3, [r7, #4] + 8000aca: 6bdb ldr r3, [r3, #60] ; 0x3c + 8000acc: 2b0a cmp r3, #10 + 8000ace: d107 bne.n 8000ae0 <_ZN3Pid6updateEf+0x4c> + this->error_sum_array_[0] = this->error_; + 8000ad0: 687b ldr r3, [r7, #4] + 8000ad2: 68da ldr r2, [r3, #12] + 8000ad4: 687b ldr r3, [r7, #4] + 8000ad6: 615a str r2, [r3, #20] + this->error_sum_index_ = 0; + 8000ad8: 687b ldr r3, [r7, #4] + 8000ada: 2200 movs r2, #0 + 8000adc: 63da str r2, [r3, #60] ; 0x3c + 8000ade: e00e b.n 8000afe <_ZN3Pid6updateEf+0x6a> + } else { + this->error_sum_array_[this->error_sum_index_] = this->error_; + 8000ae0: 687b ldr r3, [r7, #4] + 8000ae2: 6bdb ldr r3, [r3, #60] ; 0x3c + 8000ae4: 687a ldr r2, [r7, #4] + 8000ae6: 68d2 ldr r2, [r2, #12] + 8000ae8: 6879 ldr r1, [r7, #4] + 8000aea: 3304 adds r3, #4 + 8000aec: 009b lsls r3, r3, #2 + 8000aee: 440b add r3, r1 + 8000af0: 3304 adds r3, #4 + 8000af2: 601a str r2, [r3, #0] + this->error_sum_index_++; + 8000af4: 687b ldr r3, [r7, #4] + 8000af6: 6bdb ldr r3, [r3, #60] ; 0x3c + 8000af8: 1c5a adds r2, r3, #1 + 8000afa: 687b ldr r3, [r7, #4] + 8000afc: 63da str r2, [r3, #60] ; 0x3c + } + + float error_sum = 0; + 8000afe: f04f 0300 mov.w r3, #0 + 8000b02: 617b str r3, [r7, #20] + for (int i = 0; i < 10; i++) { + 8000b04: 2300 movs r3, #0 + 8000b06: 613b str r3, [r7, #16] + 8000b08: 693b ldr r3, [r7, #16] + 8000b0a: 2b09 cmp r3, #9 + 8000b0c: dc11 bgt.n 8000b32 <_ZN3Pid6updateEf+0x9e> + error_sum += this->error_sum_array_[i]; + 8000b0e: 687a ldr r2, [r7, #4] + 8000b10: 693b ldr r3, [r7, #16] + 8000b12: 3304 adds r3, #4 + 8000b14: 009b lsls r3, r3, #2 + 8000b16: 4413 add r3, r2 + 8000b18: 3304 adds r3, #4 + 8000b1a: edd3 7a00 vldr s15, [r3] + 8000b1e: ed97 7a05 vldr s14, [r7, #20] + 8000b22: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b26: edc7 7a05 vstr s15, [r7, #20] + for (int i = 0; i < 10; i++) { + 8000b2a: 693b ldr r3, [r7, #16] + 8000b2c: 3301 adds r3, #1 + 8000b2e: 613b str r3, [r7, #16] + 8000b30: e7ea b.n 8000b08 <_ZN3Pid6updateEf+0x74> + } -08000aec
: + output += error_sum * this->ki_; + 8000b32: 687b ldr r3, [r7, #4] + 8000b34: ed93 7a01 vldr s14, [r3, #4] + 8000b38: edd7 7a05 vldr s15, [r7, #20] + 8000b3c: ee67 7a27 vmul.f32 s15, s14, s15 + 8000b40: ed97 7a03 vldr s14, [r7, #12] + 8000b44: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b48: edc7 7a03 vstr s15, [r7, #12] + + //derivative term + output += (this->error_ - this->previous_error_); + 8000b4c: 687b ldr r3, [r7, #4] + 8000b4e: ed93 7a03 vldr s14, [r3, #12] + 8000b52: 687b ldr r3, [r7, #4] + 8000b54: edd3 7a10 vldr s15, [r3, #64] ; 0x40 + 8000b58: ee77 7a67 vsub.f32 s15, s14, s15 + 8000b5c: ed97 7a03 vldr s14, [r7, #12] + 8000b60: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b64: edc7 7a03 vstr s15, [r7, #12] + this->previous_error_ = this->error_; + 8000b68: 687b ldr r3, [r7, #4] + 8000b6a: 68da ldr r2, [r3, #12] + 8000b6c: 687b ldr r3, [r7, #4] + 8000b6e: 641a str r2, [r3, #64] ; 0x40 + + int integer_output = (int) output; + 8000b70: edd7 7a03 vldr s15, [r7, #12] + 8000b74: eefd 7ae7 vcvt.s32.f32 s15, s15 + 8000b78: ee17 3a90 vmov r3, s15 + 8000b7c: 60bb str r3, [r7, #8] + + return integer_output; + 8000b7e: 68bb ldr r3, [r7, #8] + + } + 8000b80: 4618 mov r0, r3 + 8000b82: 371c adds r7, #28 + 8000b84: 46bd mov sp, r7 + 8000b86: f85d 7b04 ldr.w r7, [sp], #4 + 8000b8a: 4770 bx lr + +08000b8c
: /** - * @brief The application entry point. - * @retval int - */ -int main(void) { - 8000aec: b580 push {r7, lr} - 8000aee: af00 add r7, sp, #0 - /* USER CODE END 1 */ + * @brief The application entry point. + * @retval int + */ +int main(void) +{ + 8000b8c: b580 push {r7, lr} + 8000b8e: af00 add r7, sp, #0 + /* MCU Configuration--------------------------------------------------------*/ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ HAL_Init(); - 8000af0: f000 ff91 bl 8001a16 + 8000b90: f000 ffa5 bl 8001ade /* USER CODE BEGIN Init */ /* USER CODE END Init */ /* Configure the system clock */ SystemClock_Config(); - 8000af4: f000 f848 bl 8000b88 <_Z18SystemClock_Configv> + 8000b94: f000 f84e bl 8000c34 <_Z18SystemClock_Configv> /* USER CODE BEGIN SysInit */ /* USER CODE END SysInit */ /* Initialize all configured peripherals */ MX_GPIO_Init(); - 8000af8: f000 fb20 bl 800113c <_ZL12MX_GPIO_Initv> + 8000b98: f000 fb26 bl 80011e8 <_ZL12MX_GPIO_Initv> MX_TIM2_Init(); - 8000afc: f000 f8ea bl 8000cd4 <_ZL12MX_TIM2_Initv> + 8000b9c: f000 f8f0 bl 8000d80 <_ZL12MX_TIM2_Initv> MX_TIM3_Init(); - 8000b00: f000 f946 bl 8000d90 <_ZL12MX_TIM3_Initv> + 8000ba0: f000 f94c bl 8000e3c <_ZL12MX_TIM3_Initv> MX_TIM4_Init(); - 8000b04: f000 f9a2 bl 8000e4c <_ZL12MX_TIM4_Initv> + 8000ba4: f000 f9a8 bl 8000ef8 <_ZL12MX_TIM4_Initv> MX_TIM5_Init(); - 8000b08: f000 fa40 bl 8000f8c <_ZL12MX_TIM5_Initv> + 8000ba8: f000 fa46 bl 8001038 <_ZL12MX_TIM5_Initv> MX_USART6_UART_Init(); - 8000b0c: f000 fae0 bl 80010d0 <_ZL19MX_USART6_UART_Initv> + 8000bac: f000 fae6 bl 800117c <_ZL19MX_USART6_UART_Initv> MX_TIM6_Init(); - 8000b10: f000 fa9c bl 800104c <_ZL12MX_TIM6_Initv> + 8000bb0: f000 faa2 bl 80010f8 <_ZL12MX_TIM6_Initv> /* Initialize interrupts */ MX_NVIC_Init(); - 8000b14: f000 f8c2 bl 8000c9c <_ZL12MX_NVIC_Initv> + 8000bb4: f000 f8c8 bl 8000d48 <_ZL12MX_NVIC_Initv> /* USER CODE BEGIN 2 */ left_encoder.Setup(); - 8000b18: 480e ldr r0, [pc, #56] ; (8000b54 ) - 8000b1a: f7ff fd53 bl 80005c4 <_ZN7Encoder5SetupEv> + 8000bb8: 4811 ldr r0, [pc, #68] ; (8000c00 ) + 8000bba: f7ff fd03 bl 80005c4 <_ZN7Encoder5SetupEv> right_encoder.Setup(); - 8000b1e: 480e ldr r0, [pc, #56] ; (8000b58 ) - 8000b20: f7ff fd50 bl 80005c4 <_ZN7Encoder5SetupEv> + 8000bbe: 4811 ldr r0, [pc, #68] ; (8000c04 ) + 8000bc0: f7ff fd00 bl 80005c4 <_ZN7Encoder5SetupEv> left_motor.setup(); - 8000b24: 480d ldr r0, [pc, #52] ; (8000b5c ) - 8000b26: f7ff fe3c bl 80007a2 <_ZN15MotorController5setupEv> + 8000bc4: 4810 ldr r0, [pc, #64] ; (8000c08 ) + 8000bc6: f7ff fdec bl 80007a2 <_ZN15MotorController5setupEv> right_motor.setup(); - 8000b2a: 480d ldr r0, [pc, #52] ; (8000b60 ) - 8000b2c: f7ff fe39 bl 80007a2 <_ZN15MotorController5setupEv> + 8000bca: 4810 ldr r0, [pc, #64] ; (8000c0c ) + 8000bcc: f7ff fde9 bl 80007a2 <_ZN15MotorController5setupEv> tx_buffer = (uint8_t*) &odom_msg; - 8000b30: 4b0c ldr r3, [pc, #48] ; (8000b64 ) - 8000b32: 4a0d ldr r2, [pc, #52] ; (8000b68 ) - 8000b34: 601a str r2, [r3, #0] + 8000bd0: 4b0f ldr r3, [pc, #60] ; (8000c10 ) + 8000bd2: 4a10 ldr r2, [pc, #64] ; (8000c14 ) + 8000bd4: 601a str r2, [r3, #0] rx_buffer = (uint8_t*) &vel_msg; - 8000b36: 4b0d ldr r3, [pc, #52] ; (8000b6c ) - 8000b38: 4a0d ldr r2, [pc, #52] ; (8000b70 ) - 8000b3a: 601a str r2, [r3, #0] + 8000bd6: 4b10 ldr r3, [pc, #64] ; (8000c18 ) + 8000bd8: 4a10 ldr r2, [pc, #64] ; (8000c1c ) + 8000bda: 601a str r2, [r3, #0] address = &left_dutycycle; - 8000b3c: 4b0d ldr r3, [pc, #52] ; (8000b74 ) - 8000b3e: 4a0e ldr r2, [pc, #56] ; (8000b78 ) - 8000b40: 601a str r2, [r3, #0] + 8000bdc: 4b10 ldr r3, [pc, #64] ; (8000c20 ) + 8000bde: 4a11 ldr r2, [pc, #68] ; (8000c24 ) + 8000be0: 601a str r2, [r3, #0] //Enables UART RX interrupt -// HAL_UART_Receive_IT(&huart6, rx_buffer, 8); - - //test plot stuff - HAL_UART_Receive_IT(&huart6, (uint8_t*) &rx_test, 4); - 8000b42: 2204 movs r2, #4 - 8000b44: 490d ldr r1, [pc, #52] ; (8000b7c ) - 8000b46: 480e ldr r0, [pc, #56] ; (8000b80 ) - 8000b48: f003 fd02 bl 8004550 + HAL_UART_Receive_IT(&huart6, rx_buffer, 8); + 8000be2: 4b0d ldr r3, [pc, #52] ; (8000c18 ) + 8000be4: 681b ldr r3, [r3, #0] + 8000be6: 2208 movs r2, #8 + 8000be8: 4619 mov r1, r3 + 8000bea: 480f ldr r0, [pc, #60] ; (8000c28 ) + 8000bec: f003 fd14 bl 8004618 //Enables TIM3 interrupt (used for PID control) HAL_TIM_Base_Start_IT(&htim3); - 8000b4c: 480d ldr r0, [pc, #52] ; (8000b84 ) - 8000b4e: f002 fb61 bl 8003214 + 8000bf0: 480e ldr r0, [pc, #56] ; (8000c2c ) + 8000bf2: f002 fb73 bl 80032dc + + //Enables TIM6 interrupt (used for periodic transmission) + HAL_TIM_Base_Start_IT(&htim6); + 8000bf6: 480e ldr r0, [pc, #56] ; (8000c30 ) + 8000bf8: f002 fb70 bl 80032dc /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { - 8000b52: e7fe b.n 8000b52 - 8000b54: 200001f0 .word 0x200001f0 - 8000b58: 2000020c .word 0x2000020c - 8000b5c: 2000034c .word 0x2000034c - 8000b60: 20000364 .word 0x20000364 - 8000b64: 2000037c .word 0x2000037c - 8000b68: 20000384 .word 0x20000384 - 8000b6c: 20000380 .word 0x20000380 - 8000b70: 20000390 .word 0x20000390 - 8000b74: 20000348 .word 0x20000348 - 8000b78: 20000344 .word 0x20000344 - 8000b7c: 20000398 .word 0x20000398 - 8000b80: 20000170 .word 0x20000170 - 8000b84: 20000070 .word 0x20000070 - -08000b88 <_Z18SystemClock_Configv>: - + 8000bfc: e7fe b.n 8000bfc + 8000bfe: bf00 nop + 8000c00: 200001ec .word 0x200001ec + 8000c04: 20000208 .word 0x20000208 + 8000c08: 2000034c .word 0x2000034c + 8000c0c: 20000364 .word 0x20000364 + 8000c10: 2000037c .word 0x2000037c + 8000c14: 20000384 .word 0x20000384 + 8000c18: 20000380 .word 0x20000380 + 8000c1c: 20000390 .word 0x20000390 + 8000c20: 20000348 .word 0x20000348 + 8000c24: 20000340 .word 0x20000340 + 8000c28: 2000016c .word 0x2000016c + 8000c2c: 2000006c .word 0x2000006c + 8000c30: 2000012c .word 0x2000012c + +08000c34 <_Z18SystemClock_Configv>: /** - * @brief System Clock Configuration - * @retval None - */ -void SystemClock_Config(void) { - 8000b88: b580 push {r7, lr} - 8000b8a: b0b8 sub sp, #224 ; 0xe0 - 8000b8c: af00 add r7, sp, #0 - RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; - 8000b8e: f107 03ac add.w r3, r7, #172 ; 0xac - 8000b92: 2234 movs r2, #52 ; 0x34 - 8000b94: 2100 movs r1, #0 - 8000b96: 4618 mov r0, r3 - 8000b98: f004 fb82 bl 80052a0 - RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; - 8000b9c: f107 0398 add.w r3, r7, #152 ; 0x98 - 8000ba0: 2200 movs r2, #0 - 8000ba2: 601a str r2, [r3, #0] - 8000ba4: 605a str r2, [r3, #4] - 8000ba6: 609a str r2, [r3, #8] - 8000ba8: 60da str r2, [r3, #12] - 8000baa: 611a str r2, [r3, #16] - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; - 8000bac: f107 0308 add.w r3, r7, #8 - 8000bb0: 2290 movs r2, #144 ; 0x90 - 8000bb2: 2100 movs r1, #0 - 8000bb4: 4618 mov r0, r3 - 8000bb6: f004 fb73 bl 80052a0 + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) +{ + 8000c34: b580 push {r7, lr} + 8000c36: b0b8 sub sp, #224 ; 0xe0 + 8000c38: af00 add r7, sp, #0 + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + 8000c3a: f107 03ac add.w r3, r7, #172 ; 0xac + 8000c3e: 2234 movs r2, #52 ; 0x34 + 8000c40: 2100 movs r1, #0 + 8000c42: 4618 mov r0, r3 + 8000c44: f004 fb90 bl 8005368 + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + 8000c48: f107 0398 add.w r3, r7, #152 ; 0x98 + 8000c4c: 2200 movs r2, #0 + 8000c4e: 601a str r2, [r3, #0] + 8000c50: 605a str r2, [r3, #4] + 8000c52: 609a str r2, [r3, #8] + 8000c54: 60da str r2, [r3, #12] + 8000c56: 611a str r2, [r3, #16] + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; + 8000c58: f107 0308 add.w r3, r7, #8 + 8000c5c: 2290 movs r2, #144 ; 0x90 + 8000c5e: 2100 movs r1, #0 + 8000c60: 4618 mov r0, r3 + 8000c62: f004 fb81 bl 8005368 /** Configure the main internal regulator output voltage - */ + */ __HAL_RCC_PWR_CLK_ENABLE(); - 8000bba: 4b36 ldr r3, [pc, #216] ; (8000c94 <_Z18SystemClock_Configv+0x10c>) - 8000bbc: 6c1b ldr r3, [r3, #64] ; 0x40 - 8000bbe: 4a35 ldr r2, [pc, #212] ; (8000c94 <_Z18SystemClock_Configv+0x10c>) - 8000bc0: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8000bc4: 6413 str r3, [r2, #64] ; 0x40 - 8000bc6: 4b33 ldr r3, [pc, #204] ; (8000c94 <_Z18SystemClock_Configv+0x10c>) - 8000bc8: 6c1b ldr r3, [r3, #64] ; 0x40 - 8000bca: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8000bce: 607b str r3, [r7, #4] - 8000bd0: 687b ldr r3, [r7, #4] + 8000c66: 4b36 ldr r3, [pc, #216] ; (8000d40 <_Z18SystemClock_Configv+0x10c>) + 8000c68: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000c6a: 4a35 ldr r2, [pc, #212] ; (8000d40 <_Z18SystemClock_Configv+0x10c>) + 8000c6c: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8000c70: 6413 str r3, [r2, #64] ; 0x40 + 8000c72: 4b33 ldr r3, [pc, #204] ; (8000d40 <_Z18SystemClock_Configv+0x10c>) + 8000c74: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000c76: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8000c7a: 607b str r3, [r7, #4] + 8000c7c: 687b ldr r3, [r7, #4] __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); - 8000bd2: 4b31 ldr r3, [pc, #196] ; (8000c98 <_Z18SystemClock_Configv+0x110>) - 8000bd4: 681b ldr r3, [r3, #0] - 8000bd6: f423 4340 bic.w r3, r3, #49152 ; 0xc000 - 8000bda: 4a2f ldr r2, [pc, #188] ; (8000c98 <_Z18SystemClock_Configv+0x110>) - 8000bdc: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 8000be0: 6013 str r3, [r2, #0] - 8000be2: 4b2d ldr r3, [pc, #180] ; (8000c98 <_Z18SystemClock_Configv+0x110>) - 8000be4: 681b ldr r3, [r3, #0] - 8000be6: f403 4340 and.w r3, r3, #49152 ; 0xc000 - 8000bea: 603b str r3, [r7, #0] - 8000bec: 683b ldr r3, [r7, #0] + 8000c7e: 4b31 ldr r3, [pc, #196] ; (8000d44 <_Z18SystemClock_Configv+0x110>) + 8000c80: 681b ldr r3, [r3, #0] + 8000c82: f423 4340 bic.w r3, r3, #49152 ; 0xc000 + 8000c86: 4a2f ldr r2, [pc, #188] ; (8000d44 <_Z18SystemClock_Configv+0x110>) + 8000c88: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8000c8c: 6013 str r3, [r2, #0] + 8000c8e: 4b2d ldr r3, [pc, #180] ; (8000d44 <_Z18SystemClock_Configv+0x110>) + 8000c90: 681b ldr r3, [r3, #0] + 8000c92: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8000c96: 603b str r3, [r7, #0] + 8000c98: 683b ldr r3, [r7, #0] /** Initializes the CPU, AHB and APB busses clocks - */ + */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; - 8000bee: 2302 movs r3, #2 - 8000bf0: f8c7 30ac str.w r3, [r7, #172] ; 0xac + 8000c9a: 2302 movs r3, #2 + 8000c9c: f8c7 30ac str.w r3, [r7, #172] ; 0xac RCC_OscInitStruct.HSIState = RCC_HSI_ON; - 8000bf4: 2301 movs r3, #1 - 8000bf6: f8c7 30b8 str.w r3, [r7, #184] ; 0xb8 + 8000ca0: 2301 movs r3, #1 + 8000ca2: f8c7 30b8 str.w r3, [r7, #184] ; 0xb8 RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; - 8000bfa: 2310 movs r3, #16 - 8000bfc: f8c7 30bc str.w r3, [r7, #188] ; 0xbc + 8000ca6: 2310 movs r3, #16 + 8000ca8: f8c7 30bc str.w r3, [r7, #188] ; 0xbc RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - 8000c00: 2300 movs r3, #0 - 8000c02: f8c7 30c4 str.w r3, [r7, #196] ; 0xc4 - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { - 8000c06: f107 03ac add.w r3, r7, #172 ; 0xac - 8000c0a: 4618 mov r0, r3 - 8000c0c: f001 fa70 bl 80020f0 - 8000c10: 4603 mov r3, r0 - 8000c12: 2b00 cmp r3, #0 - 8000c14: bf14 ite ne - 8000c16: 2301 movne r3, #1 - 8000c18: 2300 moveq r3, #0 - 8000c1a: b2db uxtb r3, r3 - 8000c1c: 2b00 cmp r3, #0 - 8000c1e: d001 beq.n 8000c24 <_Z18SystemClock_Configv+0x9c> + 8000cac: 2300 movs r3, #0 + 8000cae: f8c7 30c4 str.w r3, [r7, #196] ; 0xc4 + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + 8000cb2: f107 03ac add.w r3, r7, #172 ; 0xac + 8000cb6: 4618 mov r0, r3 + 8000cb8: f001 fa7e bl 80021b8 + 8000cbc: 4603 mov r3, r0 + 8000cbe: 2b00 cmp r3, #0 + 8000cc0: bf14 ite ne + 8000cc2: 2301 movne r3, #1 + 8000cc4: 2300 moveq r3, #0 + 8000cc6: b2db uxtb r3, r3 + 8000cc8: 2b00 cmp r3, #0 + 8000cca: d001 beq.n 8000cd0 <_Z18SystemClock_Configv+0x9c> + { Error_Handler(); - 8000c20: f000 fc36 bl 8001490 + 8000ccc: f000 fc45 bl 800155a } /** Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK - 8000c24: 230f movs r3, #15 - 8000c26: f8c7 3098 str.w r3, [r7, #152] ; 0x98 - | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + 8000cd0: 230f movs r3, #15 + 8000cd2: f8c7 3098 str.w r3, [r7, #152] ; 0x98 + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; - 8000c2a: 2300 movs r3, #0 - 8000c2c: f8c7 309c str.w r3, [r7, #156] ; 0x9c + 8000cd6: 2300 movs r3, #0 + 8000cd8: f8c7 309c str.w r3, [r7, #156] ; 0x9c RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - 8000c30: 2300 movs r3, #0 - 8000c32: f8c7 30a0 str.w r3, [r7, #160] ; 0xa0 + 8000cdc: 2300 movs r3, #0 + 8000cde: f8c7 30a0 str.w r3, [r7, #160] ; 0xa0 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; - 8000c36: 2300 movs r3, #0 - 8000c38: f8c7 30a4 str.w r3, [r7, #164] ; 0xa4 + 8000ce2: 2300 movs r3, #0 + 8000ce4: f8c7 30a4 str.w r3, [r7, #164] ; 0xa4 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - 8000c3c: 2300 movs r3, #0 - 8000c3e: f8c7 30a8 str.w r3, [r7, #168] ; 0xa8 - - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { - 8000c42: f107 0398 add.w r3, r7, #152 ; 0x98 - 8000c46: 2100 movs r1, #0 - 8000c48: 4618 mov r0, r3 - 8000c4a: f001 fcc3 bl 80025d4 - 8000c4e: 4603 mov r3, r0 - 8000c50: 2b00 cmp r3, #0 - 8000c52: bf14 ite ne - 8000c54: 2301 movne r3, #1 - 8000c56: 2300 moveq r3, #0 - 8000c58: b2db uxtb r3, r3 - 8000c5a: 2b00 cmp r3, #0 - 8000c5c: d001 beq.n 8000c62 <_Z18SystemClock_Configv+0xda> + 8000ce8: 2300 movs r3, #0 + 8000cea: f8c7 30a8 str.w r3, [r7, #168] ; 0xa8 + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) + 8000cee: f107 0398 add.w r3, r7, #152 ; 0x98 + 8000cf2: 2100 movs r1, #0 + 8000cf4: 4618 mov r0, r3 + 8000cf6: f001 fcd1 bl 800269c + 8000cfa: 4603 mov r3, r0 + 8000cfc: 2b00 cmp r3, #0 + 8000cfe: bf14 ite ne + 8000d00: 2301 movne r3, #1 + 8000d02: 2300 moveq r3, #0 + 8000d04: b2db uxtb r3, r3 + 8000d06: 2b00 cmp r3, #0 + 8000d08: d001 beq.n 8000d0e <_Z18SystemClock_Configv+0xda> + { Error_Handler(); - 8000c5e: f000 fc17 bl 8001490 + 8000d0a: f000 fc26 bl 800155a } PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; - 8000c62: f44f 6300 mov.w r3, #2048 ; 0x800 - 8000c66: 60bb str r3, [r7, #8] + 8000d0e: f44f 6300 mov.w r3, #2048 ; 0x800 + 8000d12: 60bb str r3, [r7, #8] PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - 8000c68: 2300 movs r3, #0 - 8000c6a: 663b str r3, [r7, #96] ; 0x60 - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { - 8000c6c: f107 0308 add.w r3, r7, #8 - 8000c70: 4618 mov r0, r3 - 8000c72: f001 fe7d bl 8002970 - 8000c76: 4603 mov r3, r0 - 8000c78: 2b00 cmp r3, #0 - 8000c7a: bf14 ite ne - 8000c7c: 2301 movne r3, #1 - 8000c7e: 2300 moveq r3, #0 - 8000c80: b2db uxtb r3, r3 - 8000c82: 2b00 cmp r3, #0 - 8000c84: d001 beq.n 8000c8a <_Z18SystemClock_Configv+0x102> + 8000d14: 2300 movs r3, #0 + 8000d16: 663b str r3, [r7, #96] ; 0x60 + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) + 8000d18: f107 0308 add.w r3, r7, #8 + 8000d1c: 4618 mov r0, r3 + 8000d1e: f001 fe8b bl 8002a38 + 8000d22: 4603 mov r3, r0 + 8000d24: 2b00 cmp r3, #0 + 8000d26: bf14 ite ne + 8000d28: 2301 movne r3, #1 + 8000d2a: 2300 moveq r3, #0 + 8000d2c: b2db uxtb r3, r3 + 8000d2e: 2b00 cmp r3, #0 + 8000d30: d001 beq.n 8000d36 <_Z18SystemClock_Configv+0x102> + { Error_Handler(); - 8000c86: f000 fc03 bl 8001490 + 8000d32: f000 fc12 bl 800155a } } - 8000c8a: bf00 nop - 8000c8c: 37e0 adds r7, #224 ; 0xe0 - 8000c8e: 46bd mov sp, r7 - 8000c90: bd80 pop {r7, pc} - 8000c92: bf00 nop - 8000c94: 40023800 .word 0x40023800 - 8000c98: 40007000 .word 0x40007000 - -08000c9c <_ZL12MX_NVIC_Initv>: - + 8000d36: bf00 nop + 8000d38: 37e0 adds r7, #224 ; 0xe0 + 8000d3a: 46bd mov sp, r7 + 8000d3c: bd80 pop {r7, pc} + 8000d3e: bf00 nop + 8000d40: 40023800 .word 0x40023800 + 8000d44: 40007000 .word 0x40007000 + +08000d48 <_ZL12MX_NVIC_Initv>: /** - * @brief NVIC Configuration. - * @retval None - */ -static void MX_NVIC_Init(void) { - 8000c9c: b580 push {r7, lr} - 8000c9e: af00 add r7, sp, #0 + * @brief NVIC Configuration. + * @retval None + */ +static void MX_NVIC_Init(void) +{ + 8000d48: b580 push {r7, lr} + 8000d4a: af00 add r7, sp, #0 /* TIM3_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM3_IRQn, 2, 1); - 8000ca0: 2201 movs r2, #1 - 8000ca2: 2102 movs r1, #2 - 8000ca4: 201d movs r0, #29 - 8000ca6: f000 ffee bl 8001c86 + 8000d4c: 2201 movs r2, #1 + 8000d4e: 2102 movs r1, #2 + 8000d50: 201d movs r0, #29 + 8000d52: f000 fffc bl 8001d4e HAL_NVIC_EnableIRQ(TIM3_IRQn); - 8000caa: 201d movs r0, #29 - 8000cac: f001 f807 bl 8001cbe + 8000d56: 201d movs r0, #29 + 8000d58: f001 f815 bl 8001d86 /* TIM6_DAC_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 2, 2); - 8000cb0: 2202 movs r2, #2 - 8000cb2: 2102 movs r1, #2 - 8000cb4: 2036 movs r0, #54 ; 0x36 - 8000cb6: f000 ffe6 bl 8001c86 + 8000d5c: 2202 movs r2, #2 + 8000d5e: 2102 movs r1, #2 + 8000d60: 2036 movs r0, #54 ; 0x36 + 8000d62: f000 fff4 bl 8001d4e HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); - 8000cba: 2036 movs r0, #54 ; 0x36 - 8000cbc: f000 ffff bl 8001cbe + 8000d66: 2036 movs r0, #54 ; 0x36 + 8000d68: f001 f80d bl 8001d86 /* USART6_IRQn interrupt configuration */ HAL_NVIC_SetPriority(USART6_IRQn, 2, 0); - 8000cc0: 2200 movs r2, #0 - 8000cc2: 2102 movs r1, #2 - 8000cc4: 2047 movs r0, #71 ; 0x47 - 8000cc6: f000 ffde bl 8001c86 + 8000d6c: 2200 movs r2, #0 + 8000d6e: 2102 movs r1, #2 + 8000d70: 2047 movs r0, #71 ; 0x47 + 8000d72: f000 ffec bl 8001d4e HAL_NVIC_EnableIRQ(USART6_IRQn); - 8000cca: 2047 movs r0, #71 ; 0x47 - 8000ccc: f000 fff7 bl 8001cbe + 8000d76: 2047 movs r0, #71 ; 0x47 + 8000d78: f001 f805 bl 8001d86 } - 8000cd0: bf00 nop - 8000cd2: bd80 pop {r7, pc} + 8000d7c: bf00 nop + 8000d7e: bd80 pop {r7, pc} -08000cd4 <_ZL12MX_TIM2_Initv>: -/** - * @brief TIM2 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM2_Init(void) { - 8000cd4: b580 push {r7, lr} - 8000cd6: b08c sub sp, #48 ; 0x30 - 8000cd8: af00 add r7, sp, #0 +08000d80 <_ZL12MX_TIM2_Initv>: + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) +{ + 8000d80: b580 push {r7, lr} + 8000d82: b08c sub sp, #48 ; 0x30 + 8000d84: af00 add r7, sp, #0 /* USER CODE BEGIN TIM2_Init 0 */ /* USER CODE END TIM2_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - 8000cda: f107 030c add.w r3, r7, #12 - 8000cde: 2224 movs r2, #36 ; 0x24 - 8000ce0: 2100 movs r1, #0 - 8000ce2: 4618 mov r0, r3 - 8000ce4: f004 fadc bl 80052a0 - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - 8000ce8: 463b mov r3, r7 - 8000cea: 2200 movs r2, #0 - 8000cec: 601a str r2, [r3, #0] - 8000cee: 605a str r2, [r3, #4] - 8000cf0: 609a str r2, [r3, #8] + TIM_Encoder_InitTypeDef sConfig = {0}; + 8000d86: f107 030c add.w r3, r7, #12 + 8000d8a: 2224 movs r2, #36 ; 0x24 + 8000d8c: 2100 movs r1, #0 + 8000d8e: 4618 mov r0, r3 + 8000d90: f004 faea bl 8005368 + TIM_MasterConfigTypeDef sMasterConfig = {0}; + 8000d94: 463b mov r3, r7 + 8000d96: 2200 movs r2, #0 + 8000d98: 601a str r2, [r3, #0] + 8000d9a: 605a str r2, [r3, #4] + 8000d9c: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM2_Init 1 */ /* USER CODE END TIM2_Init 1 */ htim2.Instance = TIM2; - 8000cf2: 4b26 ldr r3, [pc, #152] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000cf4: f04f 4280 mov.w r2, #1073741824 ; 0x40000000 - 8000cf8: 601a str r2, [r3, #0] + 8000d9e: 4b26 ldr r3, [pc, #152] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000da0: f04f 4280 mov.w r2, #1073741824 ; 0x40000000 + 8000da4: 601a str r2, [r3, #0] htim2.Init.Prescaler = 0; - 8000cfa: 4b24 ldr r3, [pc, #144] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000cfc: 2200 movs r2, #0 - 8000cfe: 605a str r2, [r3, #4] + 8000da6: 4b24 ldr r3, [pc, #144] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000da8: 2200 movs r2, #0 + 8000daa: 605a str r2, [r3, #4] htim2.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000d00: 4b22 ldr r3, [pc, #136] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d02: 2200 movs r2, #0 - 8000d04: 609a str r2, [r3, #8] + 8000dac: 4b22 ldr r3, [pc, #136] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000dae: 2200 movs r2, #0 + 8000db0: 609a str r2, [r3, #8] htim2.Init.Period = 4294967295; - 8000d06: 4b21 ldr r3, [pc, #132] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d08: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8000d0c: 60da str r2, [r3, #12] + 8000db2: 4b21 ldr r3, [pc, #132] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000db4: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8000db8: 60da str r2, [r3, #12] htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000d0e: 4b1f ldr r3, [pc, #124] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d10: 2200 movs r2, #0 - 8000d12: 611a str r2, [r3, #16] + 8000dba: 4b1f ldr r3, [pc, #124] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000dbc: 2200 movs r2, #0 + 8000dbe: 611a str r2, [r3, #16] htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000d14: 4b1d ldr r3, [pc, #116] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d16: 2200 movs r2, #0 - 8000d18: 619a str r2, [r3, #24] + 8000dc0: 4b1d ldr r3, [pc, #116] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000dc2: 2200 movs r2, #0 + 8000dc4: 619a str r2, [r3, #24] sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - 8000d1a: 2303 movs r3, #3 - 8000d1c: 60fb str r3, [r7, #12] + 8000dc6: 2303 movs r3, #3 + 8000dc8: 60fb str r3, [r7, #12] sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - 8000d1e: 2300 movs r3, #0 - 8000d20: 613b str r3, [r7, #16] + 8000dca: 2300 movs r3, #0 + 8000dcc: 613b str r3, [r7, #16] sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - 8000d22: 2301 movs r3, #1 - 8000d24: 617b str r3, [r7, #20] + 8000dce: 2301 movs r3, #1 + 8000dd0: 617b str r3, [r7, #20] sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - 8000d26: 2300 movs r3, #0 - 8000d28: 61bb str r3, [r7, #24] + 8000dd2: 2300 movs r3, #0 + 8000dd4: 61bb str r3, [r7, #24] sConfig.IC1Filter = 0; - 8000d2a: 2300 movs r3, #0 - 8000d2c: 61fb str r3, [r7, #28] + 8000dd6: 2300 movs r3, #0 + 8000dd8: 61fb str r3, [r7, #28] sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - 8000d2e: 2300 movs r3, #0 - 8000d30: 623b str r3, [r7, #32] + 8000dda: 2300 movs r3, #0 + 8000ddc: 623b str r3, [r7, #32] sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - 8000d32: 2301 movs r3, #1 - 8000d34: 627b str r3, [r7, #36] ; 0x24 + 8000dde: 2301 movs r3, #1 + 8000de0: 627b str r3, [r7, #36] ; 0x24 sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - 8000d36: 2300 movs r3, #0 - 8000d38: 62bb str r3, [r7, #40] ; 0x28 + 8000de2: 2300 movs r3, #0 + 8000de4: 62bb str r3, [r7, #40] ; 0x28 sConfig.IC2Filter = 0; - 8000d3a: 2300 movs r3, #0 - 8000d3c: 62fb str r3, [r7, #44] ; 0x2c - if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { - 8000d3e: f107 030c add.w r3, r7, #12 - 8000d42: 4619 mov r1, r3 - 8000d44: 4811 ldr r0, [pc, #68] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d46: f002 fb09 bl 800335c - 8000d4a: 4603 mov r3, r0 - 8000d4c: 2b00 cmp r3, #0 - 8000d4e: bf14 ite ne - 8000d50: 2301 movne r3, #1 - 8000d52: 2300 moveq r3, #0 - 8000d54: b2db uxtb r3, r3 - 8000d56: 2b00 cmp r3, #0 - 8000d58: d001 beq.n 8000d5e <_ZL12MX_TIM2_Initv+0x8a> + 8000de6: 2300 movs r3, #0 + 8000de8: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) + 8000dea: f107 030c add.w r3, r7, #12 + 8000dee: 4619 mov r1, r3 + 8000df0: 4811 ldr r0, [pc, #68] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000df2: f002 fb17 bl 8003424 + 8000df6: 4603 mov r3, r0 + 8000df8: 2b00 cmp r3, #0 + 8000dfa: bf14 ite ne + 8000dfc: 2301 movne r3, #1 + 8000dfe: 2300 moveq r3, #0 + 8000e00: b2db uxtb r3, r3 + 8000e02: 2b00 cmp r3, #0 + 8000e04: d001 beq.n 8000e0a <_ZL12MX_TIM2_Initv+0x8a> + { Error_Handler(); - 8000d5a: f000 fb99 bl 8001490 + 8000e06: f000 fba8 bl 800155a } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8000d5e: 2300 movs r3, #0 - 8000d60: 603b str r3, [r7, #0] + 8000e0a: 2300 movs r3, #0 + 8000e0c: 603b str r3, [r7, #0] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8000d62: 2300 movs r3, #0 - 8000d64: 60bb str r3, [r7, #8] - if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) { - 8000d66: 463b mov r3, r7 - 8000d68: 4619 mov r1, r3 - 8000d6a: 4808 ldr r0, [pc, #32] ; (8000d8c <_ZL12MX_TIM2_Initv+0xb8>) - 8000d6c: f003 fa96 bl 800429c - 8000d70: 4603 mov r3, r0 - 8000d72: 2b00 cmp r3, #0 - 8000d74: bf14 ite ne - 8000d76: 2301 movne r3, #1 - 8000d78: 2300 moveq r3, #0 - 8000d7a: b2db uxtb r3, r3 - 8000d7c: 2b00 cmp r3, #0 - 8000d7e: d001 beq.n 8000d84 <_ZL12MX_TIM2_Initv+0xb0> + 8000e0e: 2300 movs r3, #0 + 8000e10: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) + 8000e12: 463b mov r3, r7 + 8000e14: 4619 mov r1, r3 + 8000e16: 4808 ldr r0, [pc, #32] ; (8000e38 <_ZL12MX_TIM2_Initv+0xb8>) + 8000e18: f003 faa4 bl 8004364 + 8000e1c: 4603 mov r3, r0 + 8000e1e: 2b00 cmp r3, #0 + 8000e20: bf14 ite ne + 8000e22: 2301 movne r3, #1 + 8000e24: 2300 moveq r3, #0 + 8000e26: b2db uxtb r3, r3 + 8000e28: 2b00 cmp r3, #0 + 8000e2a: d001 beq.n 8000e30 <_ZL12MX_TIM2_Initv+0xb0> + { Error_Handler(); - 8000d80: f000 fb86 bl 8001490 + 8000e2c: f000 fb95 bl 800155a } /* USER CODE BEGIN TIM2_Init 2 */ /* USER CODE END TIM2_Init 2 */ } - 8000d84: bf00 nop - 8000d86: 3730 adds r7, #48 ; 0x30 - 8000d88: 46bd mov sp, r7 - 8000d8a: bd80 pop {r7, pc} - 8000d8c: 20000030 .word 0x20000030 - -08000d90 <_ZL12MX_TIM3_Initv>: -/** - * @brief TIM3 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM3_Init(void) { - 8000d90: b580 push {r7, lr} - 8000d92: b088 sub sp, #32 - 8000d94: af00 add r7, sp, #0 + 8000e30: bf00 nop + 8000e32: 3730 adds r7, #48 ; 0x30 + 8000e34: 46bd mov sp, r7 + 8000e36: bd80 pop {r7, pc} + 8000e38: 2000002c .word 0x2000002c + +08000e3c <_ZL12MX_TIM3_Initv>: + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) +{ + 8000e3c: b580 push {r7, lr} + 8000e3e: b088 sub sp, #32 + 8000e40: af00 add r7, sp, #0 /* USER CODE BEGIN TIM3_Init 0 */ /* USER CODE END TIM3_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - 8000d96: f107 0310 add.w r3, r7, #16 - 8000d9a: 2200 movs r2, #0 - 8000d9c: 601a str r2, [r3, #0] - 8000d9e: 605a str r2, [r3, #4] - 8000da0: 609a str r2, [r3, #8] - 8000da2: 60da str r2, [r3, #12] - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - 8000da4: 1d3b adds r3, r7, #4 - 8000da6: 2200 movs r2, #0 - 8000da8: 601a str r2, [r3, #0] - 8000daa: 605a str r2, [r3, #4] - 8000dac: 609a str r2, [r3, #8] + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + 8000e42: f107 0310 add.w r3, r7, #16 + 8000e46: 2200 movs r2, #0 + 8000e48: 601a str r2, [r3, #0] + 8000e4a: 605a str r2, [r3, #4] + 8000e4c: 609a str r2, [r3, #8] + 8000e4e: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = {0}; + 8000e50: 1d3b adds r3, r7, #4 + 8000e52: 2200 movs r2, #0 + 8000e54: 601a str r2, [r3, #0] + 8000e56: 605a str r2, [r3, #4] + 8000e58: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM3_Init 1 */ /* USER CODE END TIM3_Init 1 */ htim3.Instance = TIM3; - 8000dae: 4b25 ldr r3, [pc, #148] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000db0: 4a25 ldr r2, [pc, #148] ; (8000e48 <_ZL12MX_TIM3_Initv+0xb8>) - 8000db2: 601a str r2, [r3, #0] + 8000e5a: 4b25 ldr r3, [pc, #148] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e5c: 4a25 ldr r2, [pc, #148] ; (8000ef4 <_ZL12MX_TIM3_Initv+0xb8>) + 8000e5e: 601a str r2, [r3, #0] htim3.Init.Prescaler = 999; - 8000db4: 4b23 ldr r3, [pc, #140] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000db6: f240 32e7 movw r2, #999 ; 0x3e7 - 8000dba: 605a str r2, [r3, #4] + 8000e60: 4b23 ldr r3, [pc, #140] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e62: f240 32e7 movw r2, #999 ; 0x3e7 + 8000e66: 605a str r2, [r3, #4] htim3.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000dbc: 4b21 ldr r3, [pc, #132] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dbe: 2200 movs r2, #0 - 8000dc0: 609a str r2, [r3, #8] + 8000e68: 4b21 ldr r3, [pc, #132] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e6a: 2200 movs r2, #0 + 8000e6c: 609a str r2, [r3, #8] htim3.Init.Period = 159; - 8000dc2: 4b20 ldr r3, [pc, #128] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dc4: 229f movs r2, #159 ; 0x9f - 8000dc6: 60da str r2, [r3, #12] + 8000e6e: 4b20 ldr r3, [pc, #128] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e70: 229f movs r2, #159 ; 0x9f + 8000e72: 60da str r2, [r3, #12] htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000dc8: 4b1e ldr r3, [pc, #120] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dca: 2200 movs r2, #0 - 8000dcc: 611a str r2, [r3, #16] + 8000e74: 4b1e ldr r3, [pc, #120] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e76: 2200 movs r2, #0 + 8000e78: 611a str r2, [r3, #16] htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000dce: 4b1d ldr r3, [pc, #116] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dd0: 2200 movs r2, #0 - 8000dd2: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { - 8000dd4: 481b ldr r0, [pc, #108] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dd6: f002 f9f1 bl 80031bc - 8000dda: 4603 mov r3, r0 - 8000ddc: 2b00 cmp r3, #0 - 8000dde: bf14 ite ne - 8000de0: 2301 movne r3, #1 - 8000de2: 2300 moveq r3, #0 - 8000de4: b2db uxtb r3, r3 - 8000de6: 2b00 cmp r3, #0 - 8000de8: d001 beq.n 8000dee <_ZL12MX_TIM3_Initv+0x5e> + 8000e7a: 4b1d ldr r3, [pc, #116] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e7c: 2200 movs r2, #0 + 8000e7e: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) + 8000e80: 481b ldr r0, [pc, #108] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000e82: f002 f9ff bl 8003284 + 8000e86: 4603 mov r3, r0 + 8000e88: 2b00 cmp r3, #0 + 8000e8a: bf14 ite ne + 8000e8c: 2301 movne r3, #1 + 8000e8e: 2300 moveq r3, #0 + 8000e90: b2db uxtb r3, r3 + 8000e92: 2b00 cmp r3, #0 + 8000e94: d001 beq.n 8000e9a <_ZL12MX_TIM3_Initv+0x5e> + { Error_Handler(); - 8000dea: f000 fb51 bl 8001490 + 8000e96: f000 fb60 bl 800155a } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - 8000dee: f44f 5380 mov.w r3, #4096 ; 0x1000 - 8000df2: 613b str r3, [r7, #16] - if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { - 8000df4: f107 0310 add.w r3, r7, #16 - 8000df8: 4619 mov r1, r3 - 8000dfa: 4812 ldr r0, [pc, #72] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000dfc: f002 fdae bl 800395c - 8000e00: 4603 mov r3, r0 - 8000e02: 2b00 cmp r3, #0 - 8000e04: bf14 ite ne - 8000e06: 2301 movne r3, #1 - 8000e08: 2300 moveq r3, #0 - 8000e0a: b2db uxtb r3, r3 - 8000e0c: 2b00 cmp r3, #0 - 8000e0e: d001 beq.n 8000e14 <_ZL12MX_TIM3_Initv+0x84> + 8000e9a: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8000e9e: 613b str r3, [r7, #16] + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) + 8000ea0: f107 0310 add.w r3, r7, #16 + 8000ea4: 4619 mov r1, r3 + 8000ea6: 4812 ldr r0, [pc, #72] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000ea8: f002 fdbc bl 8003a24 + 8000eac: 4603 mov r3, r0 + 8000eae: 2b00 cmp r3, #0 + 8000eb0: bf14 ite ne + 8000eb2: 2301 movne r3, #1 + 8000eb4: 2300 moveq r3, #0 + 8000eb6: b2db uxtb r3, r3 + 8000eb8: 2b00 cmp r3, #0 + 8000eba: d001 beq.n 8000ec0 <_ZL12MX_TIM3_Initv+0x84> + { Error_Handler(); - 8000e10: f000 fb3e bl 8001490 + 8000ebc: f000 fb4d bl 800155a } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8000e14: 2300 movs r3, #0 - 8000e16: 607b str r3, [r7, #4] + 8000ec0: 2300 movs r3, #0 + 8000ec2: 607b str r3, [r7, #4] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8000e18: 2300 movs r3, #0 - 8000e1a: 60fb str r3, [r7, #12] - if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) { - 8000e1c: 1d3b adds r3, r7, #4 - 8000e1e: 4619 mov r1, r3 - 8000e20: 4808 ldr r0, [pc, #32] ; (8000e44 <_ZL12MX_TIM3_Initv+0xb4>) - 8000e22: f003 fa3b bl 800429c - 8000e26: 4603 mov r3, r0 - 8000e28: 2b00 cmp r3, #0 - 8000e2a: bf14 ite ne - 8000e2c: 2301 movne r3, #1 - 8000e2e: 2300 moveq r3, #0 - 8000e30: b2db uxtb r3, r3 - 8000e32: 2b00 cmp r3, #0 - 8000e34: d001 beq.n 8000e3a <_ZL12MX_TIM3_Initv+0xaa> + 8000ec4: 2300 movs r3, #0 + 8000ec6: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) + 8000ec8: 1d3b adds r3, r7, #4 + 8000eca: 4619 mov r1, r3 + 8000ecc: 4808 ldr r0, [pc, #32] ; (8000ef0 <_ZL12MX_TIM3_Initv+0xb4>) + 8000ece: f003 fa49 bl 8004364 + 8000ed2: 4603 mov r3, r0 + 8000ed4: 2b00 cmp r3, #0 + 8000ed6: bf14 ite ne + 8000ed8: 2301 movne r3, #1 + 8000eda: 2300 moveq r3, #0 + 8000edc: b2db uxtb r3, r3 + 8000ede: 2b00 cmp r3, #0 + 8000ee0: d001 beq.n 8000ee6 <_ZL12MX_TIM3_Initv+0xaa> + { Error_Handler(); - 8000e36: f000 fb2b bl 8001490 + 8000ee2: f000 fb3a bl 800155a } /* USER CODE BEGIN TIM3_Init 2 */ /* USER CODE END TIM3_Init 2 */ } - 8000e3a: bf00 nop - 8000e3c: 3720 adds r7, #32 - 8000e3e: 46bd mov sp, r7 - 8000e40: bd80 pop {r7, pc} - 8000e42: bf00 nop - 8000e44: 20000070 .word 0x20000070 - 8000e48: 40000400 .word 0x40000400 - -08000e4c <_ZL12MX_TIM4_Initv>: -/** - * @brief TIM4 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM4_Init(void) { - 8000e4c: b580 push {r7, lr} - 8000e4e: b08e sub sp, #56 ; 0x38 - 8000e50: af00 add r7, sp, #0 + 8000ee6: bf00 nop + 8000ee8: 3720 adds r7, #32 + 8000eea: 46bd mov sp, r7 + 8000eec: bd80 pop {r7, pc} + 8000eee: bf00 nop + 8000ef0: 2000006c .word 0x2000006c + 8000ef4: 40000400 .word 0x40000400 + +08000ef8 <_ZL12MX_TIM4_Initv>: + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) +{ + 8000ef8: b580 push {r7, lr} + 8000efa: b08e sub sp, #56 ; 0x38 + 8000efc: af00 add r7, sp, #0 /* USER CODE BEGIN TIM4_Init 0 */ /* USER CODE END TIM4_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - 8000e52: f107 0328 add.w r3, r7, #40 ; 0x28 - 8000e56: 2200 movs r2, #0 - 8000e58: 601a str r2, [r3, #0] - 8000e5a: 605a str r2, [r3, #4] - 8000e5c: 609a str r2, [r3, #8] - 8000e5e: 60da str r2, [r3, #12] - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - 8000e60: f107 031c add.w r3, r7, #28 - 8000e64: 2200 movs r2, #0 - 8000e66: 601a str r2, [r3, #0] - 8000e68: 605a str r2, [r3, #4] - 8000e6a: 609a str r2, [r3, #8] - TIM_OC_InitTypeDef sConfigOC = { 0 }; - 8000e6c: 463b mov r3, r7 - 8000e6e: 2200 movs r2, #0 - 8000e70: 601a str r2, [r3, #0] - 8000e72: 605a str r2, [r3, #4] - 8000e74: 609a str r2, [r3, #8] - 8000e76: 60da str r2, [r3, #12] - 8000e78: 611a str r2, [r3, #16] - 8000e7a: 615a str r2, [r3, #20] - 8000e7c: 619a str r2, [r3, #24] + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + 8000efe: f107 0328 add.w r3, r7, #40 ; 0x28 + 8000f02: 2200 movs r2, #0 + 8000f04: 601a str r2, [r3, #0] + 8000f06: 605a str r2, [r3, #4] + 8000f08: 609a str r2, [r3, #8] + 8000f0a: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = {0}; + 8000f0c: f107 031c add.w r3, r7, #28 + 8000f10: 2200 movs r2, #0 + 8000f12: 601a str r2, [r3, #0] + 8000f14: 605a str r2, [r3, #4] + 8000f16: 609a str r2, [r3, #8] + TIM_OC_InitTypeDef sConfigOC = {0}; + 8000f18: 463b mov r3, r7 + 8000f1a: 2200 movs r2, #0 + 8000f1c: 601a str r2, [r3, #0] + 8000f1e: 605a str r2, [r3, #4] + 8000f20: 609a str r2, [r3, #8] + 8000f22: 60da str r2, [r3, #12] + 8000f24: 611a str r2, [r3, #16] + 8000f26: 615a str r2, [r3, #20] + 8000f28: 619a str r2, [r3, #24] /* USER CODE BEGIN TIM4_Init 1 */ /* USER CODE END TIM4_Init 1 */ htim4.Instance = TIM4; - 8000e7e: 4b41 ldr r3, [pc, #260] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000e80: 4a41 ldr r2, [pc, #260] ; (8000f88 <_ZL12MX_TIM4_Initv+0x13c>) - 8000e82: 601a str r2, [r3, #0] + 8000f2a: 4b41 ldr r3, [pc, #260] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f2c: 4a41 ldr r2, [pc, #260] ; (8001034 <_ZL12MX_TIM4_Initv+0x13c>) + 8000f2e: 601a str r2, [r3, #0] htim4.Init.Prescaler = 0; - 8000e84: 4b3f ldr r3, [pc, #252] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000e86: 2200 movs r2, #0 - 8000e88: 605a str r2, [r3, #4] + 8000f30: 4b3f ldr r3, [pc, #252] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f32: 2200 movs r2, #0 + 8000f34: 605a str r2, [r3, #4] htim4.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000e8a: 4b3e ldr r3, [pc, #248] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000e8c: 2200 movs r2, #0 - 8000e8e: 609a str r2, [r3, #8] + 8000f36: 4b3e ldr r3, [pc, #248] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f38: 2200 movs r2, #0 + 8000f3a: 609a str r2, [r3, #8] htim4.Init.Period = 799; - 8000e90: 4b3c ldr r3, [pc, #240] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000e92: f240 321f movw r2, #799 ; 0x31f - 8000e96: 60da str r2, [r3, #12] + 8000f3c: 4b3c ldr r3, [pc, #240] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f3e: f240 321f movw r2, #799 ; 0x31f + 8000f42: 60da str r2, [r3, #12] htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000e98: 4b3a ldr r3, [pc, #232] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000e9a: 2200 movs r2, #0 - 8000e9c: 611a str r2, [r3, #16] + 8000f44: 4b3a ldr r3, [pc, #232] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f46: 2200 movs r2, #0 + 8000f48: 611a str r2, [r3, #16] htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000e9e: 4b39 ldr r3, [pc, #228] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000ea0: 2200 movs r2, #0 - 8000ea2: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { - 8000ea4: 4837 ldr r0, [pc, #220] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000ea6: f002 f989 bl 80031bc - 8000eaa: 4603 mov r3, r0 - 8000eac: 2b00 cmp r3, #0 - 8000eae: bf14 ite ne - 8000eb0: 2301 movne r3, #1 - 8000eb2: 2300 moveq r3, #0 - 8000eb4: b2db uxtb r3, r3 - 8000eb6: 2b00 cmp r3, #0 - 8000eb8: d001 beq.n 8000ebe <_ZL12MX_TIM4_Initv+0x72> + 8000f4a: 4b39 ldr r3, [pc, #228] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f4c: 2200 movs r2, #0 + 8000f4e: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) + 8000f50: 4837 ldr r0, [pc, #220] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f52: f002 f997 bl 8003284 + 8000f56: 4603 mov r3, r0 + 8000f58: 2b00 cmp r3, #0 + 8000f5a: bf14 ite ne + 8000f5c: 2301 movne r3, #1 + 8000f5e: 2300 moveq r3, #0 + 8000f60: b2db uxtb r3, r3 + 8000f62: 2b00 cmp r3, #0 + 8000f64: d001 beq.n 8000f6a <_ZL12MX_TIM4_Initv+0x72> + { Error_Handler(); - 8000eba: f000 fae9 bl 8001490 + 8000f66: f000 faf8 bl 800155a } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - 8000ebe: f44f 5380 mov.w r3, #4096 ; 0x1000 - 8000ec2: 62bb str r3, [r7, #40] ; 0x28 - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { - 8000ec4: f107 0328 add.w r3, r7, #40 ; 0x28 - 8000ec8: 4619 mov r1, r3 - 8000eca: 482e ldr r0, [pc, #184] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000ecc: f002 fd46 bl 800395c - 8000ed0: 4603 mov r3, r0 - 8000ed2: 2b00 cmp r3, #0 - 8000ed4: bf14 ite ne - 8000ed6: 2301 movne r3, #1 - 8000ed8: 2300 moveq r3, #0 - 8000eda: b2db uxtb r3, r3 - 8000edc: 2b00 cmp r3, #0 - 8000ede: d001 beq.n 8000ee4 <_ZL12MX_TIM4_Initv+0x98> + 8000f6a: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8000f6e: 62bb str r3, [r7, #40] ; 0x28 + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) + 8000f70: f107 0328 add.w r3, r7, #40 ; 0x28 + 8000f74: 4619 mov r1, r3 + 8000f76: 482e ldr r0, [pc, #184] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f78: f002 fd54 bl 8003a24 + 8000f7c: 4603 mov r3, r0 + 8000f7e: 2b00 cmp r3, #0 + 8000f80: bf14 ite ne + 8000f82: 2301 movne r3, #1 + 8000f84: 2300 moveq r3, #0 + 8000f86: b2db uxtb r3, r3 + 8000f88: 2b00 cmp r3, #0 + 8000f8a: d001 beq.n 8000f90 <_ZL12MX_TIM4_Initv+0x98> + { Error_Handler(); - 8000ee0: f000 fad6 bl 8001490 - } - if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { - 8000ee4: 4827 ldr r0, [pc, #156] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000ee6: f002 f9bf bl 8003268 - 8000eea: 4603 mov r3, r0 - 8000eec: 2b00 cmp r3, #0 - 8000eee: bf14 ite ne - 8000ef0: 2301 movne r3, #1 - 8000ef2: 2300 moveq r3, #0 - 8000ef4: b2db uxtb r3, r3 - 8000ef6: 2b00 cmp r3, #0 - 8000ef8: d001 beq.n 8000efe <_ZL12MX_TIM4_Initv+0xb2> + 8000f8c: f000 fae5 bl 800155a + } + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) + 8000f90: 4827 ldr r0, [pc, #156] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000f92: f002 f9cd bl 8003330 + 8000f96: 4603 mov r3, r0 + 8000f98: 2b00 cmp r3, #0 + 8000f9a: bf14 ite ne + 8000f9c: 2301 movne r3, #1 + 8000f9e: 2300 moveq r3, #0 + 8000fa0: b2db uxtb r3, r3 + 8000fa2: 2b00 cmp r3, #0 + 8000fa4: d001 beq.n 8000faa <_ZL12MX_TIM4_Initv+0xb2> + { Error_Handler(); - 8000efa: f000 fac9 bl 8001490 + 8000fa6: f000 fad8 bl 800155a } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8000efe: 2300 movs r3, #0 - 8000f00: 61fb str r3, [r7, #28] + 8000faa: 2300 movs r3, #0 + 8000fac: 61fb str r3, [r7, #28] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8000f02: 2300 movs r3, #0 - 8000f04: 627b str r3, [r7, #36] ; 0x24 - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) { - 8000f06: f107 031c add.w r3, r7, #28 - 8000f0a: 4619 mov r1, r3 - 8000f0c: 481d ldr r0, [pc, #116] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000f0e: f003 f9c5 bl 800429c - 8000f12: 4603 mov r3, r0 - 8000f14: 2b00 cmp r3, #0 - 8000f16: bf14 ite ne - 8000f18: 2301 movne r3, #1 - 8000f1a: 2300 moveq r3, #0 - 8000f1c: b2db uxtb r3, r3 - 8000f1e: 2b00 cmp r3, #0 - 8000f20: d001 beq.n 8000f26 <_ZL12MX_TIM4_Initv+0xda> + 8000fae: 2300 movs r3, #0 + 8000fb0: 627b str r3, [r7, #36] ; 0x24 + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) + 8000fb2: f107 031c add.w r3, r7, #28 + 8000fb6: 4619 mov r1, r3 + 8000fb8: 481d ldr r0, [pc, #116] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000fba: f003 f9d3 bl 8004364 + 8000fbe: 4603 mov r3, r0 + 8000fc0: 2b00 cmp r3, #0 + 8000fc2: bf14 ite ne + 8000fc4: 2301 movne r3, #1 + 8000fc6: 2300 moveq r3, #0 + 8000fc8: b2db uxtb r3, r3 + 8000fca: 2b00 cmp r3, #0 + 8000fcc: d001 beq.n 8000fd2 <_ZL12MX_TIM4_Initv+0xda> + { Error_Handler(); - 8000f22: f000 fab5 bl 8001490 + 8000fce: f000 fac4 bl 800155a } sConfigOC.OCMode = TIM_OCMODE_PWM1; - 8000f26: 2360 movs r3, #96 ; 0x60 - 8000f28: 603b str r3, [r7, #0] + 8000fd2: 2360 movs r3, #96 ; 0x60 + 8000fd4: 603b str r3, [r7, #0] sConfigOC.Pulse = 0; - 8000f2a: 2300 movs r3, #0 - 8000f2c: 607b str r3, [r7, #4] + 8000fd6: 2300 movs r3, #0 + 8000fd8: 607b str r3, [r7, #4] sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - 8000f2e: 2300 movs r3, #0 - 8000f30: 60bb str r3, [r7, #8] + 8000fda: 2300 movs r3, #0 + 8000fdc: 60bb str r3, [r7, #8] sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - 8000f32: 2300 movs r3, #0 - 8000f34: 613b str r3, [r7, #16] - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) { - 8000f36: 463b mov r3, r7 - 8000f38: 2208 movs r2, #8 - 8000f3a: 4619 mov r1, r3 - 8000f3c: 4811 ldr r0, [pc, #68] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000f3e: f002 fbf5 bl 800372c - 8000f42: 4603 mov r3, r0 - 8000f44: 2b00 cmp r3, #0 - 8000f46: bf14 ite ne - 8000f48: 2301 movne r3, #1 - 8000f4a: 2300 moveq r3, #0 - 8000f4c: b2db uxtb r3, r3 - 8000f4e: 2b00 cmp r3, #0 - 8000f50: d001 beq.n 8000f56 <_ZL12MX_TIM4_Initv+0x10a> + 8000fde: 2300 movs r3, #0 + 8000fe0: 613b str r3, [r7, #16] + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) + 8000fe2: 463b mov r3, r7 + 8000fe4: 2208 movs r2, #8 + 8000fe6: 4619 mov r1, r3 + 8000fe8: 4811 ldr r0, [pc, #68] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8000fea: f002 fc03 bl 80037f4 + 8000fee: 4603 mov r3, r0 + 8000ff0: 2b00 cmp r3, #0 + 8000ff2: bf14 ite ne + 8000ff4: 2301 movne r3, #1 + 8000ff6: 2300 moveq r3, #0 + 8000ff8: b2db uxtb r3, r3 + 8000ffa: 2b00 cmp r3, #0 + 8000ffc: d001 beq.n 8001002 <_ZL12MX_TIM4_Initv+0x10a> + { Error_Handler(); - 8000f52: f000 fa9d bl 8001490 - } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) { - 8000f56: 463b mov r3, r7 - 8000f58: 220c movs r2, #12 - 8000f5a: 4619 mov r1, r3 - 8000f5c: 4809 ldr r0, [pc, #36] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000f5e: f002 fbe5 bl 800372c - 8000f62: 4603 mov r3, r0 - 8000f64: 2b00 cmp r3, #0 - 8000f66: bf14 ite ne - 8000f68: 2301 movne r3, #1 - 8000f6a: 2300 moveq r3, #0 - 8000f6c: b2db uxtb r3, r3 - 8000f6e: 2b00 cmp r3, #0 - 8000f70: d001 beq.n 8000f76 <_ZL12MX_TIM4_Initv+0x12a> + 8000ffe: f000 faac bl 800155a + } + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) + 8001002: 463b mov r3, r7 + 8001004: 220c movs r2, #12 + 8001006: 4619 mov r1, r3 + 8001008: 4809 ldr r0, [pc, #36] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 800100a: f002 fbf3 bl 80037f4 + 800100e: 4603 mov r3, r0 + 8001010: 2b00 cmp r3, #0 + 8001012: bf14 ite ne + 8001014: 2301 movne r3, #1 + 8001016: 2300 moveq r3, #0 + 8001018: b2db uxtb r3, r3 + 800101a: 2b00 cmp r3, #0 + 800101c: d001 beq.n 8001022 <_ZL12MX_TIM4_Initv+0x12a> + { Error_Handler(); - 8000f72: f000 fa8d bl 8001490 + 800101e: f000 fa9c bl 800155a } /* USER CODE BEGIN TIM4_Init 2 */ /* USER CODE END TIM4_Init 2 */ HAL_TIM_MspPostInit(&htim4); - 8000f76: 4803 ldr r0, [pc, #12] ; (8000f84 <_ZL12MX_TIM4_Initv+0x138>) - 8000f78: f000 fc1e bl 80017b8 + 8001022: 4803 ldr r0, [pc, #12] ; (8001030 <_ZL12MX_TIM4_Initv+0x138>) + 8001024: f000 fc2c bl 8001880 } - 8000f7c: bf00 nop - 8000f7e: 3738 adds r7, #56 ; 0x38 - 8000f80: 46bd mov sp, r7 - 8000f82: bd80 pop {r7, pc} - 8000f84: 200000b0 .word 0x200000b0 - 8000f88: 40000800 .word 0x40000800 - -08000f8c <_ZL12MX_TIM5_Initv>: -/** - * @brief TIM5 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM5_Init(void) { - 8000f8c: b580 push {r7, lr} - 8000f8e: b08c sub sp, #48 ; 0x30 - 8000f90: af00 add r7, sp, #0 + 8001028: bf00 nop + 800102a: 3738 adds r7, #56 ; 0x38 + 800102c: 46bd mov sp, r7 + 800102e: bd80 pop {r7, pc} + 8001030: 200000ac .word 0x200000ac + 8001034: 40000800 .word 0x40000800 + +08001038 <_ZL12MX_TIM5_Initv>: + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) +{ + 8001038: b580 push {r7, lr} + 800103a: b08c sub sp, #48 ; 0x30 + 800103c: af00 add r7, sp, #0 /* USER CODE BEGIN TIM5_Init 0 */ /* USER CODE END TIM5_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - 8000f92: f107 030c add.w r3, r7, #12 - 8000f96: 2224 movs r2, #36 ; 0x24 - 8000f98: 2100 movs r1, #0 - 8000f9a: 4618 mov r0, r3 - 8000f9c: f004 f980 bl 80052a0 - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - 8000fa0: 463b mov r3, r7 - 8000fa2: 2200 movs r2, #0 - 8000fa4: 601a str r2, [r3, #0] - 8000fa6: 605a str r2, [r3, #4] - 8000fa8: 609a str r2, [r3, #8] + TIM_Encoder_InitTypeDef sConfig = {0}; + 800103e: f107 030c add.w r3, r7, #12 + 8001042: 2224 movs r2, #36 ; 0x24 + 8001044: 2100 movs r1, #0 + 8001046: 4618 mov r0, r3 + 8001048: f004 f98e bl 8005368 + TIM_MasterConfigTypeDef sMasterConfig = {0}; + 800104c: 463b mov r3, r7 + 800104e: 2200 movs r2, #0 + 8001050: 601a str r2, [r3, #0] + 8001052: 605a str r2, [r3, #4] + 8001054: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM5_Init 1 */ /* USER CODE END TIM5_Init 1 */ htim5.Instance = TIM5; - 8000faa: 4b26 ldr r3, [pc, #152] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fac: 4a26 ldr r2, [pc, #152] ; (8001048 <_ZL12MX_TIM5_Initv+0xbc>) - 8000fae: 601a str r2, [r3, #0] + 8001056: 4b26 ldr r3, [pc, #152] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 8001058: 4a26 ldr r2, [pc, #152] ; (80010f4 <_ZL12MX_TIM5_Initv+0xbc>) + 800105a: 601a str r2, [r3, #0] htim5.Init.Prescaler = 0; - 8000fb0: 4b24 ldr r3, [pc, #144] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fb2: 2200 movs r2, #0 - 8000fb4: 605a str r2, [r3, #4] + 800105c: 4b24 ldr r3, [pc, #144] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 800105e: 2200 movs r2, #0 + 8001060: 605a str r2, [r3, #4] htim5.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000fb6: 4b23 ldr r3, [pc, #140] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fb8: 2200 movs r2, #0 - 8000fba: 609a str r2, [r3, #8] + 8001062: 4b23 ldr r3, [pc, #140] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 8001064: 2200 movs r2, #0 + 8001066: 609a str r2, [r3, #8] htim5.Init.Period = 4294967295; - 8000fbc: 4b21 ldr r3, [pc, #132] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fbe: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8000fc2: 60da str r2, [r3, #12] + 8001068: 4b21 ldr r3, [pc, #132] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 800106a: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 800106e: 60da str r2, [r3, #12] htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000fc4: 4b1f ldr r3, [pc, #124] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fc6: 2200 movs r2, #0 - 8000fc8: 611a str r2, [r3, #16] + 8001070: 4b1f ldr r3, [pc, #124] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 8001072: 2200 movs r2, #0 + 8001074: 611a str r2, [r3, #16] htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000fca: 4b1e ldr r3, [pc, #120] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000fcc: 2200 movs r2, #0 - 8000fce: 619a str r2, [r3, #24] + 8001076: 4b1e ldr r3, [pc, #120] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 8001078: 2200 movs r2, #0 + 800107a: 619a str r2, [r3, #24] sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - 8000fd0: 2303 movs r3, #3 - 8000fd2: 60fb str r3, [r7, #12] + 800107c: 2303 movs r3, #3 + 800107e: 60fb str r3, [r7, #12] sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - 8000fd4: 2300 movs r3, #0 - 8000fd6: 613b str r3, [r7, #16] + 8001080: 2300 movs r3, #0 + 8001082: 613b str r3, [r7, #16] sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - 8000fd8: 2301 movs r3, #1 - 8000fda: 617b str r3, [r7, #20] + 8001084: 2301 movs r3, #1 + 8001086: 617b str r3, [r7, #20] sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - 8000fdc: 2300 movs r3, #0 - 8000fde: 61bb str r3, [r7, #24] + 8001088: 2300 movs r3, #0 + 800108a: 61bb str r3, [r7, #24] sConfig.IC1Filter = 0; - 8000fe0: 2300 movs r3, #0 - 8000fe2: 61fb str r3, [r7, #28] + 800108c: 2300 movs r3, #0 + 800108e: 61fb str r3, [r7, #28] sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - 8000fe4: 2300 movs r3, #0 - 8000fe6: 623b str r3, [r7, #32] + 8001090: 2300 movs r3, #0 + 8001092: 623b str r3, [r7, #32] sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - 8000fe8: 2301 movs r3, #1 - 8000fea: 627b str r3, [r7, #36] ; 0x24 + 8001094: 2301 movs r3, #1 + 8001096: 627b str r3, [r7, #36] ; 0x24 sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - 8000fec: 2300 movs r3, #0 - 8000fee: 62bb str r3, [r7, #40] ; 0x28 + 8001098: 2300 movs r3, #0 + 800109a: 62bb str r3, [r7, #40] ; 0x28 sConfig.IC2Filter = 0; - 8000ff0: 2300 movs r3, #0 - 8000ff2: 62fb str r3, [r7, #44] ; 0x2c - if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { - 8000ff4: f107 030c add.w r3, r7, #12 - 8000ff8: 4619 mov r1, r3 - 8000ffa: 4812 ldr r0, [pc, #72] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8000ffc: f002 f9ae bl 800335c - 8001000: 4603 mov r3, r0 - 8001002: 2b00 cmp r3, #0 - 8001004: bf14 ite ne - 8001006: 2301 movne r3, #1 - 8001008: 2300 moveq r3, #0 - 800100a: b2db uxtb r3, r3 - 800100c: 2b00 cmp r3, #0 - 800100e: d001 beq.n 8001014 <_ZL12MX_TIM5_Initv+0x88> + 800109c: 2300 movs r3, #0 + 800109e: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) + 80010a0: f107 030c add.w r3, r7, #12 + 80010a4: 4619 mov r1, r3 + 80010a6: 4812 ldr r0, [pc, #72] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 80010a8: f002 f9bc bl 8003424 + 80010ac: 4603 mov r3, r0 + 80010ae: 2b00 cmp r3, #0 + 80010b0: bf14 ite ne + 80010b2: 2301 movne r3, #1 + 80010b4: 2300 moveq r3, #0 + 80010b6: b2db uxtb r3, r3 + 80010b8: 2b00 cmp r3, #0 + 80010ba: d001 beq.n 80010c0 <_ZL12MX_TIM5_Initv+0x88> + { Error_Handler(); - 8001010: f000 fa3e bl 8001490 + 80010bc: f000 fa4d bl 800155a } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8001014: 2300 movs r3, #0 - 8001016: 603b str r3, [r7, #0] + 80010c0: 2300 movs r3, #0 + 80010c2: 603b str r3, [r7, #0] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8001018: 2300 movs r3, #0 - 800101a: 60bb str r3, [r7, #8] - if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) { - 800101c: 463b mov r3, r7 - 800101e: 4619 mov r1, r3 - 8001020: 4808 ldr r0, [pc, #32] ; (8001044 <_ZL12MX_TIM5_Initv+0xb8>) - 8001022: f003 f93b bl 800429c - 8001026: 4603 mov r3, r0 - 8001028: 2b00 cmp r3, #0 - 800102a: bf14 ite ne - 800102c: 2301 movne r3, #1 - 800102e: 2300 moveq r3, #0 - 8001030: b2db uxtb r3, r3 - 8001032: 2b00 cmp r3, #0 - 8001034: d001 beq.n 800103a <_ZL12MX_TIM5_Initv+0xae> + 80010c4: 2300 movs r3, #0 + 80010c6: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) + 80010c8: 463b mov r3, r7 + 80010ca: 4619 mov r1, r3 + 80010cc: 4808 ldr r0, [pc, #32] ; (80010f0 <_ZL12MX_TIM5_Initv+0xb8>) + 80010ce: f003 f949 bl 8004364 + 80010d2: 4603 mov r3, r0 + 80010d4: 2b00 cmp r3, #0 + 80010d6: bf14 ite ne + 80010d8: 2301 movne r3, #1 + 80010da: 2300 moveq r3, #0 + 80010dc: b2db uxtb r3, r3 + 80010de: 2b00 cmp r3, #0 + 80010e0: d001 beq.n 80010e6 <_ZL12MX_TIM5_Initv+0xae> + { Error_Handler(); - 8001036: f000 fa2b bl 8001490 + 80010e2: f000 fa3a bl 800155a } /* USER CODE BEGIN TIM5_Init 2 */ /* USER CODE END TIM5_Init 2 */ } - 800103a: bf00 nop - 800103c: 3730 adds r7, #48 ; 0x30 - 800103e: 46bd mov sp, r7 - 8001040: bd80 pop {r7, pc} - 8001042: bf00 nop - 8001044: 200000f0 .word 0x200000f0 - 8001048: 40000c00 .word 0x40000c00 - -0800104c <_ZL12MX_TIM6_Initv>: -/** - * @brief TIM6 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM6_Init(void) { - 800104c: b580 push {r7, lr} - 800104e: b084 sub sp, #16 - 8001050: af00 add r7, sp, #0 + 80010e6: bf00 nop + 80010e8: 3730 adds r7, #48 ; 0x30 + 80010ea: 46bd mov sp, r7 + 80010ec: bd80 pop {r7, pc} + 80010ee: bf00 nop + 80010f0: 200000ec .word 0x200000ec + 80010f4: 40000c00 .word 0x40000c00 + +080010f8 <_ZL12MX_TIM6_Initv>: + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) +{ + 80010f8: b580 push {r7, lr} + 80010fa: b084 sub sp, #16 + 80010fc: af00 add r7, sp, #0 /* USER CODE BEGIN TIM6_Init 0 */ /* USER CODE END TIM6_Init 0 */ - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - 8001052: 1d3b adds r3, r7, #4 - 8001054: 2200 movs r2, #0 - 8001056: 601a str r2, [r3, #0] - 8001058: 605a str r2, [r3, #4] - 800105a: 609a str r2, [r3, #8] + TIM_MasterConfigTypeDef sMasterConfig = {0}; + 80010fe: 1d3b adds r3, r7, #4 + 8001100: 2200 movs r2, #0 + 8001102: 601a str r2, [r3, #0] + 8001104: 605a str r2, [r3, #4] + 8001106: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM6_Init 1 */ /* USER CODE END TIM6_Init 1 */ htim6.Instance = TIM6; - 800105c: 4b1a ldr r3, [pc, #104] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 800105e: 4a1b ldr r2, [pc, #108] ; (80010cc <_ZL12MX_TIM6_Initv+0x80>) - 8001060: 601a str r2, [r3, #0] + 8001108: 4b1a ldr r3, [pc, #104] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 800110a: 4a1b ldr r2, [pc, #108] ; (8001178 <_ZL12MX_TIM6_Initv+0x80>) + 800110c: 601a str r2, [r3, #0] htim6.Init.Prescaler = 9999; - 8001062: 4b19 ldr r3, [pc, #100] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 8001064: f242 720f movw r2, #9999 ; 0x270f - 8001068: 605a str r2, [r3, #4] + 800110e: 4b19 ldr r3, [pc, #100] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 8001110: f242 720f movw r2, #9999 ; 0x270f + 8001114: 605a str r2, [r3, #4] htim6.Init.CounterMode = TIM_COUNTERMODE_UP; - 800106a: 4b17 ldr r3, [pc, #92] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 800106c: 2200 movs r2, #0 - 800106e: 609a str r2, [r3, #8] + 8001116: 4b17 ldr r3, [pc, #92] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 8001118: 2200 movs r2, #0 + 800111a: 609a str r2, [r3, #8] htim6.Init.Period = 799; - 8001070: 4b15 ldr r3, [pc, #84] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 8001072: f240 321f movw r2, #799 ; 0x31f - 8001076: 60da str r2, [r3, #12] + 800111c: 4b15 ldr r3, [pc, #84] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 800111e: f240 321f movw r2, #799 ; 0x31f + 8001122: 60da str r2, [r3, #12] htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8001078: 4b13 ldr r3, [pc, #76] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 800107a: 2200 movs r2, #0 - 800107c: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { - 800107e: 4812 ldr r0, [pc, #72] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 8001080: f002 f89c bl 80031bc - 8001084: 4603 mov r3, r0 - 8001086: 2b00 cmp r3, #0 - 8001088: bf14 ite ne - 800108a: 2301 movne r3, #1 - 800108c: 2300 moveq r3, #0 - 800108e: b2db uxtb r3, r3 - 8001090: 2b00 cmp r3, #0 - 8001092: d001 beq.n 8001098 <_ZL12MX_TIM6_Initv+0x4c> + 8001124: 4b13 ldr r3, [pc, #76] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 8001126: 2200 movs r2, #0 + 8001128: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) + 800112a: 4812 ldr r0, [pc, #72] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 800112c: f002 f8aa bl 8003284 + 8001130: 4603 mov r3, r0 + 8001132: 2b00 cmp r3, #0 + 8001134: bf14 ite ne + 8001136: 2301 movne r3, #1 + 8001138: 2300 moveq r3, #0 + 800113a: b2db uxtb r3, r3 + 800113c: 2b00 cmp r3, #0 + 800113e: d001 beq.n 8001144 <_ZL12MX_TIM6_Initv+0x4c> + { Error_Handler(); - 8001094: f000 f9fc bl 8001490 + 8001140: f000 fa0b bl 800155a } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8001098: 2300 movs r3, #0 - 800109a: 607b str r3, [r7, #4] + 8001144: 2300 movs r3, #0 + 8001146: 607b str r3, [r7, #4] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 800109c: 2300 movs r3, #0 - 800109e: 60fb str r3, [r7, #12] - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { - 80010a0: 1d3b adds r3, r7, #4 - 80010a2: 4619 mov r1, r3 - 80010a4: 4808 ldr r0, [pc, #32] ; (80010c8 <_ZL12MX_TIM6_Initv+0x7c>) - 80010a6: f003 f8f9 bl 800429c - 80010aa: 4603 mov r3, r0 - 80010ac: 2b00 cmp r3, #0 - 80010ae: bf14 ite ne - 80010b0: 2301 movne r3, #1 - 80010b2: 2300 moveq r3, #0 - 80010b4: b2db uxtb r3, r3 - 80010b6: 2b00 cmp r3, #0 - 80010b8: d001 beq.n 80010be <_ZL12MX_TIM6_Initv+0x72> + 8001148: 2300 movs r3, #0 + 800114a: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) + 800114c: 1d3b adds r3, r7, #4 + 800114e: 4619 mov r1, r3 + 8001150: 4808 ldr r0, [pc, #32] ; (8001174 <_ZL12MX_TIM6_Initv+0x7c>) + 8001152: f003 f907 bl 8004364 + 8001156: 4603 mov r3, r0 + 8001158: 2b00 cmp r3, #0 + 800115a: bf14 ite ne + 800115c: 2301 movne r3, #1 + 800115e: 2300 moveq r3, #0 + 8001160: b2db uxtb r3, r3 + 8001162: 2b00 cmp r3, #0 + 8001164: d001 beq.n 800116a <_ZL12MX_TIM6_Initv+0x72> + { Error_Handler(); - 80010ba: f000 f9e9 bl 8001490 + 8001166: f000 f9f8 bl 800155a } /* USER CODE BEGIN TIM6_Init 2 */ /* USER CODE END TIM6_Init 2 */ } - 80010be: bf00 nop - 80010c0: 3710 adds r7, #16 - 80010c2: 46bd mov sp, r7 - 80010c4: bd80 pop {r7, pc} - 80010c6: bf00 nop - 80010c8: 20000130 .word 0x20000130 - 80010cc: 40001000 .word 0x40001000 - -080010d0 <_ZL19MX_USART6_UART_Initv>: -/** - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) { - 80010d0: b580 push {r7, lr} - 80010d2: af00 add r7, sp, #0 + 800116a: bf00 nop + 800116c: 3710 adds r7, #16 + 800116e: 46bd mov sp, r7 + 8001170: bd80 pop {r7, pc} + 8001172: bf00 nop + 8001174: 2000012c .word 0x2000012c + 8001178: 40001000 .word 0x40001000 + +0800117c <_ZL19MX_USART6_UART_Initv>: + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) +{ + 800117c: b580 push {r7, lr} + 800117e: af00 add r7, sp, #0 /* USER CODE END USART6_Init 0 */ /* USER CODE BEGIN USART6_Init 1 */ /* USER CODE END USART6_Init 1 */ huart6.Instance = USART6; - 80010d4: 4b17 ldr r3, [pc, #92] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010d6: 4a18 ldr r2, [pc, #96] ; (8001138 <_ZL19MX_USART6_UART_Initv+0x68>) - 80010d8: 601a str r2, [r3, #0] + 8001180: 4b17 ldr r3, [pc, #92] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 8001182: 4a18 ldr r2, [pc, #96] ; (80011e4 <_ZL19MX_USART6_UART_Initv+0x68>) + 8001184: 601a str r2, [r3, #0] huart6.Init.BaudRate = 115200; - 80010da: 4b16 ldr r3, [pc, #88] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010dc: f44f 32e1 mov.w r2, #115200 ; 0x1c200 - 80010e0: 605a str r2, [r3, #4] + 8001186: 4b16 ldr r3, [pc, #88] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 8001188: f44f 32e1 mov.w r2, #115200 ; 0x1c200 + 800118c: 605a str r2, [r3, #4] huart6.Init.WordLength = UART_WORDLENGTH_9B; - 80010e2: 4b14 ldr r3, [pc, #80] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010e4: f44f 5280 mov.w r2, #4096 ; 0x1000 - 80010e8: 609a str r2, [r3, #8] + 800118e: 4b14 ldr r3, [pc, #80] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 8001190: f44f 5280 mov.w r2, #4096 ; 0x1000 + 8001194: 609a str r2, [r3, #8] huart6.Init.StopBits = UART_STOPBITS_1; - 80010ea: 4b12 ldr r3, [pc, #72] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010ec: 2200 movs r2, #0 - 80010ee: 60da str r2, [r3, #12] + 8001196: 4b12 ldr r3, [pc, #72] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 8001198: 2200 movs r2, #0 + 800119a: 60da str r2, [r3, #12] huart6.Init.Parity = UART_PARITY_ODD; - 80010f0: 4b10 ldr r3, [pc, #64] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010f2: f44f 62c0 mov.w r2, #1536 ; 0x600 - 80010f6: 611a str r2, [r3, #16] + 800119c: 4b10 ldr r3, [pc, #64] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 800119e: f44f 62c0 mov.w r2, #1536 ; 0x600 + 80011a2: 611a str r2, [r3, #16] huart6.Init.Mode = UART_MODE_TX_RX; - 80010f8: 4b0e ldr r3, [pc, #56] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 80010fa: 220c movs r2, #12 - 80010fc: 615a str r2, [r3, #20] + 80011a4: 4b0e ldr r3, [pc, #56] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011a6: 220c movs r2, #12 + 80011a8: 615a str r2, [r3, #20] huart6.Init.HwFlowCtl = UART_HWCONTROL_NONE; - 80010fe: 4b0d ldr r3, [pc, #52] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001100: 2200 movs r2, #0 - 8001102: 619a str r2, [r3, #24] + 80011aa: 4b0d ldr r3, [pc, #52] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011ac: 2200 movs r2, #0 + 80011ae: 619a str r2, [r3, #24] huart6.Init.OverSampling = UART_OVERSAMPLING_16; - 8001104: 4b0b ldr r3, [pc, #44] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001106: 2200 movs r2, #0 - 8001108: 61da str r2, [r3, #28] + 80011b0: 4b0b ldr r3, [pc, #44] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011b2: 2200 movs r2, #0 + 80011b4: 61da str r2, [r3, #28] huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; - 800110a: 4b0a ldr r3, [pc, #40] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 800110c: 2200 movs r2, #0 - 800110e: 621a str r2, [r3, #32] + 80011b6: 4b0a ldr r3, [pc, #40] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011b8: 2200 movs r2, #0 + 80011ba: 621a str r2, [r3, #32] huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - 8001110: 4b08 ldr r3, [pc, #32] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001112: 2200 movs r2, #0 - 8001114: 625a str r2, [r3, #36] ; 0x24 - if (HAL_UART_Init(&huart6) != HAL_OK) { - 8001116: 4807 ldr r0, [pc, #28] ; (8001134 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001118: f003 f93a bl 8004390 - 800111c: 4603 mov r3, r0 - 800111e: 2b00 cmp r3, #0 - 8001120: bf14 ite ne - 8001122: 2301 movne r3, #1 - 8001124: 2300 moveq r3, #0 - 8001126: b2db uxtb r3, r3 - 8001128: 2b00 cmp r3, #0 - 800112a: d001 beq.n 8001130 <_ZL19MX_USART6_UART_Initv+0x60> + 80011bc: 4b08 ldr r3, [pc, #32] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011be: 2200 movs r2, #0 + 80011c0: 625a str r2, [r3, #36] ; 0x24 + if (HAL_UART_Init(&huart6) != HAL_OK) + 80011c2: 4807 ldr r0, [pc, #28] ; (80011e0 <_ZL19MX_USART6_UART_Initv+0x64>) + 80011c4: f003 f948 bl 8004458 + 80011c8: 4603 mov r3, r0 + 80011ca: 2b00 cmp r3, #0 + 80011cc: bf14 ite ne + 80011ce: 2301 movne r3, #1 + 80011d0: 2300 moveq r3, #0 + 80011d2: b2db uxtb r3, r3 + 80011d4: 2b00 cmp r3, #0 + 80011d6: d001 beq.n 80011dc <_ZL19MX_USART6_UART_Initv+0x60> + { Error_Handler(); - 800112c: f000 f9b0 bl 8001490 + 80011d8: f000 f9bf bl 800155a } /* USER CODE BEGIN USART6_Init 2 */ /* USER CODE END USART6_Init 2 */ } - 8001130: bf00 nop - 8001132: bd80 pop {r7, pc} - 8001134: 20000170 .word 0x20000170 - 8001138: 40011400 .word 0x40011400 - -0800113c <_ZL12MX_GPIO_Initv>: -/** - * @brief GPIO Initialization Function - * @param None - * @retval None - */ -static void MX_GPIO_Init(void) { - 800113c: b580 push {r7, lr} - 800113e: b08c sub sp, #48 ; 0x30 - 8001140: af00 add r7, sp, #0 - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; - 8001142: f107 031c add.w r3, r7, #28 - 8001146: 2200 movs r2, #0 - 8001148: 601a str r2, [r3, #0] - 800114a: 605a str r2, [r3, #4] - 800114c: 609a str r2, [r3, #8] - 800114e: 60da str r2, [r3, #12] - 8001150: 611a str r2, [r3, #16] + 80011dc: bf00 nop + 80011de: bd80 pop {r7, pc} + 80011e0: 2000016c .word 0x2000016c + 80011e4: 40011400 .word 0x40011400 + +080011e8 <_ZL12MX_GPIO_Initv>: + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) +{ + 80011e8: b580 push {r7, lr} + 80011ea: b08c sub sp, #48 ; 0x30 + 80011ec: af00 add r7, sp, #0 + GPIO_InitTypeDef GPIO_InitStruct = {0}; + 80011ee: f107 031c add.w r3, r7, #28 + 80011f2: 2200 movs r2, #0 + 80011f4: 601a str r2, [r3, #0] + 80011f6: 605a str r2, [r3, #4] + 80011f8: 609a str r2, [r3, #8] + 80011fa: 60da str r2, [r3, #12] + 80011fc: 611a str r2, [r3, #16] /* GPIO Ports Clock Enable */ __HAL_RCC_GPIOC_CLK_ENABLE(); - 8001152: 4b5e ldr r3, [pc, #376] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001154: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001156: 4a5d ldr r2, [pc, #372] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001158: f043 0304 orr.w r3, r3, #4 - 800115c: 6313 str r3, [r2, #48] ; 0x30 - 800115e: 4b5b ldr r3, [pc, #364] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001160: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001162: f003 0304 and.w r3, r3, #4 - 8001166: 61bb str r3, [r7, #24] - 8001168: 69bb ldr r3, [r7, #24] + 80011fe: 4b5e ldr r3, [pc, #376] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001200: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001202: 4a5d ldr r2, [pc, #372] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001204: f043 0304 orr.w r3, r3, #4 + 8001208: 6313 str r3, [r2, #48] ; 0x30 + 800120a: 4b5b ldr r3, [pc, #364] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800120c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800120e: f003 0304 and.w r3, r3, #4 + 8001212: 61bb str r3, [r7, #24] + 8001214: 69bb ldr r3, [r7, #24] __HAL_RCC_GPIOA_CLK_ENABLE(); - 800116a: 4b58 ldr r3, [pc, #352] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 800116c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800116e: 4a57 ldr r2, [pc, #348] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001170: f043 0301 orr.w r3, r3, #1 - 8001174: 6313 str r3, [r2, #48] ; 0x30 - 8001176: 4b55 ldr r3, [pc, #340] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001178: 6b1b ldr r3, [r3, #48] ; 0x30 - 800117a: f003 0301 and.w r3, r3, #1 - 800117e: 617b str r3, [r7, #20] - 8001180: 697b ldr r3, [r7, #20] + 8001216: 4b58 ldr r3, [pc, #352] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001218: 6b1b ldr r3, [r3, #48] ; 0x30 + 800121a: 4a57 ldr r2, [pc, #348] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800121c: f043 0301 orr.w r3, r3, #1 + 8001220: 6313 str r3, [r2, #48] ; 0x30 + 8001222: 4b55 ldr r3, [pc, #340] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001224: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001226: f003 0301 and.w r3, r3, #1 + 800122a: 617b str r3, [r7, #20] + 800122c: 697b ldr r3, [r7, #20] __HAL_RCC_GPIOF_CLK_ENABLE(); - 8001182: 4b52 ldr r3, [pc, #328] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001184: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001186: 4a51 ldr r2, [pc, #324] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001188: f043 0320 orr.w r3, r3, #32 - 800118c: 6313 str r3, [r2, #48] ; 0x30 - 800118e: 4b4f ldr r3, [pc, #316] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 8001190: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001192: f003 0320 and.w r3, r3, #32 - 8001196: 613b str r3, [r7, #16] - 8001198: 693b ldr r3, [r7, #16] + 800122e: 4b52 ldr r3, [pc, #328] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001230: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001232: 4a51 ldr r2, [pc, #324] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001234: f043 0320 orr.w r3, r3, #32 + 8001238: 6313 str r3, [r2, #48] ; 0x30 + 800123a: 4b4f ldr r3, [pc, #316] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800123c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800123e: f003 0320 and.w r3, r3, #32 + 8001242: 613b str r3, [r7, #16] + 8001244: 693b ldr r3, [r7, #16] __HAL_RCC_GPIOE_CLK_ENABLE(); - 800119a: 4b4c ldr r3, [pc, #304] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 800119c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800119e: 4a4b ldr r2, [pc, #300] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011a0: f043 0310 orr.w r3, r3, #16 - 80011a4: 6313 str r3, [r2, #48] ; 0x30 - 80011a6: 4b49 ldr r3, [pc, #292] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011a8: 6b1b ldr r3, [r3, #48] ; 0x30 - 80011aa: f003 0310 and.w r3, r3, #16 - 80011ae: 60fb str r3, [r7, #12] - 80011b0: 68fb ldr r3, [r7, #12] + 8001246: 4b4c ldr r3, [pc, #304] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001248: 6b1b ldr r3, [r3, #48] ; 0x30 + 800124a: 4a4b ldr r2, [pc, #300] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800124c: f043 0310 orr.w r3, r3, #16 + 8001250: 6313 str r3, [r2, #48] ; 0x30 + 8001252: 4b49 ldr r3, [pc, #292] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001254: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001256: f003 0310 and.w r3, r3, #16 + 800125a: 60fb str r3, [r7, #12] + 800125c: 68fb ldr r3, [r7, #12] __HAL_RCC_GPIOD_CLK_ENABLE(); - 80011b2: 4b46 ldr r3, [pc, #280] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011b4: 6b1b ldr r3, [r3, #48] ; 0x30 - 80011b6: 4a45 ldr r2, [pc, #276] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011b8: f043 0308 orr.w r3, r3, #8 - 80011bc: 6313 str r3, [r2, #48] ; 0x30 - 80011be: 4b43 ldr r3, [pc, #268] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011c0: 6b1b ldr r3, [r3, #48] ; 0x30 - 80011c2: f003 0308 and.w r3, r3, #8 - 80011c6: 60bb str r3, [r7, #8] - 80011c8: 68bb ldr r3, [r7, #8] + 800125e: 4b46 ldr r3, [pc, #280] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001260: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001262: 4a45 ldr r2, [pc, #276] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001264: f043 0308 orr.w r3, r3, #8 + 8001268: 6313 str r3, [r2, #48] ; 0x30 + 800126a: 4b43 ldr r3, [pc, #268] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800126c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800126e: f003 0308 and.w r3, r3, #8 + 8001272: 60bb str r3, [r7, #8] + 8001274: 68bb ldr r3, [r7, #8] __HAL_RCC_GPIOB_CLK_ENABLE(); - 80011ca: 4b40 ldr r3, [pc, #256] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011cc: 6b1b ldr r3, [r3, #48] ; 0x30 - 80011ce: 4a3f ldr r2, [pc, #252] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011d0: f043 0302 orr.w r3, r3, #2 - 80011d4: 6313 str r3, [r2, #48] ; 0x30 - 80011d6: 4b3d ldr r3, [pc, #244] ; (80012cc <_ZL12MX_GPIO_Initv+0x190>) - 80011d8: 6b1b ldr r3, [r3, #48] ; 0x30 - 80011da: f003 0302 and.w r3, r3, #2 - 80011de: 607b str r3, [r7, #4] - 80011e0: 687b ldr r3, [r7, #4] + 8001276: 4b40 ldr r3, [pc, #256] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001278: 6b1b ldr r3, [r3, #48] ; 0x30 + 800127a: 4a3f ldr r2, [pc, #252] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 800127c: f043 0302 orr.w r3, r3, #2 + 8001280: 6313 str r3, [r2, #48] ; 0x30 + 8001282: 4b3d ldr r3, [pc, #244] ; (8001378 <_ZL12MX_GPIO_Initv+0x190>) + 8001284: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001286: f003 0302 and.w r3, r3, #2 + 800128a: 607b str r3, [r7, #4] + 800128c: 687b ldr r3, [r7, #4] /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin, GPIO_PIN_RESET); - 80011e2: 2200 movs r2, #0 - 80011e4: f44f 5140 mov.w r1, #12288 ; 0x3000 - 80011e8: 4839 ldr r0, [pc, #228] ; (80012d0 <_ZL12MX_GPIO_Initv+0x194>) - 80011ea: f000 ff4f bl 800208c + HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin, GPIO_PIN_RESET); + 800128e: 2200 movs r2, #0 + 8001290: f44f 5140 mov.w r1, #12288 ; 0x3000 + 8001294: 4839 ldr r0, [pc, #228] ; (800137c <_ZL12MX_GPIO_Initv+0x194>) + 8001296: f000 ff5d bl 8002154 /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, sleep2_Pin | sleep1_Pin, GPIO_PIN_SET); - 80011ee: 2201 movs r2, #1 - 80011f0: f44f 4140 mov.w r1, #49152 ; 0xc000 - 80011f4: 4836 ldr r0, [pc, #216] ; (80012d0 <_ZL12MX_GPIO_Initv+0x194>) - 80011f6: f000 ff49 bl 800208c + HAL_GPIO_WritePin(GPIOF, sleep2_Pin|sleep1_Pin, GPIO_PIN_SET); + 800129a: 2201 movs r2, #1 + 800129c: f44f 4140 mov.w r1, #49152 ; 0xc000 + 80012a0: 4836 ldr r0, [pc, #216] ; (800137c <_ZL12MX_GPIO_Initv+0x194>) + 80012a2: f000 ff57 bl 8002154 /*Configure GPIO pin : user_button_Pin */ GPIO_InitStruct.Pin = user_button_Pin; - 80011fa: f44f 5300 mov.w r3, #8192 ; 0x2000 - 80011fe: 61fb str r3, [r7, #28] + 80012a6: f44f 5300 mov.w r3, #8192 ; 0x2000 + 80012aa: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; - 8001200: 4b34 ldr r3, [pc, #208] ; (80012d4 <_ZL12MX_GPIO_Initv+0x198>) - 8001202: 623b str r3, [r7, #32] + 80012ac: 4b34 ldr r3, [pc, #208] ; (8001380 <_ZL12MX_GPIO_Initv+0x198>) + 80012ae: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001204: 2300 movs r3, #0 - 8001206: 627b str r3, [r7, #36] ; 0x24 + 80012b0: 2300 movs r3, #0 + 80012b2: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(user_button_GPIO_Port, &GPIO_InitStruct); - 8001208: f107 031c add.w r3, r7, #28 - 800120c: 4619 mov r1, r3 - 800120e: 4832 ldr r0, [pc, #200] ; (80012d8 <_ZL12MX_GPIO_Initv+0x19c>) - 8001210: f000 fd92 bl 8001d38 + 80012b4: f107 031c add.w r3, r7, #28 + 80012b8: 4619 mov r1, r3 + 80012ba: 4832 ldr r0, [pc, #200] ; (8001384 <_ZL12MX_GPIO_Initv+0x19c>) + 80012bc: f000 fda0 bl 8001e00 /*Configure GPIO pin : current2_Pin */ GPIO_InitStruct.Pin = current2_Pin; - 8001214: 2301 movs r3, #1 - 8001216: 61fb str r3, [r7, #28] + 80012c0: 2301 movs r3, #1 + 80012c2: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - 8001218: 2303 movs r3, #3 - 800121a: 623b str r3, [r7, #32] + 80012c4: 2303 movs r3, #3 + 80012c6: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800121c: 2300 movs r3, #0 - 800121e: 627b str r3, [r7, #36] ; 0x24 + 80012c8: 2300 movs r3, #0 + 80012ca: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(current2_GPIO_Port, &GPIO_InitStruct); - 8001220: f107 031c add.w r3, r7, #28 - 8001224: 4619 mov r1, r3 - 8001226: 482c ldr r0, [pc, #176] ; (80012d8 <_ZL12MX_GPIO_Initv+0x19c>) - 8001228: f000 fd86 bl 8001d38 + 80012cc: f107 031c add.w r3, r7, #28 + 80012d0: 4619 mov r1, r3 + 80012d2: 482c ldr r0, [pc, #176] ; (8001384 <_ZL12MX_GPIO_Initv+0x19c>) + 80012d4: f000 fd94 bl 8001e00 /*Configure GPIO pin : current1_Pin */ GPIO_InitStruct.Pin = current1_Pin; - 800122c: 2308 movs r3, #8 - 800122e: 61fb str r3, [r7, #28] + 80012d8: 2308 movs r3, #8 + 80012da: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - 8001230: 2303 movs r3, #3 - 8001232: 623b str r3, [r7, #32] + 80012dc: 2303 movs r3, #3 + 80012de: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001234: 2300 movs r3, #0 - 8001236: 627b str r3, [r7, #36] ; 0x24 + 80012e0: 2300 movs r3, #0 + 80012e2: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(current1_GPIO_Port, &GPIO_InitStruct); - 8001238: f107 031c add.w r3, r7, #28 - 800123c: 4619 mov r1, r3 - 800123e: 4827 ldr r0, [pc, #156] ; (80012dc <_ZL12MX_GPIO_Initv+0x1a0>) - 8001240: f000 fd7a bl 8001d38 + 80012e4: f107 031c add.w r3, r7, #28 + 80012e8: 4619 mov r1, r3 + 80012ea: 4827 ldr r0, [pc, #156] ; (8001388 <_ZL12MX_GPIO_Initv+0x1a0>) + 80012ec: f000 fd88 bl 8001e00 /*Configure GPIO pin : fault2_Pin */ GPIO_InitStruct.Pin = fault2_Pin; - 8001244: 2340 movs r3, #64 ; 0x40 - 8001246: 61fb str r3, [r7, #28] + 80012f0: 2340 movs r3, #64 ; 0x40 + 80012f2: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - 8001248: 2300 movs r3, #0 - 800124a: 623b str r3, [r7, #32] + 80012f4: 2300 movs r3, #0 + 80012f6: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800124c: 2300 movs r3, #0 - 800124e: 627b str r3, [r7, #36] ; 0x24 + 80012f8: 2300 movs r3, #0 + 80012fa: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); - 8001250: f107 031c add.w r3, r7, #28 - 8001254: 4619 mov r1, r3 - 8001256: 4821 ldr r0, [pc, #132] ; (80012dc <_ZL12MX_GPIO_Initv+0x1a0>) - 8001258: f000 fd6e bl 8001d38 + 80012fc: f107 031c add.w r3, r7, #28 + 8001300: 4619 mov r1, r3 + 8001302: 4821 ldr r0, [pc, #132] ; (8001388 <_ZL12MX_GPIO_Initv+0x1a0>) + 8001304: f000 fd7c bl 8001e00 /*Configure GPIO pins : dir2_Pin dir1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin; - 800125c: f44f 5340 mov.w r3, #12288 ; 0x3000 - 8001260: 61fb str r3, [r7, #28] + GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin; + 8001308: f44f 5340 mov.w r3, #12288 ; 0x3000 + 800130c: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - 8001262: 2301 movs r3, #1 - 8001264: 623b str r3, [r7, #32] + 800130e: 2301 movs r3, #1 + 8001310: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001266: 2300 movs r3, #0 - 8001268: 627b str r3, [r7, #36] ; 0x24 + 8001312: 2300 movs r3, #0 + 8001314: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 800126a: 2300 movs r3, #0 - 800126c: 62bb str r3, [r7, #40] ; 0x28 + 8001316: 2300 movs r3, #0 + 8001318: 62bb str r3, [r7, #40] ; 0x28 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); - 800126e: f107 031c add.w r3, r7, #28 - 8001272: 4619 mov r1, r3 - 8001274: 4816 ldr r0, [pc, #88] ; (80012d0 <_ZL12MX_GPIO_Initv+0x194>) - 8001276: f000 fd5f bl 8001d38 + 800131a: f107 031c add.w r3, r7, #28 + 800131e: 4619 mov r1, r3 + 8001320: 4816 ldr r0, [pc, #88] ; (800137c <_ZL12MX_GPIO_Initv+0x194>) + 8001322: f000 fd6d bl 8001e00 /*Configure GPIO pins : sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = sleep2_Pin | sleep1_Pin; - 800127a: f44f 4340 mov.w r3, #49152 ; 0xc000 - 800127e: 61fb str r3, [r7, #28] + GPIO_InitStruct.Pin = sleep2_Pin|sleep1_Pin; + 8001326: f44f 4340 mov.w r3, #49152 ; 0xc000 + 800132a: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - 8001280: 2301 movs r3, #1 - 8001282: 623b str r3, [r7, #32] + 800132c: 2301 movs r3, #1 + 800132e: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_PULLUP; - 8001284: 2301 movs r3, #1 - 8001286: 627b str r3, [r7, #36] ; 0x24 + 8001330: 2301 movs r3, #1 + 8001332: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001288: 2300 movs r3, #0 - 800128a: 62bb str r3, [r7, #40] ; 0x28 + 8001334: 2300 movs r3, #0 + 8001336: 62bb str r3, [r7, #40] ; 0x28 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); - 800128c: f107 031c add.w r3, r7, #28 - 8001290: 4619 mov r1, r3 - 8001292: 480f ldr r0, [pc, #60] ; (80012d0 <_ZL12MX_GPIO_Initv+0x194>) - 8001294: f000 fd50 bl 8001d38 + 8001338: f107 031c add.w r3, r7, #28 + 800133c: 4619 mov r1, r3 + 800133e: 480f ldr r0, [pc, #60] ; (800137c <_ZL12MX_GPIO_Initv+0x194>) + 8001340: f000 fd5e bl 8001e00 /*Configure GPIO pin : fault1_Pin */ GPIO_InitStruct.Pin = fault1_Pin; - 8001298: f44f 7300 mov.w r3, #512 ; 0x200 - 800129c: 61fb str r3, [r7, #28] + 8001344: f44f 7300 mov.w r3, #512 ; 0x200 + 8001348: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - 800129e: 2300 movs r3, #0 - 80012a0: 623b str r3, [r7, #32] + 800134a: 2300 movs r3, #0 + 800134c: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80012a2: 2300 movs r3, #0 - 80012a4: 627b str r3, [r7, #36] ; 0x24 + 800134e: 2300 movs r3, #0 + 8001350: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(fault1_GPIO_Port, &GPIO_InitStruct); - 80012a6: f107 031c add.w r3, r7, #28 - 80012aa: 4619 mov r1, r3 - 80012ac: 480c ldr r0, [pc, #48] ; (80012e0 <_ZL12MX_GPIO_Initv+0x1a4>) - 80012ae: f000 fd43 bl 8001d38 + 8001352: f107 031c add.w r3, r7, #28 + 8001356: 4619 mov r1, r3 + 8001358: 480c ldr r0, [pc, #48] ; (800138c <_ZL12MX_GPIO_Initv+0x1a4>) + 800135a: f000 fd51 bl 8001e00 /* EXTI interrupt init*/ HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0); - 80012b2: 2200 movs r2, #0 - 80012b4: 2100 movs r1, #0 - 80012b6: 2028 movs r0, #40 ; 0x28 - 80012b8: f000 fce5 bl 8001c86 + 800135e: 2200 movs r2, #0 + 8001360: 2100 movs r1, #0 + 8001362: 2028 movs r0, #40 ; 0x28 + 8001364: f000 fcf3 bl 8001d4e HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); - 80012bc: 2028 movs r0, #40 ; 0x28 - 80012be: f000 fcfe bl 8001cbe + 8001368: 2028 movs r0, #40 ; 0x28 + 800136a: f000 fd0c bl 8001d86 } - 80012c2: bf00 nop - 80012c4: 3730 adds r7, #48 ; 0x30 - 80012c6: 46bd mov sp, r7 - 80012c8: bd80 pop {r7, pc} - 80012ca: bf00 nop - 80012cc: 40023800 .word 0x40023800 - 80012d0: 40021400 .word 0x40021400 - 80012d4: 10110000 .word 0x10110000 - 80012d8: 40020800 .word 0x40020800 - 80012dc: 40020000 .word 0x40020000 - 80012e0: 40021000 .word 0x40021000 - 80012e4: 00000000 .word 0x00000000 - -080012e8 : + 800136e: bf00 nop + 8001370: 3730 adds r7, #48 ; 0x30 + 8001372: 46bd mov sp, r7 + 8001374: bd80 pop {r7, pc} + 8001376: bf00 nop + 8001378: 40023800 .word 0x40023800 + 800137c: 40021400 .word 0x40021400 + 8001380: 10110000 .word 0x10110000 + 8001384: 40020800 .word 0x40020800 + 8001388: 40020000 .word 0x40020000 + 800138c: 40021000 .word 0x40021000 + +08001390 : /* USER CODE BEGIN 4 */ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { - 80012e8: b580 push {r7, lr} - 80012ea: b082 sub sp, #8 - 80012ec: af00 add r7, sp, #0 - 80012ee: 6078 str r0, [r7, #4] + 8001390: b580 push {r7, lr} + 8001392: b082 sub sp, #8 + 8001394: af00 add r7, sp, #0 + 8001396: 6078 str r0, [r7, #4] //TIMER 100Hz PID control if (htim->Instance == TIM3) { - 80012f0: 687b ldr r3, [r7, #4] - 80012f2: 681b ldr r3, [r3, #0] - 80012f4: 4a3c ldr r2, [pc, #240] ; (80013e8 ) - 80012f6: 4293 cmp r3, r2 - 80012f8: d125 bne.n 8001346 -// left_motor.set_speed(left_dutycycle); -// right_motor.set_speed(right_dutycycle); -// -// new_time = HAL_GetTick(); - - if (state == 0) { - 80012fa: 4b3c ldr r3, [pc, #240] ; (80013ec ) - 80012fc: 681b ldr r3, [r3, #0] - 80012fe: 2b00 cmp r3, #0 - 8001300: d121 bne.n 8001346 - left_velocity += 0.01; - 8001302: 4b3b ldr r3, [pc, #236] ; (80013f0 ) - 8001304: edd3 7a00 vldr s15, [r3] - 8001308: eeb7 7ae7 vcvt.f64.f32 d7, s15 - 800130c: ed9f 6b32 vldr d6, [pc, #200] ; 80013d8 - 8001310: ee37 7b06 vadd.f64 d7, d7, d6 - 8001314: eef7 7bc7 vcvt.f32.f64 s15, d7 - 8001318: 4b35 ldr r3, [pc, #212] ; (80013f0 ) - 800131a: edc3 7a00 vstr s15, [r3] - right_velocity += 0.1; - 800131e: 4b35 ldr r3, [pc, #212] ; (80013f4 ) - 8001320: edd3 7a00 vldr s15, [r3] - 8001324: eeb7 7ae7 vcvt.f64.f32 d7, s15 - 8001328: ed9f 6b2d vldr d6, [pc, #180] ; 80013e0 - 800132c: ee37 7b06 vadd.f64 d7, d7, d6 - 8001330: eef7 7bc7 vcvt.f32.f64 s15, d7 - 8001334: 4b2f ldr r3, [pc, #188] ; (80013f4 ) - 8001336: edc3 7a00 vstr s15, [r3] - HAL_UART_Transmit(&huart6, (uint8_t*) &rx_test, 4, 100); - 800133a: 2364 movs r3, #100 ; 0x64 - 800133c: 2204 movs r2, #4 - 800133e: 492e ldr r1, [pc, #184] ; (80013f8 ) - 8001340: 482e ldr r0, [pc, #184] ; (80013fc ) - 8001342: f003 f873 bl 800442c - } + 8001398: 687b ldr r3, [r7, #4] + 800139a: 681b ldr r3, [r3, #0] + 800139c: 4a39 ldr r2, [pc, #228] ; (8001484 ) + 800139e: 4293 cmp r3, r2 + 80013a0: d131 bne.n 8001406 + + left_velocity = left_encoder.GetLinearVelocity(); + 80013a2: 4839 ldr r0, [pc, #228] ; (8001488 ) + 80013a4: f7ff f942 bl 800062c <_ZN7Encoder17GetLinearVelocityEv> + 80013a8: eef0 7a40 vmov.f32 s15, s0 + 80013ac: 4b37 ldr r3, [pc, #220] ; (800148c ) + 80013ae: edc3 7a00 vstr s15, [r3] + right_velocity = right_encoder.GetLinearVelocity(); + 80013b2: 4837 ldr r0, [pc, #220] ; (8001490 ) + 80013b4: f7ff f93a bl 800062c <_ZN7Encoder17GetLinearVelocityEv> + 80013b8: eef0 7a40 vmov.f32 s15, s0 + 80013bc: 4b35 ldr r3, [pc, #212] ; (8001494 ) + 80013be: edc3 7a00 vstr s15, [r3] + left_dutycycle = left_pid.update(left_velocity); + 80013c2: 4b32 ldr r3, [pc, #200] ; (800148c ) + 80013c4: edd3 7a00 vldr s15, [r3] + 80013c8: eeb0 0a67 vmov.f32 s0, s15 + 80013cc: 4832 ldr r0, [pc, #200] ; (8001498 ) + 80013ce: f7ff fb61 bl 8000a94 <_ZN3Pid6updateEf> + 80013d2: 4602 mov r2, r0 + 80013d4: 4b31 ldr r3, [pc, #196] ; (800149c ) + 80013d6: 601a str r2, [r3, #0] + right_dutycycle = right_pid.update(right_velocity); + 80013d8: 4b2e ldr r3, [pc, #184] ; (8001494 ) + 80013da: edd3 7a00 vldr s15, [r3] + 80013de: eeb0 0a67 vmov.f32 s0, s15 + 80013e2: 482f ldr r0, [pc, #188] ; (80014a0 ) + 80013e4: f7ff fb56 bl 8000a94 <_ZN3Pid6updateEf> + 80013e8: 4602 mov r2, r0 + 80013ea: 4b2e ldr r3, [pc, #184] ; (80014a4 ) + 80013ec: 601a str r2, [r3, #0] + + left_motor.set_speed(left_dutycycle); + 80013ee: 4b2b ldr r3, [pc, #172] ; (800149c ) + 80013f0: 681b ldr r3, [r3, #0] + 80013f2: 4619 mov r1, r3 + 80013f4: 482c ldr r0, [pc, #176] ; (80014a8 ) + 80013f6: f7ff f9e5 bl 80007c4 <_ZN15MotorController9set_speedEi> + right_motor.set_speed(right_dutycycle); + 80013fa: 4b2a ldr r3, [pc, #168] ; (80014a4 ) + 80013fc: 681b ldr r3, [r3, #0] + 80013fe: 4619 mov r1, r3 + 8001400: 482a ldr r0, [pc, #168] ; (80014ac ) + 8001402: f7ff f9df bl 80007c4 <_ZN15MotorController9set_speedEi> } //TIMER 2Hz Transmit if (htim->Instance == TIM6) { - 8001346: 687b ldr r3, [r7, #4] - 8001348: 681b ldr r3, [r3, #0] - 800134a: 4a2d ldr r2, [pc, #180] ; (8001400 ) - 800134c: 4293 cmp r3, r2 - 800134e: d13f bne.n 80013d0 - if (left_dutycycle >= 790) { - 8001350: 4b2c ldr r3, [pc, #176] ; (8001404 ) - 8001352: 681b ldr r3, [r3, #0] - 8001354: f240 3215 movw r2, #789 ; 0x315 - 8001358: 4293 cmp r3, r2 - 800135a: dd03 ble.n 8001364 - flag = false; - 800135c: 4b2a ldr r3, [pc, #168] ; (8001408 ) - 800135e: 2200 movs r2, #0 - 8001360: 701a strb r2, [r3, #0] - 8001362: e008 b.n 8001376 - } else if (left_dutycycle <= -790) { - 8001364: 4b27 ldr r3, [pc, #156] ; (8001404 ) - 8001366: 681b ldr r3, [r3, #0] - 8001368: f46f 7245 mvn.w r2, #788 ; 0x314 - 800136c: 4293 cmp r3, r2 - 800136e: da02 bge.n 8001376 - flag = true; - 8001370: 4b25 ldr r3, [pc, #148] ; (8001408 ) - 8001372: 2201 movs r2, #1 - 8001374: 701a strb r2, [r3, #0] - } - - left_motor.set_speed(left_dutycycle); - 8001376: 4b23 ldr r3, [pc, #140] ; (8001404 ) - 8001378: 681b ldr r3, [r3, #0] - 800137a: 4619 mov r1, r3 - 800137c: 4823 ldr r0, [pc, #140] ; (800140c ) - 800137e: f7ff fa20 bl 80007c2 <_ZN15MotorController9set_speedEi> - odom_msg.angular_velocity = left_dutycycle; - 8001382: 4b20 ldr r3, [pc, #128] ; (8001404 ) - 8001384: 681b ldr r3, [r3, #0] - 8001386: ee07 3a90 vmov s15, r3 - 800138a: eef8 7ae7 vcvt.f32.s32 s15, s15 - 800138e: 4b20 ldr r3, [pc, #128] ; (8001410 ) - 8001390: edc3 7a00 vstr s15, [r3] - odom_msg.linear_velocity = left_encoder.GetLinearVelocity(); - 8001394: 481f ldr r0, [pc, #124] ; (8001414 ) - 8001396: f7ff f949 bl 800062c <_ZN7Encoder17GetLinearVelocityEv> - 800139a: eef0 7a40 vmov.f32 s15, s0 - 800139e: 4b1c ldr r3, [pc, #112] ; (8001410 ) - 80013a0: edc3 7a01 vstr s15, [r3, #4] - if (flag) - 80013a4: 4b18 ldr r3, [pc, #96] ; (8001408 ) - 80013a6: 781b ldrb r3, [r3, #0] - 80013a8: 2b00 cmp r3, #0 - 80013aa: d005 beq.n 80013b8 - left_dutycycle++; - 80013ac: 4b15 ldr r3, [pc, #84] ; (8001404 ) - 80013ae: 681b ldr r3, [r3, #0] - 80013b0: 3301 adds r3, #1 - 80013b2: 4a14 ldr r2, [pc, #80] ; (8001404 ) - 80013b4: 6013 str r3, [r2, #0] - 80013b6: e004 b.n 80013c2 - else - left_dutycycle--; - 80013b8: 4b12 ldr r3, [pc, #72] ; (8001404 ) - 80013ba: 681b ldr r3, [r3, #0] - 80013bc: 3b01 subs r3, #1 - 80013be: 4a11 ldr r2, [pc, #68] ; (8001404 ) - 80013c0: 6013 str r3, [r2, #0] + 8001406: 687b ldr r3, [r7, #4] + 8001408: 681b ldr r3, [r3, #0] + 800140a: 4a29 ldr r2, [pc, #164] ; (80014b0 ) + 800140c: 4293 cmp r3, r2 + 800140e: d135 bne.n 800147c + + left_velocity = left_encoder.GetLinearVelocity(); + 8001410: 481d ldr r0, [pc, #116] ; (8001488 ) + 8001412: f7ff f90b bl 800062c <_ZN7Encoder17GetLinearVelocityEv> + 8001416: eef0 7a40 vmov.f32 s15, s0 + 800141a: 4b1c ldr r3, [pc, #112] ; (800148c ) + 800141c: edc3 7a00 vstr s15, [r3] + right_velocity = right_encoder.GetLinearVelocity(); + 8001420: 481b ldr r0, [pc, #108] ; (8001490 ) + 8001422: f7ff f903 bl 800062c <_ZN7Encoder17GetLinearVelocityEv> + 8001426: eef0 7a40 vmov.f32 s15, s0 + 800142a: 4b1a ldr r3, [pc, #104] ; (8001494 ) + 800142c: edc3 7a00 vstr s15, [r3] + + odom_msg.angular_velocity = (right_velocity - left_velocity)/baseline; + 8001430: 4b18 ldr r3, [pc, #96] ; (8001494 ) + 8001432: ed93 7a00 vldr s14, [r3] + 8001436: 4b15 ldr r3, [pc, #84] ; (800148c ) + 8001438: edd3 7a00 vldr s15, [r3] + 800143c: ee77 6a67 vsub.f32 s13, s14, s15 + 8001440: 4b1c ldr r3, [pc, #112] ; (80014b4 ) + 8001442: ed93 7a00 vldr s14, [r3] + 8001446: eec6 7a87 vdiv.f32 s15, s13, s14 + 800144a: 4b1b ldr r3, [pc, #108] ; (80014b8 ) + 800144c: edc3 7a00 vstr s15, [r3] + odom_msg.linear_velocity = (right_velocity + left_velocity)/2; + 8001450: 4b10 ldr r3, [pc, #64] ; (8001494 ) + 8001452: ed93 7a00 vldr s14, [r3] + 8001456: 4b0d ldr r3, [pc, #52] ; (800148c ) + 8001458: edd3 7a00 vldr s15, [r3] + 800145c: ee37 7a27 vadd.f32 s14, s14, s15 + 8001460: eef0 6a00 vmov.f32 s13, #0 ; 0x40000000 2.0 + 8001464: eec7 7a26 vdiv.f32 s15, s14, s13 + 8001468: 4b13 ldr r3, [pc, #76] ; (80014b8 ) + 800146a: edc3 7a01 vstr s15, [r3, #4] HAL_UART_Transmit(&huart6, tx_buffer, 8, 100); - 80013c2: 4b15 ldr r3, [pc, #84] ; (8001418 ) - 80013c4: 6819 ldr r1, [r3, #0] - 80013c6: 2364 movs r3, #100 ; 0x64 - 80013c8: 2208 movs r2, #8 - 80013ca: 480c ldr r0, [pc, #48] ; (80013fc ) - 80013cc: f003 f82e bl 800442c + 800146e: 4b13 ldr r3, [pc, #76] ; (80014bc ) + 8001470: 6819 ldr r1, [r3, #0] + 8001472: 2364 movs r3, #100 ; 0x64 + 8001474: 2208 movs r2, #8 + 8001476: 4812 ldr r0, [pc, #72] ; (80014c0 ) + 8001478: f003 f83c bl 80044f4 } } - 80013d0: bf00 nop - 80013d2: 3708 adds r7, #8 - 80013d4: 46bd mov sp, r7 - 80013d6: bd80 pop {r7, pc} - 80013d8: 47ae147b .word 0x47ae147b - 80013dc: 3f847ae1 .word 0x3f847ae1 - 80013e0: 9999999a .word 0x9999999a - 80013e4: 3fb99999 .word 0x3fb99999 - 80013e8: 40000400 .word 0x40000400 - 80013ec: 20000004 .word 0x20000004 - 80013f0: 20000270 .word 0x20000270 - 80013f4: 20000274 .word 0x20000274 - 80013f8: 20000398 .word 0x20000398 - 80013fc: 20000170 .word 0x20000170 - 8001400: 40001000 .word 0x40001000 - 8001404: 20000344 .word 0x20000344 - 8001408: 20000000 .word 0x20000000 - 800140c: 2000034c .word 0x2000034c - 8001410: 20000384 .word 0x20000384 - 8001414: 200001f0 .word 0x200001f0 - 8001418: 2000037c .word 0x2000037c - -0800141c : + 800147c: bf00 nop + 800147e: 3708 adds r7, #8 + 8001480: 46bd mov sp, r7 + 8001482: bd80 pop {r7, pc} + 8001484: 40000400 .word 0x40000400 + 8001488: 200001ec .word 0x200001ec + 800148c: 2000026c .word 0x2000026c + 8001490: 20000208 .word 0x20000208 + 8001494: 20000270 .word 0x20000270 + 8001498: 20000274 .word 0x20000274 + 800149c: 20000340 .word 0x20000340 + 80014a0: 200002b8 .word 0x200002b8 + 80014a4: 20000344 .word 0x20000344 + 80014a8: 2000034c .word 0x2000034c + 80014ac: 20000364 .word 0x20000364 + 80014b0: 40001000 .word 0x40001000 + 80014b4: 20000000 .word 0x20000000 + 80014b8: 20000384 .word 0x20000384 + 80014bc: 2000037c .word 0x2000037c + 80014c0: 2000016c .word 0x2000016c + +080014c4 : void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) { - 800141c: b580 push {r7, lr} - 800141e: b082 sub sp, #8 - 8001420: af00 add r7, sp, #0 - 8001422: 6078 str r0, [r7, #4] - - //abilita interrupt nuovamente -// HAL_UART_Receive_IT(&huart6, rx_buffer, 8); - - //test plot - HAL_UART_Receive_IT(&huart6, (uint8_t*) &rx_test, 4); - 8001424: 2204 movs r2, #4 - 8001426: 4904 ldr r1, [pc, #16] ; (8001438 ) - 8001428: 4804 ldr r0, [pc, #16] ; (800143c ) - 800142a: f003 f891 bl 8004550 + 80014c4: b580 push {r7, lr} + 80014c6: b084 sub sp, #16 + 80014c8: af00 add r7, sp, #0 + 80014ca: 6078 str r0, [r7, #4] + float left_setpoint; + float right_setpoint; + + left_setpoint = -(vel_msg.angular_velocity * baseline) + + vel_msg.linear_velocity; + 80014cc: 4b17 ldr r3, [pc, #92] ; (800152c ) + 80014ce: ed93 7a01 vldr s14, [r3, #4] + left_setpoint = -(vel_msg.angular_velocity * baseline) + 80014d2: 4b16 ldr r3, [pc, #88] ; (800152c ) + 80014d4: edd3 6a00 vldr s13, [r3] + 80014d8: 4b15 ldr r3, [pc, #84] ; (8001530 ) + 80014da: edd3 7a00 vldr s15, [r3] + 80014de: ee66 7aa7 vmul.f32 s15, s13, s15 + 80014e2: ee77 7a67 vsub.f32 s15, s14, s15 + 80014e6: edc7 7a03 vstr s15, [r7, #12] + right_setpoint = vel_msg.linear_velocity * 2 - left_setpoint; + 80014ea: 4b10 ldr r3, [pc, #64] ; (800152c ) + 80014ec: edd3 7a01 vldr s15, [r3, #4] + 80014f0: ee37 7aa7 vadd.f32 s14, s15, s15 + 80014f4: edd7 7a03 vldr s15, [r7, #12] + 80014f8: ee77 7a67 vsub.f32 s15, s14, s15 + 80014fc: edc7 7a02 vstr s15, [r7, #8] + + left_pid.set(left_setpoint); + 8001500: ed97 0a03 vldr s0, [r7, #12] + 8001504: 480b ldr r0, [pc, #44] ; (8001534 ) + 8001506: f7ff fab6 bl 8000a76 <_ZN3Pid3setEf> + right_pid.set(right_setpoint); + 800150a: ed97 0a02 vldr s0, [r7, #8] + 800150e: 480a ldr r0, [pc, #40] ; (8001538 ) + 8001510: f7ff fab1 bl 8000a76 <_ZN3Pid3setEf> + + //TODO cross pid + + //Enables interrupt again + HAL_UART_Receive_IT(&huart6, rx_buffer, 8); + 8001514: 4b09 ldr r3, [pc, #36] ; (800153c ) + 8001516: 681b ldr r3, [r3, #0] + 8001518: 2208 movs r2, #8 + 800151a: 4619 mov r1, r3 + 800151c: 4808 ldr r0, [pc, #32] ; (8001540 ) + 800151e: f003 f87b bl 8004618 } - 800142e: bf00 nop - 8001430: 3708 adds r7, #8 - 8001432: 46bd mov sp, r7 - 8001434: bd80 pop {r7, pc} - 8001436: bf00 nop - 8001438: 20000398 .word 0x20000398 - 800143c: 20000170 .word 0x20000170 - -08001440 : + 8001522: bf00 nop + 8001524: 3710 adds r7, #16 + 8001526: 46bd mov sp, r7 + 8001528: bd80 pop {r7, pc} + 800152a: bf00 nop + 800152c: 20000390 .word 0x20000390 + 8001530: 20000000 .word 0x20000000 + 8001534: 20000274 .word 0x20000274 + 8001538: 200002b8 .word 0x200002b8 + 800153c: 20000380 .word 0x20000380 + 8001540: 2000016c .word 0x2000016c + +08001544 : void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { - 8001440: b580 push {r7, lr} - 8001442: b082 sub sp, #8 - 8001444: af00 add r7, sp, #0 - 8001446: 4603 mov r3, r0 - 8001448: 80fb strh r3, [r7, #6] + 8001544: b480 push {r7} + 8001546: b083 sub sp, #12 + 8001548: af00 add r7, sp, #0 + 800154a: 4603 mov r3, r0 + 800154c: 80fb strh r3, [r7, #6] + //Blue user button on the NUCLEO board if (GPIO_Pin == GPIO_PIN_13) { - 800144a: 88fb ldrh r3, [r7, #6] - 800144c: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 8001450: d114 bne.n 800147c - if (state == 0) { - 8001452: 4b0c ldr r3, [pc, #48] ; (8001484 ) - 8001454: 681b ldr r3, [r3, #0] - 8001456: 2b00 cmp r3, #0 - 8001458: d109 bne.n 800146e - state = 1; - 800145a: 4b0a ldr r3, [pc, #40] ; (8001484 ) - 800145c: 2201 movs r2, #1 - 800145e: 601a str r2, [r3, #0] - left_motor.brake(); - 8001460: 4809 ldr r0, [pc, #36] ; (8001488 ) - 8001462: f7ff fac6 bl 80009f2 <_ZN15MotorController5brakeEv> - right_motor.brake(); - 8001466: 4809 ldr r0, [pc, #36] ; (800148c ) - 8001468: f7ff fac3 bl 80009f2 <_ZN15MotorController5brakeEv> - else if (state == 1) { - state = 0; - } - + //TODO do we need it? } } - 800146c: e006 b.n 800147c - else if (state == 1) { - 800146e: 4b05 ldr r3, [pc, #20] ; (8001484 ) - 8001470: 681b ldr r3, [r3, #0] - 8001472: 2b01 cmp r3, #1 - 8001474: d102 bne.n 800147c - state = 0; - 8001476: 4b03 ldr r3, [pc, #12] ; (8001484 ) - 8001478: 2200 movs r2, #0 - 800147a: 601a str r2, [r3, #0] -} - 800147c: bf00 nop - 800147e: 3708 adds r7, #8 - 8001480: 46bd mov sp, r7 - 8001482: bd80 pop {r7, pc} - 8001484: 20000004 .word 0x20000004 - 8001488: 2000034c .word 0x2000034c - 800148c: 20000364 .word 0x20000364 - -08001490 : + 800154e: bf00 nop + 8001550: 370c adds r7, #12 + 8001552: 46bd mov sp, r7 + 8001554: f85d 7b04 ldr.w r7, [sp], #4 + 8001558: 4770 bx lr +0800155a : /** - * @brief This function is executed in case of error occurrence. - * @retval None - */ -void Error_Handler(void) { - 8001490: b480 push {r7} - 8001492: af00 add r7, sp, #0 + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) +{ + 800155a: b480 push {r7} + 800155c: af00 add r7, sp, #0 /* USER CODE BEGIN Error_Handler_Debug */ /* User can add his own implementation to report the HAL error return state */ /* USER CODE END Error_Handler_Debug */ } - 8001494: bf00 nop - 8001496: 46bd mov sp, r7 - 8001498: f85d 7b04 ldr.w r7, [sp], #4 - 800149c: 4770 bx lr - ... - -080014a0 <_Z41__static_initialization_and_destruction_0ii>: - 80014a0: b5f0 push {r4, r5, r6, r7, lr} - 80014a2: b08f sub sp, #60 ; 0x3c - 80014a4: af0c add r7, sp, #48 ; 0x30 - 80014a6: 6078 str r0, [r7, #4] - 80014a8: 6039 str r1, [r7, #0] - 80014aa: 687b ldr r3, [r7, #4] - 80014ac: 2b01 cmp r3, #1 - 80014ae: d158 bne.n 8001562 <_Z41__static_initialization_and_destruction_0ii+0xc2> - 80014b0: 683b ldr r3, [r7, #0] - 80014b2: f64f 72ff movw r2, #65535 ; 0xffff - 80014b6: 4293 cmp r3, r2 - 80014b8: d153 bne.n 8001562 <_Z41__static_initialization_and_destruction_0ii+0xc2> -Encoder left_encoder = Encoder(&htim5); - 80014ba: 492c ldr r1, [pc, #176] ; (800156c <_Z41__static_initialization_and_destruction_0ii+0xcc>) - 80014bc: 482c ldr r0, [pc, #176] ; (8001570 <_Z41__static_initialization_and_destruction_0ii+0xd0>) - 80014be: f7ff f863 bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> -Encoder right_encoder = Encoder(&htim2); - 80014c2: 492c ldr r1, [pc, #176] ; (8001574 <_Z41__static_initialization_and_destruction_0ii+0xd4>) - 80014c4: 482c ldr r0, [pc, #176] ; (8001578 <_Z41__static_initialization_and_destruction_0ii+0xd8>) - 80014c6: f7ff f85f bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> + 800155e: bf00 nop + 8001560: 46bd mov sp, r7 + 8001562: f85d 7b04 ldr.w r7, [sp], #4 + 8001566: 4770 bx lr + +08001568 <_Z41__static_initialization_and_destruction_0ii>: + 8001568: b5f0 push {r4, r5, r6, r7, lr} + 800156a: b08f sub sp, #60 ; 0x3c + 800156c: af0c add r7, sp, #48 ; 0x30 + 800156e: 6078 str r0, [r7, #4] + 8001570: 6039 str r1, [r7, #0] + 8001572: 687b ldr r3, [r7, #4] + 8001574: 2b01 cmp r3, #1 + 8001576: d158 bne.n 800162a <_Z41__static_initialization_and_destruction_0ii+0xc2> + 8001578: 683b ldr r3, [r7, #0] + 800157a: f64f 72ff movw r2, #65535 ; 0xffff + 800157e: 4293 cmp r3, r2 + 8001580: d153 bne.n 800162a <_Z41__static_initialization_and_destruction_0ii+0xc2> +Encoder left_encoder = Encoder(&htim2); + 8001582: 492c ldr r1, [pc, #176] ; (8001634 <_Z41__static_initialization_and_destruction_0ii+0xcc>) + 8001584: 482c ldr r0, [pc, #176] ; (8001638 <_Z41__static_initialization_and_destruction_0ii+0xd0>) + 8001586: f7fe ffff bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> +Encoder right_encoder = Encoder(&htim5); + 800158a: 492c ldr r1, [pc, #176] ; (800163c <_Z41__static_initialization_and_destruction_0ii+0xd4>) + 800158c: 482c ldr r0, [pc, #176] ; (8001640 <_Z41__static_initialization_and_destruction_0ii+0xd8>) + 800158e: f7fe fffb bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> Odometry odom = Odometry(left_encoder, right_encoder); - 80014ca: 4e29 ldr r6, [pc, #164] ; (8001570 <_Z41__static_initialization_and_destruction_0ii+0xd0>) - 80014cc: 4b2a ldr r3, [pc, #168] ; (8001578 <_Z41__static_initialization_and_destruction_0ii+0xd8>) - 80014ce: ac04 add r4, sp, #16 - 80014d0: 461d mov r5, r3 - 80014d2: cd0f ldmia r5!, {r0, r1, r2, r3} - 80014d4: c40f stmia r4!, {r0, r1, r2, r3} - 80014d6: e895 0007 ldmia.w r5, {r0, r1, r2} - 80014da: e884 0007 stmia.w r4, {r0, r1, r2} - 80014de: 466c mov r4, sp - 80014e0: f106 030c add.w r3, r6, #12 - 80014e4: cb0f ldmia r3, {r0, r1, r2, r3} - 80014e6: e884 000f stmia.w r4, {r0, r1, r2, r3} - 80014ea: e896 000e ldmia.w r6, {r1, r2, r3} - 80014ee: 4823 ldr r0, [pc, #140] ; (800157c <_Z41__static_initialization_and_destruction_0ii+0xdc>) - 80014f0: f7ff f902 bl 80006f8 <_ZN8OdometryC1E7EncoderS0_> + 8001592: 4e29 ldr r6, [pc, #164] ; (8001638 <_Z41__static_initialization_and_destruction_0ii+0xd0>) + 8001594: 4b2a ldr r3, [pc, #168] ; (8001640 <_Z41__static_initialization_and_destruction_0ii+0xd8>) + 8001596: ac04 add r4, sp, #16 + 8001598: 461d mov r5, r3 + 800159a: cd0f ldmia r5!, {r0, r1, r2, r3} + 800159c: c40f stmia r4!, {r0, r1, r2, r3} + 800159e: e895 0007 ldmia.w r5, {r0, r1, r2} + 80015a2: e884 0007 stmia.w r4, {r0, r1, r2} + 80015a6: 466c mov r4, sp + 80015a8: f106 030c add.w r3, r6, #12 + 80015ac: cb0f ldmia r3, {r0, r1, r2, r3} + 80015ae: e884 000f stmia.w r4, {r0, r1, r2, r3} + 80015b2: e896 000e ldmia.w r6, {r1, r2, r3} + 80015b6: 4823 ldr r0, [pc, #140] ; (8001644 <_Z41__static_initialization_and_destruction_0ii+0xdc>) + 80015b8: f7ff f89e bl 80006f8 <_ZN8OdometryC1E7EncoderS0_> Pid left_pid(690, 0, 0); - 80014f4: ed9f 1a22 vldr s2, [pc, #136] ; 8001580 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80014f8: eddf 0a21 vldr s1, [pc, #132] ; 8001580 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80014fc: ed9f 0a21 vldr s0, [pc, #132] ; 8001584 <_Z41__static_initialization_and_destruction_0ii+0xe4> - 8001500: 4821 ldr r0, [pc, #132] ; (8001588 <_Z41__static_initialization_and_destruction_0ii+0xe8>) - 8001502: f7ff fab7 bl 8000a74 <_ZN3PidC1Efff> + 80015bc: ed9f 1a22 vldr s2, [pc, #136] ; 8001648 <_Z41__static_initialization_and_destruction_0ii+0xe0> + 80015c0: eddf 0a21 vldr s1, [pc, #132] ; 8001648 <_Z41__static_initialization_and_destruction_0ii+0xe0> + 80015c4: ed9f 0a21 vldr s0, [pc, #132] ; 800164c <_Z41__static_initialization_and_destruction_0ii+0xe4> + 80015c8: 4821 ldr r0, [pc, #132] ; (8001650 <_Z41__static_initialization_and_destruction_0ii+0xe8>) + 80015ca: f7ff fa19 bl 8000a00 <_ZN3PidC1Efff> Pid right_pid(650, 100, 0.0); - 8001506: ed9f 1a1e vldr s2, [pc, #120] ; 8001580 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 800150a: eddf 0a20 vldr s1, [pc, #128] ; 800158c <_Z41__static_initialization_and_destruction_0ii+0xec> - 800150e: ed9f 0a20 vldr s0, [pc, #128] ; 8001590 <_Z41__static_initialization_and_destruction_0ii+0xf0> - 8001512: 4820 ldr r0, [pc, #128] ; (8001594 <_Z41__static_initialization_and_destruction_0ii+0xf4>) - 8001514: f7ff faae bl 8000a74 <_ZN3PidC1Efff> + 80015ce: ed9f 1a1e vldr s2, [pc, #120] ; 8001648 <_Z41__static_initialization_and_destruction_0ii+0xe0> + 80015d2: eddf 0a20 vldr s1, [pc, #128] ; 8001654 <_Z41__static_initialization_and_destruction_0ii+0xec> + 80015d6: ed9f 0a20 vldr s0, [pc, #128] ; 8001658 <_Z41__static_initialization_and_destruction_0ii+0xf0> + 80015da: 4820 ldr r0, [pc, #128] ; (800165c <_Z41__static_initialization_and_destruction_0ii+0xf4>) + 80015dc: f7ff fa10 bl 8000a00 <_ZN3PidC1Efff> Pid cross_pid(1, 0.1, 0.0); - 8001518: ed9f 1a19 vldr s2, [pc, #100] ; 8001580 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 800151c: eddf 0a1e vldr s1, [pc, #120] ; 8001598 <_Z41__static_initialization_and_destruction_0ii+0xf8> - 8001520: eeb7 0a00 vmov.f32 s0, #112 ; 0x3f800000 1.0 - 8001524: 481d ldr r0, [pc, #116] ; (800159c <_Z41__static_initialization_and_destruction_0ii+0xfc>) - 8001526: f7ff faa5 bl 8000a74 <_ZN3PidC1Efff> + 80015e0: ed9f 1a19 vldr s2, [pc, #100] ; 8001648 <_Z41__static_initialization_and_destruction_0ii+0xe0> + 80015e4: eddf 0a1e vldr s1, [pc, #120] ; 8001660 <_Z41__static_initialization_and_destruction_0ii+0xf8> + 80015e8: eeb7 0a00 vmov.f32 s0, #112 ; 0x3f800000 1.0 + 80015ec: 481d ldr r0, [pc, #116] ; (8001664 <_Z41__static_initialization_and_destruction_0ii+0xfc>) + 80015ee: f7ff fa07 bl 8000a00 <_ZN3PidC1Efff> TIM_CHANNEL_4); - 800152a: 230c movs r3, #12 - 800152c: 9302 str r3, [sp, #8] - 800152e: 4b1c ldr r3, [pc, #112] ; (80015a0 <_Z41__static_initialization_and_destruction_0ii+0x100>) - 8001530: 9301 str r3, [sp, #4] - 8001532: f44f 5300 mov.w r3, #8192 ; 0x2000 - 8001536: 9300 str r3, [sp, #0] - 8001538: 4b1a ldr r3, [pc, #104] ; (80015a4 <_Z41__static_initialization_and_destruction_0ii+0x104>) - 800153a: f44f 4200 mov.w r2, #32768 ; 0x8000 - 800153e: 4919 ldr r1, [pc, #100] ; (80015a4 <_Z41__static_initialization_and_destruction_0ii+0x104>) - 8001540: 4819 ldr r0, [pc, #100] ; (80015a8 <_Z41__static_initialization_and_destruction_0ii+0x108>) - 8001542: f7ff f90d bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> + 80015f2: 230c movs r3, #12 + 80015f4: 9302 str r3, [sp, #8] + 80015f6: 4b1c ldr r3, [pc, #112] ; (8001668 <_Z41__static_initialization_and_destruction_0ii+0x100>) + 80015f8: 9301 str r3, [sp, #4] + 80015fa: f44f 5300 mov.w r3, #8192 ; 0x2000 + 80015fe: 9300 str r3, [sp, #0] + 8001600: 4b1a ldr r3, [pc, #104] ; (800166c <_Z41__static_initialization_and_destruction_0ii+0x104>) + 8001602: f44f 4200 mov.w r2, #32768 ; 0x8000 + 8001606: 4919 ldr r1, [pc, #100] ; (800166c <_Z41__static_initialization_and_destruction_0ii+0x104>) + 8001608: 4819 ldr r0, [pc, #100] ; (8001670 <_Z41__static_initialization_and_destruction_0ii+0x108>) + 800160a: f7ff f8a9 bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> TIM_CHANNEL_3); - 8001546: 2308 movs r3, #8 - 8001548: 9302 str r3, [sp, #8] - 800154a: 4b15 ldr r3, [pc, #84] ; (80015a0 <_Z41__static_initialization_and_destruction_0ii+0x100>) - 800154c: 9301 str r3, [sp, #4] - 800154e: f44f 5380 mov.w r3, #4096 ; 0x1000 - 8001552: 9300 str r3, [sp, #0] - 8001554: 4b13 ldr r3, [pc, #76] ; (80015a4 <_Z41__static_initialization_and_destruction_0ii+0x104>) - 8001556: f44f 4280 mov.w r2, #16384 ; 0x4000 - 800155a: 4912 ldr r1, [pc, #72] ; (80015a4 <_Z41__static_initialization_and_destruction_0ii+0x104>) - 800155c: 4813 ldr r0, [pc, #76] ; (80015ac <_Z41__static_initialization_and_destruction_0ii+0x10c>) - 800155e: f7ff f8ff bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> + 800160e: 2308 movs r3, #8 + 8001610: 9302 str r3, [sp, #8] + 8001612: 4b15 ldr r3, [pc, #84] ; (8001668 <_Z41__static_initialization_and_destruction_0ii+0x100>) + 8001614: 9301 str r3, [sp, #4] + 8001616: f44f 5380 mov.w r3, #4096 ; 0x1000 + 800161a: 9300 str r3, [sp, #0] + 800161c: 4b13 ldr r3, [pc, #76] ; (800166c <_Z41__static_initialization_and_destruction_0ii+0x104>) + 800161e: f44f 4280 mov.w r2, #16384 ; 0x4000 + 8001622: 4912 ldr r1, [pc, #72] ; (800166c <_Z41__static_initialization_and_destruction_0ii+0x104>) + 8001624: 4813 ldr r0, [pc, #76] ; (8001674 <_Z41__static_initialization_and_destruction_0ii+0x10c>) + 8001626: f7ff f89b bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> } - 8001562: bf00 nop - 8001564: 370c adds r7, #12 - 8001566: 46bd mov sp, r7 - 8001568: bdf0 pop {r4, r5, r6, r7, pc} - 800156a: bf00 nop - 800156c: 200000f0 .word 0x200000f0 - 8001570: 200001f0 .word 0x200001f0 - 8001574: 20000030 .word 0x20000030 - 8001578: 2000020c .word 0x2000020c - 800157c: 20000228 .word 0x20000228 - 8001580: 00000000 .word 0x00000000 - 8001584: 442c8000 .word 0x442c8000 - 8001588: 20000278 .word 0x20000278 - 800158c: 42c80000 .word 0x42c80000 - 8001590: 44228000 .word 0x44228000 - 8001594: 200002bc .word 0x200002bc - 8001598: 3dcccccd .word 0x3dcccccd - 800159c: 20000300 .word 0x20000300 - 80015a0: 200000b0 .word 0x200000b0 - 80015a4: 40021400 .word 0x40021400 - 80015a8: 2000034c .word 0x2000034c - 80015ac: 20000364 .word 0x20000364 - -080015b0 <_GLOBAL__sub_I_htim2>: - 80015b0: b580 push {r7, lr} - 80015b2: af00 add r7, sp, #0 - 80015b4: f64f 71ff movw r1, #65535 ; 0xffff - 80015b8: 2001 movs r0, #1 - 80015ba: f7ff ff71 bl 80014a0 <_Z41__static_initialization_and_destruction_0ii> - 80015be: bd80 pop {r7, pc} - -080015c0 : + 800162a: bf00 nop + 800162c: 370c adds r7, #12 + 800162e: 46bd mov sp, r7 + 8001630: bdf0 pop {r4, r5, r6, r7, pc} + 8001632: bf00 nop + 8001634: 2000002c .word 0x2000002c + 8001638: 200001ec .word 0x200001ec + 800163c: 200000ec .word 0x200000ec + 8001640: 20000208 .word 0x20000208 + 8001644: 20000224 .word 0x20000224 + 8001648: 00000000 .word 0x00000000 + 800164c: 442c8000 .word 0x442c8000 + 8001650: 20000274 .word 0x20000274 + 8001654: 42c80000 .word 0x42c80000 + 8001658: 44228000 .word 0x44228000 + 800165c: 200002b8 .word 0x200002b8 + 8001660: 3dcccccd .word 0x3dcccccd + 8001664: 200002fc .word 0x200002fc + 8001668: 200000ac .word 0x200000ac + 800166c: 40021400 .word 0x40021400 + 8001670: 2000034c .word 0x2000034c + 8001674: 20000364 .word 0x20000364 + +08001678 <_GLOBAL__sub_I_htim2>: + 8001678: b580 push {r7, lr} + 800167a: af00 add r7, sp, #0 + 800167c: f64f 71ff movw r1, #65535 ; 0xffff + 8001680: 2001 movs r0, #1 + 8001682: f7ff ff71 bl 8001568 <_Z41__static_initialization_and_destruction_0ii> + 8001686: bd80 pop {r7, pc} + +08001688 : void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); /** * Initializes the Global MSP. */ void HAL_MspInit(void) { - 80015c0: b480 push {r7} - 80015c2: b083 sub sp, #12 - 80015c4: af00 add r7, sp, #0 + 8001688: b480 push {r7} + 800168a: b083 sub sp, #12 + 800168c: af00 add r7, sp, #0 /* USER CODE BEGIN MspInit 0 */ /* USER CODE END MspInit 0 */ __HAL_RCC_PWR_CLK_ENABLE(); - 80015c6: 4b0f ldr r3, [pc, #60] ; (8001604 ) - 80015c8: 6c1b ldr r3, [r3, #64] ; 0x40 - 80015ca: 4a0e ldr r2, [pc, #56] ; (8001604 ) - 80015cc: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 80015d0: 6413 str r3, [r2, #64] ; 0x40 - 80015d2: 4b0c ldr r3, [pc, #48] ; (8001604 ) - 80015d4: 6c1b ldr r3, [r3, #64] ; 0x40 - 80015d6: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 80015da: 607b str r3, [r7, #4] - 80015dc: 687b ldr r3, [r7, #4] + 800168e: 4b0f ldr r3, [pc, #60] ; (80016cc ) + 8001690: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001692: 4a0e ldr r2, [pc, #56] ; (80016cc ) + 8001694: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8001698: 6413 str r3, [r2, #64] ; 0x40 + 800169a: 4b0c ldr r3, [pc, #48] ; (80016cc ) + 800169c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800169e: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 80016a2: 607b str r3, [r7, #4] + 80016a4: 687b ldr r3, [r7, #4] __HAL_RCC_SYSCFG_CLK_ENABLE(); - 80015de: 4b09 ldr r3, [pc, #36] ; (8001604 ) - 80015e0: 6c5b ldr r3, [r3, #68] ; 0x44 - 80015e2: 4a08 ldr r2, [pc, #32] ; (8001604 ) - 80015e4: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 80015e8: 6453 str r3, [r2, #68] ; 0x44 - 80015ea: 4b06 ldr r3, [pc, #24] ; (8001604 ) - 80015ec: 6c5b ldr r3, [r3, #68] ; 0x44 - 80015ee: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 80015f2: 603b str r3, [r7, #0] - 80015f4: 683b ldr r3, [r7, #0] + 80016a6: 4b09 ldr r3, [pc, #36] ; (80016cc ) + 80016a8: 6c5b ldr r3, [r3, #68] ; 0x44 + 80016aa: 4a08 ldr r2, [pc, #32] ; (80016cc ) + 80016ac: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 80016b0: 6453 str r3, [r2, #68] ; 0x44 + 80016b2: 4b06 ldr r3, [pc, #24] ; (80016cc ) + 80016b4: 6c5b ldr r3, [r3, #68] ; 0x44 + 80016b6: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 80016ba: 603b str r3, [r7, #0] + 80016bc: 683b ldr r3, [r7, #0] /* System interrupt init*/ /* USER CODE BEGIN MspInit 1 */ /* USER CODE END MspInit 1 */ } - 80015f6: bf00 nop - 80015f8: 370c adds r7, #12 - 80015fa: 46bd mov sp, r7 - 80015fc: f85d 7b04 ldr.w r7, [sp], #4 - 8001600: 4770 bx lr - 8001602: bf00 nop - 8001604: 40023800 .word 0x40023800 - -08001608 : + 80016be: bf00 nop + 80016c0: 370c adds r7, #12 + 80016c2: 46bd mov sp, r7 + 80016c4: f85d 7b04 ldr.w r7, [sp], #4 + 80016c8: 4770 bx lr + 80016ca: bf00 nop + 80016cc: 40023800 .word 0x40023800 + +080016d0 : * This function configures the hardware resources used in this example * @param htim_encoder: TIM_Encoder handle pointer * @retval None */ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) { - 8001608: b580 push {r7, lr} - 800160a: b08c sub sp, #48 ; 0x30 - 800160c: af00 add r7, sp, #0 - 800160e: 6078 str r0, [r7, #4] + 80016d0: b580 push {r7, lr} + 80016d2: b08c sub sp, #48 ; 0x30 + 80016d4: af00 add r7, sp, #0 + 80016d6: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 8001610: f107 031c add.w r3, r7, #28 - 8001614: 2200 movs r2, #0 - 8001616: 601a str r2, [r3, #0] - 8001618: 605a str r2, [r3, #4] - 800161a: 609a str r2, [r3, #8] - 800161c: 60da str r2, [r3, #12] - 800161e: 611a str r2, [r3, #16] + 80016d8: f107 031c add.w r3, r7, #28 + 80016dc: 2200 movs r2, #0 + 80016de: 601a str r2, [r3, #0] + 80016e0: 605a str r2, [r3, #4] + 80016e2: 609a str r2, [r3, #8] + 80016e4: 60da str r2, [r3, #12] + 80016e6: 611a str r2, [r3, #16] if(htim_encoder->Instance==TIM2) - 8001620: 687b ldr r3, [r7, #4] - 8001622: 681b ldr r3, [r3, #0] - 8001624: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 8001628: d144 bne.n 80016b4 + 80016e8: 687b ldr r3, [r7, #4] + 80016ea: 681b ldr r3, [r3, #0] + 80016ec: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 80016f0: d144 bne.n 800177c { /* USER CODE BEGIN TIM2_MspInit 0 */ /* USER CODE END TIM2_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_TIM2_CLK_ENABLE(); - 800162a: 4b3b ldr r3, [pc, #236] ; (8001718 ) - 800162c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800162e: 4a3a ldr r2, [pc, #232] ; (8001718 ) - 8001630: f043 0301 orr.w r3, r3, #1 - 8001634: 6413 str r3, [r2, #64] ; 0x40 - 8001636: 4b38 ldr r3, [pc, #224] ; (8001718 ) - 8001638: 6c1b ldr r3, [r3, #64] ; 0x40 - 800163a: f003 0301 and.w r3, r3, #1 - 800163e: 61bb str r3, [r7, #24] - 8001640: 69bb ldr r3, [r7, #24] + 80016f2: 4b3b ldr r3, [pc, #236] ; (80017e0 ) + 80016f4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80016f6: 4a3a ldr r2, [pc, #232] ; (80017e0 ) + 80016f8: f043 0301 orr.w r3, r3, #1 + 80016fc: 6413 str r3, [r2, #64] ; 0x40 + 80016fe: 4b38 ldr r3, [pc, #224] ; (80017e0 ) + 8001700: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001702: f003 0301 and.w r3, r3, #1 + 8001706: 61bb str r3, [r7, #24] + 8001708: 69bb ldr r3, [r7, #24] __HAL_RCC_GPIOA_CLK_ENABLE(); - 8001642: 4b35 ldr r3, [pc, #212] ; (8001718 ) - 8001644: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001646: 4a34 ldr r2, [pc, #208] ; (8001718 ) - 8001648: f043 0301 orr.w r3, r3, #1 - 800164c: 6313 str r3, [r2, #48] ; 0x30 - 800164e: 4b32 ldr r3, [pc, #200] ; (8001718 ) - 8001650: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001652: f003 0301 and.w r3, r3, #1 - 8001656: 617b str r3, [r7, #20] - 8001658: 697b ldr r3, [r7, #20] + 800170a: 4b35 ldr r3, [pc, #212] ; (80017e0 ) + 800170c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800170e: 4a34 ldr r2, [pc, #208] ; (80017e0 ) + 8001710: f043 0301 orr.w r3, r3, #1 + 8001714: 6313 str r3, [r2, #48] ; 0x30 + 8001716: 4b32 ldr r3, [pc, #200] ; (80017e0 ) + 8001718: 6b1b ldr r3, [r3, #48] ; 0x30 + 800171a: f003 0301 and.w r3, r3, #1 + 800171e: 617b str r3, [r7, #20] + 8001720: 697b ldr r3, [r7, #20] __HAL_RCC_GPIOB_CLK_ENABLE(); - 800165a: 4b2f ldr r3, [pc, #188] ; (8001718 ) - 800165c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800165e: 4a2e ldr r2, [pc, #184] ; (8001718 ) - 8001660: f043 0302 orr.w r3, r3, #2 - 8001664: 6313 str r3, [r2, #48] ; 0x30 - 8001666: 4b2c ldr r3, [pc, #176] ; (8001718 ) - 8001668: 6b1b ldr r3, [r3, #48] ; 0x30 - 800166a: f003 0302 and.w r3, r3, #2 - 800166e: 613b str r3, [r7, #16] - 8001670: 693b ldr r3, [r7, #16] + 8001722: 4b2f ldr r3, [pc, #188] ; (80017e0 ) + 8001724: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001726: 4a2e ldr r2, [pc, #184] ; (80017e0 ) + 8001728: f043 0302 orr.w r3, r3, #2 + 800172c: 6313 str r3, [r2, #48] ; 0x30 + 800172e: 4b2c ldr r3, [pc, #176] ; (80017e0 ) + 8001730: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001732: f003 0302 and.w r3, r3, #2 + 8001736: 613b str r3, [r7, #16] + 8001738: 693b ldr r3, [r7, #16] /**TIM2 GPIO Configuration PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ - GPIO_InitStruct.Pin = encoder_dx1_Pin; - 8001672: 2320 movs r3, #32 - 8001674: 61fb str r3, [r7, #28] + GPIO_InitStruct.Pin = encoder_sx1_Pin; + 800173a: 2320 movs r3, #32 + 800173c: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 8001676: 2302 movs r3, #2 - 8001678: 623b str r3, [r7, #32] + 800173e: 2302 movs r3, #2 + 8001740: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800167a: 2300 movs r3, #0 - 800167c: 627b str r3, [r7, #36] ; 0x24 + 8001742: 2300 movs r3, #0 + 8001744: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 800167e: 2300 movs r3, #0 - 8001680: 62bb str r3, [r7, #40] ; 0x28 + 8001746: 2300 movs r3, #0 + 8001748: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - 8001682: 2301 movs r3, #1 - 8001684: 62fb str r3, [r7, #44] ; 0x2c - HAL_GPIO_Init(encoder_dx1_GPIO_Port, &GPIO_InitStruct); - 8001686: f107 031c add.w r3, r7, #28 - 800168a: 4619 mov r1, r3 - 800168c: 4823 ldr r0, [pc, #140] ; (800171c ) - 800168e: f000 fb53 bl 8001d38 - - GPIO_InitStruct.Pin = encoder_dx2_Pin; - 8001692: 2308 movs r3, #8 - 8001694: 61fb str r3, [r7, #28] + 800174a: 2301 movs r3, #1 + 800174c: 62fb str r3, [r7, #44] ; 0x2c + HAL_GPIO_Init(encoder_sx1_GPIO_Port, &GPIO_InitStruct); + 800174e: f107 031c add.w r3, r7, #28 + 8001752: 4619 mov r1, r3 + 8001754: 4823 ldr r0, [pc, #140] ; (80017e4 ) + 8001756: f000 fb53 bl 8001e00 + + GPIO_InitStruct.Pin = encoder_sx2_Pin; + 800175a: 2308 movs r3, #8 + 800175c: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 8001696: 2302 movs r3, #2 - 8001698: 623b str r3, [r7, #32] + 800175e: 2302 movs r3, #2 + 8001760: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800169a: 2300 movs r3, #0 - 800169c: 627b str r3, [r7, #36] ; 0x24 + 8001762: 2300 movs r3, #0 + 8001764: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 800169e: 2300 movs r3, #0 - 80016a0: 62bb str r3, [r7, #40] ; 0x28 + 8001766: 2300 movs r3, #0 + 8001768: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - 80016a2: 2301 movs r3, #1 - 80016a4: 62fb str r3, [r7, #44] ; 0x2c - HAL_GPIO_Init(encoder_dx2_GPIO_Port, &GPIO_InitStruct); - 80016a6: f107 031c add.w r3, r7, #28 - 80016aa: 4619 mov r1, r3 - 80016ac: 481c ldr r0, [pc, #112] ; (8001720 ) - 80016ae: f000 fb43 bl 8001d38 + 800176a: 2301 movs r3, #1 + 800176c: 62fb str r3, [r7, #44] ; 0x2c + HAL_GPIO_Init(encoder_sx2_GPIO_Port, &GPIO_InitStruct); + 800176e: f107 031c add.w r3, r7, #28 + 8001772: 4619 mov r1, r3 + 8001774: 481c ldr r0, [pc, #112] ; (80017e8 ) + 8001776: f000 fb43 bl 8001e00 /* USER CODE BEGIN TIM5_MspInit 1 */ /* USER CODE END TIM5_MspInit 1 */ } } - 80016b2: e02c b.n 800170e + 800177a: e02c b.n 80017d6 else if(htim_encoder->Instance==TIM5) - 80016b4: 687b ldr r3, [r7, #4] - 80016b6: 681b ldr r3, [r3, #0] - 80016b8: 4a1a ldr r2, [pc, #104] ; (8001724 ) - 80016ba: 4293 cmp r3, r2 - 80016bc: d127 bne.n 800170e + 800177c: 687b ldr r3, [r7, #4] + 800177e: 681b ldr r3, [r3, #0] + 8001780: 4a1a ldr r2, [pc, #104] ; (80017ec ) + 8001782: 4293 cmp r3, r2 + 8001784: d127 bne.n 80017d6 __HAL_RCC_TIM5_CLK_ENABLE(); - 80016be: 4b16 ldr r3, [pc, #88] ; (8001718 ) - 80016c0: 6c1b ldr r3, [r3, #64] ; 0x40 - 80016c2: 4a15 ldr r2, [pc, #84] ; (8001718 ) - 80016c4: f043 0308 orr.w r3, r3, #8 - 80016c8: 6413 str r3, [r2, #64] ; 0x40 - 80016ca: 4b13 ldr r3, [pc, #76] ; (8001718 ) - 80016cc: 6c1b ldr r3, [r3, #64] ; 0x40 - 80016ce: f003 0308 and.w r3, r3, #8 - 80016d2: 60fb str r3, [r7, #12] - 80016d4: 68fb ldr r3, [r7, #12] + 8001786: 4b16 ldr r3, [pc, #88] ; (80017e0 ) + 8001788: 6c1b ldr r3, [r3, #64] ; 0x40 + 800178a: 4a15 ldr r2, [pc, #84] ; (80017e0 ) + 800178c: f043 0308 orr.w r3, r3, #8 + 8001790: 6413 str r3, [r2, #64] ; 0x40 + 8001792: 4b13 ldr r3, [pc, #76] ; (80017e0 ) + 8001794: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001796: f003 0308 and.w r3, r3, #8 + 800179a: 60fb str r3, [r7, #12] + 800179c: 68fb ldr r3, [r7, #12] __HAL_RCC_GPIOA_CLK_ENABLE(); - 80016d6: 4b10 ldr r3, [pc, #64] ; (8001718 ) - 80016d8: 6b1b ldr r3, [r3, #48] ; 0x30 - 80016da: 4a0f ldr r2, [pc, #60] ; (8001718 ) - 80016dc: f043 0301 orr.w r3, r3, #1 - 80016e0: 6313 str r3, [r2, #48] ; 0x30 - 80016e2: 4b0d ldr r3, [pc, #52] ; (8001718 ) - 80016e4: 6b1b ldr r3, [r3, #48] ; 0x30 - 80016e6: f003 0301 and.w r3, r3, #1 - 80016ea: 60bb str r3, [r7, #8] - 80016ec: 68bb ldr r3, [r7, #8] - GPIO_InitStruct.Pin = encoder_sx1_Pin|encoder_sx2_Pin; - 80016ee: 2303 movs r3, #3 - 80016f0: 61fb str r3, [r7, #28] + 800179e: 4b10 ldr r3, [pc, #64] ; (80017e0 ) + 80017a0: 6b1b ldr r3, [r3, #48] ; 0x30 + 80017a2: 4a0f ldr r2, [pc, #60] ; (80017e0 ) + 80017a4: f043 0301 orr.w r3, r3, #1 + 80017a8: 6313 str r3, [r2, #48] ; 0x30 + 80017aa: 4b0d ldr r3, [pc, #52] ; (80017e0 ) + 80017ac: 6b1b ldr r3, [r3, #48] ; 0x30 + 80017ae: f003 0301 and.w r3, r3, #1 + 80017b2: 60bb str r3, [r7, #8] + 80017b4: 68bb ldr r3, [r7, #8] + GPIO_InitStruct.Pin = encoder_dx1_Pin|encoder_dx2_Pin; + 80017b6: 2303 movs r3, #3 + 80017b8: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 80016f2: 2302 movs r3, #2 - 80016f4: 623b str r3, [r7, #32] + 80017ba: 2302 movs r3, #2 + 80017bc: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80016f6: 2300 movs r3, #0 - 80016f8: 627b str r3, [r7, #36] ; 0x24 + 80017be: 2300 movs r3, #0 + 80017c0: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 80016fa: 2300 movs r3, #0 - 80016fc: 62bb str r3, [r7, #40] ; 0x28 + 80017c2: 2300 movs r3, #0 + 80017c4: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF2_TIM5; - 80016fe: 2302 movs r3, #2 - 8001700: 62fb str r3, [r7, #44] ; 0x2c + 80017c6: 2302 movs r3, #2 + 80017c8: 62fb str r3, [r7, #44] ; 0x2c HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - 8001702: f107 031c add.w r3, r7, #28 - 8001706: 4619 mov r1, r3 - 8001708: 4804 ldr r0, [pc, #16] ; (800171c ) - 800170a: f000 fb15 bl 8001d38 + 80017ca: f107 031c add.w r3, r7, #28 + 80017ce: 4619 mov r1, r3 + 80017d0: 4804 ldr r0, [pc, #16] ; (80017e4 ) + 80017d2: f000 fb15 bl 8001e00 } - 800170e: bf00 nop - 8001710: 3730 adds r7, #48 ; 0x30 - 8001712: 46bd mov sp, r7 - 8001714: bd80 pop {r7, pc} - 8001716: bf00 nop - 8001718: 40023800 .word 0x40023800 - 800171c: 40020000 .word 0x40020000 - 8001720: 40020400 .word 0x40020400 - 8001724: 40000c00 .word 0x40000c00 - -08001728 : + 80017d6: bf00 nop + 80017d8: 3730 adds r7, #48 ; 0x30 + 80017da: 46bd mov sp, r7 + 80017dc: bd80 pop {r7, pc} + 80017de: bf00 nop + 80017e0: 40023800 .word 0x40023800 + 80017e4: 40020000 .word 0x40020000 + 80017e8: 40020400 .word 0x40020400 + 80017ec: 40000c00 .word 0x40000c00 + +080017f0 : * This function configures the hardware resources used in this example * @param htim_base: TIM_Base handle pointer * @retval None */ void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) { - 8001728: b480 push {r7} - 800172a: b087 sub sp, #28 - 800172c: af00 add r7, sp, #0 - 800172e: 6078 str r0, [r7, #4] + 80017f0: b480 push {r7} + 80017f2: b087 sub sp, #28 + 80017f4: af00 add r7, sp, #0 + 80017f6: 6078 str r0, [r7, #4] if(htim_base->Instance==TIM3) - 8001730: 687b ldr r3, [r7, #4] - 8001732: 681b ldr r3, [r3, #0] - 8001734: 4a1c ldr r2, [pc, #112] ; (80017a8 ) - 8001736: 4293 cmp r3, r2 - 8001738: d10c bne.n 8001754 + 80017f8: 687b ldr r3, [r7, #4] + 80017fa: 681b ldr r3, [r3, #0] + 80017fc: 4a1c ldr r2, [pc, #112] ; (8001870 ) + 80017fe: 4293 cmp r3, r2 + 8001800: d10c bne.n 800181c { /* USER CODE BEGIN TIM3_MspInit 0 */ /* USER CODE END TIM3_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_TIM3_CLK_ENABLE(); - 800173a: 4b1c ldr r3, [pc, #112] ; (80017ac ) - 800173c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800173e: 4a1b ldr r2, [pc, #108] ; (80017ac ) - 8001740: f043 0302 orr.w r3, r3, #2 - 8001744: 6413 str r3, [r2, #64] ; 0x40 - 8001746: 4b19 ldr r3, [pc, #100] ; (80017ac ) - 8001748: 6c1b ldr r3, [r3, #64] ; 0x40 - 800174a: f003 0302 and.w r3, r3, #2 - 800174e: 617b str r3, [r7, #20] - 8001750: 697b ldr r3, [r7, #20] + 8001802: 4b1c ldr r3, [pc, #112] ; (8001874 ) + 8001804: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001806: 4a1b ldr r2, [pc, #108] ; (8001874 ) + 8001808: f043 0302 orr.w r3, r3, #2 + 800180c: 6413 str r3, [r2, #64] ; 0x40 + 800180e: 4b19 ldr r3, [pc, #100] ; (8001874 ) + 8001810: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001812: f003 0302 and.w r3, r3, #2 + 8001816: 617b str r3, [r7, #20] + 8001818: 697b ldr r3, [r7, #20] /* USER CODE BEGIN TIM6_MspInit 1 */ /* USER CODE END TIM6_MspInit 1 */ } } - 8001752: e022 b.n 800179a + 800181a: e022 b.n 8001862 else if(htim_base->Instance==TIM4) - 8001754: 687b ldr r3, [r7, #4] - 8001756: 681b ldr r3, [r3, #0] - 8001758: 4a15 ldr r2, [pc, #84] ; (80017b0 ) - 800175a: 4293 cmp r3, r2 - 800175c: d10c bne.n 8001778 + 800181c: 687b ldr r3, [r7, #4] + 800181e: 681b ldr r3, [r3, #0] + 8001820: 4a15 ldr r2, [pc, #84] ; (8001878 ) + 8001822: 4293 cmp r3, r2 + 8001824: d10c bne.n 8001840 __HAL_RCC_TIM4_CLK_ENABLE(); - 800175e: 4b13 ldr r3, [pc, #76] ; (80017ac ) - 8001760: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001762: 4a12 ldr r2, [pc, #72] ; (80017ac ) - 8001764: f043 0304 orr.w r3, r3, #4 - 8001768: 6413 str r3, [r2, #64] ; 0x40 - 800176a: 4b10 ldr r3, [pc, #64] ; (80017ac ) - 800176c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800176e: f003 0304 and.w r3, r3, #4 - 8001772: 613b str r3, [r7, #16] - 8001774: 693b ldr r3, [r7, #16] + 8001826: 4b13 ldr r3, [pc, #76] ; (8001874 ) + 8001828: 6c1b ldr r3, [r3, #64] ; 0x40 + 800182a: 4a12 ldr r2, [pc, #72] ; (8001874 ) + 800182c: f043 0304 orr.w r3, r3, #4 + 8001830: 6413 str r3, [r2, #64] ; 0x40 + 8001832: 4b10 ldr r3, [pc, #64] ; (8001874 ) + 8001834: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001836: f003 0304 and.w r3, r3, #4 + 800183a: 613b str r3, [r7, #16] + 800183c: 693b ldr r3, [r7, #16] } - 8001776: e010 b.n 800179a + 800183e: e010 b.n 8001862 else if(htim_base->Instance==TIM6) - 8001778: 687b ldr r3, [r7, #4] - 800177a: 681b ldr r3, [r3, #0] - 800177c: 4a0d ldr r2, [pc, #52] ; (80017b4 ) - 800177e: 4293 cmp r3, r2 - 8001780: d10b bne.n 800179a + 8001840: 687b ldr r3, [r7, #4] + 8001842: 681b ldr r3, [r3, #0] + 8001844: 4a0d ldr r2, [pc, #52] ; (800187c ) + 8001846: 4293 cmp r3, r2 + 8001848: d10b bne.n 8001862 __HAL_RCC_TIM6_CLK_ENABLE(); - 8001782: 4b0a ldr r3, [pc, #40] ; (80017ac ) - 8001784: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001786: 4a09 ldr r2, [pc, #36] ; (80017ac ) - 8001788: f043 0310 orr.w r3, r3, #16 - 800178c: 6413 str r3, [r2, #64] ; 0x40 - 800178e: 4b07 ldr r3, [pc, #28] ; (80017ac ) - 8001790: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001792: f003 0310 and.w r3, r3, #16 - 8001796: 60fb str r3, [r7, #12] - 8001798: 68fb ldr r3, [r7, #12] + 800184a: 4b0a ldr r3, [pc, #40] ; (8001874 ) + 800184c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800184e: 4a09 ldr r2, [pc, #36] ; (8001874 ) + 8001850: f043 0310 orr.w r3, r3, #16 + 8001854: 6413 str r3, [r2, #64] ; 0x40 + 8001856: 4b07 ldr r3, [pc, #28] ; (8001874 ) + 8001858: 6c1b ldr r3, [r3, #64] ; 0x40 + 800185a: f003 0310 and.w r3, r3, #16 + 800185e: 60fb str r3, [r7, #12] + 8001860: 68fb ldr r3, [r7, #12] } - 800179a: bf00 nop - 800179c: 371c adds r7, #28 - 800179e: 46bd mov sp, r7 - 80017a0: f85d 7b04 ldr.w r7, [sp], #4 - 80017a4: 4770 bx lr - 80017a6: bf00 nop - 80017a8: 40000400 .word 0x40000400 - 80017ac: 40023800 .word 0x40023800 - 80017b0: 40000800 .word 0x40000800 - 80017b4: 40001000 .word 0x40001000 - -080017b8 : + 8001862: bf00 nop + 8001864: 371c adds r7, #28 + 8001866: 46bd mov sp, r7 + 8001868: f85d 7b04 ldr.w r7, [sp], #4 + 800186c: 4770 bx lr + 800186e: bf00 nop + 8001870: 40000400 .word 0x40000400 + 8001874: 40023800 .word 0x40023800 + 8001878: 40000800 .word 0x40000800 + 800187c: 40001000 .word 0x40001000 + +08001880 : void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) { - 80017b8: b580 push {r7, lr} - 80017ba: b088 sub sp, #32 - 80017bc: af00 add r7, sp, #0 - 80017be: 6078 str r0, [r7, #4] + 8001880: b580 push {r7, lr} + 8001882: b088 sub sp, #32 + 8001884: af00 add r7, sp, #0 + 8001886: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 80017c0: f107 030c add.w r3, r7, #12 - 80017c4: 2200 movs r2, #0 - 80017c6: 601a str r2, [r3, #0] - 80017c8: 605a str r2, [r3, #4] - 80017ca: 609a str r2, [r3, #8] - 80017cc: 60da str r2, [r3, #12] - 80017ce: 611a str r2, [r3, #16] + 8001888: f107 030c add.w r3, r7, #12 + 800188c: 2200 movs r2, #0 + 800188e: 601a str r2, [r3, #0] + 8001890: 605a str r2, [r3, #4] + 8001892: 609a str r2, [r3, #8] + 8001894: 60da str r2, [r3, #12] + 8001896: 611a str r2, [r3, #16] if(htim->Instance==TIM4) - 80017d0: 687b ldr r3, [r7, #4] - 80017d2: 681b ldr r3, [r3, #0] - 80017d4: 4a11 ldr r2, [pc, #68] ; (800181c ) - 80017d6: 4293 cmp r3, r2 - 80017d8: d11c bne.n 8001814 + 8001898: 687b ldr r3, [r7, #4] + 800189a: 681b ldr r3, [r3, #0] + 800189c: 4a11 ldr r2, [pc, #68] ; (80018e4 ) + 800189e: 4293 cmp r3, r2 + 80018a0: d11c bne.n 80018dc { /* USER CODE BEGIN TIM4_MspPostInit 0 */ /* USER CODE END TIM4_MspPostInit 0 */ __HAL_RCC_GPIOD_CLK_ENABLE(); - 80017da: 4b11 ldr r3, [pc, #68] ; (8001820 ) - 80017dc: 6b1b ldr r3, [r3, #48] ; 0x30 - 80017de: 4a10 ldr r2, [pc, #64] ; (8001820 ) - 80017e0: f043 0308 orr.w r3, r3, #8 - 80017e4: 6313 str r3, [r2, #48] ; 0x30 - 80017e6: 4b0e ldr r3, [pc, #56] ; (8001820 ) - 80017e8: 6b1b ldr r3, [r3, #48] ; 0x30 - 80017ea: f003 0308 and.w r3, r3, #8 - 80017ee: 60bb str r3, [r7, #8] - 80017f0: 68bb ldr r3, [r7, #8] + 80018a2: 4b11 ldr r3, [pc, #68] ; (80018e8 ) + 80018a4: 6b1b ldr r3, [r3, #48] ; 0x30 + 80018a6: 4a10 ldr r2, [pc, #64] ; (80018e8 ) + 80018a8: f043 0308 orr.w r3, r3, #8 + 80018ac: 6313 str r3, [r2, #48] ; 0x30 + 80018ae: 4b0e ldr r3, [pc, #56] ; (80018e8 ) + 80018b0: 6b1b ldr r3, [r3, #48] ; 0x30 + 80018b2: f003 0308 and.w r3, r3, #8 + 80018b6: 60bb str r3, [r7, #8] + 80018b8: 68bb ldr r3, [r7, #8] /**TIM4 GPIO Configuration PD14 ------> TIM4_CH3 PD15 ------> TIM4_CH4 */ GPIO_InitStruct.Pin = pwm2_Pin|pwm1_Pin; - 80017f2: f44f 4340 mov.w r3, #49152 ; 0xc000 - 80017f6: 60fb str r3, [r7, #12] + 80018ba: f44f 4340 mov.w r3, #49152 ; 0xc000 + 80018be: 60fb str r3, [r7, #12] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 80017f8: 2302 movs r3, #2 - 80017fa: 613b str r3, [r7, #16] + 80018c0: 2302 movs r3, #2 + 80018c2: 613b str r3, [r7, #16] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80017fc: 2300 movs r3, #0 - 80017fe: 617b str r3, [r7, #20] + 80018c4: 2300 movs r3, #0 + 80018c6: 617b str r3, [r7, #20] GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001800: 2300 movs r3, #0 - 8001802: 61bb str r3, [r7, #24] + 80018c8: 2300 movs r3, #0 + 80018ca: 61bb str r3, [r7, #24] GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; - 8001804: 2302 movs r3, #2 - 8001806: 61fb str r3, [r7, #28] + 80018cc: 2302 movs r3, #2 + 80018ce: 61fb str r3, [r7, #28] HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - 8001808: f107 030c add.w r3, r7, #12 - 800180c: 4619 mov r1, r3 - 800180e: 4805 ldr r0, [pc, #20] ; (8001824 ) - 8001810: f000 fa92 bl 8001d38 + 80018d0: f107 030c add.w r3, r7, #12 + 80018d4: 4619 mov r1, r3 + 80018d6: 4805 ldr r0, [pc, #20] ; (80018ec ) + 80018d8: f000 fa92 bl 8001e00 /* USER CODE BEGIN TIM4_MspPostInit 1 */ /* USER CODE END TIM4_MspPostInit 1 */ } } - 8001814: bf00 nop - 8001816: 3720 adds r7, #32 - 8001818: 46bd mov sp, r7 - 800181a: bd80 pop {r7, pc} - 800181c: 40000800 .word 0x40000800 - 8001820: 40023800 .word 0x40023800 - 8001824: 40020c00 .word 0x40020c00 - -08001828 : + 80018dc: bf00 nop + 80018de: 3720 adds r7, #32 + 80018e0: 46bd mov sp, r7 + 80018e2: bd80 pop {r7, pc} + 80018e4: 40000800 .word 0x40000800 + 80018e8: 40023800 .word 0x40023800 + 80018ec: 40020c00 .word 0x40020c00 + +080018f0 : * This function configures the hardware resources used in this example * @param huart: UART handle pointer * @retval None */ void HAL_UART_MspInit(UART_HandleTypeDef* huart) { - 8001828: b580 push {r7, lr} - 800182a: b08a sub sp, #40 ; 0x28 - 800182c: af00 add r7, sp, #0 - 800182e: 6078 str r0, [r7, #4] + 80018f0: b580 push {r7, lr} + 80018f2: b08a sub sp, #40 ; 0x28 + 80018f4: af00 add r7, sp, #0 + 80018f6: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 8001830: f107 0314 add.w r3, r7, #20 - 8001834: 2200 movs r2, #0 - 8001836: 601a str r2, [r3, #0] - 8001838: 605a str r2, [r3, #4] - 800183a: 609a str r2, [r3, #8] - 800183c: 60da str r2, [r3, #12] - 800183e: 611a str r2, [r3, #16] + 80018f8: f107 0314 add.w r3, r7, #20 + 80018fc: 2200 movs r2, #0 + 80018fe: 601a str r2, [r3, #0] + 8001900: 605a str r2, [r3, #4] + 8001902: 609a str r2, [r3, #8] + 8001904: 60da str r2, [r3, #12] + 8001906: 611a str r2, [r3, #16] if(huart->Instance==USART6) - 8001840: 687b ldr r3, [r7, #4] - 8001842: 681b ldr r3, [r3, #0] - 8001844: 4a17 ldr r2, [pc, #92] ; (80018a4 ) - 8001846: 4293 cmp r3, r2 - 8001848: d127 bne.n 800189a + 8001908: 687b ldr r3, [r7, #4] + 800190a: 681b ldr r3, [r3, #0] + 800190c: 4a17 ldr r2, [pc, #92] ; (800196c ) + 800190e: 4293 cmp r3, r2 + 8001910: d127 bne.n 8001962 { /* USER CODE BEGIN USART6_MspInit 0 */ /* USER CODE END USART6_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_USART6_CLK_ENABLE(); - 800184a: 4b17 ldr r3, [pc, #92] ; (80018a8 ) - 800184c: 6c5b ldr r3, [r3, #68] ; 0x44 - 800184e: 4a16 ldr r2, [pc, #88] ; (80018a8 ) - 8001850: f043 0320 orr.w r3, r3, #32 - 8001854: 6453 str r3, [r2, #68] ; 0x44 - 8001856: 4b14 ldr r3, [pc, #80] ; (80018a8 ) - 8001858: 6c5b ldr r3, [r3, #68] ; 0x44 - 800185a: f003 0320 and.w r3, r3, #32 - 800185e: 613b str r3, [r7, #16] - 8001860: 693b ldr r3, [r7, #16] + 8001912: 4b17 ldr r3, [pc, #92] ; (8001970 ) + 8001914: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001916: 4a16 ldr r2, [pc, #88] ; (8001970 ) + 8001918: f043 0320 orr.w r3, r3, #32 + 800191c: 6453 str r3, [r2, #68] ; 0x44 + 800191e: 4b14 ldr r3, [pc, #80] ; (8001970 ) + 8001920: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001922: f003 0320 and.w r3, r3, #32 + 8001926: 613b str r3, [r7, #16] + 8001928: 693b ldr r3, [r7, #16] __HAL_RCC_GPIOC_CLK_ENABLE(); - 8001862: 4b11 ldr r3, [pc, #68] ; (80018a8 ) - 8001864: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001866: 4a10 ldr r2, [pc, #64] ; (80018a8 ) - 8001868: f043 0304 orr.w r3, r3, #4 - 800186c: 6313 str r3, [r2, #48] ; 0x30 - 800186e: 4b0e ldr r3, [pc, #56] ; (80018a8 ) - 8001870: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001872: f003 0304 and.w r3, r3, #4 - 8001876: 60fb str r3, [r7, #12] - 8001878: 68fb ldr r3, [r7, #12] + 800192a: 4b11 ldr r3, [pc, #68] ; (8001970 ) + 800192c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800192e: 4a10 ldr r2, [pc, #64] ; (8001970 ) + 8001930: f043 0304 orr.w r3, r3, #4 + 8001934: 6313 str r3, [r2, #48] ; 0x30 + 8001936: 4b0e ldr r3, [pc, #56] ; (8001970 ) + 8001938: 6b1b ldr r3, [r3, #48] ; 0x30 + 800193a: f003 0304 and.w r3, r3, #4 + 800193e: 60fb str r3, [r7, #12] + 8001940: 68fb ldr r3, [r7, #12] /**USART6 GPIO Configuration PC6 ------> USART6_TX PC7 ------> USART6_RX */ GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; - 800187a: 23c0 movs r3, #192 ; 0xc0 - 800187c: 617b str r3, [r7, #20] + 8001942: 23c0 movs r3, #192 ; 0xc0 + 8001944: 617b str r3, [r7, #20] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 800187e: 2302 movs r3, #2 - 8001880: 61bb str r3, [r7, #24] + 8001946: 2302 movs r3, #2 + 8001948: 61bb str r3, [r7, #24] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001882: 2300 movs r3, #0 - 8001884: 61fb str r3, [r7, #28] + 800194a: 2300 movs r3, #0 + 800194c: 61fb str r3, [r7, #28] GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - 8001886: 2303 movs r3, #3 - 8001888: 623b str r3, [r7, #32] + 800194e: 2303 movs r3, #3 + 8001950: 623b str r3, [r7, #32] GPIO_InitStruct.Alternate = GPIO_AF8_USART6; - 800188a: 2308 movs r3, #8 - 800188c: 627b str r3, [r7, #36] ; 0x24 + 8001952: 2308 movs r3, #8 + 8001954: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - 800188e: f107 0314 add.w r3, r7, #20 - 8001892: 4619 mov r1, r3 - 8001894: 4805 ldr r0, [pc, #20] ; (80018ac ) - 8001896: f000 fa4f bl 8001d38 + 8001956: f107 0314 add.w r3, r7, #20 + 800195a: 4619 mov r1, r3 + 800195c: 4805 ldr r0, [pc, #20] ; (8001974 ) + 800195e: f000 fa4f bl 8001e00 /* USER CODE BEGIN USART6_MspInit 1 */ /* USER CODE END USART6_MspInit 1 */ } } - 800189a: bf00 nop - 800189c: 3728 adds r7, #40 ; 0x28 - 800189e: 46bd mov sp, r7 - 80018a0: bd80 pop {r7, pc} - 80018a2: bf00 nop - 80018a4: 40011400 .word 0x40011400 - 80018a8: 40023800 .word 0x40023800 - 80018ac: 40020800 .word 0x40020800 - -080018b0 : + 8001962: bf00 nop + 8001964: 3728 adds r7, #40 ; 0x28 + 8001966: 46bd mov sp, r7 + 8001968: bd80 pop {r7, pc} + 800196a: bf00 nop + 800196c: 40011400 .word 0x40011400 + 8001970: 40023800 .word 0x40023800 + 8001974: 40020800 .word 0x40020800 + +08001978 : /******************************************************************************/ /** * @brief This function handles Non maskable interrupt. */ void NMI_Handler(void) { - 80018b0: b480 push {r7} - 80018b2: af00 add r7, sp, #0 + 8001978: b480 push {r7} + 800197a: af00 add r7, sp, #0 /* USER CODE END NonMaskableInt_IRQn 0 */ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ /* USER CODE END NonMaskableInt_IRQn 1 */ } - 80018b4: bf00 nop - 80018b6: 46bd mov sp, r7 - 80018b8: f85d 7b04 ldr.w r7, [sp], #4 - 80018bc: 4770 bx lr + 800197c: bf00 nop + 800197e: 46bd mov sp, r7 + 8001980: f85d 7b04 ldr.w r7, [sp], #4 + 8001984: 4770 bx lr -080018be : +08001986 : /** * @brief This function handles Hard fault interrupt. */ void HardFault_Handler(void) { - 80018be: b480 push {r7} - 80018c0: af00 add r7, sp, #0 + 8001986: b480 push {r7} + 8001988: af00 add r7, sp, #0 /* USER CODE BEGIN HardFault_IRQn 0 */ /* USER CODE END HardFault_IRQn 0 */ while (1) - 80018c2: e7fe b.n 80018c2 + 800198a: e7fe b.n 800198a -080018c4 : +0800198c : /** * @brief This function handles Memory management fault. */ void MemManage_Handler(void) { - 80018c4: b480 push {r7} - 80018c6: af00 add r7, sp, #0 + 800198c: b480 push {r7} + 800198e: af00 add r7, sp, #0 /* USER CODE BEGIN MemoryManagement_IRQn 0 */ /* USER CODE END MemoryManagement_IRQn 0 */ while (1) - 80018c8: e7fe b.n 80018c8 + 8001990: e7fe b.n 8001990 -080018ca : +08001992 : /** * @brief This function handles Pre-fetch fault, memory access fault. */ void BusFault_Handler(void) { - 80018ca: b480 push {r7} - 80018cc: af00 add r7, sp, #0 + 8001992: b480 push {r7} + 8001994: af00 add r7, sp, #0 /* USER CODE BEGIN BusFault_IRQn 0 */ /* USER CODE END BusFault_IRQn 0 */ while (1) - 80018ce: e7fe b.n 80018ce + 8001996: e7fe b.n 8001996 -080018d0 : +08001998 : /** * @brief This function handles Undefined instruction or illegal state. */ void UsageFault_Handler(void) { - 80018d0: b480 push {r7} - 80018d2: af00 add r7, sp, #0 + 8001998: b480 push {r7} + 800199a: af00 add r7, sp, #0 /* USER CODE BEGIN UsageFault_IRQn 0 */ /* USER CODE END UsageFault_IRQn 0 */ while (1) - 80018d4: e7fe b.n 80018d4 + 800199c: e7fe b.n 800199c -080018d6 : +0800199e : /** * @brief This function handles System service call via SWI instruction. */ void SVC_Handler(void) { - 80018d6: b480 push {r7} - 80018d8: af00 add r7, sp, #0 + 800199e: b480 push {r7} + 80019a0: af00 add r7, sp, #0 /* USER CODE END SVCall_IRQn 0 */ /* USER CODE BEGIN SVCall_IRQn 1 */ /* USER CODE END SVCall_IRQn 1 */ } - 80018da: bf00 nop - 80018dc: 46bd mov sp, r7 - 80018de: f85d 7b04 ldr.w r7, [sp], #4 - 80018e2: 4770 bx lr + 80019a2: bf00 nop + 80019a4: 46bd mov sp, r7 + 80019a6: f85d 7b04 ldr.w r7, [sp], #4 + 80019aa: 4770 bx lr -080018e4 : +080019ac : /** * @brief This function handles Debug monitor. */ void DebugMon_Handler(void) { - 80018e4: b480 push {r7} - 80018e6: af00 add r7, sp, #0 + 80019ac: b480 push {r7} + 80019ae: af00 add r7, sp, #0 /* USER CODE END DebugMonitor_IRQn 0 */ /* USER CODE BEGIN DebugMonitor_IRQn 1 */ /* USER CODE END DebugMonitor_IRQn 1 */ } - 80018e8: bf00 nop - 80018ea: 46bd mov sp, r7 - 80018ec: f85d 7b04 ldr.w r7, [sp], #4 - 80018f0: 4770 bx lr + 80019b0: bf00 nop + 80019b2: 46bd mov sp, r7 + 80019b4: f85d 7b04 ldr.w r7, [sp], #4 + 80019b8: 4770 bx lr -080018f2 : +080019ba : /** * @brief This function handles Pendable request for system service. */ void PendSV_Handler(void) { - 80018f2: b480 push {r7} - 80018f4: af00 add r7, sp, #0 + 80019ba: b480 push {r7} + 80019bc: af00 add r7, sp, #0 /* USER CODE END PendSV_IRQn 0 */ /* USER CODE BEGIN PendSV_IRQn 1 */ /* USER CODE END PendSV_IRQn 1 */ } - 80018f6: bf00 nop - 80018f8: 46bd mov sp, r7 - 80018fa: f85d 7b04 ldr.w r7, [sp], #4 - 80018fe: 4770 bx lr + 80019be: bf00 nop + 80019c0: 46bd mov sp, r7 + 80019c2: f85d 7b04 ldr.w r7, [sp], #4 + 80019c6: 4770 bx lr -08001900 : +080019c8 : /** * @brief This function handles System tick timer. */ void SysTick_Handler(void) { - 8001900: b580 push {r7, lr} - 8001902: af00 add r7, sp, #0 + 80019c8: b580 push {r7, lr} + 80019ca: af00 add r7, sp, #0 /* USER CODE BEGIN SysTick_IRQn 0 */ /* USER CODE END SysTick_IRQn 0 */ HAL_IncTick(); - 8001904: f000 f8c4 bl 8001a90 + 80019cc: f000 f8c4 bl 8001b58 /* USER CODE BEGIN SysTick_IRQn 1 */ /* USER CODE END SysTick_IRQn 1 */ } - 8001908: bf00 nop - 800190a: bd80 pop {r7, pc} + 80019d0: bf00 nop + 80019d2: bd80 pop {r7, pc} -0800190c : +080019d4 : /** * @brief This function handles TIM3 global interrupt. */ void TIM3_IRQHandler(void) { - 800190c: b580 push {r7, lr} - 800190e: af00 add r7, sp, #0 + 80019d4: b580 push {r7, lr} + 80019d6: af00 add r7, sp, #0 /* USER CODE BEGIN TIM3_IRQn 0 */ /* USER CODE END TIM3_IRQn 0 */ HAL_TIM_IRQHandler(&htim3); - 8001910: 4802 ldr r0, [pc, #8] ; (800191c ) - 8001912: f001 fdec bl 80034ee + 80019d8: 4802 ldr r0, [pc, #8] ; (80019e4 ) + 80019da: f001 fdec bl 80035b6 /* USER CODE BEGIN TIM3_IRQn 1 */ /* USER CODE END TIM3_IRQn 1 */ } - 8001916: bf00 nop - 8001918: bd80 pop {r7, pc} - 800191a: bf00 nop - 800191c: 20000070 .word 0x20000070 + 80019de: bf00 nop + 80019e0: bd80 pop {r7, pc} + 80019e2: bf00 nop + 80019e4: 2000006c .word 0x2000006c -08001920 : +080019e8 : /** * @brief This function handles EXTI line[15:10] interrupts. */ void EXTI15_10_IRQHandler(void) { - 8001920: b580 push {r7, lr} - 8001922: af00 add r7, sp, #0 + 80019e8: b580 push {r7, lr} + 80019ea: af00 add r7, sp, #0 /* USER CODE BEGIN EXTI15_10_IRQn 0 */ /* USER CODE END EXTI15_10_IRQn 0 */ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_13); - 8001924: f44f 5000 mov.w r0, #8192 ; 0x2000 - 8001928: f000 fbca bl 80020c0 + 80019ec: f44f 5000 mov.w r0, #8192 ; 0x2000 + 80019f0: f000 fbca bl 8002188 /* USER CODE BEGIN EXTI15_10_IRQn 1 */ /* USER CODE END EXTI15_10_IRQn 1 */ } - 800192c: bf00 nop - 800192e: bd80 pop {r7, pc} + 80019f4: bf00 nop + 80019f6: bd80 pop {r7, pc} -08001930 : +080019f8 : /** * @brief This function handles TIM6 global interrupt, DAC1 and DAC2 underrun error interrupts. */ void TIM6_DAC_IRQHandler(void) { - 8001930: b580 push {r7, lr} - 8001932: af00 add r7, sp, #0 + 80019f8: b580 push {r7, lr} + 80019fa: af00 add r7, sp, #0 /* USER CODE BEGIN TIM6_DAC_IRQn 0 */ /* USER CODE END TIM6_DAC_IRQn 0 */ HAL_TIM_IRQHandler(&htim6); - 8001934: 4802 ldr r0, [pc, #8] ; (8001940 ) - 8001936: f001 fdda bl 80034ee + 80019fc: 4802 ldr r0, [pc, #8] ; (8001a08 ) + 80019fe: f001 fdda bl 80035b6 /* USER CODE BEGIN TIM6_DAC_IRQn 1 */ /* USER CODE END TIM6_DAC_IRQn 1 */ } - 800193a: bf00 nop - 800193c: bd80 pop {r7, pc} - 800193e: bf00 nop - 8001940: 20000130 .word 0x20000130 + 8001a02: bf00 nop + 8001a04: bd80 pop {r7, pc} + 8001a06: bf00 nop + 8001a08: 2000012c .word 0x2000012c -08001944 : +08001a0c : /** * @brief This function handles USART6 global interrupt. */ void USART6_IRQHandler(void) { - 8001944: b580 push {r7, lr} - 8001946: af00 add r7, sp, #0 + 8001a0c: b580 push {r7, lr} + 8001a0e: af00 add r7, sp, #0 /* USER CODE BEGIN USART6_IRQn 0 */ /* USER CODE END USART6_IRQn 0 */ HAL_UART_IRQHandler(&huart6); - 8001948: 4802 ldr r0, [pc, #8] ; (8001954 ) - 800194a: f002 fea3 bl 8004694 + 8001a10: 4802 ldr r0, [pc, #8] ; (8001a1c ) + 8001a12: f002 fea3 bl 800475c /* USER CODE BEGIN USART6_IRQn 1 */ /* USER CODE END USART6_IRQn 1 */ } - 800194e: bf00 nop - 8001950: bd80 pop {r7, pc} - 8001952: bf00 nop - 8001954: 20000170 .word 0x20000170 + 8001a16: bf00 nop + 8001a18: bd80 pop {r7, pc} + 8001a1a: bf00 nop + 8001a1c: 2000016c .word 0x2000016c -08001958 : +08001a20 : * SystemFrequency variable. * @param None * @retval None */ void SystemInit(void) { - 8001958: b480 push {r7} - 800195a: af00 add r7, sp, #0 + 8001a20: b480 push {r7} + 8001a22: af00 add r7, sp, #0 /* FPU settings ------------------------------------------------------------*/ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ - 800195c: 4b15 ldr r3, [pc, #84] ; (80019b4 ) - 800195e: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8001962: 4a14 ldr r2, [pc, #80] ; (80019b4 ) - 8001964: f443 0370 orr.w r3, r3, #15728640 ; 0xf00000 - 8001968: f8c2 3088 str.w r3, [r2, #136] ; 0x88 + 8001a24: 4b15 ldr r3, [pc, #84] ; (8001a7c ) + 8001a26: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8001a2a: 4a14 ldr r2, [pc, #80] ; (8001a7c ) + 8001a2c: f443 0370 orr.w r3, r3, #15728640 ; 0xf00000 + 8001a30: f8c2 3088 str.w r3, [r2, #136] ; 0x88 #endif /* Reset the RCC clock configuration to the default reset state ------------*/ /* Set HSION bit */ RCC->CR |= (uint32_t)0x00000001; - 800196c: 4b12 ldr r3, [pc, #72] ; (80019b8 ) - 800196e: 681b ldr r3, [r3, #0] - 8001970: 4a11 ldr r2, [pc, #68] ; (80019b8 ) - 8001972: f043 0301 orr.w r3, r3, #1 - 8001976: 6013 str r3, [r2, #0] + 8001a34: 4b12 ldr r3, [pc, #72] ; (8001a80 ) + 8001a36: 681b ldr r3, [r3, #0] + 8001a38: 4a11 ldr r2, [pc, #68] ; (8001a80 ) + 8001a3a: f043 0301 orr.w r3, r3, #1 + 8001a3e: 6013 str r3, [r2, #0] /* Reset CFGR register */ RCC->CFGR = 0x00000000; - 8001978: 4b0f ldr r3, [pc, #60] ; (80019b8 ) - 800197a: 2200 movs r2, #0 - 800197c: 609a str r2, [r3, #8] + 8001a40: 4b0f ldr r3, [pc, #60] ; (8001a80 ) + 8001a42: 2200 movs r2, #0 + 8001a44: 609a str r2, [r3, #8] /* Reset HSEON, CSSON and PLLON bits */ RCC->CR &= (uint32_t)0xFEF6FFFF; - 800197e: 4b0e ldr r3, [pc, #56] ; (80019b8 ) - 8001980: 681a ldr r2, [r3, #0] - 8001982: 490d ldr r1, [pc, #52] ; (80019b8 ) - 8001984: 4b0d ldr r3, [pc, #52] ; (80019bc ) - 8001986: 4013 ands r3, r2 - 8001988: 600b str r3, [r1, #0] + 8001a46: 4b0e ldr r3, [pc, #56] ; (8001a80 ) + 8001a48: 681a ldr r2, [r3, #0] + 8001a4a: 490d ldr r1, [pc, #52] ; (8001a80 ) + 8001a4c: 4b0d ldr r3, [pc, #52] ; (8001a84 ) + 8001a4e: 4013 ands r3, r2 + 8001a50: 600b str r3, [r1, #0] /* Reset PLLCFGR register */ RCC->PLLCFGR = 0x24003010; - 800198a: 4b0b ldr r3, [pc, #44] ; (80019b8 ) - 800198c: 4a0c ldr r2, [pc, #48] ; (80019c0 ) - 800198e: 605a str r2, [r3, #4] + 8001a52: 4b0b ldr r3, [pc, #44] ; (8001a80 ) + 8001a54: 4a0c ldr r2, [pc, #48] ; (8001a88 ) + 8001a56: 605a str r2, [r3, #4] /* Reset HSEBYP bit */ RCC->CR &= (uint32_t)0xFFFBFFFF; - 8001990: 4b09 ldr r3, [pc, #36] ; (80019b8 ) - 8001992: 681b ldr r3, [r3, #0] - 8001994: 4a08 ldr r2, [pc, #32] ; (80019b8 ) - 8001996: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 800199a: 6013 str r3, [r2, #0] + 8001a58: 4b09 ldr r3, [pc, #36] ; (8001a80 ) + 8001a5a: 681b ldr r3, [r3, #0] + 8001a5c: 4a08 ldr r2, [pc, #32] ; (8001a80 ) + 8001a5e: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8001a62: 6013 str r3, [r2, #0] /* Disable all interrupts */ RCC->CIR = 0x00000000; - 800199c: 4b06 ldr r3, [pc, #24] ; (80019b8 ) - 800199e: 2200 movs r2, #0 - 80019a0: 60da str r2, [r3, #12] + 8001a64: 4b06 ldr r3, [pc, #24] ; (8001a80 ) + 8001a66: 2200 movs r2, #0 + 8001a68: 60da str r2, [r3, #12] /* Configure the Vector Table location add offset address ------------------*/ #ifdef VECT_TAB_SRAM SCB->VTOR = RAMDTCM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ #else SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ - 80019a2: 4b04 ldr r3, [pc, #16] ; (80019b4 ) - 80019a4: f04f 6200 mov.w r2, #134217728 ; 0x8000000 - 80019a8: 609a str r2, [r3, #8] + 8001a6a: 4b04 ldr r3, [pc, #16] ; (8001a7c ) + 8001a6c: f04f 6200 mov.w r2, #134217728 ; 0x8000000 + 8001a70: 609a str r2, [r3, #8] #endif } - 80019aa: bf00 nop - 80019ac: 46bd mov sp, r7 - 80019ae: f85d 7b04 ldr.w r7, [sp], #4 - 80019b2: 4770 bx lr - 80019b4: e000ed00 .word 0xe000ed00 - 80019b8: 40023800 .word 0x40023800 - 80019bc: fef6ffff .word 0xfef6ffff - 80019c0: 24003010 .word 0x24003010 + 8001a72: bf00 nop + 8001a74: 46bd mov sp, r7 + 8001a76: f85d 7b04 ldr.w r7, [sp], #4 + 8001a7a: 4770 bx lr + 8001a7c: e000ed00 .word 0xe000ed00 + 8001a80: 40023800 .word 0x40023800 + 8001a84: fef6ffff .word 0xfef6ffff + 8001a88: 24003010 .word 0x24003010 -080019c4 : +08001a8c : .section .text.Reset_Handler .weak Reset_Handler .type Reset_Handler, %function Reset_Handler: ldr sp, =_estack /* set stack pointer */ - 80019c4: f8df d034 ldr.w sp, [pc, #52] ; 80019fc + 8001a8c: f8df d034 ldr.w sp, [pc, #52] ; 8001ac4 /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 - 80019c8: 2100 movs r1, #0 + 8001a90: 2100 movs r1, #0 b LoopCopyDataInit - 80019ca: e003 b.n 80019d4 + 8001a92: e003 b.n 8001a9c -080019cc : +08001a94 : CopyDataInit: ldr r3, =_sidata - 80019cc: 4b0c ldr r3, [pc, #48] ; (8001a00 ) + 8001a94: 4b0c ldr r3, [pc, #48] ; (8001ac8 ) ldr r3, [r3, r1] - 80019ce: 585b ldr r3, [r3, r1] + 8001a96: 585b ldr r3, [r3, r1] str r3, [r0, r1] - 80019d0: 5043 str r3, [r0, r1] + 8001a98: 5043 str r3, [r0, r1] adds r1, r1, #4 - 80019d2: 3104 adds r1, #4 + 8001a9a: 3104 adds r1, #4 -080019d4 : +08001a9c : LoopCopyDataInit: ldr r0, =_sdata - 80019d4: 480b ldr r0, [pc, #44] ; (8001a04 ) + 8001a9c: 480b ldr r0, [pc, #44] ; (8001acc ) ldr r3, =_edata - 80019d6: 4b0c ldr r3, [pc, #48] ; (8001a08 ) + 8001a9e: 4b0c ldr r3, [pc, #48] ; (8001ad0 ) adds r2, r0, r1 - 80019d8: 1842 adds r2, r0, r1 + 8001aa0: 1842 adds r2, r0, r1 cmp r2, r3 - 80019da: 429a cmp r2, r3 + 8001aa2: 429a cmp r2, r3 bcc CopyDataInit - 80019dc: d3f6 bcc.n 80019cc + 8001aa4: d3f6 bcc.n 8001a94 ldr r2, =_sbss - 80019de: 4a0b ldr r2, [pc, #44] ; (8001a0c ) + 8001aa6: 4a0b ldr r2, [pc, #44] ; (8001ad4 ) b LoopFillZerobss - 80019e0: e002 b.n 80019e8 + 8001aa8: e002 b.n 8001ab0 -080019e2 : +08001aaa : /* Zero fill the bss segment. */ FillZerobss: movs r3, #0 - 80019e2: 2300 movs r3, #0 + 8001aaa: 2300 movs r3, #0 str r3, [r2], #4 - 80019e4: f842 3b04 str.w r3, [r2], #4 + 8001aac: f842 3b04 str.w r3, [r2], #4 -080019e8 : +08001ab0 : LoopFillZerobss: ldr r3, = _ebss - 80019e8: 4b09 ldr r3, [pc, #36] ; (8001a10 ) + 8001ab0: 4b09 ldr r3, [pc, #36] ; (8001ad8 ) cmp r2, r3 - 80019ea: 429a cmp r2, r3 + 8001ab2: 429a cmp r2, r3 bcc FillZerobss - 80019ec: d3f9 bcc.n 80019e2 + 8001ab4: d3f9 bcc.n 8001aaa /* Call the clock system initialization function.*/ bl SystemInit - 80019ee: f7ff ffb3 bl 8001958 + 8001ab6: f7ff ffb3 bl 8001a20 /* Call static constructors */ bl __libc_init_array - 80019f2: f003 fc31 bl 8005258 <__libc_init_array> + 8001aba: f003 fc31 bl 8005320 <__libc_init_array> /* Call the application's entry point.*/ bl main - 80019f6: f7ff f879 bl 8000aec
+ 8001abe: f7ff f865 bl 8000b8c
bx lr - 80019fa: 4770 bx lr + 8001ac2: 4770 bx lr ldr sp, =_estack /* set stack pointer */ - 80019fc: 20080000 .word 0x20080000 + 8001ac4: 20080000 .word 0x20080000 ldr r3, =_sidata - 8001a00: 080052f4 .word 0x080052f4 + 8001ac8: 080053bc .word 0x080053bc ldr r0, =_sdata - 8001a04: 20000000 .word 0x20000000 + 8001acc: 20000000 .word 0x20000000 ldr r3, =_edata - 8001a08: 20000014 .word 0x20000014 + 8001ad0: 20000010 .word 0x20000010 ldr r2, =_sbss - 8001a0c: 20000014 .word 0x20000014 + 8001ad4: 20000010 .word 0x20000010 ldr r3, = _ebss - 8001a10: 200003a0 .word 0x200003a0 + 8001ad8: 2000039c .word 0x2000039c -08001a14 : +08001adc : * @retval None */ .section .text.Default_Handler,"ax",%progbits Default_Handler: Infinite_Loop: b Infinite_Loop - 8001a14: e7fe b.n 8001a14 + 8001adc: e7fe b.n 8001adc -08001a16 : +08001ade : * need to ensure that the SysTick time base is always set to 1 millisecond * to have correct HAL operation. * @retval HAL status */ HAL_StatusTypeDef HAL_Init(void) { - 8001a16: b580 push {r7, lr} - 8001a18: af00 add r7, sp, #0 + 8001ade: b580 push {r7, lr} + 8001ae0: af00 add r7, sp, #0 #if (PREFETCH_ENABLE != 0U) __HAL_FLASH_PREFETCH_BUFFER_ENABLE(); #endif /* PREFETCH_ENABLE */ /* Set Interrupt Group Priority */ HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - 8001a1a: 2003 movs r0, #3 - 8001a1c: f000 f928 bl 8001c70 + 8001ae2: 2003 movs r0, #3 + 8001ae4: f000 f928 bl 8001d38 /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ HAL_InitTick(TICK_INT_PRIORITY); - 8001a20: 2000 movs r0, #0 - 8001a22: f000 f805 bl 8001a30 + 8001ae8: 2000 movs r0, #0 + 8001aea: f000 f805 bl 8001af8 /* Init the low level hardware */ HAL_MspInit(); - 8001a26: f7ff fdcb bl 80015c0 + 8001aee: f7ff fdcb bl 8001688 /* Return function status */ return HAL_OK; - 8001a2a: 2300 movs r3, #0 + 8001af2: 2300 movs r3, #0 } - 8001a2c: 4618 mov r0, r3 - 8001a2e: bd80 pop {r7, pc} + 8001af4: 4618 mov r0, r3 + 8001af6: bd80 pop {r7, pc} -08001a30 : +08001af8 : * implementation in user file. * @param TickPriority Tick interrupt priority. * @retval HAL status */ __weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) { - 8001a30: b580 push {r7, lr} - 8001a32: b082 sub sp, #8 - 8001a34: af00 add r7, sp, #0 - 8001a36: 6078 str r0, [r7, #4] + 8001af8: b580 push {r7, lr} + 8001afa: b082 sub sp, #8 + 8001afc: af00 add r7, sp, #0 + 8001afe: 6078 str r0, [r7, #4] /* Configure the SysTick to have interrupt in 1ms time basis*/ if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) - 8001a38: 4b12 ldr r3, [pc, #72] ; (8001a84 ) - 8001a3a: 681a ldr r2, [r3, #0] - 8001a3c: 4b12 ldr r3, [pc, #72] ; (8001a88 ) - 8001a3e: 781b ldrb r3, [r3, #0] - 8001a40: 4619 mov r1, r3 - 8001a42: f44f 737a mov.w r3, #1000 ; 0x3e8 - 8001a46: fbb3 f3f1 udiv r3, r3, r1 - 8001a4a: fbb2 f3f3 udiv r3, r2, r3 - 8001a4e: 4618 mov r0, r3 - 8001a50: f000 f943 bl 8001cda - 8001a54: 4603 mov r3, r0 - 8001a56: 2b00 cmp r3, #0 - 8001a58: d001 beq.n 8001a5e + 8001b00: 4b12 ldr r3, [pc, #72] ; (8001b4c ) + 8001b02: 681a ldr r2, [r3, #0] + 8001b04: 4b12 ldr r3, [pc, #72] ; (8001b50 ) + 8001b06: 781b ldrb r3, [r3, #0] + 8001b08: 4619 mov r1, r3 + 8001b0a: f44f 737a mov.w r3, #1000 ; 0x3e8 + 8001b0e: fbb3 f3f1 udiv r3, r3, r1 + 8001b12: fbb2 f3f3 udiv r3, r2, r3 + 8001b16: 4618 mov r0, r3 + 8001b18: f000 f943 bl 8001da2 + 8001b1c: 4603 mov r3, r0 + 8001b1e: 2b00 cmp r3, #0 + 8001b20: d001 beq.n 8001b26 { return HAL_ERROR; - 8001a5a: 2301 movs r3, #1 - 8001a5c: e00e b.n 8001a7c + 8001b22: 2301 movs r3, #1 + 8001b24: e00e b.n 8001b44 } /* Configure the SysTick IRQ priority */ if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - 8001a5e: 687b ldr r3, [r7, #4] - 8001a60: 2b0f cmp r3, #15 - 8001a62: d80a bhi.n 8001a7a + 8001b26: 687b ldr r3, [r7, #4] + 8001b28: 2b0f cmp r3, #15 + 8001b2a: d80a bhi.n 8001b42 { HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); - 8001a64: 2200 movs r2, #0 - 8001a66: 6879 ldr r1, [r7, #4] - 8001a68: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff - 8001a6c: f000 f90b bl 8001c86 + 8001b2c: 2200 movs r2, #0 + 8001b2e: 6879 ldr r1, [r7, #4] + 8001b30: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001b34: f000 f90b bl 8001d4e uwTickPrio = TickPriority; - 8001a70: 4a06 ldr r2, [pc, #24] ; (8001a8c ) - 8001a72: 687b ldr r3, [r7, #4] - 8001a74: 6013 str r3, [r2, #0] + 8001b38: 4a06 ldr r2, [pc, #24] ; (8001b54 ) + 8001b3a: 687b ldr r3, [r7, #4] + 8001b3c: 6013 str r3, [r2, #0] { return HAL_ERROR; } /* Return function status */ return HAL_OK; - 8001a76: 2300 movs r3, #0 - 8001a78: e000 b.n 8001a7c + 8001b3e: 2300 movs r3, #0 + 8001b40: e000 b.n 8001b44 return HAL_ERROR; - 8001a7a: 2301 movs r3, #1 + 8001b42: 2301 movs r3, #1 } - 8001a7c: 4618 mov r0, r3 - 8001a7e: 3708 adds r7, #8 - 8001a80: 46bd mov sp, r7 - 8001a82: bd80 pop {r7, pc} - 8001a84: 20000008 .word 0x20000008 - 8001a88: 20000010 .word 0x20000010 - 8001a8c: 2000000c .word 0x2000000c - -08001a90 : + 8001b44: 4618 mov r0, r3 + 8001b46: 3708 adds r7, #8 + 8001b48: 46bd mov sp, r7 + 8001b4a: bd80 pop {r7, pc} + 8001b4c: 20000004 .word 0x20000004 + 8001b50: 2000000c .word 0x2000000c + 8001b54: 20000008 .word 0x20000008 + +08001b58 : * @note This function is declared as __weak to be overwritten in case of other * implementations in user file. * @retval None */ __weak void HAL_IncTick(void) { - 8001a90: b480 push {r7} - 8001a92: af00 add r7, sp, #0 + 8001b58: b480 push {r7} + 8001b5a: af00 add r7, sp, #0 uwTick += uwTickFreq; - 8001a94: 4b06 ldr r3, [pc, #24] ; (8001ab0 ) - 8001a96: 781b ldrb r3, [r3, #0] - 8001a98: 461a mov r2, r3 - 8001a9a: 4b06 ldr r3, [pc, #24] ; (8001ab4 ) - 8001a9c: 681b ldr r3, [r3, #0] - 8001a9e: 4413 add r3, r2 - 8001aa0: 4a04 ldr r2, [pc, #16] ; (8001ab4 ) - 8001aa2: 6013 str r3, [r2, #0] + 8001b5c: 4b06 ldr r3, [pc, #24] ; (8001b78 ) + 8001b5e: 781b ldrb r3, [r3, #0] + 8001b60: 461a mov r2, r3 + 8001b62: 4b06 ldr r3, [pc, #24] ; (8001b7c ) + 8001b64: 681b ldr r3, [r3, #0] + 8001b66: 4413 add r3, r2 + 8001b68: 4a04 ldr r2, [pc, #16] ; (8001b7c ) + 8001b6a: 6013 str r3, [r2, #0] } - 8001aa4: bf00 nop - 8001aa6: 46bd mov sp, r7 - 8001aa8: f85d 7b04 ldr.w r7, [sp], #4 - 8001aac: 4770 bx lr - 8001aae: bf00 nop - 8001ab0: 20000010 .word 0x20000010 - 8001ab4: 2000039c .word 0x2000039c - -08001ab8 : + 8001b6c: bf00 nop + 8001b6e: 46bd mov sp, r7 + 8001b70: f85d 7b04 ldr.w r7, [sp], #4 + 8001b74: 4770 bx lr + 8001b76: bf00 nop + 8001b78: 2000000c .word 0x2000000c + 8001b7c: 20000398 .word 0x20000398 + +08001b80 : * @note This function is declared as __weak to be overwritten in case of other * implementations in user file. * @retval tick value */ __weak uint32_t HAL_GetTick(void) { - 8001ab8: b480 push {r7} - 8001aba: af00 add r7, sp, #0 + 8001b80: b480 push {r7} + 8001b82: af00 add r7, sp, #0 return uwTick; - 8001abc: 4b03 ldr r3, [pc, #12] ; (8001acc ) - 8001abe: 681b ldr r3, [r3, #0] + 8001b84: 4b03 ldr r3, [pc, #12] ; (8001b94 ) + 8001b86: 681b ldr r3, [r3, #0] } - 8001ac0: 4618 mov r0, r3 - 8001ac2: 46bd mov sp, r7 - 8001ac4: f85d 7b04 ldr.w r7, [sp], #4 - 8001ac8: 4770 bx lr - 8001aca: bf00 nop - 8001acc: 2000039c .word 0x2000039c - -08001ad0 <__NVIC_SetPriorityGrouping>: + 8001b88: 4618 mov r0, r3 + 8001b8a: 46bd mov sp, r7 + 8001b8c: f85d 7b04 ldr.w r7, [sp], #4 + 8001b90: 4770 bx lr + 8001b92: bf00 nop + 8001b94: 20000398 .word 0x20000398 + +08001b98 <__NVIC_SetPriorityGrouping>: In case of a conflict between priority grouping and available priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. \param [in] PriorityGroup Priority grouping field. */ __STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { - 8001ad0: b480 push {r7} - 8001ad2: b085 sub sp, #20 - 8001ad4: af00 add r7, sp, #0 - 8001ad6: 6078 str r0, [r7, #4] + 8001b98: b480 push {r7} + 8001b9a: b085 sub sp, #20 + 8001b9c: af00 add r7, sp, #0 + 8001b9e: 6078 str r0, [r7, #4] uint32_t reg_value; uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - 8001ad8: 687b ldr r3, [r7, #4] - 8001ada: f003 0307 and.w r3, r3, #7 - 8001ade: 60fb str r3, [r7, #12] + 8001ba0: 687b ldr r3, [r7, #4] + 8001ba2: f003 0307 and.w r3, r3, #7 + 8001ba6: 60fb str r3, [r7, #12] reg_value = SCB->AIRCR; /* read old register configuration */ - 8001ae0: 4b0b ldr r3, [pc, #44] ; (8001b10 <__NVIC_SetPriorityGrouping+0x40>) - 8001ae2: 68db ldr r3, [r3, #12] - 8001ae4: 60bb str r3, [r7, #8] + 8001ba8: 4b0b ldr r3, [pc, #44] ; (8001bd8 <__NVIC_SetPriorityGrouping+0x40>) + 8001baa: 68db ldr r3, [r3, #12] + 8001bac: 60bb str r3, [r7, #8] reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - 8001ae6: 68ba ldr r2, [r7, #8] - 8001ae8: f64f 03ff movw r3, #63743 ; 0xf8ff - 8001aec: 4013 ands r3, r2 - 8001aee: 60bb str r3, [r7, #8] + 8001bae: 68ba ldr r2, [r7, #8] + 8001bb0: f64f 03ff movw r3, #63743 ; 0xf8ff + 8001bb4: 4013 ands r3, r2 + 8001bb6: 60bb str r3, [r7, #8] reg_value = (reg_value | ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - 8001af0: 68fb ldr r3, [r7, #12] - 8001af2: 021a lsls r2, r3, #8 + 8001bb8: 68fb ldr r3, [r7, #12] + 8001bba: 021a lsls r2, r3, #8 ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - 8001af4: 68bb ldr r3, [r7, #8] - 8001af6: 431a orrs r2, r3 + 8001bbc: 68bb ldr r3, [r7, #8] + 8001bbe: 431a orrs r2, r3 reg_value = (reg_value | - 8001af8: 4b06 ldr r3, [pc, #24] ; (8001b14 <__NVIC_SetPriorityGrouping+0x44>) - 8001afa: 4313 orrs r3, r2 - 8001afc: 60bb str r3, [r7, #8] + 8001bc0: 4b06 ldr r3, [pc, #24] ; (8001bdc <__NVIC_SetPriorityGrouping+0x44>) + 8001bc2: 4313 orrs r3, r2 + 8001bc4: 60bb str r3, [r7, #8] SCB->AIRCR = reg_value; - 8001afe: 4a04 ldr r2, [pc, #16] ; (8001b10 <__NVIC_SetPriorityGrouping+0x40>) - 8001b00: 68bb ldr r3, [r7, #8] - 8001b02: 60d3 str r3, [r2, #12] + 8001bc6: 4a04 ldr r2, [pc, #16] ; (8001bd8 <__NVIC_SetPriorityGrouping+0x40>) + 8001bc8: 68bb ldr r3, [r7, #8] + 8001bca: 60d3 str r3, [r2, #12] } - 8001b04: bf00 nop - 8001b06: 3714 adds r7, #20 - 8001b08: 46bd mov sp, r7 - 8001b0a: f85d 7b04 ldr.w r7, [sp], #4 - 8001b0e: 4770 bx lr - 8001b10: e000ed00 .word 0xe000ed00 - 8001b14: 05fa0000 .word 0x05fa0000 - -08001b18 <__NVIC_GetPriorityGrouping>: + 8001bcc: bf00 nop + 8001bce: 3714 adds r7, #20 + 8001bd0: 46bd mov sp, r7 + 8001bd2: f85d 7b04 ldr.w r7, [sp], #4 + 8001bd6: 4770 bx lr + 8001bd8: e000ed00 .word 0xe000ed00 + 8001bdc: 05fa0000 .word 0x05fa0000 + +08001be0 <__NVIC_GetPriorityGrouping>: \brief Get Priority Grouping \details Reads the priority grouping field from the NVIC Interrupt Controller. \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). */ __STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) { - 8001b18: b480 push {r7} - 8001b1a: af00 add r7, sp, #0 + 8001be0: b480 push {r7} + 8001be2: af00 add r7, sp, #0 return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); - 8001b1c: 4b04 ldr r3, [pc, #16] ; (8001b30 <__NVIC_GetPriorityGrouping+0x18>) - 8001b1e: 68db ldr r3, [r3, #12] - 8001b20: 0a1b lsrs r3, r3, #8 - 8001b22: f003 0307 and.w r3, r3, #7 + 8001be4: 4b04 ldr r3, [pc, #16] ; (8001bf8 <__NVIC_GetPriorityGrouping+0x18>) + 8001be6: 68db ldr r3, [r3, #12] + 8001be8: 0a1b lsrs r3, r3, #8 + 8001bea: f003 0307 and.w r3, r3, #7 } - 8001b26: 4618 mov r0, r3 - 8001b28: 46bd mov sp, r7 - 8001b2a: f85d 7b04 ldr.w r7, [sp], #4 - 8001b2e: 4770 bx lr - 8001b30: e000ed00 .word 0xe000ed00 + 8001bee: 4618 mov r0, r3 + 8001bf0: 46bd mov sp, r7 + 8001bf2: f85d 7b04 ldr.w r7, [sp], #4 + 8001bf6: 4770 bx lr + 8001bf8: e000ed00 .word 0xe000ed00 -08001b34 <__NVIC_EnableIRQ>: +08001bfc <__NVIC_EnableIRQ>: \details Enables a device specific interrupt in the NVIC interrupt controller. \param [in] IRQn Device specific interrupt number. \note IRQn must not be negative. */ __STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) { - 8001b34: b480 push {r7} - 8001b36: b083 sub sp, #12 - 8001b38: af00 add r7, sp, #0 - 8001b3a: 4603 mov r3, r0 - 8001b3c: 71fb strb r3, [r7, #7] + 8001bfc: b480 push {r7} + 8001bfe: b083 sub sp, #12 + 8001c00: af00 add r7, sp, #0 + 8001c02: 4603 mov r3, r0 + 8001c04: 71fb strb r3, [r7, #7] if ((int32_t)(IRQn) >= 0) - 8001b3e: f997 3007 ldrsb.w r3, [r7, #7] - 8001b42: 2b00 cmp r3, #0 - 8001b44: db0b blt.n 8001b5e <__NVIC_EnableIRQ+0x2a> + 8001c06: f997 3007 ldrsb.w r3, [r7, #7] + 8001c0a: 2b00 cmp r3, #0 + 8001c0c: db0b blt.n 8001c26 <__NVIC_EnableIRQ+0x2a> { NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - 8001b46: 79fb ldrb r3, [r7, #7] - 8001b48: f003 021f and.w r2, r3, #31 - 8001b4c: 4907 ldr r1, [pc, #28] ; (8001b6c <__NVIC_EnableIRQ+0x38>) - 8001b4e: f997 3007 ldrsb.w r3, [r7, #7] - 8001b52: 095b lsrs r3, r3, #5 - 8001b54: 2001 movs r0, #1 - 8001b56: fa00 f202 lsl.w r2, r0, r2 - 8001b5a: f841 2023 str.w r2, [r1, r3, lsl #2] + 8001c0e: 79fb ldrb r3, [r7, #7] + 8001c10: f003 021f and.w r2, r3, #31 + 8001c14: 4907 ldr r1, [pc, #28] ; (8001c34 <__NVIC_EnableIRQ+0x38>) + 8001c16: f997 3007 ldrsb.w r3, [r7, #7] + 8001c1a: 095b lsrs r3, r3, #5 + 8001c1c: 2001 movs r0, #1 + 8001c1e: fa00 f202 lsl.w r2, r0, r2 + 8001c22: f841 2023 str.w r2, [r1, r3, lsl #2] } } - 8001b5e: bf00 nop - 8001b60: 370c adds r7, #12 - 8001b62: 46bd mov sp, r7 - 8001b64: f85d 7b04 ldr.w r7, [sp], #4 - 8001b68: 4770 bx lr - 8001b6a: bf00 nop - 8001b6c: e000e100 .word 0xe000e100 - -08001b70 <__NVIC_SetPriority>: + 8001c26: bf00 nop + 8001c28: 370c adds r7, #12 + 8001c2a: 46bd mov sp, r7 + 8001c2c: f85d 7b04 ldr.w r7, [sp], #4 + 8001c30: 4770 bx lr + 8001c32: bf00 nop + 8001c34: e000e100 .word 0xe000e100 + +08001c38 <__NVIC_SetPriority>: \param [in] IRQn Interrupt number. \param [in] priority Priority to set. \note The priority cannot be set for every processor exception. */ __STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) { - 8001b70: b480 push {r7} - 8001b72: b083 sub sp, #12 - 8001b74: af00 add r7, sp, #0 - 8001b76: 4603 mov r3, r0 - 8001b78: 6039 str r1, [r7, #0] - 8001b7a: 71fb strb r3, [r7, #7] + 8001c38: b480 push {r7} + 8001c3a: b083 sub sp, #12 + 8001c3c: af00 add r7, sp, #0 + 8001c3e: 4603 mov r3, r0 + 8001c40: 6039 str r1, [r7, #0] + 8001c42: 71fb strb r3, [r7, #7] if ((int32_t)(IRQn) >= 0) - 8001b7c: f997 3007 ldrsb.w r3, [r7, #7] - 8001b80: 2b00 cmp r3, #0 - 8001b82: db0a blt.n 8001b9a <__NVIC_SetPriority+0x2a> + 8001c44: f997 3007 ldrsb.w r3, [r7, #7] + 8001c48: 2b00 cmp r3, #0 + 8001c4a: db0a blt.n 8001c62 <__NVIC_SetPriority+0x2a> { NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - 8001b84: 683b ldr r3, [r7, #0] - 8001b86: b2da uxtb r2, r3 - 8001b88: 490c ldr r1, [pc, #48] ; (8001bbc <__NVIC_SetPriority+0x4c>) - 8001b8a: f997 3007 ldrsb.w r3, [r7, #7] - 8001b8e: 0112 lsls r2, r2, #4 - 8001b90: b2d2 uxtb r2, r2 - 8001b92: 440b add r3, r1 - 8001b94: f883 2300 strb.w r2, [r3, #768] ; 0x300 + 8001c4c: 683b ldr r3, [r7, #0] + 8001c4e: b2da uxtb r2, r3 + 8001c50: 490c ldr r1, [pc, #48] ; (8001c84 <__NVIC_SetPriority+0x4c>) + 8001c52: f997 3007 ldrsb.w r3, [r7, #7] + 8001c56: 0112 lsls r2, r2, #4 + 8001c58: b2d2 uxtb r2, r2 + 8001c5a: 440b add r3, r1 + 8001c5c: f883 2300 strb.w r2, [r3, #768] ; 0x300 } else { SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); } } - 8001b98: e00a b.n 8001bb0 <__NVIC_SetPriority+0x40> + 8001c60: e00a b.n 8001c78 <__NVIC_SetPriority+0x40> SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - 8001b9a: 683b ldr r3, [r7, #0] - 8001b9c: b2da uxtb r2, r3 - 8001b9e: 4908 ldr r1, [pc, #32] ; (8001bc0 <__NVIC_SetPriority+0x50>) - 8001ba0: 79fb ldrb r3, [r7, #7] - 8001ba2: f003 030f and.w r3, r3, #15 - 8001ba6: 3b04 subs r3, #4 - 8001ba8: 0112 lsls r2, r2, #4 - 8001baa: b2d2 uxtb r2, r2 - 8001bac: 440b add r3, r1 - 8001bae: 761a strb r2, [r3, #24] + 8001c62: 683b ldr r3, [r7, #0] + 8001c64: b2da uxtb r2, r3 + 8001c66: 4908 ldr r1, [pc, #32] ; (8001c88 <__NVIC_SetPriority+0x50>) + 8001c68: 79fb ldrb r3, [r7, #7] + 8001c6a: f003 030f and.w r3, r3, #15 + 8001c6e: 3b04 subs r3, #4 + 8001c70: 0112 lsls r2, r2, #4 + 8001c72: b2d2 uxtb r2, r2 + 8001c74: 440b add r3, r1 + 8001c76: 761a strb r2, [r3, #24] } - 8001bb0: bf00 nop - 8001bb2: 370c adds r7, #12 - 8001bb4: 46bd mov sp, r7 - 8001bb6: f85d 7b04 ldr.w r7, [sp], #4 - 8001bba: 4770 bx lr - 8001bbc: e000e100 .word 0xe000e100 - 8001bc0: e000ed00 .word 0xe000ed00 - -08001bc4 : + 8001c78: bf00 nop + 8001c7a: 370c adds r7, #12 + 8001c7c: 46bd mov sp, r7 + 8001c7e: f85d 7b04 ldr.w r7, [sp], #4 + 8001c82: 4770 bx lr + 8001c84: e000e100 .word 0xe000e100 + 8001c88: e000ed00 .word 0xe000ed00 + +08001c8c : \param [in] PreemptPriority Preemptive priority value (starting from 0). \param [in] SubPriority Subpriority value (starting from 0). \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). */ __STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) { - 8001bc4: b480 push {r7} - 8001bc6: b089 sub sp, #36 ; 0x24 - 8001bc8: af00 add r7, sp, #0 - 8001bca: 60f8 str r0, [r7, #12] - 8001bcc: 60b9 str r1, [r7, #8] - 8001bce: 607a str r2, [r7, #4] + 8001c8c: b480 push {r7} + 8001c8e: b089 sub sp, #36 ; 0x24 + 8001c90: af00 add r7, sp, #0 + 8001c92: 60f8 str r0, [r7, #12] + 8001c94: 60b9 str r1, [r7, #8] + 8001c96: 607a str r2, [r7, #4] uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - 8001bd0: 68fb ldr r3, [r7, #12] - 8001bd2: f003 0307 and.w r3, r3, #7 - 8001bd6: 61fb str r3, [r7, #28] + 8001c98: 68fb ldr r3, [r7, #12] + 8001c9a: f003 0307 and.w r3, r3, #7 + 8001c9e: 61fb str r3, [r7, #28] uint32_t PreemptPriorityBits; uint32_t SubPriorityBits; PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - 8001bd8: 69fb ldr r3, [r7, #28] - 8001bda: f1c3 0307 rsb r3, r3, #7 - 8001bde: 2b04 cmp r3, #4 - 8001be0: bf28 it cs - 8001be2: 2304 movcs r3, #4 - 8001be4: 61bb str r3, [r7, #24] + 8001ca0: 69fb ldr r3, [r7, #28] + 8001ca2: f1c3 0307 rsb r3, r3, #7 + 8001ca6: 2b04 cmp r3, #4 + 8001ca8: bf28 it cs + 8001caa: 2304 movcs r3, #4 + 8001cac: 61bb str r3, [r7, #24] SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - 8001be6: 69fb ldr r3, [r7, #28] - 8001be8: 3304 adds r3, #4 - 8001bea: 2b06 cmp r3, #6 - 8001bec: d902 bls.n 8001bf4 - 8001bee: 69fb ldr r3, [r7, #28] - 8001bf0: 3b03 subs r3, #3 - 8001bf2: e000 b.n 8001bf6 - 8001bf4: 2300 movs r3, #0 - 8001bf6: 617b str r3, [r7, #20] + 8001cae: 69fb ldr r3, [r7, #28] + 8001cb0: 3304 adds r3, #4 + 8001cb2: 2b06 cmp r3, #6 + 8001cb4: d902 bls.n 8001cbc + 8001cb6: 69fb ldr r3, [r7, #28] + 8001cb8: 3b03 subs r3, #3 + 8001cba: e000 b.n 8001cbe + 8001cbc: 2300 movs r3, #0 + 8001cbe: 617b str r3, [r7, #20] return ( ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - 8001bf8: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8001bfc: 69bb ldr r3, [r7, #24] - 8001bfe: fa02 f303 lsl.w r3, r2, r3 - 8001c02: 43da mvns r2, r3 - 8001c04: 68bb ldr r3, [r7, #8] - 8001c06: 401a ands r2, r3 - 8001c08: 697b ldr r3, [r7, #20] - 8001c0a: 409a lsls r2, r3 + 8001cc0: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8001cc4: 69bb ldr r3, [r7, #24] + 8001cc6: fa02 f303 lsl.w r3, r2, r3 + 8001cca: 43da mvns r2, r3 + 8001ccc: 68bb ldr r3, [r7, #8] + 8001cce: 401a ands r2, r3 + 8001cd0: 697b ldr r3, [r7, #20] + 8001cd2: 409a lsls r2, r3 ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - 8001c0c: f04f 31ff mov.w r1, #4294967295 ; 0xffffffff - 8001c10: 697b ldr r3, [r7, #20] - 8001c12: fa01 f303 lsl.w r3, r1, r3 - 8001c16: 43d9 mvns r1, r3 - 8001c18: 687b ldr r3, [r7, #4] - 8001c1a: 400b ands r3, r1 + 8001cd4: f04f 31ff mov.w r1, #4294967295 ; 0xffffffff + 8001cd8: 697b ldr r3, [r7, #20] + 8001cda: fa01 f303 lsl.w r3, r1, r3 + 8001cde: 43d9 mvns r1, r3 + 8001ce0: 687b ldr r3, [r7, #4] + 8001ce2: 400b ands r3, r1 ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - 8001c1c: 4313 orrs r3, r2 + 8001ce4: 4313 orrs r3, r2 ); } - 8001c1e: 4618 mov r0, r3 - 8001c20: 3724 adds r7, #36 ; 0x24 - 8001c22: 46bd mov sp, r7 - 8001c24: f85d 7b04 ldr.w r7, [sp], #4 - 8001c28: 4770 bx lr + 8001ce6: 4618 mov r0, r3 + 8001ce8: 3724 adds r7, #36 ; 0x24 + 8001cea: 46bd mov sp, r7 + 8001cec: f85d 7b04 ldr.w r7, [sp], #4 + 8001cf0: 4770 bx lr ... -08001c2c : +08001cf4 : \note When the variable __Vendor_SysTickConfig is set to 1, then the function SysTick_Config is not included. In this case, the file device.h must contain a vendor-specific implementation of this function. */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - 8001c2c: b580 push {r7, lr} - 8001c2e: b082 sub sp, #8 - 8001c30: af00 add r7, sp, #0 - 8001c32: 6078 str r0, [r7, #4] + 8001cf4: b580 push {r7, lr} + 8001cf6: b082 sub sp, #8 + 8001cf8: af00 add r7, sp, #0 + 8001cfa: 6078 str r0, [r7, #4] if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - 8001c34: 687b ldr r3, [r7, #4] - 8001c36: 3b01 subs r3, #1 - 8001c38: f1b3 7f80 cmp.w r3, #16777216 ; 0x1000000 - 8001c3c: d301 bcc.n 8001c42 + 8001cfc: 687b ldr r3, [r7, #4] + 8001cfe: 3b01 subs r3, #1 + 8001d00: f1b3 7f80 cmp.w r3, #16777216 ; 0x1000000 + 8001d04: d301 bcc.n 8001d0a { return (1UL); /* Reload value impossible */ - 8001c3e: 2301 movs r3, #1 - 8001c40: e00f b.n 8001c62 + 8001d06: 2301 movs r3, #1 + 8001d08: e00f b.n 8001d2a } SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - 8001c42: 4a0a ldr r2, [pc, #40] ; (8001c6c ) - 8001c44: 687b ldr r3, [r7, #4] - 8001c46: 3b01 subs r3, #1 - 8001c48: 6053 str r3, [r2, #4] + 8001d0a: 4a0a ldr r2, [pc, #40] ; (8001d34 ) + 8001d0c: 687b ldr r3, [r7, #4] + 8001d0e: 3b01 subs r3, #1 + 8001d10: 6053 str r3, [r2, #4] NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - 8001c4a: 210f movs r1, #15 - 8001c4c: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff - 8001c50: f7ff ff8e bl 8001b70 <__NVIC_SetPriority> + 8001d12: 210f movs r1, #15 + 8001d14: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001d18: f7ff ff8e bl 8001c38 <__NVIC_SetPriority> SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - 8001c54: 4b05 ldr r3, [pc, #20] ; (8001c6c ) - 8001c56: 2200 movs r2, #0 - 8001c58: 609a str r2, [r3, #8] + 8001d1c: 4b05 ldr r3, [pc, #20] ; (8001d34 ) + 8001d1e: 2200 movs r2, #0 + 8001d20: 609a str r2, [r3, #8] SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - 8001c5a: 4b04 ldr r3, [pc, #16] ; (8001c6c ) - 8001c5c: 2207 movs r2, #7 - 8001c5e: 601a str r2, [r3, #0] + 8001d22: 4b04 ldr r3, [pc, #16] ; (8001d34 ) + 8001d24: 2207 movs r2, #7 + 8001d26: 601a str r2, [r3, #0] SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ return (0UL); /* Function successful */ - 8001c60: 2300 movs r3, #0 + 8001d28: 2300 movs r3, #0 } - 8001c62: 4618 mov r0, r3 - 8001c64: 3708 adds r7, #8 - 8001c66: 46bd mov sp, r7 - 8001c68: bd80 pop {r7, pc} - 8001c6a: bf00 nop - 8001c6c: e000e010 .word 0xe000e010 - -08001c70 : + 8001d2a: 4618 mov r0, r3 + 8001d2c: 3708 adds r7, #8 + 8001d2e: 46bd mov sp, r7 + 8001d30: bd80 pop {r7, pc} + 8001d32: bf00 nop + 8001d34: e000e010 .word 0xe000e010 + +08001d38 : * @note When the NVIC_PriorityGroup_0 is selected, IRQ preemption is no more possible. * The pending IRQ priority will be managed only by the subpriority. * @retval None */ void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { - 8001c70: b580 push {r7, lr} - 8001c72: b082 sub sp, #8 - 8001c74: af00 add r7, sp, #0 - 8001c76: 6078 str r0, [r7, #4] + 8001d38: b580 push {r7, lr} + 8001d3a: b082 sub sp, #8 + 8001d3c: af00 add r7, sp, #0 + 8001d3e: 6078 str r0, [r7, #4] /* Check the parameters */ assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); /* Set the PRIGROUP[10:8] bits according to the PriorityGroup parameter value */ NVIC_SetPriorityGrouping(PriorityGroup); - 8001c78: 6878 ldr r0, [r7, #4] - 8001c7a: f7ff ff29 bl 8001ad0 <__NVIC_SetPriorityGrouping> + 8001d40: 6878 ldr r0, [r7, #4] + 8001d42: f7ff ff29 bl 8001b98 <__NVIC_SetPriorityGrouping> } - 8001c7e: bf00 nop - 8001c80: 3708 adds r7, #8 - 8001c82: 46bd mov sp, r7 - 8001c84: bd80 pop {r7, pc} + 8001d46: bf00 nop + 8001d48: 3708 adds r7, #8 + 8001d4a: 46bd mov sp, r7 + 8001d4c: bd80 pop {r7, pc} -08001c86 : +08001d4e : * This parameter can be a value between 0 and 15 * A lower priority value indicates a higher priority. * @retval None */ void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) { - 8001c86: b580 push {r7, lr} - 8001c88: b086 sub sp, #24 - 8001c8a: af00 add r7, sp, #0 - 8001c8c: 4603 mov r3, r0 - 8001c8e: 60b9 str r1, [r7, #8] - 8001c90: 607a str r2, [r7, #4] - 8001c92: 73fb strb r3, [r7, #15] + 8001d4e: b580 push {r7, lr} + 8001d50: b086 sub sp, #24 + 8001d52: af00 add r7, sp, #0 + 8001d54: 4603 mov r3, r0 + 8001d56: 60b9 str r1, [r7, #8] + 8001d58: 607a str r2, [r7, #4] + 8001d5a: 73fb strb r3, [r7, #15] uint32_t prioritygroup = 0x00; - 8001c94: 2300 movs r3, #0 - 8001c96: 617b str r3, [r7, #20] + 8001d5c: 2300 movs r3, #0 + 8001d5e: 617b str r3, [r7, #20] /* Check the parameters */ assert_param(IS_NVIC_SUB_PRIORITY(SubPriority)); assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); prioritygroup = NVIC_GetPriorityGrouping(); - 8001c98: f7ff ff3e bl 8001b18 <__NVIC_GetPriorityGrouping> - 8001c9c: 6178 str r0, [r7, #20] + 8001d60: f7ff ff3e bl 8001be0 <__NVIC_GetPriorityGrouping> + 8001d64: 6178 str r0, [r7, #20] NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); - 8001c9e: 687a ldr r2, [r7, #4] - 8001ca0: 68b9 ldr r1, [r7, #8] - 8001ca2: 6978 ldr r0, [r7, #20] - 8001ca4: f7ff ff8e bl 8001bc4 - 8001ca8: 4602 mov r2, r0 - 8001caa: f997 300f ldrsb.w r3, [r7, #15] - 8001cae: 4611 mov r1, r2 - 8001cb0: 4618 mov r0, r3 - 8001cb2: f7ff ff5d bl 8001b70 <__NVIC_SetPriority> + 8001d66: 687a ldr r2, [r7, #4] + 8001d68: 68b9 ldr r1, [r7, #8] + 8001d6a: 6978 ldr r0, [r7, #20] + 8001d6c: f7ff ff8e bl 8001c8c + 8001d70: 4602 mov r2, r0 + 8001d72: f997 300f ldrsb.w r3, [r7, #15] + 8001d76: 4611 mov r1, r2 + 8001d78: 4618 mov r0, r3 + 8001d7a: f7ff ff5d bl 8001c38 <__NVIC_SetPriority> } - 8001cb6: bf00 nop - 8001cb8: 3718 adds r7, #24 - 8001cba: 46bd mov sp, r7 - 8001cbc: bd80 pop {r7, pc} + 8001d7e: bf00 nop + 8001d80: 3718 adds r7, #24 + 8001d82: 46bd mov sp, r7 + 8001d84: bd80 pop {r7, pc} -08001cbe : +08001d86 : * This parameter can be an enumerator of IRQn_Type enumeration * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f7xxxx.h)) * @retval None */ void HAL_NVIC_EnableIRQ(IRQn_Type IRQn) { - 8001cbe: b580 push {r7, lr} - 8001cc0: b082 sub sp, #8 - 8001cc2: af00 add r7, sp, #0 - 8001cc4: 4603 mov r3, r0 - 8001cc6: 71fb strb r3, [r7, #7] + 8001d86: b580 push {r7, lr} + 8001d88: b082 sub sp, #8 + 8001d8a: af00 add r7, sp, #0 + 8001d8c: 4603 mov r3, r0 + 8001d8e: 71fb strb r3, [r7, #7] /* Check the parameters */ assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); /* Enable interrupt */ NVIC_EnableIRQ(IRQn); - 8001cc8: f997 3007 ldrsb.w r3, [r7, #7] - 8001ccc: 4618 mov r0, r3 - 8001cce: f7ff ff31 bl 8001b34 <__NVIC_EnableIRQ> + 8001d90: f997 3007 ldrsb.w r3, [r7, #7] + 8001d94: 4618 mov r0, r3 + 8001d96: f7ff ff31 bl 8001bfc <__NVIC_EnableIRQ> } - 8001cd2: bf00 nop - 8001cd4: 3708 adds r7, #8 - 8001cd6: 46bd mov sp, r7 - 8001cd8: bd80 pop {r7, pc} + 8001d9a: bf00 nop + 8001d9c: 3708 adds r7, #8 + 8001d9e: 46bd mov sp, r7 + 8001da0: bd80 pop {r7, pc} -08001cda : +08001da2 : * @param TicksNumb Specifies the ticks Number of ticks between two interrupts. * @retval status: - 0 Function succeeded. * - 1 Function failed. */ uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb) { - 8001cda: b580 push {r7, lr} - 8001cdc: b082 sub sp, #8 - 8001cde: af00 add r7, sp, #0 - 8001ce0: 6078 str r0, [r7, #4] + 8001da2: b580 push {r7, lr} + 8001da4: b082 sub sp, #8 + 8001da6: af00 add r7, sp, #0 + 8001da8: 6078 str r0, [r7, #4] return SysTick_Config(TicksNumb); - 8001ce2: 6878 ldr r0, [r7, #4] - 8001ce4: f7ff ffa2 bl 8001c2c - 8001ce8: 4603 mov r3, r0 + 8001daa: 6878 ldr r0, [r7, #4] + 8001dac: f7ff ffa2 bl 8001cf4 + 8001db0: 4603 mov r3, r0 } - 8001cea: 4618 mov r0, r3 - 8001cec: 3708 adds r7, #8 - 8001cee: 46bd mov sp, r7 - 8001cf0: bd80 pop {r7, pc} + 8001db2: 4618 mov r0, r3 + 8001db4: 3708 adds r7, #8 + 8001db6: 46bd mov sp, r7 + 8001db8: bd80 pop {r7, pc} -08001cf2 : +08001dba : * @param hdma pointer to a DMA_HandleTypeDef structure that contains * the configuration information for the specified DMA Stream. * @retval HAL status */ HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma) { - 8001cf2: b480 push {r7} - 8001cf4: b083 sub sp, #12 - 8001cf6: af00 add r7, sp, #0 - 8001cf8: 6078 str r0, [r7, #4] + 8001dba: b480 push {r7} + 8001dbc: b083 sub sp, #12 + 8001dbe: af00 add r7, sp, #0 + 8001dc0: 6078 str r0, [r7, #4] if(hdma->State != HAL_DMA_STATE_BUSY) - 8001cfa: 687b ldr r3, [r7, #4] - 8001cfc: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 - 8001d00: b2db uxtb r3, r3 - 8001d02: 2b02 cmp r3, #2 - 8001d04: d004 beq.n 8001d10 + 8001dc2: 687b ldr r3, [r7, #4] + 8001dc4: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 + 8001dc8: b2db uxtb r3, r3 + 8001dca: 2b02 cmp r3, #2 + 8001dcc: d004 beq.n 8001dd8 { hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - 8001d06: 687b ldr r3, [r7, #4] - 8001d08: 2280 movs r2, #128 ; 0x80 - 8001d0a: 655a str r2, [r3, #84] ; 0x54 + 8001dce: 687b ldr r3, [r7, #4] + 8001dd0: 2280 movs r2, #128 ; 0x80 + 8001dd2: 655a str r2, [r3, #84] ; 0x54 return HAL_ERROR; - 8001d0c: 2301 movs r3, #1 - 8001d0e: e00c b.n 8001d2a + 8001dd4: 2301 movs r3, #1 + 8001dd6: e00c b.n 8001df2 } else { /* Set Abort State */ hdma->State = HAL_DMA_STATE_ABORT; - 8001d10: 687b ldr r3, [r7, #4] - 8001d12: 2205 movs r2, #5 - 8001d14: f883 2035 strb.w r2, [r3, #53] ; 0x35 + 8001dd8: 687b ldr r3, [r7, #4] + 8001dda: 2205 movs r2, #5 + 8001ddc: f883 2035 strb.w r2, [r3, #53] ; 0x35 /* Disable the stream */ __HAL_DMA_DISABLE(hdma); - 8001d18: 687b ldr r3, [r7, #4] - 8001d1a: 681b ldr r3, [r3, #0] - 8001d1c: 681a ldr r2, [r3, #0] - 8001d1e: 687b ldr r3, [r7, #4] - 8001d20: 681b ldr r3, [r3, #0] - 8001d22: f022 0201 bic.w r2, r2, #1 - 8001d26: 601a str r2, [r3, #0] + 8001de0: 687b ldr r3, [r7, #4] + 8001de2: 681b ldr r3, [r3, #0] + 8001de4: 681a ldr r2, [r3, #0] + 8001de6: 687b ldr r3, [r7, #4] + 8001de8: 681b ldr r3, [r3, #0] + 8001dea: f022 0201 bic.w r2, r2, #1 + 8001dee: 601a str r2, [r3, #0] } return HAL_OK; - 8001d28: 2300 movs r3, #0 + 8001df0: 2300 movs r3, #0 } - 8001d2a: 4618 mov r0, r3 - 8001d2c: 370c adds r7, #12 - 8001d2e: 46bd mov sp, r7 - 8001d30: f85d 7b04 ldr.w r7, [sp], #4 - 8001d34: 4770 bx lr + 8001df2: 4618 mov r0, r3 + 8001df4: 370c adds r7, #12 + 8001df6: 46bd mov sp, r7 + 8001df8: f85d 7b04 ldr.w r7, [sp], #4 + 8001dfc: 4770 bx lr ... -08001d38 : +08001e00 : * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains * the configuration information for the specified GPIO peripheral. * @retval None */ void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init) { - 8001d38: b480 push {r7} - 8001d3a: b089 sub sp, #36 ; 0x24 - 8001d3c: af00 add r7, sp, #0 - 8001d3e: 6078 str r0, [r7, #4] - 8001d40: 6039 str r1, [r7, #0] + 8001e00: b480 push {r7} + 8001e02: b089 sub sp, #36 ; 0x24 + 8001e04: af00 add r7, sp, #0 + 8001e06: 6078 str r0, [r7, #4] + 8001e08: 6039 str r1, [r7, #0] uint32_t position = 0x00; - 8001d42: 2300 movs r3, #0 - 8001d44: 61fb str r3, [r7, #28] + 8001e0a: 2300 movs r3, #0 + 8001e0c: 61fb str r3, [r7, #28] uint32_t ioposition = 0x00; - 8001d46: 2300 movs r3, #0 - 8001d48: 617b str r3, [r7, #20] + 8001e0e: 2300 movs r3, #0 + 8001e10: 617b str r3, [r7, #20] uint32_t iocurrent = 0x00; - 8001d4a: 2300 movs r3, #0 - 8001d4c: 613b str r3, [r7, #16] + 8001e12: 2300 movs r3, #0 + 8001e14: 613b str r3, [r7, #16] uint32_t temp = 0x00; - 8001d4e: 2300 movs r3, #0 - 8001d50: 61bb str r3, [r7, #24] + 8001e16: 2300 movs r3, #0 + 8001e18: 61bb str r3, [r7, #24] assert_param(IS_GPIO_PIN(GPIO_Init->Pin)); assert_param(IS_GPIO_MODE(GPIO_Init->Mode)); assert_param(IS_GPIO_PULL(GPIO_Init->Pull)); /* Configure the port pins */ for(position = 0; position < GPIO_NUMBER; position++) - 8001d52: 2300 movs r3, #0 - 8001d54: 61fb str r3, [r7, #28] - 8001d56: e175 b.n 8002044 + 8001e1a: 2300 movs r3, #0 + 8001e1c: 61fb str r3, [r7, #28] + 8001e1e: e175 b.n 800210c { /* Get the IO position */ ioposition = ((uint32_t)0x01) << position; - 8001d58: 2201 movs r2, #1 - 8001d5a: 69fb ldr r3, [r7, #28] - 8001d5c: fa02 f303 lsl.w r3, r2, r3 - 8001d60: 617b str r3, [r7, #20] + 8001e20: 2201 movs r2, #1 + 8001e22: 69fb ldr r3, [r7, #28] + 8001e24: fa02 f303 lsl.w r3, r2, r3 + 8001e28: 617b str r3, [r7, #20] /* Get the current IO position */ iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; - 8001d62: 683b ldr r3, [r7, #0] - 8001d64: 681b ldr r3, [r3, #0] - 8001d66: 697a ldr r2, [r7, #20] - 8001d68: 4013 ands r3, r2 - 8001d6a: 613b str r3, [r7, #16] + 8001e2a: 683b ldr r3, [r7, #0] + 8001e2c: 681b ldr r3, [r3, #0] + 8001e2e: 697a ldr r2, [r7, #20] + 8001e30: 4013 ands r3, r2 + 8001e32: 613b str r3, [r7, #16] if(iocurrent == ioposition) - 8001d6c: 693a ldr r2, [r7, #16] - 8001d6e: 697b ldr r3, [r7, #20] - 8001d70: 429a cmp r2, r3 - 8001d72: f040 8164 bne.w 800203e + 8001e34: 693a ldr r2, [r7, #16] + 8001e36: 697b ldr r3, [r7, #20] + 8001e38: 429a cmp r2, r3 + 8001e3a: f040 8164 bne.w 8002106 { /*--------------------- GPIO Mode Configuration ------------------------*/ /* In case of Alternate function mode selection */ if((GPIO_Init->Mode == GPIO_MODE_AF_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) - 8001d76: 683b ldr r3, [r7, #0] - 8001d78: 685b ldr r3, [r3, #4] - 8001d7a: 2b02 cmp r3, #2 - 8001d7c: d003 beq.n 8001d86 - 8001d7e: 683b ldr r3, [r7, #0] - 8001d80: 685b ldr r3, [r3, #4] - 8001d82: 2b12 cmp r3, #18 - 8001d84: d123 bne.n 8001dce + 8001e3e: 683b ldr r3, [r7, #0] + 8001e40: 685b ldr r3, [r3, #4] + 8001e42: 2b02 cmp r3, #2 + 8001e44: d003 beq.n 8001e4e + 8001e46: 683b ldr r3, [r7, #0] + 8001e48: 685b ldr r3, [r3, #4] + 8001e4a: 2b12 cmp r3, #18 + 8001e4c: d123 bne.n 8001e96 { /* Check the Alternate function parameter */ assert_param(IS_GPIO_AF(GPIO_Init->Alternate)); /* Configure Alternate function mapped with the current IO */ temp = GPIOx->AFR[position >> 3]; - 8001d86: 69fb ldr r3, [r7, #28] - 8001d88: 08da lsrs r2, r3, #3 - 8001d8a: 687b ldr r3, [r7, #4] - 8001d8c: 3208 adds r2, #8 - 8001d8e: f853 3022 ldr.w r3, [r3, r2, lsl #2] - 8001d92: 61bb str r3, [r7, #24] + 8001e4e: 69fb ldr r3, [r7, #28] + 8001e50: 08da lsrs r2, r3, #3 + 8001e52: 687b ldr r3, [r7, #4] + 8001e54: 3208 adds r2, #8 + 8001e56: f853 3022 ldr.w r3, [r3, r2, lsl #2] + 8001e5a: 61bb str r3, [r7, #24] temp &= ~((uint32_t)0xF << ((uint32_t)(position & (uint32_t)0x07) * 4)) ; - 8001d94: 69fb ldr r3, [r7, #28] - 8001d96: f003 0307 and.w r3, r3, #7 - 8001d9a: 009b lsls r3, r3, #2 - 8001d9c: 220f movs r2, #15 - 8001d9e: fa02 f303 lsl.w r3, r2, r3 - 8001da2: 43db mvns r3, r3 - 8001da4: 69ba ldr r2, [r7, #24] - 8001da6: 4013 ands r3, r2 - 8001da8: 61bb str r3, [r7, #24] + 8001e5c: 69fb ldr r3, [r7, #28] + 8001e5e: f003 0307 and.w r3, r3, #7 + 8001e62: 009b lsls r3, r3, #2 + 8001e64: 220f movs r2, #15 + 8001e66: fa02 f303 lsl.w r3, r2, r3 + 8001e6a: 43db mvns r3, r3 + 8001e6c: 69ba ldr r2, [r7, #24] + 8001e6e: 4013 ands r3, r2 + 8001e70: 61bb str r3, [r7, #24] temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & (uint32_t)0x07) * 4)); - 8001daa: 683b ldr r3, [r7, #0] - 8001dac: 691a ldr r2, [r3, #16] - 8001dae: 69fb ldr r3, [r7, #28] - 8001db0: f003 0307 and.w r3, r3, #7 - 8001db4: 009b lsls r3, r3, #2 - 8001db6: fa02 f303 lsl.w r3, r2, r3 - 8001dba: 69ba ldr r2, [r7, #24] - 8001dbc: 4313 orrs r3, r2 - 8001dbe: 61bb str r3, [r7, #24] + 8001e72: 683b ldr r3, [r7, #0] + 8001e74: 691a ldr r2, [r3, #16] + 8001e76: 69fb ldr r3, [r7, #28] + 8001e78: f003 0307 and.w r3, r3, #7 + 8001e7c: 009b lsls r3, r3, #2 + 8001e7e: fa02 f303 lsl.w r3, r2, r3 + 8001e82: 69ba ldr r2, [r7, #24] + 8001e84: 4313 orrs r3, r2 + 8001e86: 61bb str r3, [r7, #24] GPIOx->AFR[position >> 3] = temp; - 8001dc0: 69fb ldr r3, [r7, #28] - 8001dc2: 08da lsrs r2, r3, #3 - 8001dc4: 687b ldr r3, [r7, #4] - 8001dc6: 3208 adds r2, #8 - 8001dc8: 69b9 ldr r1, [r7, #24] - 8001dca: f843 1022 str.w r1, [r3, r2, lsl #2] + 8001e88: 69fb ldr r3, [r7, #28] + 8001e8a: 08da lsrs r2, r3, #3 + 8001e8c: 687b ldr r3, [r7, #4] + 8001e8e: 3208 adds r2, #8 + 8001e90: 69b9 ldr r1, [r7, #24] + 8001e92: f843 1022 str.w r1, [r3, r2, lsl #2] } /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ temp = GPIOx->MODER; - 8001dce: 687b ldr r3, [r7, #4] - 8001dd0: 681b ldr r3, [r3, #0] - 8001dd2: 61bb str r3, [r7, #24] + 8001e96: 687b ldr r3, [r7, #4] + 8001e98: 681b ldr r3, [r3, #0] + 8001e9a: 61bb str r3, [r7, #24] temp &= ~(GPIO_MODER_MODER0 << (position * 2)); - 8001dd4: 69fb ldr r3, [r7, #28] - 8001dd6: 005b lsls r3, r3, #1 - 8001dd8: 2203 movs r2, #3 - 8001dda: fa02 f303 lsl.w r3, r2, r3 - 8001dde: 43db mvns r3, r3 - 8001de0: 69ba ldr r2, [r7, #24] - 8001de2: 4013 ands r3, r2 - 8001de4: 61bb str r3, [r7, #24] + 8001e9c: 69fb ldr r3, [r7, #28] + 8001e9e: 005b lsls r3, r3, #1 + 8001ea0: 2203 movs r2, #3 + 8001ea2: fa02 f303 lsl.w r3, r2, r3 + 8001ea6: 43db mvns r3, r3 + 8001ea8: 69ba ldr r2, [r7, #24] + 8001eaa: 4013 ands r3, r2 + 8001eac: 61bb str r3, [r7, #24] temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2)); - 8001de6: 683b ldr r3, [r7, #0] - 8001de8: 685b ldr r3, [r3, #4] - 8001dea: f003 0203 and.w r2, r3, #3 - 8001dee: 69fb ldr r3, [r7, #28] - 8001df0: 005b lsls r3, r3, #1 - 8001df2: fa02 f303 lsl.w r3, r2, r3 - 8001df6: 69ba ldr r2, [r7, #24] - 8001df8: 4313 orrs r3, r2 - 8001dfa: 61bb str r3, [r7, #24] + 8001eae: 683b ldr r3, [r7, #0] + 8001eb0: 685b ldr r3, [r3, #4] + 8001eb2: f003 0203 and.w r2, r3, #3 + 8001eb6: 69fb ldr r3, [r7, #28] + 8001eb8: 005b lsls r3, r3, #1 + 8001eba: fa02 f303 lsl.w r3, r2, r3 + 8001ebe: 69ba ldr r2, [r7, #24] + 8001ec0: 4313 orrs r3, r2 + 8001ec2: 61bb str r3, [r7, #24] GPIOx->MODER = temp; - 8001dfc: 687b ldr r3, [r7, #4] - 8001dfe: 69ba ldr r2, [r7, #24] - 8001e00: 601a str r2, [r3, #0] + 8001ec4: 687b ldr r3, [r7, #4] + 8001ec6: 69ba ldr r2, [r7, #24] + 8001ec8: 601a str r2, [r3, #0] /* In case of Output or Alternate function mode selection */ if((GPIO_Init->Mode == GPIO_MODE_OUTPUT_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_PP) || - 8001e02: 683b ldr r3, [r7, #0] - 8001e04: 685b ldr r3, [r3, #4] - 8001e06: 2b01 cmp r3, #1 - 8001e08: d00b beq.n 8001e22 - 8001e0a: 683b ldr r3, [r7, #0] - 8001e0c: 685b ldr r3, [r3, #4] - 8001e0e: 2b02 cmp r3, #2 - 8001e10: d007 beq.n 8001e22 + 8001eca: 683b ldr r3, [r7, #0] + 8001ecc: 685b ldr r3, [r3, #4] + 8001ece: 2b01 cmp r3, #1 + 8001ed0: d00b beq.n 8001eea + 8001ed2: 683b ldr r3, [r7, #0] + 8001ed4: 685b ldr r3, [r3, #4] + 8001ed6: 2b02 cmp r3, #2 + 8001ed8: d007 beq.n 8001eea (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) - 8001e12: 683b ldr r3, [r7, #0] - 8001e14: 685b ldr r3, [r3, #4] + 8001eda: 683b ldr r3, [r7, #0] + 8001edc: 685b ldr r3, [r3, #4] if((GPIO_Init->Mode == GPIO_MODE_OUTPUT_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_PP) || - 8001e16: 2b11 cmp r3, #17 - 8001e18: d003 beq.n 8001e22 + 8001ede: 2b11 cmp r3, #17 + 8001ee0: d003 beq.n 8001eea (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) - 8001e1a: 683b ldr r3, [r7, #0] - 8001e1c: 685b ldr r3, [r3, #4] - 8001e1e: 2b12 cmp r3, #18 - 8001e20: d130 bne.n 8001e84 + 8001ee2: 683b ldr r3, [r7, #0] + 8001ee4: 685b ldr r3, [r3, #4] + 8001ee6: 2b12 cmp r3, #18 + 8001ee8: d130 bne.n 8001f4c { /* Check the Speed parameter */ assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); /* Configure the IO Speed */ temp = GPIOx->OSPEEDR; - 8001e22: 687b ldr r3, [r7, #4] - 8001e24: 689b ldr r3, [r3, #8] - 8001e26: 61bb str r3, [r7, #24] + 8001eea: 687b ldr r3, [r7, #4] + 8001eec: 689b ldr r3, [r3, #8] + 8001eee: 61bb str r3, [r7, #24] temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2)); - 8001e28: 69fb ldr r3, [r7, #28] - 8001e2a: 005b lsls r3, r3, #1 - 8001e2c: 2203 movs r2, #3 - 8001e2e: fa02 f303 lsl.w r3, r2, r3 - 8001e32: 43db mvns r3, r3 - 8001e34: 69ba ldr r2, [r7, #24] - 8001e36: 4013 ands r3, r2 - 8001e38: 61bb str r3, [r7, #24] + 8001ef0: 69fb ldr r3, [r7, #28] + 8001ef2: 005b lsls r3, r3, #1 + 8001ef4: 2203 movs r2, #3 + 8001ef6: fa02 f303 lsl.w r3, r2, r3 + 8001efa: 43db mvns r3, r3 + 8001efc: 69ba ldr r2, [r7, #24] + 8001efe: 4013 ands r3, r2 + 8001f00: 61bb str r3, [r7, #24] temp |= (GPIO_Init->Speed << (position * 2)); - 8001e3a: 683b ldr r3, [r7, #0] - 8001e3c: 68da ldr r2, [r3, #12] - 8001e3e: 69fb ldr r3, [r7, #28] - 8001e40: 005b lsls r3, r3, #1 - 8001e42: fa02 f303 lsl.w r3, r2, r3 - 8001e46: 69ba ldr r2, [r7, #24] - 8001e48: 4313 orrs r3, r2 - 8001e4a: 61bb str r3, [r7, #24] + 8001f02: 683b ldr r3, [r7, #0] + 8001f04: 68da ldr r2, [r3, #12] + 8001f06: 69fb ldr r3, [r7, #28] + 8001f08: 005b lsls r3, r3, #1 + 8001f0a: fa02 f303 lsl.w r3, r2, r3 + 8001f0e: 69ba ldr r2, [r7, #24] + 8001f10: 4313 orrs r3, r2 + 8001f12: 61bb str r3, [r7, #24] GPIOx->OSPEEDR = temp; - 8001e4c: 687b ldr r3, [r7, #4] - 8001e4e: 69ba ldr r2, [r7, #24] - 8001e50: 609a str r2, [r3, #8] + 8001f14: 687b ldr r3, [r7, #4] + 8001f16: 69ba ldr r2, [r7, #24] + 8001f18: 609a str r2, [r3, #8] /* Configure the IO Output Type */ temp = GPIOx->OTYPER; - 8001e52: 687b ldr r3, [r7, #4] - 8001e54: 685b ldr r3, [r3, #4] - 8001e56: 61bb str r3, [r7, #24] + 8001f1a: 687b ldr r3, [r7, #4] + 8001f1c: 685b ldr r3, [r3, #4] + 8001f1e: 61bb str r3, [r7, #24] temp &= ~(GPIO_OTYPER_OT_0 << position) ; - 8001e58: 2201 movs r2, #1 - 8001e5a: 69fb ldr r3, [r7, #28] - 8001e5c: fa02 f303 lsl.w r3, r2, r3 - 8001e60: 43db mvns r3, r3 - 8001e62: 69ba ldr r2, [r7, #24] - 8001e64: 4013 ands r3, r2 - 8001e66: 61bb str r3, [r7, #24] + 8001f20: 2201 movs r2, #1 + 8001f22: 69fb ldr r3, [r7, #28] + 8001f24: fa02 f303 lsl.w r3, r2, r3 + 8001f28: 43db mvns r3, r3 + 8001f2a: 69ba ldr r2, [r7, #24] + 8001f2c: 4013 ands r3, r2 + 8001f2e: 61bb str r3, [r7, #24] temp |= (((GPIO_Init->Mode & GPIO_OUTPUT_TYPE) >> 4) << position); - 8001e68: 683b ldr r3, [r7, #0] - 8001e6a: 685b ldr r3, [r3, #4] - 8001e6c: 091b lsrs r3, r3, #4 - 8001e6e: f003 0201 and.w r2, r3, #1 - 8001e72: 69fb ldr r3, [r7, #28] - 8001e74: fa02 f303 lsl.w r3, r2, r3 - 8001e78: 69ba ldr r2, [r7, #24] - 8001e7a: 4313 orrs r3, r2 - 8001e7c: 61bb str r3, [r7, #24] + 8001f30: 683b ldr r3, [r7, #0] + 8001f32: 685b ldr r3, [r3, #4] + 8001f34: 091b lsrs r3, r3, #4 + 8001f36: f003 0201 and.w r2, r3, #1 + 8001f3a: 69fb ldr r3, [r7, #28] + 8001f3c: fa02 f303 lsl.w r3, r2, r3 + 8001f40: 69ba ldr r2, [r7, #24] + 8001f42: 4313 orrs r3, r2 + 8001f44: 61bb str r3, [r7, #24] GPIOx->OTYPER = temp; - 8001e7e: 687b ldr r3, [r7, #4] - 8001e80: 69ba ldr r2, [r7, #24] - 8001e82: 605a str r2, [r3, #4] + 8001f46: 687b ldr r3, [r7, #4] + 8001f48: 69ba ldr r2, [r7, #24] + 8001f4a: 605a str r2, [r3, #4] } /* Activate the Pull-up or Pull down resistor for the current IO */ temp = GPIOx->PUPDR; - 8001e84: 687b ldr r3, [r7, #4] - 8001e86: 68db ldr r3, [r3, #12] - 8001e88: 61bb str r3, [r7, #24] + 8001f4c: 687b ldr r3, [r7, #4] + 8001f4e: 68db ldr r3, [r3, #12] + 8001f50: 61bb str r3, [r7, #24] temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2)); - 8001e8a: 69fb ldr r3, [r7, #28] - 8001e8c: 005b lsls r3, r3, #1 - 8001e8e: 2203 movs r2, #3 - 8001e90: fa02 f303 lsl.w r3, r2, r3 - 8001e94: 43db mvns r3, r3 - 8001e96: 69ba ldr r2, [r7, #24] - 8001e98: 4013 ands r3, r2 - 8001e9a: 61bb str r3, [r7, #24] + 8001f52: 69fb ldr r3, [r7, #28] + 8001f54: 005b lsls r3, r3, #1 + 8001f56: 2203 movs r2, #3 + 8001f58: fa02 f303 lsl.w r3, r2, r3 + 8001f5c: 43db mvns r3, r3 + 8001f5e: 69ba ldr r2, [r7, #24] + 8001f60: 4013 ands r3, r2 + 8001f62: 61bb str r3, [r7, #24] temp |= ((GPIO_Init->Pull) << (position * 2)); - 8001e9c: 683b ldr r3, [r7, #0] - 8001e9e: 689a ldr r2, [r3, #8] - 8001ea0: 69fb ldr r3, [r7, #28] - 8001ea2: 005b lsls r3, r3, #1 - 8001ea4: fa02 f303 lsl.w r3, r2, r3 - 8001ea8: 69ba ldr r2, [r7, #24] - 8001eaa: 4313 orrs r3, r2 - 8001eac: 61bb str r3, [r7, #24] + 8001f64: 683b ldr r3, [r7, #0] + 8001f66: 689a ldr r2, [r3, #8] + 8001f68: 69fb ldr r3, [r7, #28] + 8001f6a: 005b lsls r3, r3, #1 + 8001f6c: fa02 f303 lsl.w r3, r2, r3 + 8001f70: 69ba ldr r2, [r7, #24] + 8001f72: 4313 orrs r3, r2 + 8001f74: 61bb str r3, [r7, #24] GPIOx->PUPDR = temp; - 8001eae: 687b ldr r3, [r7, #4] - 8001eb0: 69ba ldr r2, [r7, #24] - 8001eb2: 60da str r2, [r3, #12] + 8001f76: 687b ldr r3, [r7, #4] + 8001f78: 69ba ldr r2, [r7, #24] + 8001f7a: 60da str r2, [r3, #12] /*--------------------- EXTI Mode Configuration ------------------------*/ /* Configure the External Interrupt or event for the current IO */ if((GPIO_Init->Mode & EXTI_MODE) == EXTI_MODE) - 8001eb4: 683b ldr r3, [r7, #0] - 8001eb6: 685b ldr r3, [r3, #4] - 8001eb8: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8001ebc: 2b00 cmp r3, #0 - 8001ebe: f000 80be beq.w 800203e + 8001f7c: 683b ldr r3, [r7, #0] + 8001f7e: 685b ldr r3, [r3, #4] + 8001f80: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8001f84: 2b00 cmp r3, #0 + 8001f86: f000 80be beq.w 8002106 { /* Enable SYSCFG Clock */ __HAL_RCC_SYSCFG_CLK_ENABLE(); - 8001ec2: 4b65 ldr r3, [pc, #404] ; (8002058 ) - 8001ec4: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001ec6: 4a64 ldr r2, [pc, #400] ; (8002058 ) - 8001ec8: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 8001ecc: 6453 str r3, [r2, #68] ; 0x44 - 8001ece: 4b62 ldr r3, [pc, #392] ; (8002058 ) - 8001ed0: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001ed2: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 8001ed6: 60fb str r3, [r7, #12] - 8001ed8: 68fb ldr r3, [r7, #12] + 8001f8a: 4b65 ldr r3, [pc, #404] ; (8002120 ) + 8001f8c: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001f8e: 4a64 ldr r2, [pc, #400] ; (8002120 ) + 8001f90: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8001f94: 6453 str r3, [r2, #68] ; 0x44 + 8001f96: 4b62 ldr r3, [pc, #392] ; (8002120 ) + 8001f98: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001f9a: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8001f9e: 60fb str r3, [r7, #12] + 8001fa0: 68fb ldr r3, [r7, #12] temp = SYSCFG->EXTICR[position >> 2]; - 8001eda: 4a60 ldr r2, [pc, #384] ; (800205c ) - 8001edc: 69fb ldr r3, [r7, #28] - 8001ede: 089b lsrs r3, r3, #2 - 8001ee0: 3302 adds r3, #2 - 8001ee2: f852 3023 ldr.w r3, [r2, r3, lsl #2] - 8001ee6: 61bb str r3, [r7, #24] + 8001fa2: 4a60 ldr r2, [pc, #384] ; (8002124 ) + 8001fa4: 69fb ldr r3, [r7, #28] + 8001fa6: 089b lsrs r3, r3, #2 + 8001fa8: 3302 adds r3, #2 + 8001faa: f852 3023 ldr.w r3, [r2, r3, lsl #2] + 8001fae: 61bb str r3, [r7, #24] temp &= ~(((uint32_t)0x0F) << (4 * (position & 0x03))); - 8001ee8: 69fb ldr r3, [r7, #28] - 8001eea: f003 0303 and.w r3, r3, #3 - 8001eee: 009b lsls r3, r3, #2 - 8001ef0: 220f movs r2, #15 - 8001ef2: fa02 f303 lsl.w r3, r2, r3 - 8001ef6: 43db mvns r3, r3 - 8001ef8: 69ba ldr r2, [r7, #24] - 8001efa: 4013 ands r3, r2 - 8001efc: 61bb str r3, [r7, #24] + 8001fb0: 69fb ldr r3, [r7, #28] + 8001fb2: f003 0303 and.w r3, r3, #3 + 8001fb6: 009b lsls r3, r3, #2 + 8001fb8: 220f movs r2, #15 + 8001fba: fa02 f303 lsl.w r3, r2, r3 + 8001fbe: 43db mvns r3, r3 + 8001fc0: 69ba ldr r2, [r7, #24] + 8001fc2: 4013 ands r3, r2 + 8001fc4: 61bb str r3, [r7, #24] temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4 * (position & 0x03))); - 8001efe: 687b ldr r3, [r7, #4] - 8001f00: 4a57 ldr r2, [pc, #348] ; (8002060 ) - 8001f02: 4293 cmp r3, r2 - 8001f04: d037 beq.n 8001f76 - 8001f06: 687b ldr r3, [r7, #4] - 8001f08: 4a56 ldr r2, [pc, #344] ; (8002064 ) - 8001f0a: 4293 cmp r3, r2 - 8001f0c: d031 beq.n 8001f72 - 8001f0e: 687b ldr r3, [r7, #4] - 8001f10: 4a55 ldr r2, [pc, #340] ; (8002068 ) - 8001f12: 4293 cmp r3, r2 - 8001f14: d02b beq.n 8001f6e - 8001f16: 687b ldr r3, [r7, #4] - 8001f18: 4a54 ldr r2, [pc, #336] ; (800206c ) - 8001f1a: 4293 cmp r3, r2 - 8001f1c: d025 beq.n 8001f6a - 8001f1e: 687b ldr r3, [r7, #4] - 8001f20: 4a53 ldr r2, [pc, #332] ; (8002070 ) - 8001f22: 4293 cmp r3, r2 - 8001f24: d01f beq.n 8001f66 - 8001f26: 687b ldr r3, [r7, #4] - 8001f28: 4a52 ldr r2, [pc, #328] ; (8002074 ) - 8001f2a: 4293 cmp r3, r2 - 8001f2c: d019 beq.n 8001f62 - 8001f2e: 687b ldr r3, [r7, #4] - 8001f30: 4a51 ldr r2, [pc, #324] ; (8002078 ) - 8001f32: 4293 cmp r3, r2 - 8001f34: d013 beq.n 8001f5e - 8001f36: 687b ldr r3, [r7, #4] - 8001f38: 4a50 ldr r2, [pc, #320] ; (800207c ) - 8001f3a: 4293 cmp r3, r2 - 8001f3c: d00d beq.n 8001f5a - 8001f3e: 687b ldr r3, [r7, #4] - 8001f40: 4a4f ldr r2, [pc, #316] ; (8002080 ) - 8001f42: 4293 cmp r3, r2 - 8001f44: d007 beq.n 8001f56 - 8001f46: 687b ldr r3, [r7, #4] - 8001f48: 4a4e ldr r2, [pc, #312] ; (8002084 ) - 8001f4a: 4293 cmp r3, r2 - 8001f4c: d101 bne.n 8001f52 - 8001f4e: 2309 movs r3, #9 - 8001f50: e012 b.n 8001f78 - 8001f52: 230a movs r3, #10 - 8001f54: e010 b.n 8001f78 - 8001f56: 2308 movs r3, #8 - 8001f58: e00e b.n 8001f78 - 8001f5a: 2307 movs r3, #7 - 8001f5c: e00c b.n 8001f78 - 8001f5e: 2306 movs r3, #6 - 8001f60: e00a b.n 8001f78 - 8001f62: 2305 movs r3, #5 - 8001f64: e008 b.n 8001f78 - 8001f66: 2304 movs r3, #4 - 8001f68: e006 b.n 8001f78 - 8001f6a: 2303 movs r3, #3 - 8001f6c: e004 b.n 8001f78 - 8001f6e: 2302 movs r3, #2 - 8001f70: e002 b.n 8001f78 - 8001f72: 2301 movs r3, #1 - 8001f74: e000 b.n 8001f78 - 8001f76: 2300 movs r3, #0 - 8001f78: 69fa ldr r2, [r7, #28] - 8001f7a: f002 0203 and.w r2, r2, #3 - 8001f7e: 0092 lsls r2, r2, #2 - 8001f80: 4093 lsls r3, r2 - 8001f82: 69ba ldr r2, [r7, #24] - 8001f84: 4313 orrs r3, r2 - 8001f86: 61bb str r3, [r7, #24] + 8001fc6: 687b ldr r3, [r7, #4] + 8001fc8: 4a57 ldr r2, [pc, #348] ; (8002128 ) + 8001fca: 4293 cmp r3, r2 + 8001fcc: d037 beq.n 800203e + 8001fce: 687b ldr r3, [r7, #4] + 8001fd0: 4a56 ldr r2, [pc, #344] ; (800212c ) + 8001fd2: 4293 cmp r3, r2 + 8001fd4: d031 beq.n 800203a + 8001fd6: 687b ldr r3, [r7, #4] + 8001fd8: 4a55 ldr r2, [pc, #340] ; (8002130 ) + 8001fda: 4293 cmp r3, r2 + 8001fdc: d02b beq.n 8002036 + 8001fde: 687b ldr r3, [r7, #4] + 8001fe0: 4a54 ldr r2, [pc, #336] ; (8002134 ) + 8001fe2: 4293 cmp r3, r2 + 8001fe4: d025 beq.n 8002032 + 8001fe6: 687b ldr r3, [r7, #4] + 8001fe8: 4a53 ldr r2, [pc, #332] ; (8002138 ) + 8001fea: 4293 cmp r3, r2 + 8001fec: d01f beq.n 800202e + 8001fee: 687b ldr r3, [r7, #4] + 8001ff0: 4a52 ldr r2, [pc, #328] ; (800213c ) + 8001ff2: 4293 cmp r3, r2 + 8001ff4: d019 beq.n 800202a + 8001ff6: 687b ldr r3, [r7, #4] + 8001ff8: 4a51 ldr r2, [pc, #324] ; (8002140 ) + 8001ffa: 4293 cmp r3, r2 + 8001ffc: d013 beq.n 8002026 + 8001ffe: 687b ldr r3, [r7, #4] + 8002000: 4a50 ldr r2, [pc, #320] ; (8002144 ) + 8002002: 4293 cmp r3, r2 + 8002004: d00d beq.n 8002022 + 8002006: 687b ldr r3, [r7, #4] + 8002008: 4a4f ldr r2, [pc, #316] ; (8002148 ) + 800200a: 4293 cmp r3, r2 + 800200c: d007 beq.n 800201e + 800200e: 687b ldr r3, [r7, #4] + 8002010: 4a4e ldr r2, [pc, #312] ; (800214c ) + 8002012: 4293 cmp r3, r2 + 8002014: d101 bne.n 800201a + 8002016: 2309 movs r3, #9 + 8002018: e012 b.n 8002040 + 800201a: 230a movs r3, #10 + 800201c: e010 b.n 8002040 + 800201e: 2308 movs r3, #8 + 8002020: e00e b.n 8002040 + 8002022: 2307 movs r3, #7 + 8002024: e00c b.n 8002040 + 8002026: 2306 movs r3, #6 + 8002028: e00a b.n 8002040 + 800202a: 2305 movs r3, #5 + 800202c: e008 b.n 8002040 + 800202e: 2304 movs r3, #4 + 8002030: e006 b.n 8002040 + 8002032: 2303 movs r3, #3 + 8002034: e004 b.n 8002040 + 8002036: 2302 movs r3, #2 + 8002038: e002 b.n 8002040 + 800203a: 2301 movs r3, #1 + 800203c: e000 b.n 8002040 + 800203e: 2300 movs r3, #0 + 8002040: 69fa ldr r2, [r7, #28] + 8002042: f002 0203 and.w r2, r2, #3 + 8002046: 0092 lsls r2, r2, #2 + 8002048: 4093 lsls r3, r2 + 800204a: 69ba ldr r2, [r7, #24] + 800204c: 4313 orrs r3, r2 + 800204e: 61bb str r3, [r7, #24] SYSCFG->EXTICR[position >> 2] = temp; - 8001f88: 4934 ldr r1, [pc, #208] ; (800205c ) - 8001f8a: 69fb ldr r3, [r7, #28] - 8001f8c: 089b lsrs r3, r3, #2 - 8001f8e: 3302 adds r3, #2 - 8001f90: 69ba ldr r2, [r7, #24] - 8001f92: f841 2023 str.w r2, [r1, r3, lsl #2] + 8002050: 4934 ldr r1, [pc, #208] ; (8002124 ) + 8002052: 69fb ldr r3, [r7, #28] + 8002054: 089b lsrs r3, r3, #2 + 8002056: 3302 adds r3, #2 + 8002058: 69ba ldr r2, [r7, #24] + 800205a: f841 2023 str.w r2, [r1, r3, lsl #2] /* Clear EXTI line configuration */ temp = EXTI->IMR; - 8001f96: 4b3c ldr r3, [pc, #240] ; (8002088 ) - 8001f98: 681b ldr r3, [r3, #0] - 8001f9a: 61bb str r3, [r7, #24] + 800205e: 4b3c ldr r3, [pc, #240] ; (8002150 ) + 8002060: 681b ldr r3, [r3, #0] + 8002062: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 8001f9c: 693b ldr r3, [r7, #16] - 8001f9e: 43db mvns r3, r3 - 8001fa0: 69ba ldr r2, [r7, #24] - 8001fa2: 4013 ands r3, r2 - 8001fa4: 61bb str r3, [r7, #24] + 8002064: 693b ldr r3, [r7, #16] + 8002066: 43db mvns r3, r3 + 8002068: 69ba ldr r2, [r7, #24] + 800206a: 4013 ands r3, r2 + 800206c: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & GPIO_MODE_IT) == GPIO_MODE_IT) - 8001fa6: 683b ldr r3, [r7, #0] - 8001fa8: 685b ldr r3, [r3, #4] - 8001faa: f403 3380 and.w r3, r3, #65536 ; 0x10000 - 8001fae: 2b00 cmp r3, #0 - 8001fb0: d003 beq.n 8001fba + 800206e: 683b ldr r3, [r7, #0] + 8002070: 685b ldr r3, [r3, #4] + 8002072: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 8002076: 2b00 cmp r3, #0 + 8002078: d003 beq.n 8002082 { temp |= iocurrent; - 8001fb2: 69ba ldr r2, [r7, #24] - 8001fb4: 693b ldr r3, [r7, #16] - 8001fb6: 4313 orrs r3, r2 - 8001fb8: 61bb str r3, [r7, #24] + 800207a: 69ba ldr r2, [r7, #24] + 800207c: 693b ldr r3, [r7, #16] + 800207e: 4313 orrs r3, r2 + 8002080: 61bb str r3, [r7, #24] } EXTI->IMR = temp; - 8001fba: 4a33 ldr r2, [pc, #204] ; (8002088 ) - 8001fbc: 69bb ldr r3, [r7, #24] - 8001fbe: 6013 str r3, [r2, #0] + 8002082: 4a33 ldr r2, [pc, #204] ; (8002150 ) + 8002084: 69bb ldr r3, [r7, #24] + 8002086: 6013 str r3, [r2, #0] temp = EXTI->EMR; - 8001fc0: 4b31 ldr r3, [pc, #196] ; (8002088 ) - 8001fc2: 685b ldr r3, [r3, #4] - 8001fc4: 61bb str r3, [r7, #24] + 8002088: 4b31 ldr r3, [pc, #196] ; (8002150 ) + 800208a: 685b ldr r3, [r3, #4] + 800208c: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 8001fc6: 693b ldr r3, [r7, #16] - 8001fc8: 43db mvns r3, r3 - 8001fca: 69ba ldr r2, [r7, #24] - 8001fcc: 4013 ands r3, r2 - 8001fce: 61bb str r3, [r7, #24] + 800208e: 693b ldr r3, [r7, #16] + 8002090: 43db mvns r3, r3 + 8002092: 69ba ldr r2, [r7, #24] + 8002094: 4013 ands r3, r2 + 8002096: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & GPIO_MODE_EVT) == GPIO_MODE_EVT) - 8001fd0: 683b ldr r3, [r7, #0] - 8001fd2: 685b ldr r3, [r3, #4] - 8001fd4: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8001fd8: 2b00 cmp r3, #0 - 8001fda: d003 beq.n 8001fe4 + 8002098: 683b ldr r3, [r7, #0] + 800209a: 685b ldr r3, [r3, #4] + 800209c: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80020a0: 2b00 cmp r3, #0 + 80020a2: d003 beq.n 80020ac { temp |= iocurrent; - 8001fdc: 69ba ldr r2, [r7, #24] - 8001fde: 693b ldr r3, [r7, #16] - 8001fe0: 4313 orrs r3, r2 - 8001fe2: 61bb str r3, [r7, #24] + 80020a4: 69ba ldr r2, [r7, #24] + 80020a6: 693b ldr r3, [r7, #16] + 80020a8: 4313 orrs r3, r2 + 80020aa: 61bb str r3, [r7, #24] } EXTI->EMR = temp; - 8001fe4: 4a28 ldr r2, [pc, #160] ; (8002088 ) - 8001fe6: 69bb ldr r3, [r7, #24] - 8001fe8: 6053 str r3, [r2, #4] + 80020ac: 4a28 ldr r2, [pc, #160] ; (8002150 ) + 80020ae: 69bb ldr r3, [r7, #24] + 80020b0: 6053 str r3, [r2, #4] /* Clear Rising Falling edge configuration */ temp = EXTI->RTSR; - 8001fea: 4b27 ldr r3, [pc, #156] ; (8002088 ) - 8001fec: 689b ldr r3, [r3, #8] - 8001fee: 61bb str r3, [r7, #24] + 80020b2: 4b27 ldr r3, [pc, #156] ; (8002150 ) + 80020b4: 689b ldr r3, [r3, #8] + 80020b6: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 8001ff0: 693b ldr r3, [r7, #16] - 8001ff2: 43db mvns r3, r3 - 8001ff4: 69ba ldr r2, [r7, #24] - 8001ff6: 4013 ands r3, r2 - 8001ff8: 61bb str r3, [r7, #24] + 80020b8: 693b ldr r3, [r7, #16] + 80020ba: 43db mvns r3, r3 + 80020bc: 69ba ldr r2, [r7, #24] + 80020be: 4013 ands r3, r2 + 80020c0: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & RISING_EDGE) == RISING_EDGE) - 8001ffa: 683b ldr r3, [r7, #0] - 8001ffc: 685b ldr r3, [r3, #4] - 8001ffe: f403 1380 and.w r3, r3, #1048576 ; 0x100000 - 8002002: 2b00 cmp r3, #0 - 8002004: d003 beq.n 800200e + 80020c2: 683b ldr r3, [r7, #0] + 80020c4: 685b ldr r3, [r3, #4] + 80020c6: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 80020ca: 2b00 cmp r3, #0 + 80020cc: d003 beq.n 80020d6 { temp |= iocurrent; - 8002006: 69ba ldr r2, [r7, #24] - 8002008: 693b ldr r3, [r7, #16] - 800200a: 4313 orrs r3, r2 - 800200c: 61bb str r3, [r7, #24] + 80020ce: 69ba ldr r2, [r7, #24] + 80020d0: 693b ldr r3, [r7, #16] + 80020d2: 4313 orrs r3, r2 + 80020d4: 61bb str r3, [r7, #24] } EXTI->RTSR = temp; - 800200e: 4a1e ldr r2, [pc, #120] ; (8002088 ) - 8002010: 69bb ldr r3, [r7, #24] - 8002012: 6093 str r3, [r2, #8] + 80020d6: 4a1e ldr r2, [pc, #120] ; (8002150 ) + 80020d8: 69bb ldr r3, [r7, #24] + 80020da: 6093 str r3, [r2, #8] temp = EXTI->FTSR; - 8002014: 4b1c ldr r3, [pc, #112] ; (8002088 ) - 8002016: 68db ldr r3, [r3, #12] - 8002018: 61bb str r3, [r7, #24] + 80020dc: 4b1c ldr r3, [pc, #112] ; (8002150 ) + 80020de: 68db ldr r3, [r3, #12] + 80020e0: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 800201a: 693b ldr r3, [r7, #16] - 800201c: 43db mvns r3, r3 - 800201e: 69ba ldr r2, [r7, #24] - 8002020: 4013 ands r3, r2 - 8002022: 61bb str r3, [r7, #24] + 80020e2: 693b ldr r3, [r7, #16] + 80020e4: 43db mvns r3, r3 + 80020e6: 69ba ldr r2, [r7, #24] + 80020e8: 4013 ands r3, r2 + 80020ea: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & FALLING_EDGE) == FALLING_EDGE) - 8002024: 683b ldr r3, [r7, #0] - 8002026: 685b ldr r3, [r3, #4] - 8002028: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 800202c: 2b00 cmp r3, #0 - 800202e: d003 beq.n 8002038 + 80020ec: 683b ldr r3, [r7, #0] + 80020ee: 685b ldr r3, [r3, #4] + 80020f0: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 80020f4: 2b00 cmp r3, #0 + 80020f6: d003 beq.n 8002100 { temp |= iocurrent; - 8002030: 69ba ldr r2, [r7, #24] - 8002032: 693b ldr r3, [r7, #16] - 8002034: 4313 orrs r3, r2 - 8002036: 61bb str r3, [r7, #24] + 80020f8: 69ba ldr r2, [r7, #24] + 80020fa: 693b ldr r3, [r7, #16] + 80020fc: 4313 orrs r3, r2 + 80020fe: 61bb str r3, [r7, #24] } EXTI->FTSR = temp; - 8002038: 4a13 ldr r2, [pc, #76] ; (8002088 ) - 800203a: 69bb ldr r3, [r7, #24] - 800203c: 60d3 str r3, [r2, #12] + 8002100: 4a13 ldr r2, [pc, #76] ; (8002150 ) + 8002102: 69bb ldr r3, [r7, #24] + 8002104: 60d3 str r3, [r2, #12] for(position = 0; position < GPIO_NUMBER; position++) - 800203e: 69fb ldr r3, [r7, #28] - 8002040: 3301 adds r3, #1 - 8002042: 61fb str r3, [r7, #28] - 8002044: 69fb ldr r3, [r7, #28] - 8002046: 2b0f cmp r3, #15 - 8002048: f67f ae86 bls.w 8001d58 + 8002106: 69fb ldr r3, [r7, #28] + 8002108: 3301 adds r3, #1 + 800210a: 61fb str r3, [r7, #28] + 800210c: 69fb ldr r3, [r7, #28] + 800210e: 2b0f cmp r3, #15 + 8002110: f67f ae86 bls.w 8001e20 } } } } - 800204c: bf00 nop - 800204e: 3724 adds r7, #36 ; 0x24 - 8002050: 46bd mov sp, r7 - 8002052: f85d 7b04 ldr.w r7, [sp], #4 - 8002056: 4770 bx lr - 8002058: 40023800 .word 0x40023800 - 800205c: 40013800 .word 0x40013800 - 8002060: 40020000 .word 0x40020000 - 8002064: 40020400 .word 0x40020400 - 8002068: 40020800 .word 0x40020800 - 800206c: 40020c00 .word 0x40020c00 - 8002070: 40021000 .word 0x40021000 - 8002074: 40021400 .word 0x40021400 - 8002078: 40021800 .word 0x40021800 - 800207c: 40021c00 .word 0x40021c00 - 8002080: 40022000 .word 0x40022000 - 8002084: 40022400 .word 0x40022400 - 8002088: 40013c00 .word 0x40013c00 - -0800208c : + 8002114: bf00 nop + 8002116: 3724 adds r7, #36 ; 0x24 + 8002118: 46bd mov sp, r7 + 800211a: f85d 7b04 ldr.w r7, [sp], #4 + 800211e: 4770 bx lr + 8002120: 40023800 .word 0x40023800 + 8002124: 40013800 .word 0x40013800 + 8002128: 40020000 .word 0x40020000 + 800212c: 40020400 .word 0x40020400 + 8002130: 40020800 .word 0x40020800 + 8002134: 40020c00 .word 0x40020c00 + 8002138: 40021000 .word 0x40021000 + 800213c: 40021400 .word 0x40021400 + 8002140: 40021800 .word 0x40021800 + 8002144: 40021c00 .word 0x40021c00 + 8002148: 40022000 .word 0x40022000 + 800214c: 40022400 .word 0x40022400 + 8002150: 40013c00 .word 0x40013c00 + +08002154 : * @arg GPIO_PIN_RESET: to clear the port pin * @arg GPIO_PIN_SET: to set the port pin * @retval None */ void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState) { - 800208c: b480 push {r7} - 800208e: b083 sub sp, #12 - 8002090: af00 add r7, sp, #0 - 8002092: 6078 str r0, [r7, #4] - 8002094: 460b mov r3, r1 - 8002096: 807b strh r3, [r7, #2] - 8002098: 4613 mov r3, r2 - 800209a: 707b strb r3, [r7, #1] + 8002154: b480 push {r7} + 8002156: b083 sub sp, #12 + 8002158: af00 add r7, sp, #0 + 800215a: 6078 str r0, [r7, #4] + 800215c: 460b mov r3, r1 + 800215e: 807b strh r3, [r7, #2] + 8002160: 4613 mov r3, r2 + 8002162: 707b strb r3, [r7, #1] /* Check the parameters */ assert_param(IS_GPIO_PIN(GPIO_Pin)); assert_param(IS_GPIO_PIN_ACTION(PinState)); if(PinState != GPIO_PIN_RESET) - 800209c: 787b ldrb r3, [r7, #1] - 800209e: 2b00 cmp r3, #0 - 80020a0: d003 beq.n 80020aa + 8002164: 787b ldrb r3, [r7, #1] + 8002166: 2b00 cmp r3, #0 + 8002168: d003 beq.n 8002172 { GPIOx->BSRR = GPIO_Pin; - 80020a2: 887a ldrh r2, [r7, #2] - 80020a4: 687b ldr r3, [r7, #4] - 80020a6: 619a str r2, [r3, #24] + 800216a: 887a ldrh r2, [r7, #2] + 800216c: 687b ldr r3, [r7, #4] + 800216e: 619a str r2, [r3, #24] } else { GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; } } - 80020a8: e003 b.n 80020b2 + 8002170: e003 b.n 800217a GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; - 80020aa: 887b ldrh r3, [r7, #2] - 80020ac: 041a lsls r2, r3, #16 - 80020ae: 687b ldr r3, [r7, #4] - 80020b0: 619a str r2, [r3, #24] + 8002172: 887b ldrh r3, [r7, #2] + 8002174: 041a lsls r2, r3, #16 + 8002176: 687b ldr r3, [r7, #4] + 8002178: 619a str r2, [r3, #24] } - 80020b2: bf00 nop - 80020b4: 370c adds r7, #12 - 80020b6: 46bd mov sp, r7 - 80020b8: f85d 7b04 ldr.w r7, [sp], #4 - 80020bc: 4770 bx lr + 800217a: bf00 nop + 800217c: 370c adds r7, #12 + 800217e: 46bd mov sp, r7 + 8002180: f85d 7b04 ldr.w r7, [sp], #4 + 8002184: 4770 bx lr ... -080020c0 : +08002188 : * @brief This function handles EXTI interrupt request. * @param GPIO_Pin Specifies the pins connected EXTI line * @retval None */ void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) { - 80020c0: b580 push {r7, lr} - 80020c2: b082 sub sp, #8 - 80020c4: af00 add r7, sp, #0 - 80020c6: 4603 mov r3, r0 - 80020c8: 80fb strh r3, [r7, #6] + 8002188: b580 push {r7, lr} + 800218a: b082 sub sp, #8 + 800218c: af00 add r7, sp, #0 + 800218e: 4603 mov r3, r0 + 8002190: 80fb strh r3, [r7, #6] /* EXTI line interrupt detected */ if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) - 80020ca: 4b08 ldr r3, [pc, #32] ; (80020ec ) - 80020cc: 695a ldr r2, [r3, #20] - 80020ce: 88fb ldrh r3, [r7, #6] - 80020d0: 4013 ands r3, r2 - 80020d2: 2b00 cmp r3, #0 - 80020d4: d006 beq.n 80020e4 + 8002192: 4b08 ldr r3, [pc, #32] ; (80021b4 ) + 8002194: 695a ldr r2, [r3, #20] + 8002196: 88fb ldrh r3, [r7, #6] + 8002198: 4013 ands r3, r2 + 800219a: 2b00 cmp r3, #0 + 800219c: d006 beq.n 80021ac { __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); - 80020d6: 4a05 ldr r2, [pc, #20] ; (80020ec ) - 80020d8: 88fb ldrh r3, [r7, #6] - 80020da: 6153 str r3, [r2, #20] + 800219e: 4a05 ldr r2, [pc, #20] ; (80021b4 ) + 80021a0: 88fb ldrh r3, [r7, #6] + 80021a2: 6153 str r3, [r2, #20] HAL_GPIO_EXTI_Callback(GPIO_Pin); - 80020dc: 88fb ldrh r3, [r7, #6] - 80020de: 4618 mov r0, r3 - 80020e0: f7ff f9ae bl 8001440 + 80021a4: 88fb ldrh r3, [r7, #6] + 80021a6: 4618 mov r0, r3 + 80021a8: f7ff f9cc bl 8001544 } } - 80020e4: bf00 nop - 80020e6: 3708 adds r7, #8 - 80020e8: 46bd mov sp, r7 - 80020ea: bd80 pop {r7, pc} - 80020ec: 40013c00 .word 0x40013c00 + 80021ac: bf00 nop + 80021ae: 3708 adds r7, #8 + 80021b0: 46bd mov sp, r7 + 80021b2: bd80 pop {r7, pc} + 80021b4: 40013c00 .word 0x40013c00 -080020f0 : +080021b8 : * supported by this function. User should request a transition to HSE Off * first and then HSE On or HSE Bypass. * @retval HAL status */ HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) { - 80020f0: b580 push {r7, lr} - 80020f2: b086 sub sp, #24 - 80020f4: af00 add r7, sp, #0 - 80020f6: 6078 str r0, [r7, #4] + 80021b8: b580 push {r7, lr} + 80021ba: b086 sub sp, #24 + 80021bc: af00 add r7, sp, #0 + 80021be: 6078 str r0, [r7, #4] uint32_t tickstart; FlagStatus pwrclkchanged = RESET; - 80020f8: 2300 movs r3, #0 - 80020fa: 75fb strb r3, [r7, #23] + 80021c0: 2300 movs r3, #0 + 80021c2: 75fb strb r3, [r7, #23] /* Check Null pointer */ if(RCC_OscInitStruct == NULL) - 80020fc: 687b ldr r3, [r7, #4] - 80020fe: 2b00 cmp r3, #0 - 8002100: d101 bne.n 8002106 + 80021c4: 687b ldr r3, [r7, #4] + 80021c6: 2b00 cmp r3, #0 + 80021c8: d101 bne.n 80021ce { return HAL_ERROR; - 8002102: 2301 movs r3, #1 - 8002104: e25e b.n 80025c4 + 80021ca: 2301 movs r3, #1 + 80021cc: e25e b.n 800268c /* Check the parameters */ assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); /*------------------------------- HSE Configuration ------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - 8002106: 687b ldr r3, [r7, #4] - 8002108: 681b ldr r3, [r3, #0] - 800210a: f003 0301 and.w r3, r3, #1 - 800210e: 2b00 cmp r3, #0 - 8002110: f000 8087 beq.w 8002222 + 80021ce: 687b ldr r3, [r7, #4] + 80021d0: 681b ldr r3, [r3, #0] + 80021d2: f003 0301 and.w r3, r3, #1 + 80021d6: 2b00 cmp r3, #0 + 80021d8: f000 8087 beq.w 80022ea { /* Check the parameters */ assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); /* When the HSE is used as system clock or clock source for PLL, It can not be disabled */ if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSE) - 8002114: 4b96 ldr r3, [pc, #600] ; (8002370 ) - 8002116: 689b ldr r3, [r3, #8] - 8002118: f003 030c and.w r3, r3, #12 - 800211c: 2b04 cmp r3, #4 - 800211e: d00c beq.n 800213a + 80021dc: 4b96 ldr r3, [pc, #600] ; (8002438 ) + 80021de: 689b ldr r3, [r3, #8] + 80021e0: f003 030c and.w r3, r3, #12 + 80021e4: 2b04 cmp r3, #4 + 80021e6: d00c beq.n 8002202 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) - 8002120: 4b93 ldr r3, [pc, #588] ; (8002370 ) - 8002122: 689b ldr r3, [r3, #8] - 8002124: f003 030c and.w r3, r3, #12 - 8002128: 2b08 cmp r3, #8 - 800212a: d112 bne.n 8002152 - 800212c: 4b90 ldr r3, [pc, #576] ; (8002370 ) - 800212e: 685b ldr r3, [r3, #4] - 8002130: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 8002134: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 8002138: d10b bne.n 8002152 + 80021e8: 4b93 ldr r3, [pc, #588] ; (8002438 ) + 80021ea: 689b ldr r3, [r3, #8] + 80021ec: f003 030c and.w r3, r3, #12 + 80021f0: 2b08 cmp r3, #8 + 80021f2: d112 bne.n 800221a + 80021f4: 4b90 ldr r3, [pc, #576] ; (8002438 ) + 80021f6: 685b ldr r3, [r3, #4] + 80021f8: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 80021fc: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002200: d10b bne.n 800221a { if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - 800213a: 4b8d ldr r3, [pc, #564] ; (8002370 ) - 800213c: 681b ldr r3, [r3, #0] - 800213e: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8002142: 2b00 cmp r3, #0 - 8002144: d06c beq.n 8002220 - 8002146: 687b ldr r3, [r7, #4] - 8002148: 685b ldr r3, [r3, #4] - 800214a: 2b00 cmp r3, #0 - 800214c: d168 bne.n 8002220 + 8002202: 4b8d ldr r3, [pc, #564] ; (8002438 ) + 8002204: 681b ldr r3, [r3, #0] + 8002206: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800220a: 2b00 cmp r3, #0 + 800220c: d06c beq.n 80022e8 + 800220e: 687b ldr r3, [r7, #4] + 8002210: 685b ldr r3, [r3, #4] + 8002212: 2b00 cmp r3, #0 + 8002214: d168 bne.n 80022e8 { return HAL_ERROR; - 800214e: 2301 movs r3, #1 - 8002150: e238 b.n 80025c4 + 8002216: 2301 movs r3, #1 + 8002218: e238 b.n 800268c } } else { /* Set the new HSE configuration ---------------------------------------*/ __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - 8002152: 687b ldr r3, [r7, #4] - 8002154: 685b ldr r3, [r3, #4] - 8002156: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 800215a: d106 bne.n 800216a - 800215c: 4b84 ldr r3, [pc, #528] ; (8002370 ) - 800215e: 681b ldr r3, [r3, #0] - 8002160: 4a83 ldr r2, [pc, #524] ; (8002370 ) - 8002162: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 8002166: 6013 str r3, [r2, #0] - 8002168: e02e b.n 80021c8 - 800216a: 687b ldr r3, [r7, #4] - 800216c: 685b ldr r3, [r3, #4] - 800216e: 2b00 cmp r3, #0 - 8002170: d10c bne.n 800218c - 8002172: 4b7f ldr r3, [pc, #508] ; (8002370 ) - 8002174: 681b ldr r3, [r3, #0] - 8002176: 4a7e ldr r2, [pc, #504] ; (8002370 ) - 8002178: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 800217c: 6013 str r3, [r2, #0] - 800217e: 4b7c ldr r3, [pc, #496] ; (8002370 ) - 8002180: 681b ldr r3, [r3, #0] - 8002182: 4a7b ldr r2, [pc, #492] ; (8002370 ) - 8002184: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 8002188: 6013 str r3, [r2, #0] - 800218a: e01d b.n 80021c8 - 800218c: 687b ldr r3, [r7, #4] - 800218e: 685b ldr r3, [r3, #4] - 8002190: f5b3 2fa0 cmp.w r3, #327680 ; 0x50000 - 8002194: d10c bne.n 80021b0 - 8002196: 4b76 ldr r3, [pc, #472] ; (8002370 ) - 8002198: 681b ldr r3, [r3, #0] - 800219a: 4a75 ldr r2, [pc, #468] ; (8002370 ) - 800219c: f443 2380 orr.w r3, r3, #262144 ; 0x40000 - 80021a0: 6013 str r3, [r2, #0] - 80021a2: 4b73 ldr r3, [pc, #460] ; (8002370 ) - 80021a4: 681b ldr r3, [r3, #0] - 80021a6: 4a72 ldr r2, [pc, #456] ; (8002370 ) - 80021a8: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 80021ac: 6013 str r3, [r2, #0] - 80021ae: e00b b.n 80021c8 - 80021b0: 4b6f ldr r3, [pc, #444] ; (8002370 ) - 80021b2: 681b ldr r3, [r3, #0] - 80021b4: 4a6e ldr r2, [pc, #440] ; (8002370 ) - 80021b6: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 80021ba: 6013 str r3, [r2, #0] - 80021bc: 4b6c ldr r3, [pc, #432] ; (8002370 ) - 80021be: 681b ldr r3, [r3, #0] - 80021c0: 4a6b ldr r2, [pc, #428] ; (8002370 ) - 80021c2: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 80021c6: 6013 str r3, [r2, #0] + 800221a: 687b ldr r3, [r7, #4] + 800221c: 685b ldr r3, [r3, #4] + 800221e: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8002222: d106 bne.n 8002232 + 8002224: 4b84 ldr r3, [pc, #528] ; (8002438 ) + 8002226: 681b ldr r3, [r3, #0] + 8002228: 4a83 ldr r2, [pc, #524] ; (8002438 ) + 800222a: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 800222e: 6013 str r3, [r2, #0] + 8002230: e02e b.n 8002290 + 8002232: 687b ldr r3, [r7, #4] + 8002234: 685b ldr r3, [r3, #4] + 8002236: 2b00 cmp r3, #0 + 8002238: d10c bne.n 8002254 + 800223a: 4b7f ldr r3, [pc, #508] ; (8002438 ) + 800223c: 681b ldr r3, [r3, #0] + 800223e: 4a7e ldr r2, [pc, #504] ; (8002438 ) + 8002240: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002244: 6013 str r3, [r2, #0] + 8002246: 4b7c ldr r3, [pc, #496] ; (8002438 ) + 8002248: 681b ldr r3, [r3, #0] + 800224a: 4a7b ldr r2, [pc, #492] ; (8002438 ) + 800224c: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8002250: 6013 str r3, [r2, #0] + 8002252: e01d b.n 8002290 + 8002254: 687b ldr r3, [r7, #4] + 8002256: 685b ldr r3, [r3, #4] + 8002258: f5b3 2fa0 cmp.w r3, #327680 ; 0x50000 + 800225c: d10c bne.n 8002278 + 800225e: 4b76 ldr r3, [pc, #472] ; (8002438 ) + 8002260: 681b ldr r3, [r3, #0] + 8002262: 4a75 ldr r2, [pc, #468] ; (8002438 ) + 8002264: f443 2380 orr.w r3, r3, #262144 ; 0x40000 + 8002268: 6013 str r3, [r2, #0] + 800226a: 4b73 ldr r3, [pc, #460] ; (8002438 ) + 800226c: 681b ldr r3, [r3, #0] + 800226e: 4a72 ldr r2, [pc, #456] ; (8002438 ) + 8002270: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 8002274: 6013 str r3, [r2, #0] + 8002276: e00b b.n 8002290 + 8002278: 4b6f ldr r3, [pc, #444] ; (8002438 ) + 800227a: 681b ldr r3, [r3, #0] + 800227c: 4a6e ldr r2, [pc, #440] ; (8002438 ) + 800227e: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002282: 6013 str r3, [r2, #0] + 8002284: 4b6c ldr r3, [pc, #432] ; (8002438 ) + 8002286: 681b ldr r3, [r3, #0] + 8002288: 4a6b ldr r2, [pc, #428] ; (8002438 ) + 800228a: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 800228e: 6013 str r3, [r2, #0] /* Check the HSE State */ if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF) - 80021c8: 687b ldr r3, [r7, #4] - 80021ca: 685b ldr r3, [r3, #4] - 80021cc: 2b00 cmp r3, #0 - 80021ce: d013 beq.n 80021f8 + 8002290: 687b ldr r3, [r7, #4] + 8002292: 685b ldr r3, [r3, #4] + 8002294: 2b00 cmp r3, #0 + 8002296: d013 beq.n 80022c0 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80021d0: f7ff fc72 bl 8001ab8 - 80021d4: 6138 str r0, [r7, #16] + 8002298: f7ff fc72 bl 8001b80 + 800229c: 6138 str r0, [r7, #16] /* Wait till HSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 80021d6: e008 b.n 80021ea + 800229e: e008 b.n 80022b2 { if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - 80021d8: f7ff fc6e bl 8001ab8 - 80021dc: 4602 mov r2, r0 - 80021de: 693b ldr r3, [r7, #16] - 80021e0: 1ad3 subs r3, r2, r3 - 80021e2: 2b64 cmp r3, #100 ; 0x64 - 80021e4: d901 bls.n 80021ea + 80022a0: f7ff fc6e bl 8001b80 + 80022a4: 4602 mov r2, r0 + 80022a6: 693b ldr r3, [r7, #16] + 80022a8: 1ad3 subs r3, r2, r3 + 80022aa: 2b64 cmp r3, #100 ; 0x64 + 80022ac: d901 bls.n 80022b2 { return HAL_TIMEOUT; - 80021e6: 2303 movs r3, #3 - 80021e8: e1ec b.n 80025c4 + 80022ae: 2303 movs r3, #3 + 80022b0: e1ec b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 80021ea: 4b61 ldr r3, [pc, #388] ; (8002370 ) - 80021ec: 681b ldr r3, [r3, #0] - 80021ee: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 80021f2: 2b00 cmp r3, #0 - 80021f4: d0f0 beq.n 80021d8 - 80021f6: e014 b.n 8002222 + 80022b2: 4b61 ldr r3, [pc, #388] ; (8002438 ) + 80022b4: 681b ldr r3, [r3, #0] + 80022b6: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80022ba: 2b00 cmp r3, #0 + 80022bc: d0f0 beq.n 80022a0 + 80022be: e014 b.n 80022ea } } else { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80021f8: f7ff fc5e bl 8001ab8 - 80021fc: 6138 str r0, [r7, #16] + 80022c0: f7ff fc5e bl 8001b80 + 80022c4: 6138 str r0, [r7, #16] /* Wait till HSE is bypassed or disabled */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - 80021fe: e008 b.n 8002212 + 80022c6: e008 b.n 80022da { if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - 8002200: f7ff fc5a bl 8001ab8 - 8002204: 4602 mov r2, r0 - 8002206: 693b ldr r3, [r7, #16] - 8002208: 1ad3 subs r3, r2, r3 - 800220a: 2b64 cmp r3, #100 ; 0x64 - 800220c: d901 bls.n 8002212 + 80022c8: f7ff fc5a bl 8001b80 + 80022cc: 4602 mov r2, r0 + 80022ce: 693b ldr r3, [r7, #16] + 80022d0: 1ad3 subs r3, r2, r3 + 80022d2: 2b64 cmp r3, #100 ; 0x64 + 80022d4: d901 bls.n 80022da { return HAL_TIMEOUT; - 800220e: 2303 movs r3, #3 - 8002210: e1d8 b.n 80025c4 + 80022d6: 2303 movs r3, #3 + 80022d8: e1d8 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - 8002212: 4b57 ldr r3, [pc, #348] ; (8002370 ) - 8002214: 681b ldr r3, [r3, #0] - 8002216: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 800221a: 2b00 cmp r3, #0 - 800221c: d1f0 bne.n 8002200 - 800221e: e000 b.n 8002222 + 80022da: 4b57 ldr r3, [pc, #348] ; (8002438 ) + 80022dc: 681b ldr r3, [r3, #0] + 80022de: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80022e2: 2b00 cmp r3, #0 + 80022e4: d1f0 bne.n 80022c8 + 80022e6: e000 b.n 80022ea if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - 8002220: bf00 nop + 80022e8: bf00 nop } } } } /*----------------------------- HSI Configuration --------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - 8002222: 687b ldr r3, [r7, #4] - 8002224: 681b ldr r3, [r3, #0] - 8002226: f003 0302 and.w r3, r3, #2 - 800222a: 2b00 cmp r3, #0 - 800222c: d069 beq.n 8002302 + 80022ea: 687b ldr r3, [r7, #4] + 80022ec: 681b ldr r3, [r3, #0] + 80022ee: f003 0302 and.w r3, r3, #2 + 80022f2: 2b00 cmp r3, #0 + 80022f4: d069 beq.n 80023ca /* Check the parameters */ assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSI) - 800222e: 4b50 ldr r3, [pc, #320] ; (8002370 ) - 8002230: 689b ldr r3, [r3, #8] - 8002232: f003 030c and.w r3, r3, #12 - 8002236: 2b00 cmp r3, #0 - 8002238: d00b beq.n 8002252 + 80022f6: 4b50 ldr r3, [pc, #320] ; (8002438 ) + 80022f8: 689b ldr r3, [r3, #8] + 80022fa: f003 030c and.w r3, r3, #12 + 80022fe: 2b00 cmp r3, #0 + 8002300: d00b beq.n 800231a || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) - 800223a: 4b4d ldr r3, [pc, #308] ; (8002370 ) - 800223c: 689b ldr r3, [r3, #8] - 800223e: f003 030c and.w r3, r3, #12 - 8002242: 2b08 cmp r3, #8 - 8002244: d11c bne.n 8002280 - 8002246: 4b4a ldr r3, [pc, #296] ; (8002370 ) - 8002248: 685b ldr r3, [r3, #4] - 800224a: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 800224e: 2b00 cmp r3, #0 - 8002250: d116 bne.n 8002280 + 8002302: 4b4d ldr r3, [pc, #308] ; (8002438 ) + 8002304: 689b ldr r3, [r3, #8] + 8002306: f003 030c and.w r3, r3, #12 + 800230a: 2b08 cmp r3, #8 + 800230c: d11c bne.n 8002348 + 800230e: 4b4a ldr r3, [pc, #296] ; (8002438 ) + 8002310: 685b ldr r3, [r3, #4] + 8002312: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002316: 2b00 cmp r3, #0 + 8002318: d116 bne.n 8002348 { /* When HSI is used as system clock it will not disabled */ if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - 8002252: 4b47 ldr r3, [pc, #284] ; (8002370 ) - 8002254: 681b ldr r3, [r3, #0] - 8002256: f003 0302 and.w r3, r3, #2 - 800225a: 2b00 cmp r3, #0 - 800225c: d005 beq.n 800226a - 800225e: 687b ldr r3, [r7, #4] - 8002260: 68db ldr r3, [r3, #12] - 8002262: 2b01 cmp r3, #1 - 8002264: d001 beq.n 800226a + 800231a: 4b47 ldr r3, [pc, #284] ; (8002438 ) + 800231c: 681b ldr r3, [r3, #0] + 800231e: f003 0302 and.w r3, r3, #2 + 8002322: 2b00 cmp r3, #0 + 8002324: d005 beq.n 8002332 + 8002326: 687b ldr r3, [r7, #4] + 8002328: 68db ldr r3, [r3, #12] + 800232a: 2b01 cmp r3, #1 + 800232c: d001 beq.n 8002332 { return HAL_ERROR; - 8002266: 2301 movs r3, #1 - 8002268: e1ac b.n 80025c4 + 800232e: 2301 movs r3, #1 + 8002330: e1ac b.n 800268c } /* Otherwise, just the calibration is allowed */ else { /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - 800226a: 4b41 ldr r3, [pc, #260] ; (8002370 ) - 800226c: 681b ldr r3, [r3, #0] - 800226e: f023 02f8 bic.w r2, r3, #248 ; 0xf8 - 8002272: 687b ldr r3, [r7, #4] - 8002274: 691b ldr r3, [r3, #16] - 8002276: 00db lsls r3, r3, #3 - 8002278: 493d ldr r1, [pc, #244] ; (8002370 ) - 800227a: 4313 orrs r3, r2 - 800227c: 600b str r3, [r1, #0] + 8002332: 4b41 ldr r3, [pc, #260] ; (8002438 ) + 8002334: 681b ldr r3, [r3, #0] + 8002336: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 800233a: 687b ldr r3, [r7, #4] + 800233c: 691b ldr r3, [r3, #16] + 800233e: 00db lsls r3, r3, #3 + 8002340: 493d ldr r1, [pc, #244] ; (8002438 ) + 8002342: 4313 orrs r3, r2 + 8002344: 600b str r3, [r1, #0] if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - 800227e: e040 b.n 8002302 + 8002346: e040 b.n 80023ca } } else { /* Check the HSI State */ if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - 8002280: 687b ldr r3, [r7, #4] - 8002282: 68db ldr r3, [r3, #12] - 8002284: 2b00 cmp r3, #0 - 8002286: d023 beq.n 80022d0 + 8002348: 687b ldr r3, [r7, #4] + 800234a: 68db ldr r3, [r3, #12] + 800234c: 2b00 cmp r3, #0 + 800234e: d023 beq.n 8002398 { /* Enable the Internal High Speed oscillator (HSI). */ __HAL_RCC_HSI_ENABLE(); - 8002288: 4b39 ldr r3, [pc, #228] ; (8002370 ) - 800228a: 681b ldr r3, [r3, #0] - 800228c: 4a38 ldr r2, [pc, #224] ; (8002370 ) - 800228e: f043 0301 orr.w r3, r3, #1 - 8002292: 6013 str r3, [r2, #0] + 8002350: 4b39 ldr r3, [pc, #228] ; (8002438 ) + 8002352: 681b ldr r3, [r3, #0] + 8002354: 4a38 ldr r2, [pc, #224] ; (8002438 ) + 8002356: f043 0301 orr.w r3, r3, #1 + 800235a: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002294: f7ff fc10 bl 8001ab8 - 8002298: 6138 str r0, [r7, #16] + 800235c: f7ff fc10 bl 8001b80 + 8002360: 6138 str r0, [r7, #16] /* Wait till HSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 800229a: e008 b.n 80022ae + 8002362: e008 b.n 8002376 { if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - 800229c: f7ff fc0c bl 8001ab8 - 80022a0: 4602 mov r2, r0 - 80022a2: 693b ldr r3, [r7, #16] - 80022a4: 1ad3 subs r3, r2, r3 - 80022a6: 2b02 cmp r3, #2 - 80022a8: d901 bls.n 80022ae + 8002364: f7ff fc0c bl 8001b80 + 8002368: 4602 mov r2, r0 + 800236a: 693b ldr r3, [r7, #16] + 800236c: 1ad3 subs r3, r2, r3 + 800236e: 2b02 cmp r3, #2 + 8002370: d901 bls.n 8002376 { return HAL_TIMEOUT; - 80022aa: 2303 movs r3, #3 - 80022ac: e18a b.n 80025c4 + 8002372: 2303 movs r3, #3 + 8002374: e18a b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 80022ae: 4b30 ldr r3, [pc, #192] ; (8002370 ) - 80022b0: 681b ldr r3, [r3, #0] - 80022b2: f003 0302 and.w r3, r3, #2 - 80022b6: 2b00 cmp r3, #0 - 80022b8: d0f0 beq.n 800229c + 8002376: 4b30 ldr r3, [pc, #192] ; (8002438 ) + 8002378: 681b ldr r3, [r3, #0] + 800237a: f003 0302 and.w r3, r3, #2 + 800237e: 2b00 cmp r3, #0 + 8002380: d0f0 beq.n 8002364 } } /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - 80022ba: 4b2d ldr r3, [pc, #180] ; (8002370 ) - 80022bc: 681b ldr r3, [r3, #0] - 80022be: f023 02f8 bic.w r2, r3, #248 ; 0xf8 - 80022c2: 687b ldr r3, [r7, #4] - 80022c4: 691b ldr r3, [r3, #16] - 80022c6: 00db lsls r3, r3, #3 - 80022c8: 4929 ldr r1, [pc, #164] ; (8002370 ) - 80022ca: 4313 orrs r3, r2 - 80022cc: 600b str r3, [r1, #0] - 80022ce: e018 b.n 8002302 + 8002382: 4b2d ldr r3, [pc, #180] ; (8002438 ) + 8002384: 681b ldr r3, [r3, #0] + 8002386: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 800238a: 687b ldr r3, [r7, #4] + 800238c: 691b ldr r3, [r3, #16] + 800238e: 00db lsls r3, r3, #3 + 8002390: 4929 ldr r1, [pc, #164] ; (8002438 ) + 8002392: 4313 orrs r3, r2 + 8002394: 600b str r3, [r1, #0] + 8002396: e018 b.n 80023ca } else { /* Disable the Internal High Speed oscillator (HSI). */ __HAL_RCC_HSI_DISABLE(); - 80022d0: 4b27 ldr r3, [pc, #156] ; (8002370 ) - 80022d2: 681b ldr r3, [r3, #0] - 80022d4: 4a26 ldr r2, [pc, #152] ; (8002370 ) - 80022d6: f023 0301 bic.w r3, r3, #1 - 80022da: 6013 str r3, [r2, #0] + 8002398: 4b27 ldr r3, [pc, #156] ; (8002438 ) + 800239a: 681b ldr r3, [r3, #0] + 800239c: 4a26 ldr r2, [pc, #152] ; (8002438 ) + 800239e: f023 0301 bic.w r3, r3, #1 + 80023a2: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80022dc: f7ff fbec bl 8001ab8 - 80022e0: 6138 str r0, [r7, #16] + 80023a4: f7ff fbec bl 8001b80 + 80023a8: 6138 str r0, [r7, #16] /* Wait till HSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - 80022e2: e008 b.n 80022f6 + 80023aa: e008 b.n 80023be { if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - 80022e4: f7ff fbe8 bl 8001ab8 - 80022e8: 4602 mov r2, r0 - 80022ea: 693b ldr r3, [r7, #16] - 80022ec: 1ad3 subs r3, r2, r3 - 80022ee: 2b02 cmp r3, #2 - 80022f0: d901 bls.n 80022f6 + 80023ac: f7ff fbe8 bl 8001b80 + 80023b0: 4602 mov r2, r0 + 80023b2: 693b ldr r3, [r7, #16] + 80023b4: 1ad3 subs r3, r2, r3 + 80023b6: 2b02 cmp r3, #2 + 80023b8: d901 bls.n 80023be { return HAL_TIMEOUT; - 80022f2: 2303 movs r3, #3 - 80022f4: e166 b.n 80025c4 + 80023ba: 2303 movs r3, #3 + 80023bc: e166 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - 80022f6: 4b1e ldr r3, [pc, #120] ; (8002370 ) - 80022f8: 681b ldr r3, [r3, #0] - 80022fa: f003 0302 and.w r3, r3, #2 - 80022fe: 2b00 cmp r3, #0 - 8002300: d1f0 bne.n 80022e4 + 80023be: 4b1e ldr r3, [pc, #120] ; (8002438 ) + 80023c0: 681b ldr r3, [r3, #0] + 80023c2: f003 0302 and.w r3, r3, #2 + 80023c6: 2b00 cmp r3, #0 + 80023c8: d1f0 bne.n 80023ac } } } } /*------------------------------ LSI Configuration -------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - 8002302: 687b ldr r3, [r7, #4] - 8002304: 681b ldr r3, [r3, #0] - 8002306: f003 0308 and.w r3, r3, #8 - 800230a: 2b00 cmp r3, #0 - 800230c: d038 beq.n 8002380 + 80023ca: 687b ldr r3, [r7, #4] + 80023cc: 681b ldr r3, [r3, #0] + 80023ce: f003 0308 and.w r3, r3, #8 + 80023d2: 2b00 cmp r3, #0 + 80023d4: d038 beq.n 8002448 { /* Check the parameters */ assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); /* Check the LSI State */ if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - 800230e: 687b ldr r3, [r7, #4] - 8002310: 695b ldr r3, [r3, #20] - 8002312: 2b00 cmp r3, #0 - 8002314: d019 beq.n 800234a + 80023d6: 687b ldr r3, [r7, #4] + 80023d8: 695b ldr r3, [r3, #20] + 80023da: 2b00 cmp r3, #0 + 80023dc: d019 beq.n 8002412 { /* Enable the Internal Low Speed oscillator (LSI). */ __HAL_RCC_LSI_ENABLE(); - 8002316: 4b16 ldr r3, [pc, #88] ; (8002370 ) - 8002318: 6f5b ldr r3, [r3, #116] ; 0x74 - 800231a: 4a15 ldr r2, [pc, #84] ; (8002370 ) - 800231c: f043 0301 orr.w r3, r3, #1 - 8002320: 6753 str r3, [r2, #116] ; 0x74 + 80023de: 4b16 ldr r3, [pc, #88] ; (8002438 ) + 80023e0: 6f5b ldr r3, [r3, #116] ; 0x74 + 80023e2: 4a15 ldr r2, [pc, #84] ; (8002438 ) + 80023e4: f043 0301 orr.w r3, r3, #1 + 80023e8: 6753 str r3, [r2, #116] ; 0x74 /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002322: f7ff fbc9 bl 8001ab8 - 8002326: 6138 str r0, [r7, #16] + 80023ea: f7ff fbc9 bl 8001b80 + 80023ee: 6138 str r0, [r7, #16] /* Wait till LSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - 8002328: e008 b.n 800233c + 80023f0: e008 b.n 8002404 { if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - 800232a: f7ff fbc5 bl 8001ab8 - 800232e: 4602 mov r2, r0 - 8002330: 693b ldr r3, [r7, #16] - 8002332: 1ad3 subs r3, r2, r3 - 8002334: 2b02 cmp r3, #2 - 8002336: d901 bls.n 800233c + 80023f2: f7ff fbc5 bl 8001b80 + 80023f6: 4602 mov r2, r0 + 80023f8: 693b ldr r3, [r7, #16] + 80023fa: 1ad3 subs r3, r2, r3 + 80023fc: 2b02 cmp r3, #2 + 80023fe: d901 bls.n 8002404 { return HAL_TIMEOUT; - 8002338: 2303 movs r3, #3 - 800233a: e143 b.n 80025c4 + 8002400: 2303 movs r3, #3 + 8002402: e143 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - 800233c: 4b0c ldr r3, [pc, #48] ; (8002370 ) - 800233e: 6f5b ldr r3, [r3, #116] ; 0x74 - 8002340: f003 0302 and.w r3, r3, #2 - 8002344: 2b00 cmp r3, #0 - 8002346: d0f0 beq.n 800232a - 8002348: e01a b.n 8002380 + 8002404: 4b0c ldr r3, [pc, #48] ; (8002438 ) + 8002406: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002408: f003 0302 and.w r3, r3, #2 + 800240c: 2b00 cmp r3, #0 + 800240e: d0f0 beq.n 80023f2 + 8002410: e01a b.n 8002448 } } else { /* Disable the Internal Low Speed oscillator (LSI). */ __HAL_RCC_LSI_DISABLE(); - 800234a: 4b09 ldr r3, [pc, #36] ; (8002370 ) - 800234c: 6f5b ldr r3, [r3, #116] ; 0x74 - 800234e: 4a08 ldr r2, [pc, #32] ; (8002370 ) - 8002350: f023 0301 bic.w r3, r3, #1 - 8002354: 6753 str r3, [r2, #116] ; 0x74 + 8002412: 4b09 ldr r3, [pc, #36] ; (8002438 ) + 8002414: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002416: 4a08 ldr r2, [pc, #32] ; (8002438 ) + 8002418: f023 0301 bic.w r3, r3, #1 + 800241c: 6753 str r3, [r2, #116] ; 0x74 /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002356: f7ff fbaf bl 8001ab8 - 800235a: 6138 str r0, [r7, #16] + 800241e: f7ff fbaf bl 8001b80 + 8002422: 6138 str r0, [r7, #16] /* Wait till LSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - 800235c: e00a b.n 8002374 + 8002424: e00a b.n 800243c { if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - 800235e: f7ff fbab bl 8001ab8 - 8002362: 4602 mov r2, r0 - 8002364: 693b ldr r3, [r7, #16] - 8002366: 1ad3 subs r3, r2, r3 - 8002368: 2b02 cmp r3, #2 - 800236a: d903 bls.n 8002374 + 8002426: f7ff fbab bl 8001b80 + 800242a: 4602 mov r2, r0 + 800242c: 693b ldr r3, [r7, #16] + 800242e: 1ad3 subs r3, r2, r3 + 8002430: 2b02 cmp r3, #2 + 8002432: d903 bls.n 800243c { return HAL_TIMEOUT; - 800236c: 2303 movs r3, #3 - 800236e: e129 b.n 80025c4 - 8002370: 40023800 .word 0x40023800 + 8002434: 2303 movs r3, #3 + 8002436: e129 b.n 800268c + 8002438: 40023800 .word 0x40023800 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - 8002374: 4b95 ldr r3, [pc, #596] ; (80025cc ) - 8002376: 6f5b ldr r3, [r3, #116] ; 0x74 - 8002378: f003 0302 and.w r3, r3, #2 - 800237c: 2b00 cmp r3, #0 - 800237e: d1ee bne.n 800235e + 800243c: 4b95 ldr r3, [pc, #596] ; (8002694 ) + 800243e: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002440: f003 0302 and.w r3, r3, #2 + 8002444: 2b00 cmp r3, #0 + 8002446: d1ee bne.n 8002426 } } } } /*------------------------------ LSE Configuration -------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - 8002380: 687b ldr r3, [r7, #4] - 8002382: 681b ldr r3, [r3, #0] - 8002384: f003 0304 and.w r3, r3, #4 - 8002388: 2b00 cmp r3, #0 - 800238a: f000 80a4 beq.w 80024d6 + 8002448: 687b ldr r3, [r7, #4] + 800244a: 681b ldr r3, [r3, #0] + 800244c: f003 0304 and.w r3, r3, #4 + 8002450: 2b00 cmp r3, #0 + 8002452: f000 80a4 beq.w 800259e /* Check the parameters */ assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); /* Update LSE configuration in Backup Domain control register */ /* Requires to enable write access to Backup Domain of necessary */ if(__HAL_RCC_PWR_IS_CLK_DISABLED()) - 800238e: 4b8f ldr r3, [pc, #572] ; (80025cc ) - 8002390: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002392: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002396: 2b00 cmp r3, #0 - 8002398: d10d bne.n 80023b6 + 8002456: 4b8f ldr r3, [pc, #572] ; (8002694 ) + 8002458: 6c1b ldr r3, [r3, #64] ; 0x40 + 800245a: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 800245e: 2b00 cmp r3, #0 + 8002460: d10d bne.n 800247e { /* Enable Power Clock*/ __HAL_RCC_PWR_CLK_ENABLE(); - 800239a: 4b8c ldr r3, [pc, #560] ; (80025cc ) - 800239c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800239e: 4a8b ldr r2, [pc, #556] ; (80025cc ) - 80023a0: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 80023a4: 6413 str r3, [r2, #64] ; 0x40 - 80023a6: 4b89 ldr r3, [pc, #548] ; (80025cc ) - 80023a8: 6c1b ldr r3, [r3, #64] ; 0x40 - 80023aa: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 80023ae: 60fb str r3, [r7, #12] - 80023b0: 68fb ldr r3, [r7, #12] + 8002462: 4b8c ldr r3, [pc, #560] ; (8002694 ) + 8002464: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002466: 4a8b ldr r2, [pc, #556] ; (8002694 ) + 8002468: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 800246c: 6413 str r3, [r2, #64] ; 0x40 + 800246e: 4b89 ldr r3, [pc, #548] ; (8002694 ) + 8002470: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002472: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002476: 60fb str r3, [r7, #12] + 8002478: 68fb ldr r3, [r7, #12] pwrclkchanged = SET; - 80023b2: 2301 movs r3, #1 - 80023b4: 75fb strb r3, [r7, #23] + 800247a: 2301 movs r3, #1 + 800247c: 75fb strb r3, [r7, #23] } if(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 80023b6: 4b86 ldr r3, [pc, #536] ; (80025d0 ) - 80023b8: 681b ldr r3, [r3, #0] - 80023ba: f403 7380 and.w r3, r3, #256 ; 0x100 - 80023be: 2b00 cmp r3, #0 - 80023c0: d118 bne.n 80023f4 + 800247e: 4b86 ldr r3, [pc, #536] ; (8002698 ) + 8002480: 681b ldr r3, [r3, #0] + 8002482: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002486: 2b00 cmp r3, #0 + 8002488: d118 bne.n 80024bc { /* Enable write access to Backup domain */ PWR->CR1 |= PWR_CR1_DBP; - 80023c2: 4b83 ldr r3, [pc, #524] ; (80025d0 ) - 80023c4: 681b ldr r3, [r3, #0] - 80023c6: 4a82 ldr r2, [pc, #520] ; (80025d0 ) - 80023c8: f443 7380 orr.w r3, r3, #256 ; 0x100 - 80023cc: 6013 str r3, [r2, #0] + 800248a: 4b83 ldr r3, [pc, #524] ; (8002698 ) + 800248c: 681b ldr r3, [r3, #0] + 800248e: 4a82 ldr r2, [pc, #520] ; (8002698 ) + 8002490: f443 7380 orr.w r3, r3, #256 ; 0x100 + 8002494: 6013 str r3, [r2, #0] /* Wait for Backup domain Write protection disable */ tickstart = HAL_GetTick(); - 80023ce: f7ff fb73 bl 8001ab8 - 80023d2: 6138 str r0, [r7, #16] + 8002496: f7ff fb73 bl 8001b80 + 800249a: 6138 str r0, [r7, #16] while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 80023d4: e008 b.n 80023e8 + 800249c: e008 b.n 80024b0 { if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - 80023d6: f7ff fb6f bl 8001ab8 - 80023da: 4602 mov r2, r0 - 80023dc: 693b ldr r3, [r7, #16] - 80023de: 1ad3 subs r3, r2, r3 - 80023e0: 2b64 cmp r3, #100 ; 0x64 - 80023e2: d901 bls.n 80023e8 + 800249e: f7ff fb6f bl 8001b80 + 80024a2: 4602 mov r2, r0 + 80024a4: 693b ldr r3, [r7, #16] + 80024a6: 1ad3 subs r3, r2, r3 + 80024a8: 2b64 cmp r3, #100 ; 0x64 + 80024aa: d901 bls.n 80024b0 { return HAL_TIMEOUT; - 80023e4: 2303 movs r3, #3 - 80023e6: e0ed b.n 80025c4 + 80024ac: 2303 movs r3, #3 + 80024ae: e0ed b.n 800268c while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 80023e8: 4b79 ldr r3, [pc, #484] ; (80025d0 ) - 80023ea: 681b ldr r3, [r3, #0] - 80023ec: f403 7380 and.w r3, r3, #256 ; 0x100 - 80023f0: 2b00 cmp r3, #0 - 80023f2: d0f0 beq.n 80023d6 + 80024b0: 4b79 ldr r3, [pc, #484] ; (8002698 ) + 80024b2: 681b ldr r3, [r3, #0] + 80024b4: f403 7380 and.w r3, r3, #256 ; 0x100 + 80024b8: 2b00 cmp r3, #0 + 80024ba: d0f0 beq.n 800249e } } } /* Set the new LSE configuration -----------------------------------------*/ __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - 80023f4: 687b ldr r3, [r7, #4] - 80023f6: 689b ldr r3, [r3, #8] - 80023f8: 2b01 cmp r3, #1 - 80023fa: d106 bne.n 800240a - 80023fc: 4b73 ldr r3, [pc, #460] ; (80025cc ) - 80023fe: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002400: 4a72 ldr r2, [pc, #456] ; (80025cc ) - 8002402: f043 0301 orr.w r3, r3, #1 - 8002406: 6713 str r3, [r2, #112] ; 0x70 - 8002408: e02d b.n 8002466 - 800240a: 687b ldr r3, [r7, #4] - 800240c: 689b ldr r3, [r3, #8] - 800240e: 2b00 cmp r3, #0 - 8002410: d10c bne.n 800242c - 8002412: 4b6e ldr r3, [pc, #440] ; (80025cc ) - 8002414: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002416: 4a6d ldr r2, [pc, #436] ; (80025cc ) - 8002418: f023 0301 bic.w r3, r3, #1 - 800241c: 6713 str r3, [r2, #112] ; 0x70 - 800241e: 4b6b ldr r3, [pc, #428] ; (80025cc ) - 8002420: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002422: 4a6a ldr r2, [pc, #424] ; (80025cc ) - 8002424: f023 0304 bic.w r3, r3, #4 - 8002428: 6713 str r3, [r2, #112] ; 0x70 - 800242a: e01c b.n 8002466 - 800242c: 687b ldr r3, [r7, #4] - 800242e: 689b ldr r3, [r3, #8] - 8002430: 2b05 cmp r3, #5 - 8002432: d10c bne.n 800244e - 8002434: 4b65 ldr r3, [pc, #404] ; (80025cc ) - 8002436: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002438: 4a64 ldr r2, [pc, #400] ; (80025cc ) - 800243a: f043 0304 orr.w r3, r3, #4 - 800243e: 6713 str r3, [r2, #112] ; 0x70 - 8002440: 4b62 ldr r3, [pc, #392] ; (80025cc ) - 8002442: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002444: 4a61 ldr r2, [pc, #388] ; (80025cc ) - 8002446: f043 0301 orr.w r3, r3, #1 - 800244a: 6713 str r3, [r2, #112] ; 0x70 - 800244c: e00b b.n 8002466 - 800244e: 4b5f ldr r3, [pc, #380] ; (80025cc ) - 8002450: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002452: 4a5e ldr r2, [pc, #376] ; (80025cc ) - 8002454: f023 0301 bic.w r3, r3, #1 - 8002458: 6713 str r3, [r2, #112] ; 0x70 - 800245a: 4b5c ldr r3, [pc, #368] ; (80025cc ) - 800245c: 6f1b ldr r3, [r3, #112] ; 0x70 - 800245e: 4a5b ldr r2, [pc, #364] ; (80025cc ) - 8002460: f023 0304 bic.w r3, r3, #4 - 8002464: 6713 str r3, [r2, #112] ; 0x70 + 80024bc: 687b ldr r3, [r7, #4] + 80024be: 689b ldr r3, [r3, #8] + 80024c0: 2b01 cmp r3, #1 + 80024c2: d106 bne.n 80024d2 + 80024c4: 4b73 ldr r3, [pc, #460] ; (8002694 ) + 80024c6: 6f1b ldr r3, [r3, #112] ; 0x70 + 80024c8: 4a72 ldr r2, [pc, #456] ; (8002694 ) + 80024ca: f043 0301 orr.w r3, r3, #1 + 80024ce: 6713 str r3, [r2, #112] ; 0x70 + 80024d0: e02d b.n 800252e + 80024d2: 687b ldr r3, [r7, #4] + 80024d4: 689b ldr r3, [r3, #8] + 80024d6: 2b00 cmp r3, #0 + 80024d8: d10c bne.n 80024f4 + 80024da: 4b6e ldr r3, [pc, #440] ; (8002694 ) + 80024dc: 6f1b ldr r3, [r3, #112] ; 0x70 + 80024de: 4a6d ldr r2, [pc, #436] ; (8002694 ) + 80024e0: f023 0301 bic.w r3, r3, #1 + 80024e4: 6713 str r3, [r2, #112] ; 0x70 + 80024e6: 4b6b ldr r3, [pc, #428] ; (8002694 ) + 80024e8: 6f1b ldr r3, [r3, #112] ; 0x70 + 80024ea: 4a6a ldr r2, [pc, #424] ; (8002694 ) + 80024ec: f023 0304 bic.w r3, r3, #4 + 80024f0: 6713 str r3, [r2, #112] ; 0x70 + 80024f2: e01c b.n 800252e + 80024f4: 687b ldr r3, [r7, #4] + 80024f6: 689b ldr r3, [r3, #8] + 80024f8: 2b05 cmp r3, #5 + 80024fa: d10c bne.n 8002516 + 80024fc: 4b65 ldr r3, [pc, #404] ; (8002694 ) + 80024fe: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002500: 4a64 ldr r2, [pc, #400] ; (8002694 ) + 8002502: f043 0304 orr.w r3, r3, #4 + 8002506: 6713 str r3, [r2, #112] ; 0x70 + 8002508: 4b62 ldr r3, [pc, #392] ; (8002694 ) + 800250a: 6f1b ldr r3, [r3, #112] ; 0x70 + 800250c: 4a61 ldr r2, [pc, #388] ; (8002694 ) + 800250e: f043 0301 orr.w r3, r3, #1 + 8002512: 6713 str r3, [r2, #112] ; 0x70 + 8002514: e00b b.n 800252e + 8002516: 4b5f ldr r3, [pc, #380] ; (8002694 ) + 8002518: 6f1b ldr r3, [r3, #112] ; 0x70 + 800251a: 4a5e ldr r2, [pc, #376] ; (8002694 ) + 800251c: f023 0301 bic.w r3, r3, #1 + 8002520: 6713 str r3, [r2, #112] ; 0x70 + 8002522: 4b5c ldr r3, [pc, #368] ; (8002694 ) + 8002524: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002526: 4a5b ldr r2, [pc, #364] ; (8002694 ) + 8002528: f023 0304 bic.w r3, r3, #4 + 800252c: 6713 str r3, [r2, #112] ; 0x70 /* Check the LSE State */ if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - 8002466: 687b ldr r3, [r7, #4] - 8002468: 689b ldr r3, [r3, #8] - 800246a: 2b00 cmp r3, #0 - 800246c: d015 beq.n 800249a + 800252e: 687b ldr r3, [r7, #4] + 8002530: 689b ldr r3, [r3, #8] + 8002532: 2b00 cmp r3, #0 + 8002534: d015 beq.n 8002562 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800246e: f7ff fb23 bl 8001ab8 - 8002472: 6138 str r0, [r7, #16] + 8002536: f7ff fb23 bl 8001b80 + 800253a: 6138 str r0, [r7, #16] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002474: e00a b.n 800248c + 800253c: e00a b.n 8002554 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 8002476: f7ff fb1f bl 8001ab8 - 800247a: 4602 mov r2, r0 - 800247c: 693b ldr r3, [r7, #16] - 800247e: 1ad3 subs r3, r2, r3 - 8002480: f241 3288 movw r2, #5000 ; 0x1388 - 8002484: 4293 cmp r3, r2 - 8002486: d901 bls.n 800248c + 800253e: f7ff fb1f bl 8001b80 + 8002542: 4602 mov r2, r0 + 8002544: 693b ldr r3, [r7, #16] + 8002546: 1ad3 subs r3, r2, r3 + 8002548: f241 3288 movw r2, #5000 ; 0x1388 + 800254c: 4293 cmp r3, r2 + 800254e: d901 bls.n 8002554 { return HAL_TIMEOUT; - 8002488: 2303 movs r3, #3 - 800248a: e09b b.n 80025c4 + 8002550: 2303 movs r3, #3 + 8002552: e09b b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 800248c: 4b4f ldr r3, [pc, #316] ; (80025cc ) - 800248e: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002490: f003 0302 and.w r3, r3, #2 - 8002494: 2b00 cmp r3, #0 - 8002496: d0ee beq.n 8002476 - 8002498: e014 b.n 80024c4 + 8002554: 4b4f ldr r3, [pc, #316] ; (8002694 ) + 8002556: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002558: f003 0302 and.w r3, r3, #2 + 800255c: 2b00 cmp r3, #0 + 800255e: d0ee beq.n 800253e + 8002560: e014 b.n 800258c } } else { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800249a: f7ff fb0d bl 8001ab8 - 800249e: 6138 str r0, [r7, #16] + 8002562: f7ff fb0d bl 8001b80 + 8002566: 6138 str r0, [r7, #16] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - 80024a0: e00a b.n 80024b8 + 8002568: e00a b.n 8002580 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 80024a2: f7ff fb09 bl 8001ab8 - 80024a6: 4602 mov r2, r0 - 80024a8: 693b ldr r3, [r7, #16] - 80024aa: 1ad3 subs r3, r2, r3 - 80024ac: f241 3288 movw r2, #5000 ; 0x1388 - 80024b0: 4293 cmp r3, r2 - 80024b2: d901 bls.n 80024b8 + 800256a: f7ff fb09 bl 8001b80 + 800256e: 4602 mov r2, r0 + 8002570: 693b ldr r3, [r7, #16] + 8002572: 1ad3 subs r3, r2, r3 + 8002574: f241 3288 movw r2, #5000 ; 0x1388 + 8002578: 4293 cmp r3, r2 + 800257a: d901 bls.n 8002580 { return HAL_TIMEOUT; - 80024b4: 2303 movs r3, #3 - 80024b6: e085 b.n 80025c4 + 800257c: 2303 movs r3, #3 + 800257e: e085 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - 80024b8: 4b44 ldr r3, [pc, #272] ; (80025cc ) - 80024ba: 6f1b ldr r3, [r3, #112] ; 0x70 - 80024bc: f003 0302 and.w r3, r3, #2 - 80024c0: 2b00 cmp r3, #0 - 80024c2: d1ee bne.n 80024a2 + 8002580: 4b44 ldr r3, [pc, #272] ; (8002694 ) + 8002582: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002584: f003 0302 and.w r3, r3, #2 + 8002588: 2b00 cmp r3, #0 + 800258a: d1ee bne.n 800256a } } } /* Restore clock configuration if changed */ if(pwrclkchanged == SET) - 80024c4: 7dfb ldrb r3, [r7, #23] - 80024c6: 2b01 cmp r3, #1 - 80024c8: d105 bne.n 80024d6 + 800258c: 7dfb ldrb r3, [r7, #23] + 800258e: 2b01 cmp r3, #1 + 8002590: d105 bne.n 800259e { __HAL_RCC_PWR_CLK_DISABLE(); - 80024ca: 4b40 ldr r3, [pc, #256] ; (80025cc ) - 80024cc: 6c1b ldr r3, [r3, #64] ; 0x40 - 80024ce: 4a3f ldr r2, [pc, #252] ; (80025cc ) - 80024d0: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 - 80024d4: 6413 str r3, [r2, #64] ; 0x40 + 8002592: 4b40 ldr r3, [pc, #256] ; (8002694 ) + 8002594: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002596: 4a3f ldr r2, [pc, #252] ; (8002694 ) + 8002598: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 800259c: 6413 str r3, [r2, #64] ; 0x40 } } /*-------------------------------- PLL Configuration -----------------------*/ /* Check the parameters */ assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) - 80024d6: 687b ldr r3, [r7, #4] - 80024d8: 699b ldr r3, [r3, #24] - 80024da: 2b00 cmp r3, #0 - 80024dc: d071 beq.n 80025c2 + 800259e: 687b ldr r3, [r7, #4] + 80025a0: 699b ldr r3, [r3, #24] + 80025a2: 2b00 cmp r3, #0 + 80025a4: d071 beq.n 800268a { /* Check if the PLL is used as system clock or not */ if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK) - 80024de: 4b3b ldr r3, [pc, #236] ; (80025cc ) - 80024e0: 689b ldr r3, [r3, #8] - 80024e2: f003 030c and.w r3, r3, #12 - 80024e6: 2b08 cmp r3, #8 - 80024e8: d069 beq.n 80025be + 80025a6: 4b3b ldr r3, [pc, #236] ; (8002694 ) + 80025a8: 689b ldr r3, [r3, #8] + 80025aa: f003 030c and.w r3, r3, #12 + 80025ae: 2b08 cmp r3, #8 + 80025b0: d069 beq.n 8002686 { if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - 80024ea: 687b ldr r3, [r7, #4] - 80024ec: 699b ldr r3, [r3, #24] - 80024ee: 2b02 cmp r3, #2 - 80024f0: d14b bne.n 800258a + 80025b2: 687b ldr r3, [r7, #4] + 80025b4: 699b ldr r3, [r3, #24] + 80025b6: 2b02 cmp r3, #2 + 80025b8: d14b bne.n 8002652 #if defined (RCC_PLLCFGR_PLLR) assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); #endif /* Disable the main PLL. */ __HAL_RCC_PLL_DISABLE(); - 80024f2: 4b36 ldr r3, [pc, #216] ; (80025cc ) - 80024f4: 681b ldr r3, [r3, #0] - 80024f6: 4a35 ldr r2, [pc, #212] ; (80025cc ) - 80024f8: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 80024fc: 6013 str r3, [r2, #0] + 80025ba: 4b36 ldr r3, [pc, #216] ; (8002694 ) + 80025bc: 681b ldr r3, [r3, #0] + 80025be: 4a35 ldr r2, [pc, #212] ; (8002694 ) + 80025c0: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 80025c4: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80024fe: f7ff fadb bl 8001ab8 - 8002502: 6138 str r0, [r7, #16] + 80025c6: f7ff fadb bl 8001b80 + 80025ca: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 8002504: e008 b.n 8002518 + 80025cc: e008 b.n 80025e0 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 8002506: f7ff fad7 bl 8001ab8 - 800250a: 4602 mov r2, r0 - 800250c: 693b ldr r3, [r7, #16] - 800250e: 1ad3 subs r3, r2, r3 - 8002510: 2b02 cmp r3, #2 - 8002512: d901 bls.n 8002518 + 80025ce: f7ff fad7 bl 8001b80 + 80025d2: 4602 mov r2, r0 + 80025d4: 693b ldr r3, [r7, #16] + 80025d6: 1ad3 subs r3, r2, r3 + 80025d8: 2b02 cmp r3, #2 + 80025da: d901 bls.n 80025e0 { return HAL_TIMEOUT; - 8002514: 2303 movs r3, #3 - 8002516: e055 b.n 80025c4 + 80025dc: 2303 movs r3, #3 + 80025de: e055 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 8002518: 4b2c ldr r3, [pc, #176] ; (80025cc ) - 800251a: 681b ldr r3, [r3, #0] - 800251c: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8002520: 2b00 cmp r3, #0 - 8002522: d1f0 bne.n 8002506 + 80025e0: 4b2c ldr r3, [pc, #176] ; (8002694 ) + 80025e2: 681b ldr r3, [r3, #0] + 80025e4: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 80025e8: 2b00 cmp r3, #0 + 80025ea: d1f0 bne.n 80025ce } } /* Configure the main PLL clock source, multiplication and division factors. */ #if defined (RCC_PLLCFGR_PLLR) __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource, - 8002524: 687b ldr r3, [r7, #4] - 8002526: 69da ldr r2, [r3, #28] - 8002528: 687b ldr r3, [r7, #4] - 800252a: 6a1b ldr r3, [r3, #32] - 800252c: 431a orrs r2, r3 - 800252e: 687b ldr r3, [r7, #4] - 8002530: 6a5b ldr r3, [r3, #36] ; 0x24 - 8002532: 019b lsls r3, r3, #6 - 8002534: 431a orrs r2, r3 - 8002536: 687b ldr r3, [r7, #4] - 8002538: 6a9b ldr r3, [r3, #40] ; 0x28 - 800253a: 085b lsrs r3, r3, #1 - 800253c: 3b01 subs r3, #1 - 800253e: 041b lsls r3, r3, #16 - 8002540: 431a orrs r2, r3 - 8002542: 687b ldr r3, [r7, #4] - 8002544: 6adb ldr r3, [r3, #44] ; 0x2c - 8002546: 061b lsls r3, r3, #24 - 8002548: 431a orrs r2, r3 - 800254a: 687b ldr r3, [r7, #4] - 800254c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800254e: 071b lsls r3, r3, #28 - 8002550: 491e ldr r1, [pc, #120] ; (80025cc ) - 8002552: 4313 orrs r3, r2 - 8002554: 604b str r3, [r1, #4] + 80025ec: 687b ldr r3, [r7, #4] + 80025ee: 69da ldr r2, [r3, #28] + 80025f0: 687b ldr r3, [r7, #4] + 80025f2: 6a1b ldr r3, [r3, #32] + 80025f4: 431a orrs r2, r3 + 80025f6: 687b ldr r3, [r7, #4] + 80025f8: 6a5b ldr r3, [r3, #36] ; 0x24 + 80025fa: 019b lsls r3, r3, #6 + 80025fc: 431a orrs r2, r3 + 80025fe: 687b ldr r3, [r7, #4] + 8002600: 6a9b ldr r3, [r3, #40] ; 0x28 + 8002602: 085b lsrs r3, r3, #1 + 8002604: 3b01 subs r3, #1 + 8002606: 041b lsls r3, r3, #16 + 8002608: 431a orrs r2, r3 + 800260a: 687b ldr r3, [r7, #4] + 800260c: 6adb ldr r3, [r3, #44] ; 0x2c + 800260e: 061b lsls r3, r3, #24 + 8002610: 431a orrs r2, r3 + 8002612: 687b ldr r3, [r7, #4] + 8002614: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002616: 071b lsls r3, r3, #28 + 8002618: 491e ldr r1, [pc, #120] ; (8002694 ) + 800261a: 4313 orrs r3, r2 + 800261c: 604b str r3, [r1, #4] RCC_OscInitStruct->PLL.PLLP, RCC_OscInitStruct->PLL.PLLQ); #endif /* Enable the main PLL. */ __HAL_RCC_PLL_ENABLE(); - 8002556: 4b1d ldr r3, [pc, #116] ; (80025cc ) - 8002558: 681b ldr r3, [r3, #0] - 800255a: 4a1c ldr r2, [pc, #112] ; (80025cc ) - 800255c: f043 7380 orr.w r3, r3, #16777216 ; 0x1000000 - 8002560: 6013 str r3, [r2, #0] + 800261e: 4b1d ldr r3, [pc, #116] ; (8002694 ) + 8002620: 681b ldr r3, [r3, #0] + 8002622: 4a1c ldr r2, [pc, #112] ; (8002694 ) + 8002624: f043 7380 orr.w r3, r3, #16777216 ; 0x1000000 + 8002628: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002562: f7ff faa9 bl 8001ab8 - 8002566: 6138 str r0, [r7, #16] + 800262a: f7ff faa9 bl 8001b80 + 800262e: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 8002568: e008 b.n 800257c + 8002630: e008 b.n 8002644 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 800256a: f7ff faa5 bl 8001ab8 - 800256e: 4602 mov r2, r0 - 8002570: 693b ldr r3, [r7, #16] - 8002572: 1ad3 subs r3, r2, r3 - 8002574: 2b02 cmp r3, #2 - 8002576: d901 bls.n 800257c + 8002632: f7ff faa5 bl 8001b80 + 8002636: 4602 mov r2, r0 + 8002638: 693b ldr r3, [r7, #16] + 800263a: 1ad3 subs r3, r2, r3 + 800263c: 2b02 cmp r3, #2 + 800263e: d901 bls.n 8002644 { return HAL_TIMEOUT; - 8002578: 2303 movs r3, #3 - 800257a: e023 b.n 80025c4 + 8002640: 2303 movs r3, #3 + 8002642: e023 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 800257c: 4b13 ldr r3, [pc, #76] ; (80025cc ) - 800257e: 681b ldr r3, [r3, #0] - 8002580: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8002584: 2b00 cmp r3, #0 - 8002586: d0f0 beq.n 800256a - 8002588: e01b b.n 80025c2 + 8002644: 4b13 ldr r3, [pc, #76] ; (8002694 ) + 8002646: 681b ldr r3, [r3, #0] + 8002648: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 800264c: 2b00 cmp r3, #0 + 800264e: d0f0 beq.n 8002632 + 8002650: e01b b.n 800268a } } else { /* Disable the main PLL. */ __HAL_RCC_PLL_DISABLE(); - 800258a: 4b10 ldr r3, [pc, #64] ; (80025cc ) - 800258c: 681b ldr r3, [r3, #0] - 800258e: 4a0f ldr r2, [pc, #60] ; (80025cc ) - 8002590: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 8002594: 6013 str r3, [r2, #0] + 8002652: 4b10 ldr r3, [pc, #64] ; (8002694 ) + 8002654: 681b ldr r3, [r3, #0] + 8002656: 4a0f ldr r2, [pc, #60] ; (8002694 ) + 8002658: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 800265c: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002596: f7ff fa8f bl 8001ab8 - 800259a: 6138 str r0, [r7, #16] + 800265e: f7ff fa8f bl 8001b80 + 8002662: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 800259c: e008 b.n 80025b0 + 8002664: e008 b.n 8002678 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 800259e: f7ff fa8b bl 8001ab8 - 80025a2: 4602 mov r2, r0 - 80025a4: 693b ldr r3, [r7, #16] - 80025a6: 1ad3 subs r3, r2, r3 - 80025a8: 2b02 cmp r3, #2 - 80025aa: d901 bls.n 80025b0 + 8002666: f7ff fa8b bl 8001b80 + 800266a: 4602 mov r2, r0 + 800266c: 693b ldr r3, [r7, #16] + 800266e: 1ad3 subs r3, r2, r3 + 8002670: 2b02 cmp r3, #2 + 8002672: d901 bls.n 8002678 { return HAL_TIMEOUT; - 80025ac: 2303 movs r3, #3 - 80025ae: e009 b.n 80025c4 + 8002674: 2303 movs r3, #3 + 8002676: e009 b.n 800268c while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 80025b0: 4b06 ldr r3, [pc, #24] ; (80025cc ) - 80025b2: 681b ldr r3, [r3, #0] - 80025b4: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 80025b8: 2b00 cmp r3, #0 - 80025ba: d1f0 bne.n 800259e - 80025bc: e001 b.n 80025c2 + 8002678: 4b06 ldr r3, [pc, #24] ; (8002694 ) + 800267a: 681b ldr r3, [r3, #0] + 800267c: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002680: 2b00 cmp r3, #0 + 8002682: d1f0 bne.n 8002666 + 8002684: e001 b.n 800268a } } } else { return HAL_ERROR; - 80025be: 2301 movs r3, #1 - 80025c0: e000 b.n 80025c4 + 8002686: 2301 movs r3, #1 + 8002688: e000 b.n 800268c } } return HAL_OK; - 80025c2: 2300 movs r3, #0 + 800268a: 2300 movs r3, #0 } - 80025c4: 4618 mov r0, r3 - 80025c6: 3718 adds r7, #24 - 80025c8: 46bd mov sp, r7 - 80025ca: bd80 pop {r7, pc} - 80025cc: 40023800 .word 0x40023800 - 80025d0: 40007000 .word 0x40007000 - -080025d4 : + 800268c: 4618 mov r0, r3 + 800268e: 3718 adds r7, #24 + 8002690: 46bd mov sp, r7 + 8002692: bd80 pop {r7, pc} + 8002694: 40023800 .word 0x40023800 + 8002698: 40007000 .word 0x40007000 + +0800269c : * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency * (for more details refer to section above "Initialization/de-initialization functions") * @retval None */ HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency) { - 80025d4: b580 push {r7, lr} - 80025d6: b084 sub sp, #16 - 80025d8: af00 add r7, sp, #0 - 80025da: 6078 str r0, [r7, #4] - 80025dc: 6039 str r1, [r7, #0] + 800269c: b580 push {r7, lr} + 800269e: b084 sub sp, #16 + 80026a0: af00 add r7, sp, #0 + 80026a2: 6078 str r0, [r7, #4] + 80026a4: 6039 str r1, [r7, #0] uint32_t tickstart = 0; - 80025de: 2300 movs r3, #0 - 80025e0: 60fb str r3, [r7, #12] + 80026a6: 2300 movs r3, #0 + 80026a8: 60fb str r3, [r7, #12] /* Check Null pointer */ if(RCC_ClkInitStruct == NULL) - 80025e2: 687b ldr r3, [r7, #4] - 80025e4: 2b00 cmp r3, #0 - 80025e6: d101 bne.n 80025ec + 80026aa: 687b ldr r3, [r7, #4] + 80026ac: 2b00 cmp r3, #0 + 80026ae: d101 bne.n 80026b4 { return HAL_ERROR; - 80025e8: 2301 movs r3, #1 - 80025ea: e0ce b.n 800278a + 80026b0: 2301 movs r3, #1 + 80026b2: e0ce b.n 8002852 /* To correctly read data from FLASH memory, the number of wait states (LATENCY) must be correctly programmed according to the frequency of the CPU clock (HCLK) and the supply voltage of the device. */ /* Increasing the CPU frequency */ if(FLatency > __HAL_FLASH_GET_LATENCY()) - 80025ec: 4b69 ldr r3, [pc, #420] ; (8002794 ) - 80025ee: 681b ldr r3, [r3, #0] - 80025f0: f003 030f and.w r3, r3, #15 - 80025f4: 683a ldr r2, [r7, #0] - 80025f6: 429a cmp r2, r3 - 80025f8: d910 bls.n 800261c + 80026b4: 4b69 ldr r3, [pc, #420] ; (800285c ) + 80026b6: 681b ldr r3, [r3, #0] + 80026b8: f003 030f and.w r3, r3, #15 + 80026bc: 683a ldr r2, [r7, #0] + 80026be: 429a cmp r2, r3 + 80026c0: d910 bls.n 80026e4 { /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ __HAL_FLASH_SET_LATENCY(FLatency); - 80025fa: 4b66 ldr r3, [pc, #408] ; (8002794 ) - 80025fc: 681b ldr r3, [r3, #0] - 80025fe: f023 020f bic.w r2, r3, #15 - 8002602: 4964 ldr r1, [pc, #400] ; (8002794 ) - 8002604: 683b ldr r3, [r7, #0] - 8002606: 4313 orrs r3, r2 - 8002608: 600b str r3, [r1, #0] + 80026c2: 4b66 ldr r3, [pc, #408] ; (800285c ) + 80026c4: 681b ldr r3, [r3, #0] + 80026c6: f023 020f bic.w r2, r3, #15 + 80026ca: 4964 ldr r1, [pc, #400] ; (800285c ) + 80026cc: 683b ldr r3, [r7, #0] + 80026ce: 4313 orrs r3, r2 + 80026d0: 600b str r3, [r1, #0] /* Check that the new number of wait states is taken into account to access the Flash memory by reading the FLASH_ACR register */ if(__HAL_FLASH_GET_LATENCY() != FLatency) - 800260a: 4b62 ldr r3, [pc, #392] ; (8002794 ) - 800260c: 681b ldr r3, [r3, #0] - 800260e: f003 030f and.w r3, r3, #15 - 8002612: 683a ldr r2, [r7, #0] - 8002614: 429a cmp r2, r3 - 8002616: d001 beq.n 800261c + 80026d2: 4b62 ldr r3, [pc, #392] ; (800285c ) + 80026d4: 681b ldr r3, [r3, #0] + 80026d6: f003 030f and.w r3, r3, #15 + 80026da: 683a ldr r2, [r7, #0] + 80026dc: 429a cmp r2, r3 + 80026de: d001 beq.n 80026e4 { return HAL_ERROR; - 8002618: 2301 movs r3, #1 - 800261a: e0b6 b.n 800278a + 80026e0: 2301 movs r3, #1 + 80026e2: e0b6 b.n 8002852 } } /*-------------------------- HCLK Configuration --------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) - 800261c: 687b ldr r3, [r7, #4] - 800261e: 681b ldr r3, [r3, #0] - 8002620: f003 0302 and.w r3, r3, #2 - 8002624: 2b00 cmp r3, #0 - 8002626: d020 beq.n 800266a + 80026e4: 687b ldr r3, [r7, #4] + 80026e6: 681b ldr r3, [r3, #0] + 80026e8: f003 0302 and.w r3, r3, #2 + 80026ec: 2b00 cmp r3, #0 + 80026ee: d020 beq.n 8002732 { /* Set the highest APBx dividers in order to ensure that we do not go through a non-spec phase whatever we decrease or increase HCLK. */ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - 8002628: 687b ldr r3, [r7, #4] - 800262a: 681b ldr r3, [r3, #0] - 800262c: f003 0304 and.w r3, r3, #4 - 8002630: 2b00 cmp r3, #0 - 8002632: d005 beq.n 8002640 + 80026f0: 687b ldr r3, [r7, #4] + 80026f2: 681b ldr r3, [r3, #0] + 80026f4: f003 0304 and.w r3, r3, #4 + 80026f8: 2b00 cmp r3, #0 + 80026fa: d005 beq.n 8002708 { MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); - 8002634: 4b58 ldr r3, [pc, #352] ; (8002798 ) - 8002636: 689b ldr r3, [r3, #8] - 8002638: 4a57 ldr r2, [pc, #348] ; (8002798 ) - 800263a: f443 53e0 orr.w r3, r3, #7168 ; 0x1c00 - 800263e: 6093 str r3, [r2, #8] + 80026fc: 4b58 ldr r3, [pc, #352] ; (8002860 ) + 80026fe: 689b ldr r3, [r3, #8] + 8002700: 4a57 ldr r2, [pc, #348] ; (8002860 ) + 8002702: f443 53e0 orr.w r3, r3, #7168 ; 0x1c00 + 8002706: 6093 str r3, [r2, #8] } if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - 8002640: 687b ldr r3, [r7, #4] - 8002642: 681b ldr r3, [r3, #0] - 8002644: f003 0308 and.w r3, r3, #8 - 8002648: 2b00 cmp r3, #0 - 800264a: d005 beq.n 8002658 + 8002708: 687b ldr r3, [r7, #4] + 800270a: 681b ldr r3, [r3, #0] + 800270c: f003 0308 and.w r3, r3, #8 + 8002710: 2b00 cmp r3, #0 + 8002712: d005 beq.n 8002720 { MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); - 800264c: 4b52 ldr r3, [pc, #328] ; (8002798 ) - 800264e: 689b ldr r3, [r3, #8] - 8002650: 4a51 ldr r2, [pc, #324] ; (8002798 ) - 8002652: f443 4360 orr.w r3, r3, #57344 ; 0xe000 - 8002656: 6093 str r3, [r2, #8] + 8002714: 4b52 ldr r3, [pc, #328] ; (8002860 ) + 8002716: 689b ldr r3, [r3, #8] + 8002718: 4a51 ldr r2, [pc, #324] ; (8002860 ) + 800271a: f443 4360 orr.w r3, r3, #57344 ; 0xe000 + 800271e: 6093 str r3, [r2, #8] } /* Set the new HCLK clock divider */ assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider)); MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider); - 8002658: 4b4f ldr r3, [pc, #316] ; (8002798 ) - 800265a: 689b ldr r3, [r3, #8] - 800265c: f023 02f0 bic.w r2, r3, #240 ; 0xf0 - 8002660: 687b ldr r3, [r7, #4] - 8002662: 689b ldr r3, [r3, #8] - 8002664: 494c ldr r1, [pc, #304] ; (8002798 ) - 8002666: 4313 orrs r3, r2 - 8002668: 608b str r3, [r1, #8] + 8002720: 4b4f ldr r3, [pc, #316] ; (8002860 ) + 8002722: 689b ldr r3, [r3, #8] + 8002724: f023 02f0 bic.w r2, r3, #240 ; 0xf0 + 8002728: 687b ldr r3, [r7, #4] + 800272a: 689b ldr r3, [r3, #8] + 800272c: 494c ldr r1, [pc, #304] ; (8002860 ) + 800272e: 4313 orrs r3, r2 + 8002730: 608b str r3, [r1, #8] } /*------------------------- SYSCLK Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) - 800266a: 687b ldr r3, [r7, #4] - 800266c: 681b ldr r3, [r3, #0] - 800266e: f003 0301 and.w r3, r3, #1 - 8002672: 2b00 cmp r3, #0 - 8002674: d040 beq.n 80026f8 + 8002732: 687b ldr r3, [r7, #4] + 8002734: 681b ldr r3, [r3, #0] + 8002736: f003 0301 and.w r3, r3, #1 + 800273a: 2b00 cmp r3, #0 + 800273c: d040 beq.n 80027c0 { assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); /* HSE is selected as System Clock Source */ if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) - 8002676: 687b ldr r3, [r7, #4] - 8002678: 685b ldr r3, [r3, #4] - 800267a: 2b01 cmp r3, #1 - 800267c: d107 bne.n 800268e + 800273e: 687b ldr r3, [r7, #4] + 8002740: 685b ldr r3, [r3, #4] + 8002742: 2b01 cmp r3, #1 + 8002744: d107 bne.n 8002756 { /* Check the HSE ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 800267e: 4b46 ldr r3, [pc, #280] ; (8002798 ) - 8002680: 681b ldr r3, [r3, #0] - 8002682: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8002686: 2b00 cmp r3, #0 - 8002688: d115 bne.n 80026b6 + 8002746: 4b46 ldr r3, [pc, #280] ; (8002860 ) + 8002748: 681b ldr r3, [r3, #0] + 800274a: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800274e: 2b00 cmp r3, #0 + 8002750: d115 bne.n 800277e { return HAL_ERROR; - 800268a: 2301 movs r3, #1 - 800268c: e07d b.n 800278a + 8002752: 2301 movs r3, #1 + 8002754: e07d b.n 8002852 } } /* PLL is selected as System Clock Source */ else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) - 800268e: 687b ldr r3, [r7, #4] - 8002690: 685b ldr r3, [r3, #4] - 8002692: 2b02 cmp r3, #2 - 8002694: d107 bne.n 80026a6 + 8002756: 687b ldr r3, [r7, #4] + 8002758: 685b ldr r3, [r3, #4] + 800275a: 2b02 cmp r3, #2 + 800275c: d107 bne.n 800276e { /* Check the PLL ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 8002696: 4b40 ldr r3, [pc, #256] ; (8002798 ) - 8002698: 681b ldr r3, [r3, #0] - 800269a: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 800269e: 2b00 cmp r3, #0 - 80026a0: d109 bne.n 80026b6 + 800275e: 4b40 ldr r3, [pc, #256] ; (8002860 ) + 8002760: 681b ldr r3, [r3, #0] + 8002762: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002766: 2b00 cmp r3, #0 + 8002768: d109 bne.n 800277e { return HAL_ERROR; - 80026a2: 2301 movs r3, #1 - 80026a4: e071 b.n 800278a + 800276a: 2301 movs r3, #1 + 800276c: e071 b.n 8002852 } /* HSI is selected as System Clock Source */ else { /* Check the HSI ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 80026a6: 4b3c ldr r3, [pc, #240] ; (8002798 ) - 80026a8: 681b ldr r3, [r3, #0] - 80026aa: f003 0302 and.w r3, r3, #2 - 80026ae: 2b00 cmp r3, #0 - 80026b0: d101 bne.n 80026b6 + 800276e: 4b3c ldr r3, [pc, #240] ; (8002860 ) + 8002770: 681b ldr r3, [r3, #0] + 8002772: f003 0302 and.w r3, r3, #2 + 8002776: 2b00 cmp r3, #0 + 8002778: d101 bne.n 800277e { return HAL_ERROR; - 80026b2: 2301 movs r3, #1 - 80026b4: e069 b.n 800278a + 800277a: 2301 movs r3, #1 + 800277c: e069 b.n 8002852 } } __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); - 80026b6: 4b38 ldr r3, [pc, #224] ; (8002798 ) - 80026b8: 689b ldr r3, [r3, #8] - 80026ba: f023 0203 bic.w r2, r3, #3 - 80026be: 687b ldr r3, [r7, #4] - 80026c0: 685b ldr r3, [r3, #4] - 80026c2: 4935 ldr r1, [pc, #212] ; (8002798 ) - 80026c4: 4313 orrs r3, r2 - 80026c6: 608b str r3, [r1, #8] + 800277e: 4b38 ldr r3, [pc, #224] ; (8002860 ) + 8002780: 689b ldr r3, [r3, #8] + 8002782: f023 0203 bic.w r2, r3, #3 + 8002786: 687b ldr r3, [r7, #4] + 8002788: 685b ldr r3, [r3, #4] + 800278a: 4935 ldr r1, [pc, #212] ; (8002860 ) + 800278c: 4313 orrs r3, r2 + 800278e: 608b str r3, [r1, #8] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80026c8: f7ff f9f6 bl 8001ab8 - 80026cc: 60f8 str r0, [r7, #12] + 8002790: f7ff f9f6 bl 8001b80 + 8002794: 60f8 str r0, [r7, #12] while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - 80026ce: e00a b.n 80026e6 + 8002796: e00a b.n 80027ae { if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - 80026d0: f7ff f9f2 bl 8001ab8 - 80026d4: 4602 mov r2, r0 - 80026d6: 68fb ldr r3, [r7, #12] - 80026d8: 1ad3 subs r3, r2, r3 - 80026da: f241 3288 movw r2, #5000 ; 0x1388 - 80026de: 4293 cmp r3, r2 - 80026e0: d901 bls.n 80026e6 + 8002798: f7ff f9f2 bl 8001b80 + 800279c: 4602 mov r2, r0 + 800279e: 68fb ldr r3, [r7, #12] + 80027a0: 1ad3 subs r3, r2, r3 + 80027a2: f241 3288 movw r2, #5000 ; 0x1388 + 80027a6: 4293 cmp r3, r2 + 80027a8: d901 bls.n 80027ae { return HAL_TIMEOUT; - 80026e2: 2303 movs r3, #3 - 80026e4: e051 b.n 800278a + 80027aa: 2303 movs r3, #3 + 80027ac: e051 b.n 8002852 while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - 80026e6: 4b2c ldr r3, [pc, #176] ; (8002798 ) - 80026e8: 689b ldr r3, [r3, #8] - 80026ea: f003 020c and.w r2, r3, #12 - 80026ee: 687b ldr r3, [r7, #4] - 80026f0: 685b ldr r3, [r3, #4] - 80026f2: 009b lsls r3, r3, #2 - 80026f4: 429a cmp r2, r3 - 80026f6: d1eb bne.n 80026d0 + 80027ae: 4b2c ldr r3, [pc, #176] ; (8002860 ) + 80027b0: 689b ldr r3, [r3, #8] + 80027b2: f003 020c and.w r2, r3, #12 + 80027b6: 687b ldr r3, [r7, #4] + 80027b8: 685b ldr r3, [r3, #4] + 80027ba: 009b lsls r3, r3, #2 + 80027bc: 429a cmp r2, r3 + 80027be: d1eb bne.n 8002798 } } } /* Decreasing the number of wait states because of lower CPU frequency */ if(FLatency < __HAL_FLASH_GET_LATENCY()) - 80026f8: 4b26 ldr r3, [pc, #152] ; (8002794 ) - 80026fa: 681b ldr r3, [r3, #0] - 80026fc: f003 030f and.w r3, r3, #15 - 8002700: 683a ldr r2, [r7, #0] - 8002702: 429a cmp r2, r3 - 8002704: d210 bcs.n 8002728 + 80027c0: 4b26 ldr r3, [pc, #152] ; (800285c ) + 80027c2: 681b ldr r3, [r3, #0] + 80027c4: f003 030f and.w r3, r3, #15 + 80027c8: 683a ldr r2, [r7, #0] + 80027ca: 429a cmp r2, r3 + 80027cc: d210 bcs.n 80027f0 { /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ __HAL_FLASH_SET_LATENCY(FLatency); - 8002706: 4b23 ldr r3, [pc, #140] ; (8002794 ) - 8002708: 681b ldr r3, [r3, #0] - 800270a: f023 020f bic.w r2, r3, #15 - 800270e: 4921 ldr r1, [pc, #132] ; (8002794 ) - 8002710: 683b ldr r3, [r7, #0] - 8002712: 4313 orrs r3, r2 - 8002714: 600b str r3, [r1, #0] + 80027ce: 4b23 ldr r3, [pc, #140] ; (800285c ) + 80027d0: 681b ldr r3, [r3, #0] + 80027d2: f023 020f bic.w r2, r3, #15 + 80027d6: 4921 ldr r1, [pc, #132] ; (800285c ) + 80027d8: 683b ldr r3, [r7, #0] + 80027da: 4313 orrs r3, r2 + 80027dc: 600b str r3, [r1, #0] /* Check that the new number of wait states is taken into account to access the Flash memory by reading the FLASH_ACR register */ if(__HAL_FLASH_GET_LATENCY() != FLatency) - 8002716: 4b1f ldr r3, [pc, #124] ; (8002794 ) - 8002718: 681b ldr r3, [r3, #0] - 800271a: f003 030f and.w r3, r3, #15 - 800271e: 683a ldr r2, [r7, #0] - 8002720: 429a cmp r2, r3 - 8002722: d001 beq.n 8002728 + 80027de: 4b1f ldr r3, [pc, #124] ; (800285c ) + 80027e0: 681b ldr r3, [r3, #0] + 80027e2: f003 030f and.w r3, r3, #15 + 80027e6: 683a ldr r2, [r7, #0] + 80027e8: 429a cmp r2, r3 + 80027ea: d001 beq.n 80027f0 { return HAL_ERROR; - 8002724: 2301 movs r3, #1 - 8002726: e030 b.n 800278a + 80027ec: 2301 movs r3, #1 + 80027ee: e030 b.n 8002852 } } /*-------------------------- PCLK1 Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - 8002728: 687b ldr r3, [r7, #4] - 800272a: 681b ldr r3, [r3, #0] - 800272c: f003 0304 and.w r3, r3, #4 - 8002730: 2b00 cmp r3, #0 - 8002732: d008 beq.n 8002746 + 80027f0: 687b ldr r3, [r7, #4] + 80027f2: 681b ldr r3, [r3, #0] + 80027f4: f003 0304 and.w r3, r3, #4 + 80027f8: 2b00 cmp r3, #0 + 80027fa: d008 beq.n 800280e { assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); - 8002734: 4b18 ldr r3, [pc, #96] ; (8002798 ) - 8002736: 689b ldr r3, [r3, #8] - 8002738: f423 52e0 bic.w r2, r3, #7168 ; 0x1c00 - 800273c: 687b ldr r3, [r7, #4] - 800273e: 68db ldr r3, [r3, #12] - 8002740: 4915 ldr r1, [pc, #84] ; (8002798 ) - 8002742: 4313 orrs r3, r2 - 8002744: 608b str r3, [r1, #8] + 80027fc: 4b18 ldr r3, [pc, #96] ; (8002860 ) + 80027fe: 689b ldr r3, [r3, #8] + 8002800: f423 52e0 bic.w r2, r3, #7168 ; 0x1c00 + 8002804: 687b ldr r3, [r7, #4] + 8002806: 68db ldr r3, [r3, #12] + 8002808: 4915 ldr r1, [pc, #84] ; (8002860 ) + 800280a: 4313 orrs r3, r2 + 800280c: 608b str r3, [r1, #8] } /*-------------------------- PCLK2 Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - 8002746: 687b ldr r3, [r7, #4] - 8002748: 681b ldr r3, [r3, #0] - 800274a: f003 0308 and.w r3, r3, #8 - 800274e: 2b00 cmp r3, #0 - 8002750: d009 beq.n 8002766 + 800280e: 687b ldr r3, [r7, #4] + 8002810: 681b ldr r3, [r3, #0] + 8002812: f003 0308 and.w r3, r3, #8 + 8002816: 2b00 cmp r3, #0 + 8002818: d009 beq.n 800282e { assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3)); - 8002752: 4b11 ldr r3, [pc, #68] ; (8002798 ) - 8002754: 689b ldr r3, [r3, #8] - 8002756: f423 4260 bic.w r2, r3, #57344 ; 0xe000 - 800275a: 687b ldr r3, [r7, #4] - 800275c: 691b ldr r3, [r3, #16] - 800275e: 00db lsls r3, r3, #3 - 8002760: 490d ldr r1, [pc, #52] ; (8002798 ) - 8002762: 4313 orrs r3, r2 - 8002764: 608b str r3, [r1, #8] + 800281a: 4b11 ldr r3, [pc, #68] ; (8002860 ) + 800281c: 689b ldr r3, [r3, #8] + 800281e: f423 4260 bic.w r2, r3, #57344 ; 0xe000 + 8002822: 687b ldr r3, [r7, #4] + 8002824: 691b ldr r3, [r3, #16] + 8002826: 00db lsls r3, r3, #3 + 8002828: 490d ldr r1, [pc, #52] ; (8002860 ) + 800282a: 4313 orrs r3, r2 + 800282c: 608b str r3, [r1, #8] } /* Update the SystemCoreClock global variable */ SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; - 8002766: f000 f81d bl 80027a4 - 800276a: 4601 mov r1, r0 - 800276c: 4b0a ldr r3, [pc, #40] ; (8002798 ) - 800276e: 689b ldr r3, [r3, #8] - 8002770: 091b lsrs r3, r3, #4 - 8002772: f003 030f and.w r3, r3, #15 - 8002776: 4a09 ldr r2, [pc, #36] ; (800279c ) - 8002778: 5cd3 ldrb r3, [r2, r3] - 800277a: fa21 f303 lsr.w r3, r1, r3 - 800277e: 4a08 ldr r2, [pc, #32] ; (80027a0 ) - 8002780: 6013 str r3, [r2, #0] + 800282e: f000 f81d bl 800286c + 8002832: 4601 mov r1, r0 + 8002834: 4b0a ldr r3, [pc, #40] ; (8002860 ) + 8002836: 689b ldr r3, [r3, #8] + 8002838: 091b lsrs r3, r3, #4 + 800283a: f003 030f and.w r3, r3, #15 + 800283e: 4a09 ldr r2, [pc, #36] ; (8002864 ) + 8002840: 5cd3 ldrb r3, [r2, r3] + 8002842: fa21 f303 lsr.w r3, r1, r3 + 8002846: 4a08 ldr r2, [pc, #32] ; (8002868 ) + 8002848: 6013 str r3, [r2, #0] /* Configure the source of time base considering new system clocks settings*/ HAL_InitTick (TICK_INT_PRIORITY); - 8002782: 2000 movs r0, #0 - 8002784: f7ff f954 bl 8001a30 + 800284a: 2000 movs r0, #0 + 800284c: f7ff f954 bl 8001af8 return HAL_OK; - 8002788: 2300 movs r3, #0 + 8002850: 2300 movs r3, #0 } - 800278a: 4618 mov r0, r3 - 800278c: 3710 adds r7, #16 - 800278e: 46bd mov sp, r7 - 8002790: bd80 pop {r7, pc} - 8002792: bf00 nop - 8002794: 40023c00 .word 0x40023c00 - 8002798: 40023800 .word 0x40023800 - 800279c: 080052c8 .word 0x080052c8 - 80027a0: 20000008 .word 0x20000008 - -080027a4 : + 8002852: 4618 mov r0, r3 + 8002854: 3710 adds r7, #16 + 8002856: 46bd mov sp, r7 + 8002858: bd80 pop {r7, pc} + 800285a: bf00 nop + 800285c: 40023c00 .word 0x40023c00 + 8002860: 40023800 .word 0x40023800 + 8002864: 08005390 .word 0x08005390 + 8002868: 20000004 .word 0x20000004 + +0800286c : * * * @retval SYSCLK frequency */ uint32_t HAL_RCC_GetSysClockFreq(void) { - 80027a4: b5f0 push {r4, r5, r6, r7, lr} - 80027a6: b085 sub sp, #20 - 80027a8: af00 add r7, sp, #0 + 800286c: b5f0 push {r4, r5, r6, r7, lr} + 800286e: b085 sub sp, #20 + 8002870: af00 add r7, sp, #0 uint32_t pllm = 0, pllvco = 0, pllp = 0; - 80027aa: 2300 movs r3, #0 - 80027ac: 607b str r3, [r7, #4] - 80027ae: 2300 movs r3, #0 - 80027b0: 60fb str r3, [r7, #12] - 80027b2: 2300 movs r3, #0 - 80027b4: 603b str r3, [r7, #0] + 8002872: 2300 movs r3, #0 + 8002874: 607b str r3, [r7, #4] + 8002876: 2300 movs r3, #0 + 8002878: 60fb str r3, [r7, #12] + 800287a: 2300 movs r3, #0 + 800287c: 603b str r3, [r7, #0] uint32_t sysclockfreq = 0; - 80027b6: 2300 movs r3, #0 - 80027b8: 60bb str r3, [r7, #8] + 800287e: 2300 movs r3, #0 + 8002880: 60bb str r3, [r7, #8] /* Get SYSCLK source -------------------------------------------------------*/ switch (RCC->CFGR & RCC_CFGR_SWS) - 80027ba: 4b50 ldr r3, [pc, #320] ; (80028fc ) - 80027bc: 689b ldr r3, [r3, #8] - 80027be: f003 030c and.w r3, r3, #12 - 80027c2: 2b04 cmp r3, #4 - 80027c4: d007 beq.n 80027d6 - 80027c6: 2b08 cmp r3, #8 - 80027c8: d008 beq.n 80027dc - 80027ca: 2b00 cmp r3, #0 - 80027cc: f040 808d bne.w 80028ea + 8002882: 4b50 ldr r3, [pc, #320] ; (80029c4 ) + 8002884: 689b ldr r3, [r3, #8] + 8002886: f003 030c and.w r3, r3, #12 + 800288a: 2b04 cmp r3, #4 + 800288c: d007 beq.n 800289e + 800288e: 2b08 cmp r3, #8 + 8002890: d008 beq.n 80028a4 + 8002892: 2b00 cmp r3, #0 + 8002894: f040 808d bne.w 80029b2 { case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */ { sysclockfreq = HSI_VALUE; - 80027d0: 4b4b ldr r3, [pc, #300] ; (8002900 ) - 80027d2: 60bb str r3, [r7, #8] + 8002898: 4b4b ldr r3, [pc, #300] ; (80029c8 ) + 800289a: 60bb str r3, [r7, #8] break; - 80027d4: e08c b.n 80028f0 + 800289c: e08c b.n 80029b8 } case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock source */ { sysclockfreq = HSE_VALUE; - 80027d6: 4b4b ldr r3, [pc, #300] ; (8002904 ) - 80027d8: 60bb str r3, [r7, #8] + 800289e: 4b4b ldr r3, [pc, #300] ; (80029cc ) + 80028a0: 60bb str r3, [r7, #8] break; - 80027da: e089 b.n 80028f0 + 80028a2: e089 b.n 80029b8 } case RCC_SYSCLKSOURCE_STATUS_PLLCLK: /* PLL used as system clock source */ { /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN SYSCLK = PLL_VCO / PLLP */ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - 80027dc: 4b47 ldr r3, [pc, #284] ; (80028fc ) - 80027de: 685b ldr r3, [r3, #4] - 80027e0: f003 033f and.w r3, r3, #63 ; 0x3f - 80027e4: 607b str r3, [r7, #4] + 80028a4: 4b47 ldr r3, [pc, #284] ; (80029c4 ) + 80028a6: 685b ldr r3, [r3, #4] + 80028a8: f003 033f and.w r3, r3, #63 ; 0x3f + 80028ac: 607b str r3, [r7, #4] if (__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLCFGR_PLLSRC_HSI) - 80027e6: 4b45 ldr r3, [pc, #276] ; (80028fc ) - 80027e8: 685b ldr r3, [r3, #4] - 80027ea: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 80027ee: 2b00 cmp r3, #0 - 80027f0: d023 beq.n 800283a + 80028ae: 4b45 ldr r3, [pc, #276] ; (80029c4 ) + 80028b0: 685b ldr r3, [r3, #4] + 80028b2: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 80028b6: 2b00 cmp r3, #0 + 80028b8: d023 beq.n 8002902 { /* HSE used as PLL clock source */ pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - 80027f2: 4b42 ldr r3, [pc, #264] ; (80028fc ) - 80027f4: 685b ldr r3, [r3, #4] - 80027f6: 099b lsrs r3, r3, #6 - 80027f8: f04f 0400 mov.w r4, #0 - 80027fc: f240 11ff movw r1, #511 ; 0x1ff - 8002800: f04f 0200 mov.w r2, #0 - 8002804: ea03 0501 and.w r5, r3, r1 - 8002808: ea04 0602 and.w r6, r4, r2 - 800280c: 4a3d ldr r2, [pc, #244] ; (8002904 ) - 800280e: fb02 f106 mul.w r1, r2, r6 - 8002812: 2200 movs r2, #0 - 8002814: fb02 f205 mul.w r2, r2, r5 - 8002818: 440a add r2, r1 - 800281a: 493a ldr r1, [pc, #232] ; (8002904 ) - 800281c: fba5 0101 umull r0, r1, r5, r1 - 8002820: 1853 adds r3, r2, r1 - 8002822: 4619 mov r1, r3 - 8002824: 687b ldr r3, [r7, #4] - 8002826: f04f 0400 mov.w r4, #0 - 800282a: 461a mov r2, r3 - 800282c: 4623 mov r3, r4 - 800282e: f7fd fd03 bl 8000238 <__aeabi_uldivmod> - 8002832: 4603 mov r3, r0 - 8002834: 460c mov r4, r1 - 8002836: 60fb str r3, [r7, #12] - 8002838: e049 b.n 80028ce + 80028ba: 4b42 ldr r3, [pc, #264] ; (80029c4 ) + 80028bc: 685b ldr r3, [r3, #4] + 80028be: 099b lsrs r3, r3, #6 + 80028c0: f04f 0400 mov.w r4, #0 + 80028c4: f240 11ff movw r1, #511 ; 0x1ff + 80028c8: f04f 0200 mov.w r2, #0 + 80028cc: ea03 0501 and.w r5, r3, r1 + 80028d0: ea04 0602 and.w r6, r4, r2 + 80028d4: 4a3d ldr r2, [pc, #244] ; (80029cc ) + 80028d6: fb02 f106 mul.w r1, r2, r6 + 80028da: 2200 movs r2, #0 + 80028dc: fb02 f205 mul.w r2, r2, r5 + 80028e0: 440a add r2, r1 + 80028e2: 493a ldr r1, [pc, #232] ; (80029cc ) + 80028e4: fba5 0101 umull r0, r1, r5, r1 + 80028e8: 1853 adds r3, r2, r1 + 80028ea: 4619 mov r1, r3 + 80028ec: 687b ldr r3, [r7, #4] + 80028ee: f04f 0400 mov.w r4, #0 + 80028f2: 461a mov r2, r3 + 80028f4: 4623 mov r3, r4 + 80028f6: f7fd fc9f bl 8000238 <__aeabi_uldivmod> + 80028fa: 4603 mov r3, r0 + 80028fc: 460c mov r4, r1 + 80028fe: 60fb str r3, [r7, #12] + 8002900: e049 b.n 8002996 } else { /* HSI used as PLL clock source */ pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - 800283a: 4b30 ldr r3, [pc, #192] ; (80028fc ) - 800283c: 685b ldr r3, [r3, #4] - 800283e: 099b lsrs r3, r3, #6 - 8002840: f04f 0400 mov.w r4, #0 - 8002844: f240 11ff movw r1, #511 ; 0x1ff - 8002848: f04f 0200 mov.w r2, #0 - 800284c: ea03 0501 and.w r5, r3, r1 - 8002850: ea04 0602 and.w r6, r4, r2 - 8002854: 4629 mov r1, r5 - 8002856: 4632 mov r2, r6 - 8002858: f04f 0300 mov.w r3, #0 - 800285c: f04f 0400 mov.w r4, #0 - 8002860: 0154 lsls r4, r2, #5 - 8002862: ea44 64d1 orr.w r4, r4, r1, lsr #27 - 8002866: 014b lsls r3, r1, #5 - 8002868: 4619 mov r1, r3 - 800286a: 4622 mov r2, r4 - 800286c: 1b49 subs r1, r1, r5 - 800286e: eb62 0206 sbc.w r2, r2, r6 - 8002872: f04f 0300 mov.w r3, #0 - 8002876: f04f 0400 mov.w r4, #0 - 800287a: 0194 lsls r4, r2, #6 - 800287c: ea44 6491 orr.w r4, r4, r1, lsr #26 - 8002880: 018b lsls r3, r1, #6 - 8002882: 1a5b subs r3, r3, r1 - 8002884: eb64 0402 sbc.w r4, r4, r2 - 8002888: f04f 0100 mov.w r1, #0 - 800288c: f04f 0200 mov.w r2, #0 - 8002890: 00e2 lsls r2, r4, #3 - 8002892: ea42 7253 orr.w r2, r2, r3, lsr #29 - 8002896: 00d9 lsls r1, r3, #3 - 8002898: 460b mov r3, r1 - 800289a: 4614 mov r4, r2 - 800289c: 195b adds r3, r3, r5 - 800289e: eb44 0406 adc.w r4, r4, r6 - 80028a2: f04f 0100 mov.w r1, #0 - 80028a6: f04f 0200 mov.w r2, #0 - 80028aa: 02a2 lsls r2, r4, #10 - 80028ac: ea42 5293 orr.w r2, r2, r3, lsr #22 - 80028b0: 0299 lsls r1, r3, #10 - 80028b2: 460b mov r3, r1 - 80028b4: 4614 mov r4, r2 - 80028b6: 4618 mov r0, r3 - 80028b8: 4621 mov r1, r4 - 80028ba: 687b ldr r3, [r7, #4] - 80028bc: f04f 0400 mov.w r4, #0 - 80028c0: 461a mov r2, r3 - 80028c2: 4623 mov r3, r4 - 80028c4: f7fd fcb8 bl 8000238 <__aeabi_uldivmod> - 80028c8: 4603 mov r3, r0 - 80028ca: 460c mov r4, r1 - 80028cc: 60fb str r3, [r7, #12] + 8002902: 4b30 ldr r3, [pc, #192] ; (80029c4 ) + 8002904: 685b ldr r3, [r3, #4] + 8002906: 099b lsrs r3, r3, #6 + 8002908: f04f 0400 mov.w r4, #0 + 800290c: f240 11ff movw r1, #511 ; 0x1ff + 8002910: f04f 0200 mov.w r2, #0 + 8002914: ea03 0501 and.w r5, r3, r1 + 8002918: ea04 0602 and.w r6, r4, r2 + 800291c: 4629 mov r1, r5 + 800291e: 4632 mov r2, r6 + 8002920: f04f 0300 mov.w r3, #0 + 8002924: f04f 0400 mov.w r4, #0 + 8002928: 0154 lsls r4, r2, #5 + 800292a: ea44 64d1 orr.w r4, r4, r1, lsr #27 + 800292e: 014b lsls r3, r1, #5 + 8002930: 4619 mov r1, r3 + 8002932: 4622 mov r2, r4 + 8002934: 1b49 subs r1, r1, r5 + 8002936: eb62 0206 sbc.w r2, r2, r6 + 800293a: f04f 0300 mov.w r3, #0 + 800293e: f04f 0400 mov.w r4, #0 + 8002942: 0194 lsls r4, r2, #6 + 8002944: ea44 6491 orr.w r4, r4, r1, lsr #26 + 8002948: 018b lsls r3, r1, #6 + 800294a: 1a5b subs r3, r3, r1 + 800294c: eb64 0402 sbc.w r4, r4, r2 + 8002950: f04f 0100 mov.w r1, #0 + 8002954: f04f 0200 mov.w r2, #0 + 8002958: 00e2 lsls r2, r4, #3 + 800295a: ea42 7253 orr.w r2, r2, r3, lsr #29 + 800295e: 00d9 lsls r1, r3, #3 + 8002960: 460b mov r3, r1 + 8002962: 4614 mov r4, r2 + 8002964: 195b adds r3, r3, r5 + 8002966: eb44 0406 adc.w r4, r4, r6 + 800296a: f04f 0100 mov.w r1, #0 + 800296e: f04f 0200 mov.w r2, #0 + 8002972: 02a2 lsls r2, r4, #10 + 8002974: ea42 5293 orr.w r2, r2, r3, lsr #22 + 8002978: 0299 lsls r1, r3, #10 + 800297a: 460b mov r3, r1 + 800297c: 4614 mov r4, r2 + 800297e: 4618 mov r0, r3 + 8002980: 4621 mov r1, r4 + 8002982: 687b ldr r3, [r7, #4] + 8002984: f04f 0400 mov.w r4, #0 + 8002988: 461a mov r2, r3 + 800298a: 4623 mov r3, r4 + 800298c: f7fd fc54 bl 8000238 <__aeabi_uldivmod> + 8002990: 4603 mov r3, r0 + 8002992: 460c mov r4, r1 + 8002994: 60fb str r3, [r7, #12] } pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1 ) *2); - 80028ce: 4b0b ldr r3, [pc, #44] ; (80028fc ) - 80028d0: 685b ldr r3, [r3, #4] - 80028d2: 0c1b lsrs r3, r3, #16 - 80028d4: f003 0303 and.w r3, r3, #3 - 80028d8: 3301 adds r3, #1 - 80028da: 005b lsls r3, r3, #1 - 80028dc: 603b str r3, [r7, #0] + 8002996: 4b0b ldr r3, [pc, #44] ; (80029c4 ) + 8002998: 685b ldr r3, [r3, #4] + 800299a: 0c1b lsrs r3, r3, #16 + 800299c: f003 0303 and.w r3, r3, #3 + 80029a0: 3301 adds r3, #1 + 80029a2: 005b lsls r3, r3, #1 + 80029a4: 603b str r3, [r7, #0] sysclockfreq = pllvco/pllp; - 80028de: 68fa ldr r2, [r7, #12] - 80028e0: 683b ldr r3, [r7, #0] - 80028e2: fbb2 f3f3 udiv r3, r2, r3 - 80028e6: 60bb str r3, [r7, #8] + 80029a6: 68fa ldr r2, [r7, #12] + 80029a8: 683b ldr r3, [r7, #0] + 80029aa: fbb2 f3f3 udiv r3, r2, r3 + 80029ae: 60bb str r3, [r7, #8] break; - 80028e8: e002 b.n 80028f0 + 80029b0: e002 b.n 80029b8 } default: { sysclockfreq = HSI_VALUE; - 80028ea: 4b05 ldr r3, [pc, #20] ; (8002900 ) - 80028ec: 60bb str r3, [r7, #8] + 80029b2: 4b05 ldr r3, [pc, #20] ; (80029c8 ) + 80029b4: 60bb str r3, [r7, #8] break; - 80028ee: bf00 nop + 80029b6: bf00 nop } } return sysclockfreq; - 80028f0: 68bb ldr r3, [r7, #8] + 80029b8: 68bb ldr r3, [r7, #8] } - 80028f2: 4618 mov r0, r3 - 80028f4: 3714 adds r7, #20 - 80028f6: 46bd mov sp, r7 - 80028f8: bdf0 pop {r4, r5, r6, r7, pc} - 80028fa: bf00 nop - 80028fc: 40023800 .word 0x40023800 - 8002900: 00f42400 .word 0x00f42400 - 8002904: 017d7840 .word 0x017d7840 - -08002908 : + 80029ba: 4618 mov r0, r3 + 80029bc: 3714 adds r7, #20 + 80029be: 46bd mov sp, r7 + 80029c0: bdf0 pop {r4, r5, r6, r7, pc} + 80029c2: bf00 nop + 80029c4: 40023800 .word 0x40023800 + 80029c8: 00f42400 .word 0x00f42400 + 80029cc: 017d7840 .word 0x017d7840 + +080029d0 : * right HCLK value. Otherwise, any configuration based on this function will be incorrect. * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency. * @retval HCLK frequency */ uint32_t HAL_RCC_GetHCLKFreq(void) { - 8002908: b480 push {r7} - 800290a: af00 add r7, sp, #0 + 80029d0: b480 push {r7} + 80029d2: af00 add r7, sp, #0 return SystemCoreClock; - 800290c: 4b03 ldr r3, [pc, #12] ; (800291c ) - 800290e: 681b ldr r3, [r3, #0] + 80029d4: 4b03 ldr r3, [pc, #12] ; (80029e4 ) + 80029d6: 681b ldr r3, [r3, #0] } - 8002910: 4618 mov r0, r3 - 8002912: 46bd mov sp, r7 - 8002914: f85d 7b04 ldr.w r7, [sp], #4 - 8002918: 4770 bx lr - 800291a: bf00 nop - 800291c: 20000008 .word 0x20000008 - -08002920 : + 80029d8: 4618 mov r0, r3 + 80029da: 46bd mov sp, r7 + 80029dc: f85d 7b04 ldr.w r7, [sp], #4 + 80029e0: 4770 bx lr + 80029e2: bf00 nop + 80029e4: 20000004 .word 0x20000004 + +080029e8 : * @note Each time PCLK1 changes, this function must be called to update the * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect. * @retval PCLK1 frequency */ uint32_t HAL_RCC_GetPCLK1Freq(void) { - 8002920: b580 push {r7, lr} - 8002922: af00 add r7, sp, #0 + 80029e8: b580 push {r7, lr} + 80029ea: af00 add r7, sp, #0 /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/ return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> RCC_CFGR_PPRE1_Pos]); - 8002924: f7ff fff0 bl 8002908 - 8002928: 4601 mov r1, r0 - 800292a: 4b05 ldr r3, [pc, #20] ; (8002940 ) - 800292c: 689b ldr r3, [r3, #8] - 800292e: 0a9b lsrs r3, r3, #10 - 8002930: f003 0307 and.w r3, r3, #7 - 8002934: 4a03 ldr r2, [pc, #12] ; (8002944 ) - 8002936: 5cd3 ldrb r3, [r2, r3] - 8002938: fa21 f303 lsr.w r3, r1, r3 + 80029ec: f7ff fff0 bl 80029d0 + 80029f0: 4601 mov r1, r0 + 80029f2: 4b05 ldr r3, [pc, #20] ; (8002a08 ) + 80029f4: 689b ldr r3, [r3, #8] + 80029f6: 0a9b lsrs r3, r3, #10 + 80029f8: f003 0307 and.w r3, r3, #7 + 80029fc: 4a03 ldr r2, [pc, #12] ; (8002a0c ) + 80029fe: 5cd3 ldrb r3, [r2, r3] + 8002a00: fa21 f303 lsr.w r3, r1, r3 } - 800293c: 4618 mov r0, r3 - 800293e: bd80 pop {r7, pc} - 8002940: 40023800 .word 0x40023800 - 8002944: 080052d8 .word 0x080052d8 + 8002a04: 4618 mov r0, r3 + 8002a06: bd80 pop {r7, pc} + 8002a08: 40023800 .word 0x40023800 + 8002a0c: 080053a0 .word 0x080053a0 -08002948 : +08002a10 : * @note Each time PCLK2 changes, this function must be called to update the * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect. * @retval PCLK2 frequency */ uint32_t HAL_RCC_GetPCLK2Freq(void) { - 8002948: b580 push {r7, lr} - 800294a: af00 add r7, sp, #0 + 8002a10: b580 push {r7, lr} + 8002a12: af00 add r7, sp, #0 /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/ return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> RCC_CFGR_PPRE2_Pos]); - 800294c: f7ff ffdc bl 8002908 - 8002950: 4601 mov r1, r0 - 8002952: 4b05 ldr r3, [pc, #20] ; (8002968 ) - 8002954: 689b ldr r3, [r3, #8] - 8002956: 0b5b lsrs r3, r3, #13 - 8002958: f003 0307 and.w r3, r3, #7 - 800295c: 4a03 ldr r2, [pc, #12] ; (800296c ) - 800295e: 5cd3 ldrb r3, [r2, r3] - 8002960: fa21 f303 lsr.w r3, r1, r3 + 8002a14: f7ff ffdc bl 80029d0 + 8002a18: 4601 mov r1, r0 + 8002a1a: 4b05 ldr r3, [pc, #20] ; (8002a30 ) + 8002a1c: 689b ldr r3, [r3, #8] + 8002a1e: 0b5b lsrs r3, r3, #13 + 8002a20: f003 0307 and.w r3, r3, #7 + 8002a24: 4a03 ldr r2, [pc, #12] ; (8002a34 ) + 8002a26: 5cd3 ldrb r3, [r2, r3] + 8002a28: fa21 f303 lsr.w r3, r1, r3 } - 8002964: 4618 mov r0, r3 - 8002966: bd80 pop {r7, pc} - 8002968: 40023800 .word 0x40023800 - 800296c: 080052d8 .word 0x080052d8 + 8002a2c: 4618 mov r0, r3 + 8002a2e: bd80 pop {r7, pc} + 8002a30: 40023800 .word 0x40023800 + 8002a34: 080053a0 .word 0x080053a0 -08002970 : +08002a38 : * the backup registers) are set to their reset values. * * @retval HAL status */ HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) { - 8002970: b580 push {r7, lr} - 8002972: b088 sub sp, #32 - 8002974: af00 add r7, sp, #0 - 8002976: 6078 str r0, [r7, #4] + 8002a38: b580 push {r7, lr} + 8002a3a: b088 sub sp, #32 + 8002a3c: af00 add r7, sp, #0 + 8002a3e: 6078 str r0, [r7, #4] uint32_t tickstart = 0; - 8002978: 2300 movs r3, #0 - 800297a: 617b str r3, [r7, #20] + 8002a40: 2300 movs r3, #0 + 8002a42: 617b str r3, [r7, #20] uint32_t tmpreg0 = 0; - 800297c: 2300 movs r3, #0 - 800297e: 613b str r3, [r7, #16] + 8002a44: 2300 movs r3, #0 + 8002a46: 613b str r3, [r7, #16] uint32_t tmpreg1 = 0; - 8002980: 2300 movs r3, #0 - 8002982: 60fb str r3, [r7, #12] + 8002a48: 2300 movs r3, #0 + 8002a4a: 60fb str r3, [r7, #12] uint32_t plli2sused = 0; - 8002984: 2300 movs r3, #0 - 8002986: 61fb str r3, [r7, #28] + 8002a4c: 2300 movs r3, #0 + 8002a4e: 61fb str r3, [r7, #28] uint32_t pllsaiused = 0; - 8002988: 2300 movs r3, #0 - 800298a: 61bb str r3, [r7, #24] + 8002a50: 2300 movs r3, #0 + 8002a52: 61bb str r3, [r7, #24] /* Check the parameters */ assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); /*----------------------------------- I2S configuration ----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) - 800298c: 687b ldr r3, [r7, #4] - 800298e: 681b ldr r3, [r3, #0] - 8002990: f003 0301 and.w r3, r3, #1 - 8002994: 2b00 cmp r3, #0 - 8002996: d012 beq.n 80029be + 8002a54: 687b ldr r3, [r7, #4] + 8002a56: 681b ldr r3, [r3, #0] + 8002a58: f003 0301 and.w r3, r3, #1 + 8002a5c: 2b00 cmp r3, #0 + 8002a5e: d012 beq.n 8002a86 { /* Check the parameters */ assert_param(IS_RCC_I2SCLKSOURCE(PeriphClkInit->I2sClockSelection)); /* Configure I2S Clock source */ __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2sClockSelection); - 8002998: 4b69 ldr r3, [pc, #420] ; (8002b40 ) - 800299a: 689b ldr r3, [r3, #8] - 800299c: 4a68 ldr r2, [pc, #416] ; (8002b40 ) - 800299e: f423 0300 bic.w r3, r3, #8388608 ; 0x800000 - 80029a2: 6093 str r3, [r2, #8] - 80029a4: 4b66 ldr r3, [pc, #408] ; (8002b40 ) - 80029a6: 689a ldr r2, [r3, #8] - 80029a8: 687b ldr r3, [r7, #4] - 80029aa: 6b5b ldr r3, [r3, #52] ; 0x34 - 80029ac: 4964 ldr r1, [pc, #400] ; (8002b40 ) - 80029ae: 4313 orrs r3, r2 - 80029b0: 608b str r3, [r1, #8] + 8002a60: 4b69 ldr r3, [pc, #420] ; (8002c08 ) + 8002a62: 689b ldr r3, [r3, #8] + 8002a64: 4a68 ldr r2, [pc, #416] ; (8002c08 ) + 8002a66: f423 0300 bic.w r3, r3, #8388608 ; 0x800000 + 8002a6a: 6093 str r3, [r2, #8] + 8002a6c: 4b66 ldr r3, [pc, #408] ; (8002c08 ) + 8002a6e: 689a ldr r2, [r3, #8] + 8002a70: 687b ldr r3, [r7, #4] + 8002a72: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002a74: 4964 ldr r1, [pc, #400] ; (8002c08 ) + 8002a76: 4313 orrs r3, r2 + 8002a78: 608b str r3, [r1, #8] /* Enable the PLLI2S when it's used as clock source for I2S */ if(PeriphClkInit->I2sClockSelection == RCC_I2SCLKSOURCE_PLLI2S) - 80029b2: 687b ldr r3, [r7, #4] - 80029b4: 6b5b ldr r3, [r3, #52] ; 0x34 - 80029b6: 2b00 cmp r3, #0 - 80029b8: d101 bne.n 80029be + 8002a7a: 687b ldr r3, [r7, #4] + 8002a7c: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002a7e: 2b00 cmp r3, #0 + 8002a80: d101 bne.n 8002a86 { plli2sused = 1; - 80029ba: 2301 movs r3, #1 - 80029bc: 61fb str r3, [r7, #28] + 8002a82: 2301 movs r3, #1 + 8002a84: 61fb str r3, [r7, #28] } } /*------------------------------------ SAI1 configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) - 80029be: 687b ldr r3, [r7, #4] - 80029c0: 681b ldr r3, [r3, #0] - 80029c2: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 80029c6: 2b00 cmp r3, #0 - 80029c8: d017 beq.n 80029fa + 8002a86: 687b ldr r3, [r7, #4] + 8002a88: 681b ldr r3, [r3, #0] + 8002a8a: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8002a8e: 2b00 cmp r3, #0 + 8002a90: d017 beq.n 8002ac2 { /* Check the parameters */ assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); /* Configure SAI1 Clock source */ __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); - 80029ca: 4b5d ldr r3, [pc, #372] ; (8002b40 ) - 80029cc: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80029d0: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 - 80029d4: 687b ldr r3, [r7, #4] - 80029d6: 6bdb ldr r3, [r3, #60] ; 0x3c - 80029d8: 4959 ldr r1, [pc, #356] ; (8002b40 ) - 80029da: 4313 orrs r3, r2 - 80029dc: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002a92: 4b5d ldr r3, [pc, #372] ; (8002c08 ) + 8002a94: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002a98: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 8002a9c: 687b ldr r3, [r7, #4] + 8002a9e: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002aa0: 4959 ldr r1, [pc, #356] ; (8002c08 ) + 8002aa2: 4313 orrs r3, r2 + 8002aa4: f8c1 308c str.w r3, [r1, #140] ; 0x8c /* Enable the PLLI2S when it's used as clock source for SAI */ if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S) - 80029e0: 687b ldr r3, [r7, #4] - 80029e2: 6bdb ldr r3, [r3, #60] ; 0x3c - 80029e4: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 80029e8: d101 bne.n 80029ee + 8002aa8: 687b ldr r3, [r7, #4] + 8002aaa: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002aac: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8002ab0: d101 bne.n 8002ab6 { plli2sused = 1; - 80029ea: 2301 movs r3, #1 - 80029ec: 61fb str r3, [r7, #28] + 8002ab2: 2301 movs r3, #1 + 8002ab4: 61fb str r3, [r7, #28] } /* Enable the PLLSAI when it's used as clock source for SAI */ if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) - 80029ee: 687b ldr r3, [r7, #4] - 80029f0: 6bdb ldr r3, [r3, #60] ; 0x3c - 80029f2: 2b00 cmp r3, #0 - 80029f4: d101 bne.n 80029fa + 8002ab6: 687b ldr r3, [r7, #4] + 8002ab8: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002aba: 2b00 cmp r3, #0 + 8002abc: d101 bne.n 8002ac2 { pllsaiused = 1; - 80029f6: 2301 movs r3, #1 - 80029f8: 61bb str r3, [r7, #24] + 8002abe: 2301 movs r3, #1 + 8002ac0: 61bb str r3, [r7, #24] } } /*------------------------------------ SAI2 configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) - 80029fa: 687b ldr r3, [r7, #4] - 80029fc: 681b ldr r3, [r3, #0] - 80029fe: f403 1380 and.w r3, r3, #1048576 ; 0x100000 - 8002a02: 2b00 cmp r3, #0 - 8002a04: d017 beq.n 8002a36 + 8002ac2: 687b ldr r3, [r7, #4] + 8002ac4: 681b ldr r3, [r3, #0] + 8002ac6: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8002aca: 2b00 cmp r3, #0 + 8002acc: d017 beq.n 8002afe { /* Check the parameters */ assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); /* Configure SAI2 Clock source */ __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); - 8002a06: 4b4e ldr r3, [pc, #312] ; (8002b40 ) - 8002a08: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002a0c: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 - 8002a10: 687b ldr r3, [r7, #4] - 8002a12: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002a14: 494a ldr r1, [pc, #296] ; (8002b40 ) - 8002a16: 4313 orrs r3, r2 - 8002a18: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002ace: 4b4e ldr r3, [pc, #312] ; (8002c08 ) + 8002ad0: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002ad4: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 8002ad8: 687b ldr r3, [r7, #4] + 8002ada: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002adc: 494a ldr r1, [pc, #296] ; (8002c08 ) + 8002ade: 4313 orrs r3, r2 + 8002ae0: f8c1 308c str.w r3, [r1, #140] ; 0x8c /* Enable the PLLI2S when it's used as clock source for SAI */ if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S) - 8002a1c: 687b ldr r3, [r7, #4] - 8002a1e: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002a20: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 8002a24: d101 bne.n 8002a2a + 8002ae4: 687b ldr r3, [r7, #4] + 8002ae6: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002ae8: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002aec: d101 bne.n 8002af2 { plli2sused = 1; - 8002a26: 2301 movs r3, #1 - 8002a28: 61fb str r3, [r7, #28] + 8002aee: 2301 movs r3, #1 + 8002af0: 61fb str r3, [r7, #28] } /* Enable the PLLSAI when it's used as clock source for SAI */ if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) - 8002a2a: 687b ldr r3, [r7, #4] - 8002a2c: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002a2e: 2b00 cmp r3, #0 - 8002a30: d101 bne.n 8002a36 + 8002af2: 687b ldr r3, [r7, #4] + 8002af4: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002af6: 2b00 cmp r3, #0 + 8002af8: d101 bne.n 8002afe { pllsaiused = 1; - 8002a32: 2301 movs r3, #1 - 8002a34: 61bb str r3, [r7, #24] + 8002afa: 2301 movs r3, #1 + 8002afc: 61bb str r3, [r7, #24] } } /*-------------------------------------- SPDIF-RX Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) - 8002a36: 687b ldr r3, [r7, #4] - 8002a38: 681b ldr r3, [r3, #0] - 8002a3a: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 - 8002a3e: 2b00 cmp r3, #0 - 8002a40: d001 beq.n 8002a46 + 8002afe: 687b ldr r3, [r7, #4] + 8002b00: 681b ldr r3, [r3, #0] + 8002b02: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8002b06: 2b00 cmp r3, #0 + 8002b08: d001 beq.n 8002b0e { plli2sused = 1; - 8002a42: 2301 movs r3, #1 - 8002a44: 61fb str r3, [r7, #28] + 8002b0a: 2301 movs r3, #1 + 8002b0c: 61fb str r3, [r7, #28] } /*------------------------------------ RTC configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - 8002a46: 687b ldr r3, [r7, #4] - 8002a48: 681b ldr r3, [r3, #0] - 8002a4a: f003 0320 and.w r3, r3, #32 - 8002a4e: 2b00 cmp r3, #0 - 8002a50: f000 808b beq.w 8002b6a + 8002b0e: 687b ldr r3, [r7, #4] + 8002b10: 681b ldr r3, [r3, #0] + 8002b12: f003 0320 and.w r3, r3, #32 + 8002b16: 2b00 cmp r3, #0 + 8002b18: f000 808b beq.w 8002c32 { /* Check for RTC Parameters used to output RTCCLK */ assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); /* Enable Power Clock*/ __HAL_RCC_PWR_CLK_ENABLE(); - 8002a54: 4b3a ldr r3, [pc, #232] ; (8002b40 ) - 8002a56: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002a58: 4a39 ldr r2, [pc, #228] ; (8002b40 ) - 8002a5a: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8002a5e: 6413 str r3, [r2, #64] ; 0x40 - 8002a60: 4b37 ldr r3, [pc, #220] ; (8002b40 ) - 8002a62: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002a64: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002a68: 60bb str r3, [r7, #8] - 8002a6a: 68bb ldr r3, [r7, #8] + 8002b1c: 4b3a ldr r3, [pc, #232] ; (8002c08 ) + 8002b1e: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002b20: 4a39 ldr r2, [pc, #228] ; (8002c08 ) + 8002b22: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8002b26: 6413 str r3, [r2, #64] ; 0x40 + 8002b28: 4b37 ldr r3, [pc, #220] ; (8002c08 ) + 8002b2a: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002b2c: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002b30: 60bb str r3, [r7, #8] + 8002b32: 68bb ldr r3, [r7, #8] /* Enable write access to Backup domain */ PWR->CR1 |= PWR_CR1_DBP; - 8002a6c: 4b35 ldr r3, [pc, #212] ; (8002b44 ) - 8002a6e: 681b ldr r3, [r3, #0] - 8002a70: 4a34 ldr r2, [pc, #208] ; (8002b44 ) - 8002a72: f443 7380 orr.w r3, r3, #256 ; 0x100 - 8002a76: 6013 str r3, [r2, #0] + 8002b34: 4b35 ldr r3, [pc, #212] ; (8002c0c ) + 8002b36: 681b ldr r3, [r3, #0] + 8002b38: 4a34 ldr r2, [pc, #208] ; (8002c0c ) + 8002b3a: f443 7380 orr.w r3, r3, #256 ; 0x100 + 8002b3e: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002a78: f7ff f81e bl 8001ab8 - 8002a7c: 6178 str r0, [r7, #20] + 8002b40: f7ff f81e bl 8001b80 + 8002b44: 6178 str r0, [r7, #20] /* Wait for Backup domain Write protection disable */ while((PWR->CR1 & PWR_CR1_DBP) == RESET) - 8002a7e: e008 b.n 8002a92 + 8002b46: e008 b.n 8002b5a { if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - 8002a80: f7ff f81a bl 8001ab8 - 8002a84: 4602 mov r2, r0 - 8002a86: 697b ldr r3, [r7, #20] - 8002a88: 1ad3 subs r3, r2, r3 - 8002a8a: 2b64 cmp r3, #100 ; 0x64 - 8002a8c: d901 bls.n 8002a92 + 8002b48: f7ff f81a bl 8001b80 + 8002b4c: 4602 mov r2, r0 + 8002b4e: 697b ldr r3, [r7, #20] + 8002b50: 1ad3 subs r3, r2, r3 + 8002b52: 2b64 cmp r3, #100 ; 0x64 + 8002b54: d901 bls.n 8002b5a { return HAL_TIMEOUT; - 8002a8e: 2303 movs r3, #3 - 8002a90: e38d b.n 80031ae + 8002b56: 2303 movs r3, #3 + 8002b58: e38d b.n 8003276 while((PWR->CR1 & PWR_CR1_DBP) == RESET) - 8002a92: 4b2c ldr r3, [pc, #176] ; (8002b44 ) - 8002a94: 681b ldr r3, [r3, #0] - 8002a96: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002a9a: 2b00 cmp r3, #0 - 8002a9c: d0f0 beq.n 8002a80 + 8002b5a: 4b2c ldr r3, [pc, #176] ; (8002c0c ) + 8002b5c: 681b ldr r3, [r3, #0] + 8002b5e: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002b62: 2b00 cmp r3, #0 + 8002b64: d0f0 beq.n 8002b48 } } /* Reset the Backup domain only if the RTC Clock source selection is modified */ tmpreg0 = (RCC->BDCR & RCC_BDCR_RTCSEL); - 8002a9e: 4b28 ldr r3, [pc, #160] ; (8002b40 ) - 8002aa0: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002aa2: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002aa6: 613b str r3, [r7, #16] + 8002b66: 4b28 ldr r3, [pc, #160] ; (8002c08 ) + 8002b68: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002b6a: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002b6e: 613b str r3, [r7, #16] if((tmpreg0 != 0x00000000U) && (tmpreg0 != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - 8002aa8: 693b ldr r3, [r7, #16] - 8002aaa: 2b00 cmp r3, #0 - 8002aac: d035 beq.n 8002b1a - 8002aae: 687b ldr r3, [r7, #4] - 8002ab0: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002ab2: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002ab6: 693a ldr r2, [r7, #16] - 8002ab8: 429a cmp r2, r3 - 8002aba: d02e beq.n 8002b1a + 8002b70: 693b ldr r3, [r7, #16] + 8002b72: 2b00 cmp r3, #0 + 8002b74: d035 beq.n 8002be2 + 8002b76: 687b ldr r3, [r7, #4] + 8002b78: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002b7a: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002b7e: 693a ldr r2, [r7, #16] + 8002b80: 429a cmp r2, r3 + 8002b82: d02e beq.n 8002be2 { /* Store the content of BDCR register before the reset of Backup Domain */ tmpreg0 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - 8002abc: 4b20 ldr r3, [pc, #128] ; (8002b40 ) - 8002abe: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002ac0: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8002ac4: 613b str r3, [r7, #16] + 8002b84: 4b20 ldr r3, [pc, #128] ; (8002c08 ) + 8002b86: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002b88: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8002b8c: 613b str r3, [r7, #16] /* RTC Clock selection can be changed only if the Backup Domain is reset */ __HAL_RCC_BACKUPRESET_FORCE(); - 8002ac6: 4b1e ldr r3, [pc, #120] ; (8002b40 ) - 8002ac8: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002aca: 4a1d ldr r2, [pc, #116] ; (8002b40 ) - 8002acc: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 8002ad0: 6713 str r3, [r2, #112] ; 0x70 + 8002b8e: 4b1e ldr r3, [pc, #120] ; (8002c08 ) + 8002b90: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002b92: 4a1d ldr r2, [pc, #116] ; (8002c08 ) + 8002b94: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 8002b98: 6713 str r3, [r2, #112] ; 0x70 __HAL_RCC_BACKUPRESET_RELEASE(); - 8002ad2: 4b1b ldr r3, [pc, #108] ; (8002b40 ) - 8002ad4: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002ad6: 4a1a ldr r2, [pc, #104] ; (8002b40 ) - 8002ad8: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 8002adc: 6713 str r3, [r2, #112] ; 0x70 + 8002b9a: 4b1b ldr r3, [pc, #108] ; (8002c08 ) + 8002b9c: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002b9e: 4a1a ldr r2, [pc, #104] ; (8002c08 ) + 8002ba0: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002ba4: 6713 str r3, [r2, #112] ; 0x70 /* Restore the Content of BDCR register */ RCC->BDCR = tmpreg0; - 8002ade: 4a18 ldr r2, [pc, #96] ; (8002b40 ) - 8002ae0: 693b ldr r3, [r7, #16] - 8002ae2: 6713 str r3, [r2, #112] ; 0x70 + 8002ba6: 4a18 ldr r2, [pc, #96] ; (8002c08 ) + 8002ba8: 693b ldr r3, [r7, #16] + 8002baa: 6713 str r3, [r2, #112] ; 0x70 /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ if (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - 8002ae4: 4b16 ldr r3, [pc, #88] ; (8002b40 ) - 8002ae6: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002ae8: f003 0301 and.w r3, r3, #1 - 8002aec: 2b01 cmp r3, #1 - 8002aee: d114 bne.n 8002b1a + 8002bac: 4b16 ldr r3, [pc, #88] ; (8002c08 ) + 8002bae: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002bb0: f003 0301 and.w r3, r3, #1 + 8002bb4: 2b01 cmp r3, #1 + 8002bb6: d114 bne.n 8002be2 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002af0: f7fe ffe2 bl 8001ab8 - 8002af4: 6178 str r0, [r7, #20] + 8002bb8: f7fe ffe2 bl 8001b80 + 8002bbc: 6178 str r0, [r7, #20] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002af6: e00a b.n 8002b0e + 8002bbe: e00a b.n 8002bd6 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 8002af8: f7fe ffde bl 8001ab8 - 8002afc: 4602 mov r2, r0 - 8002afe: 697b ldr r3, [r7, #20] - 8002b00: 1ad3 subs r3, r2, r3 - 8002b02: f241 3288 movw r2, #5000 ; 0x1388 - 8002b06: 4293 cmp r3, r2 - 8002b08: d901 bls.n 8002b0e + 8002bc0: f7fe ffde bl 8001b80 + 8002bc4: 4602 mov r2, r0 + 8002bc6: 697b ldr r3, [r7, #20] + 8002bc8: 1ad3 subs r3, r2, r3 + 8002bca: f241 3288 movw r2, #5000 ; 0x1388 + 8002bce: 4293 cmp r3, r2 + 8002bd0: d901 bls.n 8002bd6 { return HAL_TIMEOUT; - 8002b0a: 2303 movs r3, #3 - 8002b0c: e34f b.n 80031ae + 8002bd2: 2303 movs r3, #3 + 8002bd4: e34f b.n 8003276 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002b0e: 4b0c ldr r3, [pc, #48] ; (8002b40 ) - 8002b10: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002b12: f003 0302 and.w r3, r3, #2 - 8002b16: 2b00 cmp r3, #0 - 8002b18: d0ee beq.n 8002af8 + 8002bd6: 4b0c ldr r3, [pc, #48] ; (8002c08 ) + 8002bd8: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002bda: f003 0302 and.w r3, r3, #2 + 8002bde: 2b00 cmp r3, #0 + 8002be0: d0ee beq.n 8002bc0 } } } } __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - 8002b1a: 687b ldr r3, [r7, #4] - 8002b1c: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002b1e: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002b22: f5b3 7f40 cmp.w r3, #768 ; 0x300 - 8002b26: d111 bne.n 8002b4c - 8002b28: 4b05 ldr r3, [pc, #20] ; (8002b40 ) - 8002b2a: 689b ldr r3, [r3, #8] - 8002b2c: f423 12f8 bic.w r2, r3, #2031616 ; 0x1f0000 - 8002b30: 687b ldr r3, [r7, #4] - 8002b32: 6b19 ldr r1, [r3, #48] ; 0x30 - 8002b34: 4b04 ldr r3, [pc, #16] ; (8002b48 ) - 8002b36: 400b ands r3, r1 - 8002b38: 4901 ldr r1, [pc, #4] ; (8002b40 ) - 8002b3a: 4313 orrs r3, r2 - 8002b3c: 608b str r3, [r1, #8] - 8002b3e: e00b b.n 8002b58 - 8002b40: 40023800 .word 0x40023800 - 8002b44: 40007000 .word 0x40007000 - 8002b48: 0ffffcff .word 0x0ffffcff - 8002b4c: 4bb3 ldr r3, [pc, #716] ; (8002e1c ) - 8002b4e: 689b ldr r3, [r3, #8] - 8002b50: 4ab2 ldr r2, [pc, #712] ; (8002e1c ) - 8002b52: f423 13f8 bic.w r3, r3, #2031616 ; 0x1f0000 - 8002b56: 6093 str r3, [r2, #8] - 8002b58: 4bb0 ldr r3, [pc, #704] ; (8002e1c ) - 8002b5a: 6f1a ldr r2, [r3, #112] ; 0x70 - 8002b5c: 687b ldr r3, [r7, #4] - 8002b5e: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002b60: f3c3 030b ubfx r3, r3, #0, #12 - 8002b64: 49ad ldr r1, [pc, #692] ; (8002e1c ) - 8002b66: 4313 orrs r3, r2 - 8002b68: 670b str r3, [r1, #112] ; 0x70 + 8002be2: 687b ldr r3, [r7, #4] + 8002be4: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002be6: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002bea: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8002bee: d111 bne.n 8002c14 + 8002bf0: 4b05 ldr r3, [pc, #20] ; (8002c08 ) + 8002bf2: 689b ldr r3, [r3, #8] + 8002bf4: f423 12f8 bic.w r2, r3, #2031616 ; 0x1f0000 + 8002bf8: 687b ldr r3, [r7, #4] + 8002bfa: 6b19 ldr r1, [r3, #48] ; 0x30 + 8002bfc: 4b04 ldr r3, [pc, #16] ; (8002c10 ) + 8002bfe: 400b ands r3, r1 + 8002c00: 4901 ldr r1, [pc, #4] ; (8002c08 ) + 8002c02: 4313 orrs r3, r2 + 8002c04: 608b str r3, [r1, #8] + 8002c06: e00b b.n 8002c20 + 8002c08: 40023800 .word 0x40023800 + 8002c0c: 40007000 .word 0x40007000 + 8002c10: 0ffffcff .word 0x0ffffcff + 8002c14: 4bb3 ldr r3, [pc, #716] ; (8002ee4 ) + 8002c16: 689b ldr r3, [r3, #8] + 8002c18: 4ab2 ldr r2, [pc, #712] ; (8002ee4 ) + 8002c1a: f423 13f8 bic.w r3, r3, #2031616 ; 0x1f0000 + 8002c1e: 6093 str r3, [r2, #8] + 8002c20: 4bb0 ldr r3, [pc, #704] ; (8002ee4 ) + 8002c22: 6f1a ldr r2, [r3, #112] ; 0x70 + 8002c24: 687b ldr r3, [r7, #4] + 8002c26: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002c28: f3c3 030b ubfx r3, r3, #0, #12 + 8002c2c: 49ad ldr r1, [pc, #692] ; (8002ee4 ) + 8002c2e: 4313 orrs r3, r2 + 8002c30: 670b str r3, [r1, #112] ; 0x70 } /*------------------------------------ TIM configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - 8002b6a: 687b ldr r3, [r7, #4] - 8002b6c: 681b ldr r3, [r3, #0] - 8002b6e: f003 0310 and.w r3, r3, #16 - 8002b72: 2b00 cmp r3, #0 - 8002b74: d010 beq.n 8002b98 + 8002c32: 687b ldr r3, [r7, #4] + 8002c34: 681b ldr r3, [r3, #0] + 8002c36: f003 0310 and.w r3, r3, #16 + 8002c3a: 2b00 cmp r3, #0 + 8002c3c: d010 beq.n 8002c60 { /* Check the parameters */ assert_param(IS_RCC_TIMPRES(PeriphClkInit->TIMPresSelection)); /* Configure Timer Prescaler */ __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - 8002b76: 4ba9 ldr r3, [pc, #676] ; (8002e1c ) - 8002b78: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002b7c: 4aa7 ldr r2, [pc, #668] ; (8002e1c ) - 8002b7e: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 8002b82: f8c2 308c str.w r3, [r2, #140] ; 0x8c - 8002b86: 4ba5 ldr r3, [pc, #660] ; (8002e1c ) - 8002b88: f8d3 208c ldr.w r2, [r3, #140] ; 0x8c - 8002b8c: 687b ldr r3, [r7, #4] - 8002b8e: 6b9b ldr r3, [r3, #56] ; 0x38 - 8002b90: 49a2 ldr r1, [pc, #648] ; (8002e1c ) - 8002b92: 4313 orrs r3, r2 - 8002b94: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002c3e: 4ba9 ldr r3, [pc, #676] ; (8002ee4 ) + 8002c40: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002c44: 4aa7 ldr r2, [pc, #668] ; (8002ee4 ) + 8002c46: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 8002c4a: f8c2 308c str.w r3, [r2, #140] ; 0x8c + 8002c4e: 4ba5 ldr r3, [pc, #660] ; (8002ee4 ) + 8002c50: f8d3 208c ldr.w r2, [r3, #140] ; 0x8c + 8002c54: 687b ldr r3, [r7, #4] + 8002c56: 6b9b ldr r3, [r3, #56] ; 0x38 + 8002c58: 49a2 ldr r1, [pc, #648] ; (8002ee4 ) + 8002c5a: 4313 orrs r3, r2 + 8002c5c: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*-------------------------------------- I2C1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C1) == RCC_PERIPHCLK_I2C1) - 8002b98: 687b ldr r3, [r7, #4] - 8002b9a: 681b ldr r3, [r3, #0] - 8002b9c: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 8002ba0: 2b00 cmp r3, #0 - 8002ba2: d00a beq.n 8002bba + 8002c60: 687b ldr r3, [r7, #4] + 8002c62: 681b ldr r3, [r3, #0] + 8002c64: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8002c68: 2b00 cmp r3, #0 + 8002c6a: d00a beq.n 8002c82 { /* Check the parameters */ assert_param(IS_RCC_I2C1CLKSOURCE(PeriphClkInit->I2c1ClockSelection)); /* Configure the I2C1 clock source */ __HAL_RCC_I2C1_CONFIG(PeriphClkInit->I2c1ClockSelection); - 8002ba4: 4b9d ldr r3, [pc, #628] ; (8002e1c ) - 8002ba6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002baa: f423 3240 bic.w r2, r3, #196608 ; 0x30000 - 8002bae: 687b ldr r3, [r7, #4] - 8002bb0: 6e5b ldr r3, [r3, #100] ; 0x64 - 8002bb2: 499a ldr r1, [pc, #616] ; (8002e1c ) - 8002bb4: 4313 orrs r3, r2 - 8002bb6: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002c6c: 4b9d ldr r3, [pc, #628] ; (8002ee4 ) + 8002c6e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c72: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8002c76: 687b ldr r3, [r7, #4] + 8002c78: 6e5b ldr r3, [r3, #100] ; 0x64 + 8002c7a: 499a ldr r1, [pc, #616] ; (8002ee4 ) + 8002c7c: 4313 orrs r3, r2 + 8002c7e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C2 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C2) == RCC_PERIPHCLK_I2C2) - 8002bba: 687b ldr r3, [r7, #4] - 8002bbc: 681b ldr r3, [r3, #0] - 8002bbe: f403 4300 and.w r3, r3, #32768 ; 0x8000 - 8002bc2: 2b00 cmp r3, #0 - 8002bc4: d00a beq.n 8002bdc + 8002c82: 687b ldr r3, [r7, #4] + 8002c84: 681b ldr r3, [r3, #0] + 8002c86: f403 4300 and.w r3, r3, #32768 ; 0x8000 + 8002c8a: 2b00 cmp r3, #0 + 8002c8c: d00a beq.n 8002ca4 { /* Check the parameters */ assert_param(IS_RCC_I2C2CLKSOURCE(PeriphClkInit->I2c2ClockSelection)); /* Configure the I2C2 clock source */ __HAL_RCC_I2C2_CONFIG(PeriphClkInit->I2c2ClockSelection); - 8002bc6: 4b95 ldr r3, [pc, #596] ; (8002e1c ) - 8002bc8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002bcc: f423 2240 bic.w r2, r3, #786432 ; 0xc0000 - 8002bd0: 687b ldr r3, [r7, #4] - 8002bd2: 6e9b ldr r3, [r3, #104] ; 0x68 - 8002bd4: 4991 ldr r1, [pc, #580] ; (8002e1c ) - 8002bd6: 4313 orrs r3, r2 - 8002bd8: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002c8e: 4b95 ldr r3, [pc, #596] ; (8002ee4 ) + 8002c90: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c94: f423 2240 bic.w r2, r3, #786432 ; 0xc0000 + 8002c98: 687b ldr r3, [r7, #4] + 8002c9a: 6e9b ldr r3, [r3, #104] ; 0x68 + 8002c9c: 4991 ldr r1, [pc, #580] ; (8002ee4 ) + 8002c9e: 4313 orrs r3, r2 + 8002ca0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C3 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C3) == RCC_PERIPHCLK_I2C3) - 8002bdc: 687b ldr r3, [r7, #4] - 8002bde: 681b ldr r3, [r3, #0] - 8002be0: f403 3380 and.w r3, r3, #65536 ; 0x10000 - 8002be4: 2b00 cmp r3, #0 - 8002be6: d00a beq.n 8002bfe + 8002ca4: 687b ldr r3, [r7, #4] + 8002ca6: 681b ldr r3, [r3, #0] + 8002ca8: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 8002cac: 2b00 cmp r3, #0 + 8002cae: d00a beq.n 8002cc6 { /* Check the parameters */ assert_param(IS_RCC_I2C3CLKSOURCE(PeriphClkInit->I2c3ClockSelection)); /* Configure the I2C3 clock source */ __HAL_RCC_I2C3_CONFIG(PeriphClkInit->I2c3ClockSelection); - 8002be8: 4b8c ldr r3, [pc, #560] ; (8002e1c ) - 8002bea: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002bee: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 - 8002bf2: 687b ldr r3, [r7, #4] - 8002bf4: 6edb ldr r3, [r3, #108] ; 0x6c - 8002bf6: 4989 ldr r1, [pc, #548] ; (8002e1c ) - 8002bf8: 4313 orrs r3, r2 - 8002bfa: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002cb0: 4b8c ldr r3, [pc, #560] ; (8002ee4 ) + 8002cb2: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cb6: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 8002cba: 687b ldr r3, [r7, #4] + 8002cbc: 6edb ldr r3, [r3, #108] ; 0x6c + 8002cbe: 4989 ldr r1, [pc, #548] ; (8002ee4 ) + 8002cc0: 4313 orrs r3, r2 + 8002cc2: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C4 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C4) == RCC_PERIPHCLK_I2C4) - 8002bfe: 687b ldr r3, [r7, #4] - 8002c00: 681b ldr r3, [r3, #0] - 8002c02: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8002c06: 2b00 cmp r3, #0 - 8002c08: d00a beq.n 8002c20 + 8002cc6: 687b ldr r3, [r7, #4] + 8002cc8: 681b ldr r3, [r3, #0] + 8002cca: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 8002cce: 2b00 cmp r3, #0 + 8002cd0: d00a beq.n 8002ce8 { /* Check the parameters */ assert_param(IS_RCC_I2C4CLKSOURCE(PeriphClkInit->I2c4ClockSelection)); /* Configure the I2C4 clock source */ __HAL_RCC_I2C4_CONFIG(PeriphClkInit->I2c4ClockSelection); - 8002c0a: 4b84 ldr r3, [pc, #528] ; (8002e1c ) - 8002c0c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002c10: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 - 8002c14: 687b ldr r3, [r7, #4] - 8002c16: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002c18: 4980 ldr r1, [pc, #512] ; (8002e1c ) - 8002c1a: 4313 orrs r3, r2 - 8002c1c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002cd2: 4b84 ldr r3, [pc, #528] ; (8002ee4 ) + 8002cd4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cd8: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 8002cdc: 687b ldr r3, [r7, #4] + 8002cde: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002ce0: 4980 ldr r1, [pc, #512] ; (8002ee4 ) + 8002ce2: 4313 orrs r3, r2 + 8002ce4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART1) == RCC_PERIPHCLK_USART1) - 8002c20: 687b ldr r3, [r7, #4] - 8002c22: 681b ldr r3, [r3, #0] - 8002c24: f003 0340 and.w r3, r3, #64 ; 0x40 - 8002c28: 2b00 cmp r3, #0 - 8002c2a: d00a beq.n 8002c42 + 8002ce8: 687b ldr r3, [r7, #4] + 8002cea: 681b ldr r3, [r3, #0] + 8002cec: f003 0340 and.w r3, r3, #64 ; 0x40 + 8002cf0: 2b00 cmp r3, #0 + 8002cf2: d00a beq.n 8002d0a { /* Check the parameters */ assert_param(IS_RCC_USART1CLKSOURCE(PeriphClkInit->Usart1ClockSelection)); /* Configure the USART1 clock source */ __HAL_RCC_USART1_CONFIG(PeriphClkInit->Usart1ClockSelection); - 8002c2c: 4b7b ldr r3, [pc, #492] ; (8002e1c ) - 8002c2e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002c32: f023 0203 bic.w r2, r3, #3 - 8002c36: 687b ldr r3, [r7, #4] - 8002c38: 6c5b ldr r3, [r3, #68] ; 0x44 - 8002c3a: 4978 ldr r1, [pc, #480] ; (8002e1c ) - 8002c3c: 4313 orrs r3, r2 - 8002c3e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002cf4: 4b7b ldr r3, [pc, #492] ; (8002ee4 ) + 8002cf6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cfa: f023 0203 bic.w r2, r3, #3 + 8002cfe: 687b ldr r3, [r7, #4] + 8002d00: 6c5b ldr r3, [r3, #68] ; 0x44 + 8002d02: 4978 ldr r1, [pc, #480] ; (8002ee4 ) + 8002d04: 4313 orrs r3, r2 + 8002d06: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART2 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART2) == RCC_PERIPHCLK_USART2) - 8002c42: 687b ldr r3, [r7, #4] - 8002c44: 681b ldr r3, [r3, #0] - 8002c46: f003 0380 and.w r3, r3, #128 ; 0x80 - 8002c4a: 2b00 cmp r3, #0 - 8002c4c: d00a beq.n 8002c64 + 8002d0a: 687b ldr r3, [r7, #4] + 8002d0c: 681b ldr r3, [r3, #0] + 8002d0e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8002d12: 2b00 cmp r3, #0 + 8002d14: d00a beq.n 8002d2c { /* Check the parameters */ assert_param(IS_RCC_USART2CLKSOURCE(PeriphClkInit->Usart2ClockSelection)); /* Configure the USART2 clock source */ __HAL_RCC_USART2_CONFIG(PeriphClkInit->Usart2ClockSelection); - 8002c4e: 4b73 ldr r3, [pc, #460] ; (8002e1c ) - 8002c50: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002c54: f023 020c bic.w r2, r3, #12 - 8002c58: 687b ldr r3, [r7, #4] - 8002c5a: 6c9b ldr r3, [r3, #72] ; 0x48 - 8002c5c: 496f ldr r1, [pc, #444] ; (8002e1c ) - 8002c5e: 4313 orrs r3, r2 - 8002c60: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002d16: 4b73 ldr r3, [pc, #460] ; (8002ee4 ) + 8002d18: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d1c: f023 020c bic.w r2, r3, #12 + 8002d20: 687b ldr r3, [r7, #4] + 8002d22: 6c9b ldr r3, [r3, #72] ; 0x48 + 8002d24: 496f ldr r1, [pc, #444] ; (8002ee4 ) + 8002d26: 4313 orrs r3, r2 + 8002d28: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART3 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART3) == RCC_PERIPHCLK_USART3) - 8002c64: 687b ldr r3, [r7, #4] - 8002c66: 681b ldr r3, [r3, #0] - 8002c68: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002c6c: 2b00 cmp r3, #0 - 8002c6e: d00a beq.n 8002c86 + 8002d2c: 687b ldr r3, [r7, #4] + 8002d2e: 681b ldr r3, [r3, #0] + 8002d30: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002d34: 2b00 cmp r3, #0 + 8002d36: d00a beq.n 8002d4e { /* Check the parameters */ assert_param(IS_RCC_USART3CLKSOURCE(PeriphClkInit->Usart3ClockSelection)); /* Configure the USART3 clock source */ __HAL_RCC_USART3_CONFIG(PeriphClkInit->Usart3ClockSelection); - 8002c70: 4b6a ldr r3, [pc, #424] ; (8002e1c ) - 8002c72: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002c76: f023 0230 bic.w r2, r3, #48 ; 0x30 - 8002c7a: 687b ldr r3, [r7, #4] - 8002c7c: 6cdb ldr r3, [r3, #76] ; 0x4c - 8002c7e: 4967 ldr r1, [pc, #412] ; (8002e1c ) - 8002c80: 4313 orrs r3, r2 - 8002c82: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002d38: 4b6a ldr r3, [pc, #424] ; (8002ee4 ) + 8002d3a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d3e: f023 0230 bic.w r2, r3, #48 ; 0x30 + 8002d42: 687b ldr r3, [r7, #4] + 8002d44: 6cdb ldr r3, [r3, #76] ; 0x4c + 8002d46: 4967 ldr r1, [pc, #412] ; (8002ee4 ) + 8002d48: 4313 orrs r3, r2 + 8002d4a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART4 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART4) == RCC_PERIPHCLK_UART4) - 8002c86: 687b ldr r3, [r7, #4] - 8002c88: 681b ldr r3, [r3, #0] - 8002c8a: f403 7300 and.w r3, r3, #512 ; 0x200 - 8002c8e: 2b00 cmp r3, #0 - 8002c90: d00a beq.n 8002ca8 + 8002d4e: 687b ldr r3, [r7, #4] + 8002d50: 681b ldr r3, [r3, #0] + 8002d52: f403 7300 and.w r3, r3, #512 ; 0x200 + 8002d56: 2b00 cmp r3, #0 + 8002d58: d00a beq.n 8002d70 { /* Check the parameters */ assert_param(IS_RCC_UART4CLKSOURCE(PeriphClkInit->Uart4ClockSelection)); /* Configure the UART4 clock source */ __HAL_RCC_UART4_CONFIG(PeriphClkInit->Uart4ClockSelection); - 8002c92: 4b62 ldr r3, [pc, #392] ; (8002e1c ) - 8002c94: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002c98: f023 02c0 bic.w r2, r3, #192 ; 0xc0 - 8002c9c: 687b ldr r3, [r7, #4] - 8002c9e: 6d1b ldr r3, [r3, #80] ; 0x50 - 8002ca0: 495e ldr r1, [pc, #376] ; (8002e1c ) - 8002ca2: 4313 orrs r3, r2 - 8002ca4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002d5a: 4b62 ldr r3, [pc, #392] ; (8002ee4 ) + 8002d5c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d60: f023 02c0 bic.w r2, r3, #192 ; 0xc0 + 8002d64: 687b ldr r3, [r7, #4] + 8002d66: 6d1b ldr r3, [r3, #80] ; 0x50 + 8002d68: 495e ldr r1, [pc, #376] ; (8002ee4 ) + 8002d6a: 4313 orrs r3, r2 + 8002d6c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART5 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART5) == RCC_PERIPHCLK_UART5) - 8002ca8: 687b ldr r3, [r7, #4] - 8002caa: 681b ldr r3, [r3, #0] - 8002cac: f403 6380 and.w r3, r3, #1024 ; 0x400 - 8002cb0: 2b00 cmp r3, #0 - 8002cb2: d00a beq.n 8002cca + 8002d70: 687b ldr r3, [r7, #4] + 8002d72: 681b ldr r3, [r3, #0] + 8002d74: f403 6380 and.w r3, r3, #1024 ; 0x400 + 8002d78: 2b00 cmp r3, #0 + 8002d7a: d00a beq.n 8002d92 { /* Check the parameters */ assert_param(IS_RCC_UART5CLKSOURCE(PeriphClkInit->Uart5ClockSelection)); /* Configure the UART5 clock source */ __HAL_RCC_UART5_CONFIG(PeriphClkInit->Uart5ClockSelection); - 8002cb4: 4b59 ldr r3, [pc, #356] ; (8002e1c ) - 8002cb6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002cba: f423 7240 bic.w r2, r3, #768 ; 0x300 - 8002cbe: 687b ldr r3, [r7, #4] - 8002cc0: 6d5b ldr r3, [r3, #84] ; 0x54 - 8002cc2: 4956 ldr r1, [pc, #344] ; (8002e1c ) - 8002cc4: 4313 orrs r3, r2 - 8002cc6: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002d7c: 4b59 ldr r3, [pc, #356] ; (8002ee4 ) + 8002d7e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d82: f423 7240 bic.w r2, r3, #768 ; 0x300 + 8002d86: 687b ldr r3, [r7, #4] + 8002d88: 6d5b ldr r3, [r3, #84] ; 0x54 + 8002d8a: 4956 ldr r1, [pc, #344] ; (8002ee4 ) + 8002d8c: 4313 orrs r3, r2 + 8002d8e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART6 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART6) == RCC_PERIPHCLK_USART6) - 8002cca: 687b ldr r3, [r7, #4] - 8002ccc: 681b ldr r3, [r3, #0] - 8002cce: f403 6300 and.w r3, r3, #2048 ; 0x800 - 8002cd2: 2b00 cmp r3, #0 - 8002cd4: d00a beq.n 8002cec + 8002d92: 687b ldr r3, [r7, #4] + 8002d94: 681b ldr r3, [r3, #0] + 8002d96: f403 6300 and.w r3, r3, #2048 ; 0x800 + 8002d9a: 2b00 cmp r3, #0 + 8002d9c: d00a beq.n 8002db4 { /* Check the parameters */ assert_param(IS_RCC_USART6CLKSOURCE(PeriphClkInit->Usart6ClockSelection)); /* Configure the USART6 clock source */ __HAL_RCC_USART6_CONFIG(PeriphClkInit->Usart6ClockSelection); - 8002cd6: 4b51 ldr r3, [pc, #324] ; (8002e1c ) - 8002cd8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002cdc: f423 6240 bic.w r2, r3, #3072 ; 0xc00 - 8002ce0: 687b ldr r3, [r7, #4] - 8002ce2: 6d9b ldr r3, [r3, #88] ; 0x58 - 8002ce4: 494d ldr r1, [pc, #308] ; (8002e1c ) - 8002ce6: 4313 orrs r3, r2 - 8002ce8: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002d9e: 4b51 ldr r3, [pc, #324] ; (8002ee4 ) + 8002da0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002da4: f423 6240 bic.w r2, r3, #3072 ; 0xc00 + 8002da8: 687b ldr r3, [r7, #4] + 8002daa: 6d9b ldr r3, [r3, #88] ; 0x58 + 8002dac: 494d ldr r1, [pc, #308] ; (8002ee4 ) + 8002dae: 4313 orrs r3, r2 + 8002db0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART7 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART7) == RCC_PERIPHCLK_UART7) - 8002cec: 687b ldr r3, [r7, #4] - 8002cee: 681b ldr r3, [r3, #0] - 8002cf0: f403 5380 and.w r3, r3, #4096 ; 0x1000 - 8002cf4: 2b00 cmp r3, #0 - 8002cf6: d00a beq.n 8002d0e + 8002db4: 687b ldr r3, [r7, #4] + 8002db6: 681b ldr r3, [r3, #0] + 8002db8: f403 5380 and.w r3, r3, #4096 ; 0x1000 + 8002dbc: 2b00 cmp r3, #0 + 8002dbe: d00a beq.n 8002dd6 { /* Check the parameters */ assert_param(IS_RCC_UART7CLKSOURCE(PeriphClkInit->Uart7ClockSelection)); /* Configure the UART7 clock source */ __HAL_RCC_UART7_CONFIG(PeriphClkInit->Uart7ClockSelection); - 8002cf8: 4b48 ldr r3, [pc, #288] ; (8002e1c ) - 8002cfa: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002cfe: f423 5240 bic.w r2, r3, #12288 ; 0x3000 - 8002d02: 687b ldr r3, [r7, #4] - 8002d04: 6ddb ldr r3, [r3, #92] ; 0x5c - 8002d06: 4945 ldr r1, [pc, #276] ; (8002e1c ) - 8002d08: 4313 orrs r3, r2 - 8002d0a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002dc0: 4b48 ldr r3, [pc, #288] ; (8002ee4 ) + 8002dc2: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002dc6: f423 5240 bic.w r2, r3, #12288 ; 0x3000 + 8002dca: 687b ldr r3, [r7, #4] + 8002dcc: 6ddb ldr r3, [r3, #92] ; 0x5c + 8002dce: 4945 ldr r1, [pc, #276] ; (8002ee4 ) + 8002dd0: 4313 orrs r3, r2 + 8002dd2: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART8 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART8) == RCC_PERIPHCLK_UART8) - 8002d0e: 687b ldr r3, [r7, #4] - 8002d10: 681b ldr r3, [r3, #0] - 8002d12: f403 5300 and.w r3, r3, #8192 ; 0x2000 - 8002d16: 2b00 cmp r3, #0 - 8002d18: d00a beq.n 8002d30 + 8002dd6: 687b ldr r3, [r7, #4] + 8002dd8: 681b ldr r3, [r3, #0] + 8002dda: f403 5300 and.w r3, r3, #8192 ; 0x2000 + 8002dde: 2b00 cmp r3, #0 + 8002de0: d00a beq.n 8002df8 { /* Check the parameters */ assert_param(IS_RCC_UART8CLKSOURCE(PeriphClkInit->Uart8ClockSelection)); /* Configure the UART8 clock source */ __HAL_RCC_UART8_CONFIG(PeriphClkInit->Uart8ClockSelection); - 8002d1a: 4b40 ldr r3, [pc, #256] ; (8002e1c ) - 8002d1c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002d20: f423 4240 bic.w r2, r3, #49152 ; 0xc000 - 8002d24: 687b ldr r3, [r7, #4] - 8002d26: 6e1b ldr r3, [r3, #96] ; 0x60 - 8002d28: 493c ldr r1, [pc, #240] ; (8002e1c ) - 8002d2a: 4313 orrs r3, r2 - 8002d2c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002de2: 4b40 ldr r3, [pc, #256] ; (8002ee4 ) + 8002de4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002de8: f423 4240 bic.w r2, r3, #49152 ; 0xc000 + 8002dec: 687b ldr r3, [r7, #4] + 8002dee: 6e1b ldr r3, [r3, #96] ; 0x60 + 8002df0: 493c ldr r1, [pc, #240] ; (8002ee4 ) + 8002df2: 4313 orrs r3, r2 + 8002df4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*--------------------------------------- CEC Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) - 8002d30: 687b ldr r3, [r7, #4] - 8002d32: 681b ldr r3, [r3, #0] - 8002d34: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 8002d38: 2b00 cmp r3, #0 - 8002d3a: d00a beq.n 8002d52 + 8002df8: 687b ldr r3, [r7, #4] + 8002dfa: 681b ldr r3, [r3, #0] + 8002dfc: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002e00: 2b00 cmp r3, #0 + 8002e02: d00a beq.n 8002e1a { /* Check the parameters */ assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); /* Configure the CEC clock source */ __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); - 8002d3c: 4b37 ldr r3, [pc, #220] ; (8002e1c ) - 8002d3e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002d42: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 - 8002d46: 687b ldr r3, [r7, #4] - 8002d48: 6f9b ldr r3, [r3, #120] ; 0x78 - 8002d4a: 4934 ldr r1, [pc, #208] ; (8002e1c ) - 8002d4c: 4313 orrs r3, r2 - 8002d4e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002e04: 4b37 ldr r3, [pc, #220] ; (8002ee4 ) + 8002e06: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002e0a: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 8002e0e: 687b ldr r3, [r7, #4] + 8002e10: 6f9b ldr r3, [r3, #120] ; 0x78 + 8002e12: 4934 ldr r1, [pc, #208] ; (8002ee4 ) + 8002e14: 4313 orrs r3, r2 + 8002e16: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- CK48 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - 8002d52: 687b ldr r3, [r7, #4] - 8002d54: 681b ldr r3, [r3, #0] - 8002d56: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 8002d5a: 2b00 cmp r3, #0 - 8002d5c: d011 beq.n 8002d82 + 8002e1a: 687b ldr r3, [r7, #4] + 8002e1c: 681b ldr r3, [r3, #0] + 8002e1e: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8002e22: 2b00 cmp r3, #0 + 8002e24: d011 beq.n 8002e4a { /* Check the parameters */ assert_param(IS_RCC_CLK48SOURCE(PeriphClkInit->Clk48ClockSelection)); /* Configure the CLK48 source */ __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - 8002d5e: 4b2f ldr r3, [pc, #188] ; (8002e1c ) - 8002d60: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002d64: f023 6200 bic.w r2, r3, #134217728 ; 0x8000000 - 8002d68: 687b ldr r3, [r7, #4] - 8002d6a: 6fdb ldr r3, [r3, #124] ; 0x7c - 8002d6c: 492b ldr r1, [pc, #172] ; (8002e1c ) - 8002d6e: 4313 orrs r3, r2 - 8002d70: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002e26: 4b2f ldr r3, [pc, #188] ; (8002ee4 ) + 8002e28: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002e2c: f023 6200 bic.w r2, r3, #134217728 ; 0x8000000 + 8002e30: 687b ldr r3, [r7, #4] + 8002e32: 6fdb ldr r3, [r3, #124] ; 0x7c + 8002e34: 492b ldr r1, [pc, #172] ; (8002ee4 ) + 8002e36: 4313 orrs r3, r2 + 8002e38: f8c1 3090 str.w r3, [r1, #144] ; 0x90 /* Enable the PLLSAI when it's used as clock source for CK48 */ if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48SOURCE_PLLSAIP) - 8002d74: 687b ldr r3, [r7, #4] - 8002d76: 6fdb ldr r3, [r3, #124] ; 0x7c - 8002d78: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 - 8002d7c: d101 bne.n 8002d82 + 8002e3c: 687b ldr r3, [r7, #4] + 8002e3e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8002e40: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 8002e44: d101 bne.n 8002e4a { pllsaiused = 1; - 8002d7e: 2301 movs r3, #1 - 8002d80: 61bb str r3, [r7, #24] + 8002e46: 2301 movs r3, #1 + 8002e48: 61bb str r3, [r7, #24] } } /*-------------------------------------- LTDC Configuration -----------------------------------*/ #if defined(STM32F746xx) || defined(STM32F756xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) || defined (STM32F750xx) if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC) - 8002d82: 687b ldr r3, [r7, #4] - 8002d84: 681b ldr r3, [r3, #0] - 8002d86: f003 0308 and.w r3, r3, #8 - 8002d8a: 2b00 cmp r3, #0 - 8002d8c: d001 beq.n 8002d92 + 8002e4a: 687b ldr r3, [r7, #4] + 8002e4c: 681b ldr r3, [r3, #0] + 8002e4e: f003 0308 and.w r3, r3, #8 + 8002e52: 2b00 cmp r3, #0 + 8002e54: d001 beq.n 8002e5a { pllsaiused = 1; - 8002d8e: 2301 movs r3, #1 - 8002d90: 61bb str r3, [r7, #24] + 8002e56: 2301 movs r3, #1 + 8002e58: 61bb str r3, [r7, #24] } #endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ /*-------------------------------------- LPTIM1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - 8002d92: 687b ldr r3, [r7, #4] - 8002d94: 681b ldr r3, [r3, #0] - 8002d96: f403 2380 and.w r3, r3, #262144 ; 0x40000 - 8002d9a: 2b00 cmp r3, #0 - 8002d9c: d00a beq.n 8002db4 + 8002e5a: 687b ldr r3, [r7, #4] + 8002e5c: 681b ldr r3, [r3, #0] + 8002e5e: f403 2380 and.w r3, r3, #262144 ; 0x40000 + 8002e62: 2b00 cmp r3, #0 + 8002e64: d00a beq.n 8002e7c { /* Check the parameters */ assert_param(IS_RCC_LPTIM1CLK(PeriphClkInit->Lptim1ClockSelection)); /* Configure the LTPIM1 clock source */ __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - 8002d9e: 4b1f ldr r3, [pc, #124] ; (8002e1c ) - 8002da0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002da4: f023 7240 bic.w r2, r3, #50331648 ; 0x3000000 - 8002da8: 687b ldr r3, [r7, #4] - 8002daa: 6f5b ldr r3, [r3, #116] ; 0x74 - 8002dac: 491b ldr r1, [pc, #108] ; (8002e1c ) - 8002dae: 4313 orrs r3, r2 - 8002db0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002e66: 4b1f ldr r3, [pc, #124] ; (8002ee4 ) + 8002e68: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002e6c: f023 7240 bic.w r2, r3, #50331648 ; 0x3000000 + 8002e70: 687b ldr r3, [r7, #4] + 8002e72: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002e74: 491b ldr r1, [pc, #108] ; (8002ee4 ) + 8002e76: 4313 orrs r3, r2 + 8002e78: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*------------------------------------- SDMMC1 Configuration ------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDMMC1) == RCC_PERIPHCLK_SDMMC1) - 8002db4: 687b ldr r3, [r7, #4] - 8002db6: 681b ldr r3, [r3, #0] - 8002db8: f403 0300 and.w r3, r3, #8388608 ; 0x800000 - 8002dbc: 2b00 cmp r3, #0 - 8002dbe: d00b beq.n 8002dd8 + 8002e7c: 687b ldr r3, [r7, #4] + 8002e7e: 681b ldr r3, [r3, #0] + 8002e80: f403 0300 and.w r3, r3, #8388608 ; 0x800000 + 8002e84: 2b00 cmp r3, #0 + 8002e86: d00b beq.n 8002ea0 { /* Check the parameters */ assert_param(IS_RCC_SDMMC1CLKSOURCE(PeriphClkInit->Sdmmc1ClockSelection)); /* Configure the SDMMC1 clock source */ __HAL_RCC_SDMMC1_CONFIG(PeriphClkInit->Sdmmc1ClockSelection); - 8002dc0: 4b16 ldr r3, [pc, #88] ; (8002e1c ) - 8002dc2: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002dc6: f023 5280 bic.w r2, r3, #268435456 ; 0x10000000 - 8002dca: 687b ldr r3, [r7, #4] - 8002dcc: f8d3 3080 ldr.w r3, [r3, #128] ; 0x80 - 8002dd0: 4912 ldr r1, [pc, #72] ; (8002e1c ) - 8002dd2: 4313 orrs r3, r2 - 8002dd4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002e88: 4b16 ldr r3, [pc, #88] ; (8002ee4 ) + 8002e8a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002e8e: f023 5280 bic.w r2, r3, #268435456 ; 0x10000000 + 8002e92: 687b ldr r3, [r7, #4] + 8002e94: f8d3 3080 ldr.w r3, [r3, #128] ; 0x80 + 8002e98: 4912 ldr r1, [pc, #72] ; (8002ee4 ) + 8002e9a: 4313 orrs r3, r2 + 8002e9c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } #if defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) /*------------------------------------- SDMMC2 Configuration ------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDMMC2) == RCC_PERIPHCLK_SDMMC2) - 8002dd8: 687b ldr r3, [r7, #4] - 8002dda: 681b ldr r3, [r3, #0] - 8002ddc: f003 6380 and.w r3, r3, #67108864 ; 0x4000000 - 8002de0: 2b00 cmp r3, #0 - 8002de2: d00b beq.n 8002dfc + 8002ea0: 687b ldr r3, [r7, #4] + 8002ea2: 681b ldr r3, [r3, #0] + 8002ea4: f003 6380 and.w r3, r3, #67108864 ; 0x4000000 + 8002ea8: 2b00 cmp r3, #0 + 8002eaa: d00b beq.n 8002ec4 { /* Check the parameters */ assert_param(IS_RCC_SDMMC2CLKSOURCE(PeriphClkInit->Sdmmc2ClockSelection)); /* Configure the SDMMC2 clock source */ __HAL_RCC_SDMMC2_CONFIG(PeriphClkInit->Sdmmc2ClockSelection); - 8002de4: 4b0d ldr r3, [pc, #52] ; (8002e1c ) - 8002de6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002dea: f023 5200 bic.w r2, r3, #536870912 ; 0x20000000 - 8002dee: 687b ldr r3, [r7, #4] - 8002df0: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002df4: 4909 ldr r1, [pc, #36] ; (8002e1c ) - 8002df6: 4313 orrs r3, r2 - 8002df8: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002eac: 4b0d ldr r3, [pc, #52] ; (8002ee4 ) + 8002eae: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002eb2: f023 5200 bic.w r2, r3, #536870912 ; 0x20000000 + 8002eb6: 687b ldr r3, [r7, #4] + 8002eb8: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002ebc: 4909 ldr r1, [pc, #36] ; (8002ee4 ) + 8002ebe: 4313 orrs r3, r2 + 8002ec0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*------------------------------------- DFSDM1 Configuration -------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) - 8002dfc: 687b ldr r3, [r7, #4] - 8002dfe: 681b ldr r3, [r3, #0] - 8002e00: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 8002e04: 2b00 cmp r3, #0 - 8002e06: d00f beq.n 8002e28 + 8002ec4: 687b ldr r3, [r7, #4] + 8002ec6: 681b ldr r3, [r3, #0] + 8002ec8: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 8002ecc: 2b00 cmp r3, #0 + 8002ece: d00f beq.n 8002ef0 { /* Check the parameters */ assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); /* Configure the DFSDM1 interface clock source */ __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); - 8002e08: 4b04 ldr r3, [pc, #16] ; (8002e1c ) - 8002e0a: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002e0e: f023 7200 bic.w r2, r3, #33554432 ; 0x2000000 - 8002e12: 687b ldr r3, [r7, #4] - 8002e14: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8002e18: e002 b.n 8002e20 - 8002e1a: bf00 nop - 8002e1c: 40023800 .word 0x40023800 - 8002e20: 4985 ldr r1, [pc, #532] ; (8003038 ) - 8002e22: 4313 orrs r3, r2 - 8002e24: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002ed0: 4b04 ldr r3, [pc, #16] ; (8002ee4 ) + 8002ed2: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002ed6: f023 7200 bic.w r2, r3, #33554432 ; 0x2000000 + 8002eda: 687b ldr r3, [r7, #4] + 8002edc: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8002ee0: e002 b.n 8002ee8 + 8002ee2: bf00 nop + 8002ee4: 40023800 .word 0x40023800 + 8002ee8: 4985 ldr r1, [pc, #532] ; (8003100 ) + 8002eea: 4313 orrs r3, r2 + 8002eec: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*------------------------------------- DFSDM AUDIO Configuration -------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) - 8002e28: 687b ldr r3, [r7, #4] - 8002e2a: 681b ldr r3, [r3, #0] - 8002e2c: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002e30: 2b00 cmp r3, #0 - 8002e32: d00b beq.n 8002e4c + 8002ef0: 687b ldr r3, [r7, #4] + 8002ef2: 681b ldr r3, [r3, #0] + 8002ef4: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002ef8: 2b00 cmp r3, #0 + 8002efa: d00b beq.n 8002f14 { /* Check the parameters */ assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); /* Configure the DFSDM interface clock source */ __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); - 8002e34: 4b80 ldr r3, [pc, #512] ; (8003038 ) - 8002e36: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002e3a: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 - 8002e3e: 687b ldr r3, [r7, #4] - 8002e40: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002e44: 497c ldr r1, [pc, #496] ; (8003038 ) - 8002e46: 4313 orrs r3, r2 - 8002e48: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002efc: 4b80 ldr r3, [pc, #512] ; (8003100 ) + 8002efe: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002f02: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 8002f06: 687b ldr r3, [r7, #4] + 8002f08: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002f0c: 497c ldr r1, [pc, #496] ; (8003100 ) + 8002f0e: 4313 orrs r3, r2 + 8002f10: f8c1 308c str.w r3, [r1, #140] ; 0x8c } #endif /* STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx */ /*-------------------------------------- PLLI2S Configuration ---------------------------------*/ /* PLLI2S is configured when a peripheral will use it as source clock : SAI1, SAI2, I2S or SPDIF-RX */ if((plli2sused == 1) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) - 8002e4c: 69fb ldr r3, [r7, #28] - 8002e4e: 2b01 cmp r3, #1 - 8002e50: d005 beq.n 8002e5e - 8002e52: 687b ldr r3, [r7, #4] - 8002e54: 681b ldr r3, [r3, #0] - 8002e56: f1b3 7f00 cmp.w r3, #33554432 ; 0x2000000 - 8002e5a: f040 80d6 bne.w 800300a + 8002f14: 69fb ldr r3, [r7, #28] + 8002f16: 2b01 cmp r3, #1 + 8002f18: d005 beq.n 8002f26 + 8002f1a: 687b ldr r3, [r7, #4] + 8002f1c: 681b ldr r3, [r3, #0] + 8002f1e: f1b3 7f00 cmp.w r3, #33554432 ; 0x2000000 + 8002f22: f040 80d6 bne.w 80030d2 { /* Disable the PLLI2S */ __HAL_RCC_PLLI2S_DISABLE(); - 8002e5e: 4b76 ldr r3, [pc, #472] ; (8003038 ) - 8002e60: 681b ldr r3, [r3, #0] - 8002e62: 4a75 ldr r2, [pc, #468] ; (8003038 ) - 8002e64: f023 6380 bic.w r3, r3, #67108864 ; 0x4000000 - 8002e68: 6013 str r3, [r2, #0] + 8002f26: 4b76 ldr r3, [pc, #472] ; (8003100 ) + 8002f28: 681b ldr r3, [r3, #0] + 8002f2a: 4a75 ldr r2, [pc, #468] ; (8003100 ) + 8002f2c: f023 6380 bic.w r3, r3, #67108864 ; 0x4000000 + 8002f30: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002e6a: f7fe fe25 bl 8001ab8 - 8002e6e: 6178 str r0, [r7, #20] + 8002f32: f7fe fe25 bl 8001b80 + 8002f36: 6178 str r0, [r7, #20] /* Wait till PLLI2S is disabled */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - 8002e70: e008 b.n 8002e84 + 8002f38: e008 b.n 8002f4c { if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - 8002e72: f7fe fe21 bl 8001ab8 - 8002e76: 4602 mov r2, r0 - 8002e78: 697b ldr r3, [r7, #20] - 8002e7a: 1ad3 subs r3, r2, r3 - 8002e7c: 2b64 cmp r3, #100 ; 0x64 - 8002e7e: d901 bls.n 8002e84 + 8002f3a: f7fe fe21 bl 8001b80 + 8002f3e: 4602 mov r2, r0 + 8002f40: 697b ldr r3, [r7, #20] + 8002f42: 1ad3 subs r3, r2, r3 + 8002f44: 2b64 cmp r3, #100 ; 0x64 + 8002f46: d901 bls.n 8002f4c { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 8002e80: 2303 movs r3, #3 - 8002e82: e194 b.n 80031ae + 8002f48: 2303 movs r3, #3 + 8002f4a: e194 b.n 8003276 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - 8002e84: 4b6c ldr r3, [pc, #432] ; (8003038 ) - 8002e86: 681b ldr r3, [r3, #0] - 8002e88: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 8002e8c: 2b00 cmp r3, #0 - 8002e8e: d1f0 bne.n 8002e72 + 8002f4c: 4b6c ldr r3, [pc, #432] ; (8003100 ) + 8002f4e: 681b ldr r3, [r3, #0] + 8002f50: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 8002f54: 2b00 cmp r3, #0 + 8002f56: d1f0 bne.n 8002f3a /* check for common PLLI2S Parameters */ assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); /*----------------- In Case of PLLI2S is selected as source clock for I2S -------------------*/ if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) && (PeriphClkInit->I2sClockSelection == RCC_I2SCLKSOURCE_PLLI2S))) - 8002e90: 687b ldr r3, [r7, #4] - 8002e92: 681b ldr r3, [r3, #0] - 8002e94: f003 0301 and.w r3, r3, #1 - 8002e98: 2b00 cmp r3, #0 - 8002e9a: d021 beq.n 8002ee0 - 8002e9c: 687b ldr r3, [r7, #4] - 8002e9e: 6b5b ldr r3, [r3, #52] ; 0x34 - 8002ea0: 2b00 cmp r3, #0 - 8002ea2: d11d bne.n 8002ee0 + 8002f58: 687b ldr r3, [r7, #4] + 8002f5a: 681b ldr r3, [r3, #0] + 8002f5c: f003 0301 and.w r3, r3, #1 + 8002f60: 2b00 cmp r3, #0 + 8002f62: d021 beq.n 8002fa8 + 8002f64: 687b ldr r3, [r7, #4] + 8002f66: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002f68: 2b00 cmp r3, #0 + 8002f6a: d11d bne.n 8002fa8 { /* check for Parameters */ assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); /* Read PLLI2SP and PLLI2SQ value from PLLI2SCFGR register (this value is not needed for I2S configuration) */ tmpreg0 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos); - 8002ea4: 4b64 ldr r3, [pc, #400] ; (8003038 ) - 8002ea6: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002eaa: 0c1b lsrs r3, r3, #16 - 8002eac: f003 0303 and.w r3, r3, #3 - 8002eb0: 613b str r3, [r7, #16] + 8002f6c: 4b64 ldr r3, [pc, #400] ; (8003100 ) + 8002f6e: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002f72: 0c1b lsrs r3, r3, #16 + 8002f74: f003 0303 and.w r3, r3, #3 + 8002f78: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - 8002eb2: 4b61 ldr r3, [pc, #388] ; (8003038 ) - 8002eb4: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002eb8: 0e1b lsrs r3, r3, #24 - 8002eba: f003 030f and.w r3, r3, #15 - 8002ebe: 60fb str r3, [r7, #12] + 8002f7a: 4b61 ldr r3, [pc, #388] ; (8003100 ) + 8002f7c: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002f80: 0e1b lsrs r3, r3, #24 + 8002f82: f003 030f and.w r3, r3, #15 + 8002f86: 60fb str r3, [r7, #12] /* Configure the PLLI2S division factors */ /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , tmpreg0, tmpreg1, PeriphClkInit->PLLI2S.PLLI2SR); - 8002ec0: 687b ldr r3, [r7, #4] - 8002ec2: 685b ldr r3, [r3, #4] - 8002ec4: 019a lsls r2, r3, #6 - 8002ec6: 693b ldr r3, [r7, #16] - 8002ec8: 041b lsls r3, r3, #16 - 8002eca: 431a orrs r2, r3 - 8002ecc: 68fb ldr r3, [r7, #12] - 8002ece: 061b lsls r3, r3, #24 - 8002ed0: 431a orrs r2, r3 - 8002ed2: 687b ldr r3, [r7, #4] - 8002ed4: 689b ldr r3, [r3, #8] - 8002ed6: 071b lsls r3, r3, #28 - 8002ed8: 4957 ldr r1, [pc, #348] ; (8003038 ) - 8002eda: 4313 orrs r3, r2 - 8002edc: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 8002f88: 687b ldr r3, [r7, #4] + 8002f8a: 685b ldr r3, [r3, #4] + 8002f8c: 019a lsls r2, r3, #6 + 8002f8e: 693b ldr r3, [r7, #16] + 8002f90: 041b lsls r3, r3, #16 + 8002f92: 431a orrs r2, r3 + 8002f94: 68fb ldr r3, [r7, #12] + 8002f96: 061b lsls r3, r3, #24 + 8002f98: 431a orrs r2, r3 + 8002f9a: 687b ldr r3, [r7, #4] + 8002f9c: 689b ldr r3, [r3, #8] + 8002f9e: 071b lsls r3, r3, #28 + 8002fa0: 4957 ldr r1, [pc, #348] ; (8003100 ) + 8002fa2: 4313 orrs r3, r2 + 8002fa4: f8c1 3084 str.w r3, [r1, #132] ; 0x84 } /*----------------- In Case of PLLI2S is selected as source clock for SAI -------------------*/ if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || - 8002ee0: 687b ldr r3, [r7, #4] - 8002ee2: 681b ldr r3, [r3, #0] - 8002ee4: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 8002ee8: 2b00 cmp r3, #0 - 8002eea: d004 beq.n 8002ef6 - 8002eec: 687b ldr r3, [r7, #4] - 8002eee: 6bdb ldr r3, [r3, #60] ; 0x3c - 8002ef0: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 8002ef4: d00a beq.n 8002f0c + 8002fa8: 687b ldr r3, [r7, #4] + 8002faa: 681b ldr r3, [r3, #0] + 8002fac: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8002fb0: 2b00 cmp r3, #0 + 8002fb2: d004 beq.n 8002fbe + 8002fb4: 687b ldr r3, [r7, #4] + 8002fb6: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002fb8: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8002fbc: d00a beq.n 8002fd4 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - 8002ef6: 687b ldr r3, [r7, #4] - 8002ef8: 681b ldr r3, [r3, #0] - 8002efa: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8002fbe: 687b ldr r3, [r7, #4] + 8002fc0: 681b ldr r3, [r3, #0] + 8002fc2: f403 1380 and.w r3, r3, #1048576 ; 0x100000 if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || - 8002efe: 2b00 cmp r3, #0 - 8002f00: d02e beq.n 8002f60 + 8002fc6: 2b00 cmp r3, #0 + 8002fc8: d02e beq.n 8003028 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - 8002f02: 687b ldr r3, [r7, #4] - 8002f04: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002f06: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 8002f0a: d129 bne.n 8002f60 + 8002fca: 687b ldr r3, [r7, #4] + 8002fcc: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002fce: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002fd2: d129 bne.n 8003028 assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); /* Check for PLLI2S/DIVQ parameters */ assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); /* Read PLLI2SP and PLLI2SR values from PLLI2SCFGR register (this value is not needed for SAI configuration) */ tmpreg0 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos); - 8002f0c: 4b4a ldr r3, [pc, #296] ; (8003038 ) - 8002f0e: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002f12: 0c1b lsrs r3, r3, #16 - 8002f14: f003 0303 and.w r3, r3, #3 - 8002f18: 613b str r3, [r7, #16] + 8002fd4: 4b4a ldr r3, [pc, #296] ; (8003100 ) + 8002fd6: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002fda: 0c1b lsrs r3, r3, #16 + 8002fdc: f003 0303 and.w r3, r3, #3 + 8002fe0: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - 8002f1a: 4b47 ldr r3, [pc, #284] ; (8003038 ) - 8002f1c: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002f20: 0f1b lsrs r3, r3, #28 - 8002f22: f003 0307 and.w r3, r3, #7 - 8002f26: 60fb str r3, [r7, #12] + 8002fe2: 4b47 ldr r3, [pc, #284] ; (8003100 ) + 8002fe4: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002fe8: 0f1b lsrs r3, r3, #28 + 8002fea: f003 0307 and.w r3, r3, #7 + 8002fee: 60fb str r3, [r7, #12] /* Configure the PLLI2S division factors */ /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, tmpreg0, PeriphClkInit->PLLI2S.PLLI2SQ, tmpreg1); - 8002f28: 687b ldr r3, [r7, #4] - 8002f2a: 685b ldr r3, [r3, #4] - 8002f2c: 019a lsls r2, r3, #6 - 8002f2e: 693b ldr r3, [r7, #16] - 8002f30: 041b lsls r3, r3, #16 - 8002f32: 431a orrs r2, r3 - 8002f34: 687b ldr r3, [r7, #4] - 8002f36: 68db ldr r3, [r3, #12] - 8002f38: 061b lsls r3, r3, #24 - 8002f3a: 431a orrs r2, r3 - 8002f3c: 68fb ldr r3, [r7, #12] - 8002f3e: 071b lsls r3, r3, #28 - 8002f40: 493d ldr r1, [pc, #244] ; (8003038 ) - 8002f42: 4313 orrs r3, r2 - 8002f44: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 8002ff0: 687b ldr r3, [r7, #4] + 8002ff2: 685b ldr r3, [r3, #4] + 8002ff4: 019a lsls r2, r3, #6 + 8002ff6: 693b ldr r3, [r7, #16] + 8002ff8: 041b lsls r3, r3, #16 + 8002ffa: 431a orrs r2, r3 + 8002ffc: 687b ldr r3, [r7, #4] + 8002ffe: 68db ldr r3, [r3, #12] + 8003000: 061b lsls r3, r3, #24 + 8003002: 431a orrs r2, r3 + 8003004: 68fb ldr r3, [r7, #12] + 8003006: 071b lsls r3, r3, #28 + 8003008: 493d ldr r1, [pc, #244] ; (8003100 ) + 800300a: 4313 orrs r3, r2 + 800300c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - 8002f48: 4b3b ldr r3, [pc, #236] ; (8003038 ) - 8002f4a: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002f4e: f023 021f bic.w r2, r3, #31 - 8002f52: 687b ldr r3, [r7, #4] - 8002f54: 6a5b ldr r3, [r3, #36] ; 0x24 - 8002f56: 3b01 subs r3, #1 - 8002f58: 4937 ldr r1, [pc, #220] ; (8003038 ) - 8002f5a: 4313 orrs r3, r2 - 8002f5c: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8003010: 4b3b ldr r3, [pc, #236] ; (8003100 ) + 8003012: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003016: f023 021f bic.w r2, r3, #31 + 800301a: 687b ldr r3, [r7, #4] + 800301c: 6a5b ldr r3, [r3, #36] ; 0x24 + 800301e: 3b01 subs r3, #1 + 8003020: 4937 ldr r1, [pc, #220] ; (8003100 ) + 8003022: 4313 orrs r3, r2 + 8003024: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*----------------- In Case of PLLI2S is selected as source clock for SPDIF-RX -------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) - 8002f60: 687b ldr r3, [r7, #4] - 8002f62: 681b ldr r3, [r3, #0] - 8002f64: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 - 8002f68: 2b00 cmp r3, #0 - 8002f6a: d01d beq.n 8002fa8 + 8003028: 687b ldr r3, [r7, #4] + 800302a: 681b ldr r3, [r3, #0] + 800302c: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8003030: 2b00 cmp r3, #0 + 8003032: d01d beq.n 8003070 { /* check for Parameters */ assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); /* Read PLLI2SR value from PLLI2SCFGR register (this value is not needed for SPDIF-RX configuration) */ tmpreg0 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - 8002f6c: 4b32 ldr r3, [pc, #200] ; (8003038 ) - 8002f6e: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002f72: 0e1b lsrs r3, r3, #24 - 8002f74: f003 030f and.w r3, r3, #15 - 8002f78: 613b str r3, [r7, #16] + 8003034: 4b32 ldr r3, [pc, #200] ; (8003100 ) + 8003036: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 800303a: 0e1b lsrs r3, r3, #24 + 800303c: f003 030f and.w r3, r3, #15 + 8003040: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - 8002f7a: 4b2f ldr r3, [pc, #188] ; (8003038 ) - 8002f7c: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8002f80: 0f1b lsrs r3, r3, #28 - 8002f82: f003 0307 and.w r3, r3, #7 - 8002f86: 60fb str r3, [r7, #12] + 8003042: 4b2f ldr r3, [pc, #188] ; (8003100 ) + 8003044: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8003048: 0f1b lsrs r3, r3, #28 + 800304a: f003 0307 and.w r3, r3, #7 + 800304e: 60fb str r3, [r7, #12] /* Configure the PLLI2S division factors */ /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ /* SPDIFCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, tmpreg0, tmpreg1); - 8002f88: 687b ldr r3, [r7, #4] - 8002f8a: 685b ldr r3, [r3, #4] - 8002f8c: 019a lsls r2, r3, #6 - 8002f8e: 687b ldr r3, [r7, #4] - 8002f90: 691b ldr r3, [r3, #16] - 8002f92: 041b lsls r3, r3, #16 - 8002f94: 431a orrs r2, r3 - 8002f96: 693b ldr r3, [r7, #16] - 8002f98: 061b lsls r3, r3, #24 - 8002f9a: 431a orrs r2, r3 - 8002f9c: 68fb ldr r3, [r7, #12] - 8002f9e: 071b lsls r3, r3, #28 - 8002fa0: 4925 ldr r1, [pc, #148] ; (8003038 ) - 8002fa2: 4313 orrs r3, r2 - 8002fa4: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 8003050: 687b ldr r3, [r7, #4] + 8003052: 685b ldr r3, [r3, #4] + 8003054: 019a lsls r2, r3, #6 + 8003056: 687b ldr r3, [r7, #4] + 8003058: 691b ldr r3, [r3, #16] + 800305a: 041b lsls r3, r3, #16 + 800305c: 431a orrs r2, r3 + 800305e: 693b ldr r3, [r7, #16] + 8003060: 061b lsls r3, r3, #24 + 8003062: 431a orrs r2, r3 + 8003064: 68fb ldr r3, [r7, #12] + 8003066: 071b lsls r3, r3, #28 + 8003068: 4925 ldr r1, [pc, #148] ; (8003100 ) + 800306a: 4313 orrs r3, r2 + 800306c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 } /*----------------- In Case of PLLI2S is just selected -----------------*/ if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - 8002fa8: 687b ldr r3, [r7, #4] - 8002faa: 681b ldr r3, [r3, #0] - 8002fac: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8002fb0: 2b00 cmp r3, #0 - 8002fb2: d011 beq.n 8002fd8 + 8003070: 687b ldr r3, [r7, #4] + 8003072: 681b ldr r3, [r3, #0] + 8003074: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8003078: 2b00 cmp r3, #0 + 800307a: d011 beq.n 80030a0 assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); /* Configure the PLLI2S division factors */ /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLI2SM) */ /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - 8002fb4: 687b ldr r3, [r7, #4] - 8002fb6: 685b ldr r3, [r3, #4] - 8002fb8: 019a lsls r2, r3, #6 - 8002fba: 687b ldr r3, [r7, #4] - 8002fbc: 691b ldr r3, [r3, #16] - 8002fbe: 041b lsls r3, r3, #16 - 8002fc0: 431a orrs r2, r3 - 8002fc2: 687b ldr r3, [r7, #4] - 8002fc4: 68db ldr r3, [r3, #12] - 8002fc6: 061b lsls r3, r3, #24 - 8002fc8: 431a orrs r2, r3 - 8002fca: 687b ldr r3, [r7, #4] - 8002fcc: 689b ldr r3, [r3, #8] - 8002fce: 071b lsls r3, r3, #28 - 8002fd0: 4919 ldr r1, [pc, #100] ; (8003038 ) - 8002fd2: 4313 orrs r3, r2 - 8002fd4: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 800307c: 687b ldr r3, [r7, #4] + 800307e: 685b ldr r3, [r3, #4] + 8003080: 019a lsls r2, r3, #6 + 8003082: 687b ldr r3, [r7, #4] + 8003084: 691b ldr r3, [r3, #16] + 8003086: 041b lsls r3, r3, #16 + 8003088: 431a orrs r2, r3 + 800308a: 687b ldr r3, [r7, #4] + 800308c: 68db ldr r3, [r3, #12] + 800308e: 061b lsls r3, r3, #24 + 8003090: 431a orrs r2, r3 + 8003092: 687b ldr r3, [r7, #4] + 8003094: 689b ldr r3, [r3, #8] + 8003096: 071b lsls r3, r3, #28 + 8003098: 4919 ldr r1, [pc, #100] ; (8003100 ) + 800309a: 4313 orrs r3, r2 + 800309c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 } /* Enable the PLLI2S */ __HAL_RCC_PLLI2S_ENABLE(); - 8002fd8: 4b17 ldr r3, [pc, #92] ; (8003038 ) - 8002fda: 681b ldr r3, [r3, #0] - 8002fdc: 4a16 ldr r2, [pc, #88] ; (8003038 ) - 8002fde: f043 6380 orr.w r3, r3, #67108864 ; 0x4000000 - 8002fe2: 6013 str r3, [r2, #0] + 80030a0: 4b17 ldr r3, [pc, #92] ; (8003100 ) + 80030a2: 681b ldr r3, [r3, #0] + 80030a4: 4a16 ldr r2, [pc, #88] ; (8003100 ) + 80030a6: f043 6380 orr.w r3, r3, #67108864 ; 0x4000000 + 80030aa: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002fe4: f7fe fd68 bl 8001ab8 - 8002fe8: 6178 str r0, [r7, #20] + 80030ac: f7fe fd68 bl 8001b80 + 80030b0: 6178 str r0, [r7, #20] /* Wait till PLLI2S is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - 8002fea: e008 b.n 8002ffe + 80030b2: e008 b.n 80030c6 { if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - 8002fec: f7fe fd64 bl 8001ab8 - 8002ff0: 4602 mov r2, r0 - 8002ff2: 697b ldr r3, [r7, #20] - 8002ff4: 1ad3 subs r3, r2, r3 - 8002ff6: 2b64 cmp r3, #100 ; 0x64 - 8002ff8: d901 bls.n 8002ffe + 80030b4: f7fe fd64 bl 8001b80 + 80030b8: 4602 mov r2, r0 + 80030ba: 697b ldr r3, [r7, #20] + 80030bc: 1ad3 subs r3, r2, r3 + 80030be: 2b64 cmp r3, #100 ; 0x64 + 80030c0: d901 bls.n 80030c6 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 8002ffa: 2303 movs r3, #3 - 8002ffc: e0d7 b.n 80031ae + 80030c2: 2303 movs r3, #3 + 80030c4: e0d7 b.n 8003276 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - 8002ffe: 4b0e ldr r3, [pc, #56] ; (8003038 ) - 8003000: 681b ldr r3, [r3, #0] - 8003002: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 8003006: 2b00 cmp r3, #0 - 8003008: d0f0 beq.n 8002fec + 80030c6: 4b0e ldr r3, [pc, #56] ; (8003100 ) + 80030c8: 681b ldr r3, [r3, #0] + 80030ca: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 80030ce: 2b00 cmp r3, #0 + 80030d0: d0f0 beq.n 80030b4 } } /*-------------------------------------- PLLSAI Configuration ---------------------------------*/ /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, LTDC or CK48 */ if(pllsaiused == 1) - 800300a: 69bb ldr r3, [r7, #24] - 800300c: 2b01 cmp r3, #1 - 800300e: f040 80cd bne.w 80031ac + 80030d2: 69bb ldr r3, [r7, #24] + 80030d4: 2b01 cmp r3, #1 + 80030d6: f040 80cd bne.w 8003274 { /* Disable PLLSAI Clock */ __HAL_RCC_PLLSAI_DISABLE(); - 8003012: 4b09 ldr r3, [pc, #36] ; (8003038 ) - 8003014: 681b ldr r3, [r3, #0] - 8003016: 4a08 ldr r2, [pc, #32] ; (8003038 ) - 8003018: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 - 800301c: 6013 str r3, [r2, #0] + 80030da: 4b09 ldr r3, [pc, #36] ; (8003100 ) + 80030dc: 681b ldr r3, [r3, #0] + 80030de: 4a08 ldr r2, [pc, #32] ; (8003100 ) + 80030e0: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 80030e4: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800301e: f7fe fd4b bl 8001ab8 - 8003022: 6178 str r0, [r7, #20] + 80030e6: f7fe fd4b bl 8001b80 + 80030ea: 6178 str r0, [r7, #20] /* Wait till PLLSAI is disabled */ while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - 8003024: e00a b.n 800303c + 80030ec: e00a b.n 8003104 { if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - 8003026: f7fe fd47 bl 8001ab8 - 800302a: 4602 mov r2, r0 - 800302c: 697b ldr r3, [r7, #20] - 800302e: 1ad3 subs r3, r2, r3 - 8003030: 2b64 cmp r3, #100 ; 0x64 - 8003032: d903 bls.n 800303c + 80030ee: f7fe fd47 bl 8001b80 + 80030f2: 4602 mov r2, r0 + 80030f4: 697b ldr r3, [r7, #20] + 80030f6: 1ad3 subs r3, r2, r3 + 80030f8: 2b64 cmp r3, #100 ; 0x64 + 80030fa: d903 bls.n 8003104 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 8003034: 2303 movs r3, #3 - 8003036: e0ba b.n 80031ae - 8003038: 40023800 .word 0x40023800 + 80030fc: 2303 movs r3, #3 + 80030fe: e0ba b.n 8003276 + 8003100: 40023800 .word 0x40023800 while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - 800303c: 4b5e ldr r3, [pc, #376] ; (80031b8 ) - 800303e: 681b ldr r3, [r3, #0] - 8003040: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 - 8003044: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 - 8003048: d0ed beq.n 8003026 + 8003104: 4b5e ldr r3, [pc, #376] ; (8003280 ) + 8003106: 681b ldr r3, [r3, #0] + 8003108: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 800310c: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 8003110: d0ed beq.n 80030ee /* Check the PLLSAI division factors */ assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); /*----------------- In Case of PLLSAI is selected as source clock for SAI -------------------*/ if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) ||\ - 800304a: 687b ldr r3, [r7, #4] - 800304c: 681b ldr r3, [r3, #0] - 800304e: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 8003052: 2b00 cmp r3, #0 - 8003054: d003 beq.n 800305e - 8003056: 687b ldr r3, [r7, #4] - 8003058: 6bdb ldr r3, [r3, #60] ; 0x3c - 800305a: 2b00 cmp r3, #0 - 800305c: d009 beq.n 8003072 + 8003112: 687b ldr r3, [r7, #4] + 8003114: 681b ldr r3, [r3, #0] + 8003116: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 800311a: 2b00 cmp r3, #0 + 800311c: d003 beq.n 8003126 + 800311e: 687b ldr r3, [r7, #4] + 8003120: 6bdb ldr r3, [r3, #60] ; 0x3c + 8003122: 2b00 cmp r3, #0 + 8003124: d009 beq.n 800313a ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - 800305e: 687b ldr r3, [r7, #4] - 8003060: 681b ldr r3, [r3, #0] - 8003062: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8003126: 687b ldr r3, [r7, #4] + 8003128: 681b ldr r3, [r3, #0] + 800312a: f403 1380 and.w r3, r3, #1048576 ; 0x100000 if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) ||\ - 8003066: 2b00 cmp r3, #0 - 8003068: d02e beq.n 80030c8 + 800312e: 2b00 cmp r3, #0 + 8003130: d02e beq.n 8003190 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - 800306a: 687b ldr r3, [r7, #4] - 800306c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800306e: 2b00 cmp r3, #0 - 8003070: d12a bne.n 80030c8 + 8003132: 687b ldr r3, [r7, #4] + 8003134: 6c1b ldr r3, [r3, #64] ; 0x40 + 8003136: 2b00 cmp r3, #0 + 8003138: d12a bne.n 8003190 assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); /* check for PLLSAI/DIVQ Parameter */ assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ tmpreg0 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos); - 8003072: 4b51 ldr r3, [pc, #324] ; (80031b8 ) - 8003074: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8003078: 0c1b lsrs r3, r3, #16 - 800307a: f003 0303 and.w r3, r3, #3 - 800307e: 613b str r3, [r7, #16] + 800313a: 4b51 ldr r3, [pc, #324] ; (8003280 ) + 800313c: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003140: 0c1b lsrs r3, r3, #16 + 8003142: f003 0303 and.w r3, r3, #3 + 8003146: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - 8003080: 4b4d ldr r3, [pc, #308] ; (80031b8 ) - 8003082: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8003086: 0f1b lsrs r3, r3, #28 - 8003088: f003 0307 and.w r3, r3, #7 - 800308c: 60fb str r3, [r7, #12] + 8003148: 4b4d ldr r3, [pc, #308] ; (8003280 ) + 800314a: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800314e: 0f1b lsrs r3, r3, #28 + 8003150: f003 0307 and.w r3, r3, #7 + 8003154: 60fb str r3, [r7, #12] /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg0, PeriphClkInit->PLLSAI.PLLSAIQ, tmpreg1); - 800308e: 687b ldr r3, [r7, #4] - 8003090: 695b ldr r3, [r3, #20] - 8003092: 019a lsls r2, r3, #6 - 8003094: 693b ldr r3, [r7, #16] - 8003096: 041b lsls r3, r3, #16 - 8003098: 431a orrs r2, r3 - 800309a: 687b ldr r3, [r7, #4] - 800309c: 699b ldr r3, [r3, #24] - 800309e: 061b lsls r3, r3, #24 - 80030a0: 431a orrs r2, r3 - 80030a2: 68fb ldr r3, [r7, #12] - 80030a4: 071b lsls r3, r3, #28 - 80030a6: 4944 ldr r1, [pc, #272] ; (80031b8 ) - 80030a8: 4313 orrs r3, r2 - 80030aa: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 8003156: 687b ldr r3, [r7, #4] + 8003158: 695b ldr r3, [r3, #20] + 800315a: 019a lsls r2, r3, #6 + 800315c: 693b ldr r3, [r7, #16] + 800315e: 041b lsls r3, r3, #16 + 8003160: 431a orrs r2, r3 + 8003162: 687b ldr r3, [r7, #4] + 8003164: 699b ldr r3, [r3, #24] + 8003166: 061b lsls r3, r3, #24 + 8003168: 431a orrs r2, r3 + 800316a: 68fb ldr r3, [r7, #12] + 800316c: 071b lsls r3, r3, #28 + 800316e: 4944 ldr r1, [pc, #272] ; (8003280 ) + 8003170: 4313 orrs r3, r2 + 8003172: f8c1 3088 str.w r3, [r1, #136] ; 0x88 /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - 80030ae: 4b42 ldr r3, [pc, #264] ; (80031b8 ) - 80030b0: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80030b4: f423 52f8 bic.w r2, r3, #7936 ; 0x1f00 - 80030b8: 687b ldr r3, [r7, #4] - 80030ba: 6a9b ldr r3, [r3, #40] ; 0x28 - 80030bc: 3b01 subs r3, #1 - 80030be: 021b lsls r3, r3, #8 - 80030c0: 493d ldr r1, [pc, #244] ; (80031b8 ) - 80030c2: 4313 orrs r3, r2 - 80030c4: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8003176: 4b42 ldr r3, [pc, #264] ; (8003280 ) + 8003178: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 800317c: f423 52f8 bic.w r2, r3, #7936 ; 0x1f00 + 8003180: 687b ldr r3, [r7, #4] + 8003182: 6a9b ldr r3, [r3, #40] ; 0x28 + 8003184: 3b01 subs r3, #1 + 8003186: 021b lsls r3, r3, #8 + 8003188: 493d ldr r1, [pc, #244] ; (8003280 ) + 800318a: 4313 orrs r3, r2 + 800318c: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*----------------- In Case of PLLSAI is selected as source clock for CLK48 -------------------*/ /* In Case of PLLI2S is selected as source clock for CK48 */ if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48SOURCE_PLLSAIP)) - 80030c8: 687b ldr r3, [r7, #4] - 80030ca: 681b ldr r3, [r3, #0] - 80030cc: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 80030d0: 2b00 cmp r3, #0 - 80030d2: d022 beq.n 800311a - 80030d4: 687b ldr r3, [r7, #4] - 80030d6: 6fdb ldr r3, [r3, #124] ; 0x7c - 80030d8: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 - 80030dc: d11d bne.n 800311a + 8003190: 687b ldr r3, [r7, #4] + 8003192: 681b ldr r3, [r3, #0] + 8003194: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8003198: 2b00 cmp r3, #0 + 800319a: d022 beq.n 80031e2 + 800319c: 687b ldr r3, [r7, #4] + 800319e: 6fdb ldr r3, [r3, #124] ; 0x7c + 80031a0: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 80031a4: d11d bne.n 80031e2 { /* check for Parameters */ assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); /* Read PLLSAIQ and PLLSAIR value from PLLSAICFGR register (this value is not needed for CK48 configuration) */ tmpreg0 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - 80030de: 4b36 ldr r3, [pc, #216] ; (80031b8 ) - 80030e0: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 80030e4: 0e1b lsrs r3, r3, #24 - 80030e6: f003 030f and.w r3, r3, #15 - 80030ea: 613b str r3, [r7, #16] + 80031a6: 4b36 ldr r3, [pc, #216] ; (8003280 ) + 80031a8: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80031ac: 0e1b lsrs r3, r3, #24 + 80031ae: f003 030f and.w r3, r3, #15 + 80031b2: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - 80030ec: 4b32 ldr r3, [pc, #200] ; (80031b8 ) - 80030ee: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 80030f2: 0f1b lsrs r3, r3, #28 - 80030f4: f003 0307 and.w r3, r3, #7 - 80030f8: 60fb str r3, [r7, #12] + 80031b4: 4b32 ldr r3, [pc, #200] ; (8003280 ) + 80031b6: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80031ba: 0f1b lsrs r3, r3, #28 + 80031bc: f003 0307 and.w r3, r3, #7 + 80031c0: 60fb str r3, [r7, #12] /* Configure the PLLSAI division factors */ /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) x (PLLI2SN/PLLM) */ /* 48CLK = f(PLLSAI clock output) = f(VCO clock) / PLLSAIP */ __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIP, tmpreg0, tmpreg1); - 80030fa: 687b ldr r3, [r7, #4] - 80030fc: 695b ldr r3, [r3, #20] - 80030fe: 019a lsls r2, r3, #6 - 8003100: 687b ldr r3, [r7, #4] - 8003102: 6a1b ldr r3, [r3, #32] - 8003104: 041b lsls r3, r3, #16 - 8003106: 431a orrs r2, r3 - 8003108: 693b ldr r3, [r7, #16] - 800310a: 061b lsls r3, r3, #24 - 800310c: 431a orrs r2, r3 - 800310e: 68fb ldr r3, [r7, #12] - 8003110: 071b lsls r3, r3, #28 - 8003112: 4929 ldr r1, [pc, #164] ; (80031b8 ) - 8003114: 4313 orrs r3, r2 - 8003116: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 80031c2: 687b ldr r3, [r7, #4] + 80031c4: 695b ldr r3, [r3, #20] + 80031c6: 019a lsls r2, r3, #6 + 80031c8: 687b ldr r3, [r7, #4] + 80031ca: 6a1b ldr r3, [r3, #32] + 80031cc: 041b lsls r3, r3, #16 + 80031ce: 431a orrs r2, r3 + 80031d0: 693b ldr r3, [r7, #16] + 80031d2: 061b lsls r3, r3, #24 + 80031d4: 431a orrs r2, r3 + 80031d6: 68fb ldr r3, [r7, #12] + 80031d8: 071b lsls r3, r3, #28 + 80031da: 4929 ldr r1, [pc, #164] ; (8003280 ) + 80031dc: 4313 orrs r3, r2 + 80031de: f8c1 3088 str.w r3, [r1, #136] ; 0x88 } #if defined(STM32F746xx) || defined(STM32F756xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) || defined (STM32F750xx) /*---------------------------- LTDC configuration -------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) - 800311a: 687b ldr r3, [r7, #4] - 800311c: 681b ldr r3, [r3, #0] - 800311e: f003 0308 and.w r3, r3, #8 - 8003122: 2b00 cmp r3, #0 - 8003124: d028 beq.n 8003178 + 80031e2: 687b ldr r3, [r7, #4] + 80031e4: 681b ldr r3, [r3, #0] + 80031e6: f003 0308 and.w r3, r3, #8 + 80031ea: 2b00 cmp r3, #0 + 80031ec: d028 beq.n 8003240 { assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); /* Read PLLSAIP and PLLSAIQ value from PLLSAICFGR register (these value are not needed for LTDC configuration) */ tmpreg0 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - 8003126: 4b24 ldr r3, [pc, #144] ; (80031b8 ) - 8003128: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 800312c: 0e1b lsrs r3, r3, #24 - 800312e: f003 030f and.w r3, r3, #15 - 8003132: 613b str r3, [r7, #16] + 80031ee: 4b24 ldr r3, [pc, #144] ; (8003280 ) + 80031f0: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80031f4: 0e1b lsrs r3, r3, #24 + 80031f6: f003 030f and.w r3, r3, #15 + 80031fa: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos); - 8003134: 4b20 ldr r3, [pc, #128] ; (80031b8 ) - 8003136: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 800313a: 0c1b lsrs r3, r3, #16 - 800313c: f003 0303 and.w r3, r3, #3 - 8003140: 60fb str r3, [r7, #12] + 80031fc: 4b20 ldr r3, [pc, #128] ; (8003280 ) + 80031fe: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003202: 0c1b lsrs r3, r3, #16 + 8003204: f003 0303 and.w r3, r3, #3 + 8003208: 60fb str r3, [r7, #12] /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg1, tmpreg0, PeriphClkInit->PLLSAI.PLLSAIR); - 8003142: 687b ldr r3, [r7, #4] - 8003144: 695b ldr r3, [r3, #20] - 8003146: 019a lsls r2, r3, #6 - 8003148: 68fb ldr r3, [r7, #12] - 800314a: 041b lsls r3, r3, #16 - 800314c: 431a orrs r2, r3 - 800314e: 693b ldr r3, [r7, #16] - 8003150: 061b lsls r3, r3, #24 - 8003152: 431a orrs r2, r3 - 8003154: 687b ldr r3, [r7, #4] - 8003156: 69db ldr r3, [r3, #28] - 8003158: 071b lsls r3, r3, #28 - 800315a: 4917 ldr r1, [pc, #92] ; (80031b8 ) - 800315c: 4313 orrs r3, r2 - 800315e: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 800320a: 687b ldr r3, [r7, #4] + 800320c: 695b ldr r3, [r3, #20] + 800320e: 019a lsls r2, r3, #6 + 8003210: 68fb ldr r3, [r7, #12] + 8003212: 041b lsls r3, r3, #16 + 8003214: 431a orrs r2, r3 + 8003216: 693b ldr r3, [r7, #16] + 8003218: 061b lsls r3, r3, #24 + 800321a: 431a orrs r2, r3 + 800321c: 687b ldr r3, [r7, #4] + 800321e: 69db ldr r3, [r3, #28] + 8003220: 071b lsls r3, r3, #28 + 8003222: 4917 ldr r1, [pc, #92] ; (8003280 ) + 8003224: 4313 orrs r3, r2 + 8003226: f8c1 3088 str.w r3, [r1, #136] ; 0x88 /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - 8003162: 4b15 ldr r3, [pc, #84] ; (80031b8 ) - 8003164: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8003168: f423 3240 bic.w r2, r3, #196608 ; 0x30000 - 800316c: 687b ldr r3, [r7, #4] - 800316e: 6adb ldr r3, [r3, #44] ; 0x2c - 8003170: 4911 ldr r1, [pc, #68] ; (80031b8 ) - 8003172: 4313 orrs r3, r2 - 8003174: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 800322a: 4b15 ldr r3, [pc, #84] ; (8003280 ) + 800322c: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003230: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8003234: 687b ldr r3, [r7, #4] + 8003236: 6adb ldr r3, [r3, #44] ; 0x2c + 8003238: 4911 ldr r1, [pc, #68] ; (8003280 ) + 800323a: 4313 orrs r3, r2 + 800323c: f8c1 308c str.w r3, [r1, #140] ; 0x8c } #endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ /* Enable PLLSAI Clock */ __HAL_RCC_PLLSAI_ENABLE(); - 8003178: 4b0f ldr r3, [pc, #60] ; (80031b8 ) - 800317a: 681b ldr r3, [r3, #0] - 800317c: 4a0e ldr r2, [pc, #56] ; (80031b8 ) - 800317e: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8003182: 6013 str r3, [r2, #0] + 8003240: 4b0f ldr r3, [pc, #60] ; (8003280 ) + 8003242: 681b ldr r3, [r3, #0] + 8003244: 4a0e ldr r2, [pc, #56] ; (8003280 ) + 8003246: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 800324a: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8003184: f7fe fc98 bl 8001ab8 - 8003188: 6178 str r0, [r7, #20] + 800324c: f7fe fc98 bl 8001b80 + 8003250: 6178 str r0, [r7, #20] /* Wait till PLLSAI is ready */ while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - 800318a: e008 b.n 800319e + 8003252: e008 b.n 8003266 { if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - 800318c: f7fe fc94 bl 8001ab8 - 8003190: 4602 mov r2, r0 - 8003192: 697b ldr r3, [r7, #20] - 8003194: 1ad3 subs r3, r2, r3 - 8003196: 2b64 cmp r3, #100 ; 0x64 - 8003198: d901 bls.n 800319e + 8003254: f7fe fc94 bl 8001b80 + 8003258: 4602 mov r2, r0 + 800325a: 697b ldr r3, [r7, #20] + 800325c: 1ad3 subs r3, r2, r3 + 800325e: 2b64 cmp r3, #100 ; 0x64 + 8003260: d901 bls.n 8003266 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 800319a: 2303 movs r3, #3 - 800319c: e007 b.n 80031ae + 8003262: 2303 movs r3, #3 + 8003264: e007 b.n 8003276 while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - 800319e: 4b06 ldr r3, [pc, #24] ; (80031b8 ) - 80031a0: 681b ldr r3, [r3, #0] - 80031a2: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 - 80031a6: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 - 80031aa: d1ef bne.n 800318c + 8003266: 4b06 ldr r3, [pc, #24] ; (8003280 ) + 8003268: 681b ldr r3, [r3, #0] + 800326a: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 800326e: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 8003272: d1ef bne.n 8003254 } } } return HAL_OK; - 80031ac: 2300 movs r3, #0 + 8003274: 2300 movs r3, #0 } - 80031ae: 4618 mov r0, r3 - 80031b0: 3720 adds r7, #32 - 80031b2: 46bd mov sp, r7 - 80031b4: bd80 pop {r7, pc} - 80031b6: bf00 nop - 80031b8: 40023800 .word 0x40023800 - -080031bc : + 8003276: 4618 mov r0, r3 + 8003278: 3720 adds r7, #32 + 800327a: 46bd mov sp, r7 + 800327c: bd80 pop {r7, pc} + 800327e: bf00 nop + 8003280: 40023800 .word 0x40023800 + +08003284 : * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init() * @param htim TIM Base handle * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim) { - 80031bc: b580 push {r7, lr} - 80031be: b082 sub sp, #8 - 80031c0: af00 add r7, sp, #0 - 80031c2: 6078 str r0, [r7, #4] + 8003284: b580 push {r7, lr} + 8003286: b082 sub sp, #8 + 8003288: af00 add r7, sp, #0 + 800328a: 6078 str r0, [r7, #4] /* Check the TIM handle allocation */ if (htim == NULL) - 80031c4: 687b ldr r3, [r7, #4] - 80031c6: 2b00 cmp r3, #0 - 80031c8: d101 bne.n 80031ce + 800328c: 687b ldr r3, [r7, #4] + 800328e: 2b00 cmp r3, #0 + 8003290: d101 bne.n 8003296 { return HAL_ERROR; - 80031ca: 2301 movs r3, #1 - 80031cc: e01d b.n 800320a + 8003292: 2301 movs r3, #1 + 8003294: e01d b.n 80032d2 assert_param(IS_TIM_INSTANCE(htim->Instance)); assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); if (htim->State == HAL_TIM_STATE_RESET) - 80031ce: 687b ldr r3, [r7, #4] - 80031d0: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 80031d4: b2db uxtb r3, r3 - 80031d6: 2b00 cmp r3, #0 - 80031d8: d106 bne.n 80031e8 + 8003296: 687b ldr r3, [r7, #4] + 8003298: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 800329c: b2db uxtb r3, r3 + 800329e: 2b00 cmp r3, #0 + 80032a0: d106 bne.n 80032b0 { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 80031da: 687b ldr r3, [r7, #4] - 80031dc: 2200 movs r2, #0 - 80031de: f883 203c strb.w r2, [r3, #60] ; 0x3c + 80032a2: 687b ldr r3, [r7, #4] + 80032a4: 2200 movs r2, #0 + 80032a6: f883 203c strb.w r2, [r3, #60] ; 0x3c } /* Init the low level hardware : GPIO, CLOCK, NVIC */ htim->Base_MspInitCallback(htim); #else /* Init the low level hardware : GPIO, CLOCK, NVIC */ HAL_TIM_Base_MspInit(htim); - 80031e2: 6878 ldr r0, [r7, #4] - 80031e4: f7fe faa0 bl 8001728 + 80032aa: 6878 ldr r0, [r7, #4] + 80032ac: f7fe faa0 bl 80017f0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 80031e8: 687b ldr r3, [r7, #4] - 80031ea: 2202 movs r2, #2 - 80031ec: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80032b0: 687b ldr r3, [r7, #4] + 80032b2: 2202 movs r2, #2 + 80032b4: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Set the Time Base configuration */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 80031f0: 687b ldr r3, [r7, #4] - 80031f2: 681a ldr r2, [r3, #0] - 80031f4: 687b ldr r3, [r7, #4] - 80031f6: 3304 adds r3, #4 - 80031f8: 4619 mov r1, r3 - 80031fa: 4610 mov r0, r2 - 80031fc: f000 fc90 bl 8003b20 + 80032b8: 687b ldr r3, [r7, #4] + 80032ba: 681a ldr r2, [r3, #0] + 80032bc: 687b ldr r3, [r7, #4] + 80032be: 3304 adds r3, #4 + 80032c0: 4619 mov r1, r3 + 80032c2: 4610 mov r0, r2 + 80032c4: f000 fc90 bl 8003be8 /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 8003200: 687b ldr r3, [r7, #4] - 8003202: 2201 movs r2, #1 - 8003204: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80032c8: 687b ldr r3, [r7, #4] + 80032ca: 2201 movs r2, #1 + 80032cc: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 8003208: 2300 movs r3, #0 + 80032d0: 2300 movs r3, #0 } - 800320a: 4618 mov r0, r3 - 800320c: 3708 adds r7, #8 - 800320e: 46bd mov sp, r7 - 8003210: bd80 pop {r7, pc} + 80032d2: 4618 mov r0, r3 + 80032d4: 3708 adds r7, #8 + 80032d6: 46bd mov sp, r7 + 80032d8: bd80 pop {r7, pc} ... -08003214 : +080032dc : * @brief Starts the TIM Base generation in interrupt mode. * @param htim TIM Base handle * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim) { - 8003214: b480 push {r7} - 8003216: b085 sub sp, #20 - 8003218: af00 add r7, sp, #0 - 800321a: 6078 str r0, [r7, #4] + 80032dc: b480 push {r7} + 80032de: b085 sub sp, #20 + 80032e0: af00 add r7, sp, #0 + 80032e2: 6078 str r0, [r7, #4] /* Check the parameters */ assert_param(IS_TIM_INSTANCE(htim->Instance)); /* Enable the TIM Update interrupt */ __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE); - 800321c: 687b ldr r3, [r7, #4] - 800321e: 681b ldr r3, [r3, #0] - 8003220: 68da ldr r2, [r3, #12] - 8003222: 687b ldr r3, [r7, #4] - 8003224: 681b ldr r3, [r3, #0] - 8003226: f042 0201 orr.w r2, r2, #1 - 800322a: 60da str r2, [r3, #12] + 80032e4: 687b ldr r3, [r7, #4] + 80032e6: 681b ldr r3, [r3, #0] + 80032e8: 68da ldr r2, [r3, #12] + 80032ea: 687b ldr r3, [r7, #4] + 80032ec: 681b ldr r3, [r3, #0] + 80032ee: f042 0201 orr.w r2, r2, #1 + 80032f2: 60da str r2, [r3, #12] /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - 800322c: 687b ldr r3, [r7, #4] - 800322e: 681b ldr r3, [r3, #0] - 8003230: 689a ldr r2, [r3, #8] - 8003232: 4b0c ldr r3, [pc, #48] ; (8003264 ) - 8003234: 4013 ands r3, r2 - 8003236: 60fb str r3, [r7, #12] + 80032f4: 687b ldr r3, [r7, #4] + 80032f6: 681b ldr r3, [r3, #0] + 80032f8: 689a ldr r2, [r3, #8] + 80032fa: 4b0c ldr r3, [pc, #48] ; (800332c ) + 80032fc: 4013 ands r3, r2 + 80032fe: 60fb str r3, [r7, #12] if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - 8003238: 68fb ldr r3, [r7, #12] - 800323a: 2b06 cmp r3, #6 - 800323c: d00b beq.n 8003256 - 800323e: 68fb ldr r3, [r7, #12] - 8003240: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 8003244: d007 beq.n 8003256 + 8003300: 68fb ldr r3, [r7, #12] + 8003302: 2b06 cmp r3, #6 + 8003304: d00b beq.n 800331e + 8003306: 68fb ldr r3, [r7, #12] + 8003308: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 800330c: d007 beq.n 800331e { __HAL_TIM_ENABLE(htim); - 8003246: 687b ldr r3, [r7, #4] - 8003248: 681b ldr r3, [r3, #0] - 800324a: 681a ldr r2, [r3, #0] - 800324c: 687b ldr r3, [r7, #4] - 800324e: 681b ldr r3, [r3, #0] - 8003250: f042 0201 orr.w r2, r2, #1 - 8003254: 601a str r2, [r3, #0] + 800330e: 687b ldr r3, [r7, #4] + 8003310: 681b ldr r3, [r3, #0] + 8003312: 681a ldr r2, [r3, #0] + 8003314: 687b ldr r3, [r7, #4] + 8003316: 681b ldr r3, [r3, #0] + 8003318: f042 0201 orr.w r2, r2, #1 + 800331c: 601a str r2, [r3, #0] } /* Return function status */ return HAL_OK; - 8003256: 2300 movs r3, #0 + 800331e: 2300 movs r3, #0 } - 8003258: 4618 mov r0, r3 - 800325a: 3714 adds r7, #20 - 800325c: 46bd mov sp, r7 - 800325e: f85d 7b04 ldr.w r7, [sp], #4 - 8003262: 4770 bx lr - 8003264: 00010007 .word 0x00010007 - -08003268 : + 8003320: 4618 mov r0, r3 + 8003322: 3714 adds r7, #20 + 8003324: 46bd mov sp, r7 + 8003326: f85d 7b04 ldr.w r7, [sp], #4 + 800332a: 4770 bx lr + 800332c: 00010007 .word 0x00010007 + +08003330 : * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init() * @param htim TIM PWM handle * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim) { - 8003268: b580 push {r7, lr} - 800326a: b082 sub sp, #8 - 800326c: af00 add r7, sp, #0 - 800326e: 6078 str r0, [r7, #4] + 8003330: b580 push {r7, lr} + 8003332: b082 sub sp, #8 + 8003334: af00 add r7, sp, #0 + 8003336: 6078 str r0, [r7, #4] /* Check the TIM handle allocation */ if (htim == NULL) - 8003270: 687b ldr r3, [r7, #4] - 8003272: 2b00 cmp r3, #0 - 8003274: d101 bne.n 800327a + 8003338: 687b ldr r3, [r7, #4] + 800333a: 2b00 cmp r3, #0 + 800333c: d101 bne.n 8003342 { return HAL_ERROR; - 8003276: 2301 movs r3, #1 - 8003278: e01d b.n 80032b6 + 800333e: 2301 movs r3, #1 + 8003340: e01d b.n 800337e assert_param(IS_TIM_INSTANCE(htim->Instance)); assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); if (htim->State == HAL_TIM_STATE_RESET) - 800327a: 687b ldr r3, [r7, #4] - 800327c: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 8003280: b2db uxtb r3, r3 - 8003282: 2b00 cmp r3, #0 - 8003284: d106 bne.n 8003294 + 8003342: 687b ldr r3, [r7, #4] + 8003344: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 8003348: b2db uxtb r3, r3 + 800334a: 2b00 cmp r3, #0 + 800334c: d106 bne.n 800335c { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 8003286: 687b ldr r3, [r7, #4] - 8003288: 2200 movs r2, #0 - 800328a: f883 203c strb.w r2, [r3, #60] ; 0x3c + 800334e: 687b ldr r3, [r7, #4] + 8003350: 2200 movs r2, #0 + 8003352: f883 203c strb.w r2, [r3, #60] ; 0x3c } /* Init the low level hardware : GPIO, CLOCK, NVIC */ htim->PWM_MspInitCallback(htim); #else /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ HAL_TIM_PWM_MspInit(htim); - 800328e: 6878 ldr r0, [r7, #4] - 8003290: f000 f815 bl 80032be + 8003356: 6878 ldr r0, [r7, #4] + 8003358: f000 f815 bl 8003386 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 8003294: 687b ldr r3, [r7, #4] - 8003296: 2202 movs r2, #2 - 8003298: f883 203d strb.w r2, [r3, #61] ; 0x3d + 800335c: 687b ldr r3, [r7, #4] + 800335e: 2202 movs r2, #2 + 8003360: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Init the base time for the PWM */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 800329c: 687b ldr r3, [r7, #4] - 800329e: 681a ldr r2, [r3, #0] - 80032a0: 687b ldr r3, [r7, #4] - 80032a2: 3304 adds r3, #4 - 80032a4: 4619 mov r1, r3 - 80032a6: 4610 mov r0, r2 - 80032a8: f000 fc3a bl 8003b20 + 8003364: 687b ldr r3, [r7, #4] + 8003366: 681a ldr r2, [r3, #0] + 8003368: 687b ldr r3, [r7, #4] + 800336a: 3304 adds r3, #4 + 800336c: 4619 mov r1, r3 + 800336e: 4610 mov r0, r2 + 8003370: f000 fc3a bl 8003be8 /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 80032ac: 687b ldr r3, [r7, #4] - 80032ae: 2201 movs r2, #1 - 80032b0: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003374: 687b ldr r3, [r7, #4] + 8003376: 2201 movs r2, #1 + 8003378: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 80032b4: 2300 movs r3, #0 + 800337c: 2300 movs r3, #0 } - 80032b6: 4618 mov r0, r3 - 80032b8: 3708 adds r7, #8 - 80032ba: 46bd mov sp, r7 - 80032bc: bd80 pop {r7, pc} + 800337e: 4618 mov r0, r3 + 8003380: 3708 adds r7, #8 + 8003382: 46bd mov sp, r7 + 8003384: bd80 pop {r7, pc} -080032be : +08003386 : * @brief Initializes the TIM PWM MSP. * @param htim TIM PWM handle * @retval None */ __weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) { - 80032be: b480 push {r7} - 80032c0: b083 sub sp, #12 - 80032c2: af00 add r7, sp, #0 - 80032c4: 6078 str r0, [r7, #4] + 8003386: b480 push {r7} + 8003388: b083 sub sp, #12 + 800338a: af00 add r7, sp, #0 + 800338c: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIM_PWM_MspInit could be implemented in the user file */ } - 80032c6: bf00 nop - 80032c8: 370c adds r7, #12 - 80032ca: 46bd mov sp, r7 - 80032cc: f85d 7b04 ldr.w r7, [sp], #4 - 80032d0: 4770 bx lr + 800338e: bf00 nop + 8003390: 370c adds r7, #12 + 8003392: 46bd mov sp, r7 + 8003394: f85d 7b04 ldr.w r7, [sp], #4 + 8003398: 4770 bx lr ... -080032d4 : +0800339c : * @arg TIM_CHANNEL_5: TIM Channel 5 selected * @arg TIM_CHANNEL_6: TIM Channel 6 selected * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel) { - 80032d4: b580 push {r7, lr} - 80032d6: b084 sub sp, #16 - 80032d8: af00 add r7, sp, #0 - 80032da: 6078 str r0, [r7, #4] - 80032dc: 6039 str r1, [r7, #0] + 800339c: b580 push {r7, lr} + 800339e: b084 sub sp, #16 + 80033a0: af00 add r7, sp, #0 + 80033a2: 6078 str r0, [r7, #4] + 80033a4: 6039 str r1, [r7, #0] /* Check the parameters */ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); /* Enable the Capture compare channel */ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - 80032de: 687b ldr r3, [r7, #4] - 80032e0: 681b ldr r3, [r3, #0] - 80032e2: 2201 movs r2, #1 - 80032e4: 6839 ldr r1, [r7, #0] - 80032e6: 4618 mov r0, r3 - 80032e8: f000 ffb2 bl 8004250 + 80033a6: 687b ldr r3, [r7, #4] + 80033a8: 681b ldr r3, [r3, #0] + 80033aa: 2201 movs r2, #1 + 80033ac: 6839 ldr r1, [r7, #0] + 80033ae: 4618 mov r0, r3 + 80033b0: f000 ffb2 bl 8004318 if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - 80032ec: 687b ldr r3, [r7, #4] - 80032ee: 681b ldr r3, [r3, #0] - 80032f0: 4a17 ldr r2, [pc, #92] ; (8003350 ) - 80032f2: 4293 cmp r3, r2 - 80032f4: d004 beq.n 8003300 - 80032f6: 687b ldr r3, [r7, #4] - 80032f8: 681b ldr r3, [r3, #0] - 80032fa: 4a16 ldr r2, [pc, #88] ; (8003354 ) - 80032fc: 4293 cmp r3, r2 - 80032fe: d101 bne.n 8003304 - 8003300: 2301 movs r3, #1 - 8003302: e000 b.n 8003306 - 8003304: 2300 movs r3, #0 - 8003306: 2b00 cmp r3, #0 - 8003308: d007 beq.n 800331a + 80033b4: 687b ldr r3, [r7, #4] + 80033b6: 681b ldr r3, [r3, #0] + 80033b8: 4a17 ldr r2, [pc, #92] ; (8003418 ) + 80033ba: 4293 cmp r3, r2 + 80033bc: d004 beq.n 80033c8 + 80033be: 687b ldr r3, [r7, #4] + 80033c0: 681b ldr r3, [r3, #0] + 80033c2: 4a16 ldr r2, [pc, #88] ; (800341c ) + 80033c4: 4293 cmp r3, r2 + 80033c6: d101 bne.n 80033cc + 80033c8: 2301 movs r3, #1 + 80033ca: e000 b.n 80033ce + 80033cc: 2300 movs r3, #0 + 80033ce: 2b00 cmp r3, #0 + 80033d0: d007 beq.n 80033e2 { /* Enable the main output */ __HAL_TIM_MOE_ENABLE(htim); - 800330a: 687b ldr r3, [r7, #4] - 800330c: 681b ldr r3, [r3, #0] - 800330e: 6c5a ldr r2, [r3, #68] ; 0x44 - 8003310: 687b ldr r3, [r7, #4] - 8003312: 681b ldr r3, [r3, #0] - 8003314: f442 4200 orr.w r2, r2, #32768 ; 0x8000 - 8003318: 645a str r2, [r3, #68] ; 0x44 + 80033d2: 687b ldr r3, [r7, #4] + 80033d4: 681b ldr r3, [r3, #0] + 80033d6: 6c5a ldr r2, [r3, #68] ; 0x44 + 80033d8: 687b ldr r3, [r7, #4] + 80033da: 681b ldr r3, [r3, #0] + 80033dc: f442 4200 orr.w r2, r2, #32768 ; 0x8000 + 80033e0: 645a str r2, [r3, #68] ; 0x44 } /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - 800331a: 687b ldr r3, [r7, #4] - 800331c: 681b ldr r3, [r3, #0] - 800331e: 689a ldr r2, [r3, #8] - 8003320: 4b0d ldr r3, [pc, #52] ; (8003358 ) - 8003322: 4013 ands r3, r2 - 8003324: 60fb str r3, [r7, #12] + 80033e2: 687b ldr r3, [r7, #4] + 80033e4: 681b ldr r3, [r3, #0] + 80033e6: 689a ldr r2, [r3, #8] + 80033e8: 4b0d ldr r3, [pc, #52] ; (8003420 ) + 80033ea: 4013 ands r3, r2 + 80033ec: 60fb str r3, [r7, #12] if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - 8003326: 68fb ldr r3, [r7, #12] - 8003328: 2b06 cmp r3, #6 - 800332a: d00b beq.n 8003344 - 800332c: 68fb ldr r3, [r7, #12] - 800332e: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 8003332: d007 beq.n 8003344 + 80033ee: 68fb ldr r3, [r7, #12] + 80033f0: 2b06 cmp r3, #6 + 80033f2: d00b beq.n 800340c + 80033f4: 68fb ldr r3, [r7, #12] + 80033f6: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 80033fa: d007 beq.n 800340c { __HAL_TIM_ENABLE(htim); - 8003334: 687b ldr r3, [r7, #4] - 8003336: 681b ldr r3, [r3, #0] - 8003338: 681a ldr r2, [r3, #0] - 800333a: 687b ldr r3, [r7, #4] - 800333c: 681b ldr r3, [r3, #0] - 800333e: f042 0201 orr.w r2, r2, #1 - 8003342: 601a str r2, [r3, #0] + 80033fc: 687b ldr r3, [r7, #4] + 80033fe: 681b ldr r3, [r3, #0] + 8003400: 681a ldr r2, [r3, #0] + 8003402: 687b ldr r3, [r7, #4] + 8003404: 681b ldr r3, [r3, #0] + 8003406: f042 0201 orr.w r2, r2, #1 + 800340a: 601a str r2, [r3, #0] } /* Return function status */ return HAL_OK; - 8003344: 2300 movs r3, #0 + 800340c: 2300 movs r3, #0 } - 8003346: 4618 mov r0, r3 - 8003348: 3710 adds r7, #16 - 800334a: 46bd mov sp, r7 - 800334c: bd80 pop {r7, pc} - 800334e: bf00 nop - 8003350: 40010000 .word 0x40010000 - 8003354: 40010400 .word 0x40010400 - 8003358: 00010007 .word 0x00010007 - -0800335c : + 800340e: 4618 mov r0, r3 + 8003410: 3710 adds r7, #16 + 8003412: 46bd mov sp, r7 + 8003414: bd80 pop {r7, pc} + 8003416: bf00 nop + 8003418: 40010000 .word 0x40010000 + 800341c: 40010400 .word 0x40010400 + 8003420: 00010007 .word 0x00010007 + +08003424 : * @param htim TIM Encoder Interface handle * @param sConfig TIM Encoder Interface configuration structure * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig) { - 800335c: b580 push {r7, lr} - 800335e: b086 sub sp, #24 - 8003360: af00 add r7, sp, #0 - 8003362: 6078 str r0, [r7, #4] - 8003364: 6039 str r1, [r7, #0] + 8003424: b580 push {r7, lr} + 8003426: b086 sub sp, #24 + 8003428: af00 add r7, sp, #0 + 800342a: 6078 str r0, [r7, #4] + 800342c: 6039 str r1, [r7, #0] uint32_t tmpsmcr; uint32_t tmpccmr1; uint32_t tmpccer; /* Check the TIM handle allocation */ if (htim == NULL) - 8003366: 687b ldr r3, [r7, #4] - 8003368: 2b00 cmp r3, #0 - 800336a: d101 bne.n 8003370 + 800342e: 687b ldr r3, [r7, #4] + 8003430: 2b00 cmp r3, #0 + 8003432: d101 bne.n 8003438 { return HAL_ERROR; - 800336c: 2301 movs r3, #1 - 800336e: e07b b.n 8003468 + 8003434: 2301 movs r3, #1 + 8003436: e07b b.n 8003530 assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler)); assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter)); if (htim->State == HAL_TIM_STATE_RESET) - 8003370: 687b ldr r3, [r7, #4] - 8003372: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 8003376: b2db uxtb r3, r3 - 8003378: 2b00 cmp r3, #0 - 800337a: d106 bne.n 800338a + 8003438: 687b ldr r3, [r7, #4] + 800343a: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 800343e: b2db uxtb r3, r3 + 8003440: 2b00 cmp r3, #0 + 8003442: d106 bne.n 8003452 { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 800337c: 687b ldr r3, [r7, #4] - 800337e: 2200 movs r2, #0 - 8003380: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003444: 687b ldr r3, [r7, #4] + 8003446: 2200 movs r2, #0 + 8003448: f883 203c strb.w r2, [r3, #60] ; 0x3c } /* Init the low level hardware : GPIO, CLOCK, NVIC */ htim->Encoder_MspInitCallback(htim); #else /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ HAL_TIM_Encoder_MspInit(htim); - 8003384: 6878 ldr r0, [r7, #4] - 8003386: f7fe f93f bl 8001608 + 800344c: 6878 ldr r0, [r7, #4] + 800344e: f7fe f93f bl 80016d0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 800338a: 687b ldr r3, [r7, #4] - 800338c: 2202 movs r2, #2 - 800338e: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003452: 687b ldr r3, [r7, #4] + 8003454: 2202 movs r2, #2 + 8003456: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Reset the SMS and ECE bits */ htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); - 8003392: 687b ldr r3, [r7, #4] - 8003394: 681b ldr r3, [r3, #0] - 8003396: 6899 ldr r1, [r3, #8] - 8003398: 687b ldr r3, [r7, #4] - 800339a: 681a ldr r2, [r3, #0] - 800339c: 4b34 ldr r3, [pc, #208] ; (8003470 ) - 800339e: 400b ands r3, r1 - 80033a0: 6093 str r3, [r2, #8] + 800345a: 687b ldr r3, [r7, #4] + 800345c: 681b ldr r3, [r3, #0] + 800345e: 6899 ldr r1, [r3, #8] + 8003460: 687b ldr r3, [r7, #4] + 8003462: 681a ldr r2, [r3, #0] + 8003464: 4b34 ldr r3, [pc, #208] ; (8003538 ) + 8003466: 400b ands r3, r1 + 8003468: 6093 str r3, [r2, #8] /* Configure the Time base in the Encoder Mode */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 80033a2: 687b ldr r3, [r7, #4] - 80033a4: 681a ldr r2, [r3, #0] - 80033a6: 687b ldr r3, [r7, #4] - 80033a8: 3304 adds r3, #4 - 80033aa: 4619 mov r1, r3 - 80033ac: 4610 mov r0, r2 - 80033ae: f000 fbb7 bl 8003b20 + 800346a: 687b ldr r3, [r7, #4] + 800346c: 681a ldr r2, [r3, #0] + 800346e: 687b ldr r3, [r7, #4] + 8003470: 3304 adds r3, #4 + 8003472: 4619 mov r1, r3 + 8003474: 4610 mov r0, r2 + 8003476: f000 fbb7 bl 8003be8 /* Get the TIMx SMCR register value */ tmpsmcr = htim->Instance->SMCR; - 80033b2: 687b ldr r3, [r7, #4] - 80033b4: 681b ldr r3, [r3, #0] - 80033b6: 689b ldr r3, [r3, #8] - 80033b8: 617b str r3, [r7, #20] + 800347a: 687b ldr r3, [r7, #4] + 800347c: 681b ldr r3, [r3, #0] + 800347e: 689b ldr r3, [r3, #8] + 8003480: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmr1 = htim->Instance->CCMR1; - 80033ba: 687b ldr r3, [r7, #4] - 80033bc: 681b ldr r3, [r3, #0] - 80033be: 699b ldr r3, [r3, #24] - 80033c0: 613b str r3, [r7, #16] + 8003482: 687b ldr r3, [r7, #4] + 8003484: 681b ldr r3, [r3, #0] + 8003486: 699b ldr r3, [r3, #24] + 8003488: 613b str r3, [r7, #16] /* Get the TIMx CCER register value */ tmpccer = htim->Instance->CCER; - 80033c2: 687b ldr r3, [r7, #4] - 80033c4: 681b ldr r3, [r3, #0] - 80033c6: 6a1b ldr r3, [r3, #32] - 80033c8: 60fb str r3, [r7, #12] + 800348a: 687b ldr r3, [r7, #4] + 800348c: 681b ldr r3, [r3, #0] + 800348e: 6a1b ldr r3, [r3, #32] + 8003490: 60fb str r3, [r7, #12] /* Set the encoder Mode */ tmpsmcr |= sConfig->EncoderMode; - 80033ca: 683b ldr r3, [r7, #0] - 80033cc: 681b ldr r3, [r3, #0] - 80033ce: 697a ldr r2, [r7, #20] - 80033d0: 4313 orrs r3, r2 - 80033d2: 617b str r3, [r7, #20] + 8003492: 683b ldr r3, [r7, #0] + 8003494: 681b ldr r3, [r3, #0] + 8003496: 697a ldr r2, [r7, #20] + 8003498: 4313 orrs r3, r2 + 800349a: 617b str r3, [r7, #20] /* Select the Capture Compare 1 and the Capture Compare 2 as input */ tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); - 80033d4: 693a ldr r2, [r7, #16] - 80033d6: 4b27 ldr r3, [pc, #156] ; (8003474 ) - 80033d8: 4013 ands r3, r2 - 80033da: 613b str r3, [r7, #16] + 800349c: 693a ldr r2, [r7, #16] + 800349e: 4b27 ldr r3, [pc, #156] ; (800353c ) + 80034a0: 4013 ands r3, r2 + 80034a2: 613b str r3, [r7, #16] tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); - 80033dc: 683b ldr r3, [r7, #0] - 80033de: 689a ldr r2, [r3, #8] - 80033e0: 683b ldr r3, [r7, #0] - 80033e2: 699b ldr r3, [r3, #24] - 80033e4: 021b lsls r3, r3, #8 - 80033e6: 4313 orrs r3, r2 - 80033e8: 693a ldr r2, [r7, #16] - 80033ea: 4313 orrs r3, r2 - 80033ec: 613b str r3, [r7, #16] + 80034a4: 683b ldr r3, [r7, #0] + 80034a6: 689a ldr r2, [r3, #8] + 80034a8: 683b ldr r3, [r7, #0] + 80034aa: 699b ldr r3, [r3, #24] + 80034ac: 021b lsls r3, r3, #8 + 80034ae: 4313 orrs r3, r2 + 80034b0: 693a ldr r2, [r7, #16] + 80034b2: 4313 orrs r3, r2 + 80034b4: 613b str r3, [r7, #16] /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */ tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC); - 80033ee: 693a ldr r2, [r7, #16] - 80033f0: 4b21 ldr r3, [pc, #132] ; (8003478 ) - 80033f2: 4013 ands r3, r2 - 80033f4: 613b str r3, [r7, #16] + 80034b6: 693a ldr r2, [r7, #16] + 80034b8: 4b21 ldr r3, [pc, #132] ; (8003540 ) + 80034ba: 4013 ands r3, r2 + 80034bc: 613b str r3, [r7, #16] tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); - 80033f6: 693a ldr r2, [r7, #16] - 80033f8: 4b20 ldr r3, [pc, #128] ; (800347c ) - 80033fa: 4013 ands r3, r2 - 80033fc: 613b str r3, [r7, #16] + 80034be: 693a ldr r2, [r7, #16] + 80034c0: 4b20 ldr r3, [pc, #128] ; (8003544 ) + 80034c2: 4013 ands r3, r2 + 80034c4: 613b str r3, [r7, #16] tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); - 80033fe: 683b ldr r3, [r7, #0] - 8003400: 68da ldr r2, [r3, #12] - 8003402: 683b ldr r3, [r7, #0] - 8003404: 69db ldr r3, [r3, #28] - 8003406: 021b lsls r3, r3, #8 - 8003408: 4313 orrs r3, r2 - 800340a: 693a ldr r2, [r7, #16] - 800340c: 4313 orrs r3, r2 - 800340e: 613b str r3, [r7, #16] + 80034c6: 683b ldr r3, [r7, #0] + 80034c8: 68da ldr r2, [r3, #12] + 80034ca: 683b ldr r3, [r7, #0] + 80034cc: 69db ldr r3, [r3, #28] + 80034ce: 021b lsls r3, r3, #8 + 80034d0: 4313 orrs r3, r2 + 80034d2: 693a ldr r2, [r7, #16] + 80034d4: 4313 orrs r3, r2 + 80034d6: 613b str r3, [r7, #16] tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); - 8003410: 683b ldr r3, [r7, #0] - 8003412: 691b ldr r3, [r3, #16] - 8003414: 011a lsls r2, r3, #4 - 8003416: 683b ldr r3, [r7, #0] - 8003418: 6a1b ldr r3, [r3, #32] - 800341a: 031b lsls r3, r3, #12 - 800341c: 4313 orrs r3, r2 - 800341e: 693a ldr r2, [r7, #16] - 8003420: 4313 orrs r3, r2 - 8003422: 613b str r3, [r7, #16] + 80034d8: 683b ldr r3, [r7, #0] + 80034da: 691b ldr r3, [r3, #16] + 80034dc: 011a lsls r2, r3, #4 + 80034de: 683b ldr r3, [r7, #0] + 80034e0: 6a1b ldr r3, [r3, #32] + 80034e2: 031b lsls r3, r3, #12 + 80034e4: 4313 orrs r3, r2 + 80034e6: 693a ldr r2, [r7, #16] + 80034e8: 4313 orrs r3, r2 + 80034ea: 613b str r3, [r7, #16] /* Set the TI1 and the TI2 Polarities */ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); - 8003424: 68fb ldr r3, [r7, #12] - 8003426: f023 0322 bic.w r3, r3, #34 ; 0x22 - 800342a: 60fb str r3, [r7, #12] + 80034ec: 68fb ldr r3, [r7, #12] + 80034ee: f023 0322 bic.w r3, r3, #34 ; 0x22 + 80034f2: 60fb str r3, [r7, #12] tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); - 800342c: 68fb ldr r3, [r7, #12] - 800342e: f023 0388 bic.w r3, r3, #136 ; 0x88 - 8003432: 60fb str r3, [r7, #12] + 80034f4: 68fb ldr r3, [r7, #12] + 80034f6: f023 0388 bic.w r3, r3, #136 ; 0x88 + 80034fa: 60fb str r3, [r7, #12] tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); - 8003434: 683b ldr r3, [r7, #0] - 8003436: 685a ldr r2, [r3, #4] - 8003438: 683b ldr r3, [r7, #0] - 800343a: 695b ldr r3, [r3, #20] - 800343c: 011b lsls r3, r3, #4 - 800343e: 4313 orrs r3, r2 - 8003440: 68fa ldr r2, [r7, #12] - 8003442: 4313 orrs r3, r2 - 8003444: 60fb str r3, [r7, #12] + 80034fc: 683b ldr r3, [r7, #0] + 80034fe: 685a ldr r2, [r3, #4] + 8003500: 683b ldr r3, [r7, #0] + 8003502: 695b ldr r3, [r3, #20] + 8003504: 011b lsls r3, r3, #4 + 8003506: 4313 orrs r3, r2 + 8003508: 68fa ldr r2, [r7, #12] + 800350a: 4313 orrs r3, r2 + 800350c: 60fb str r3, [r7, #12] /* Write to TIMx SMCR */ htim->Instance->SMCR = tmpsmcr; - 8003446: 687b ldr r3, [r7, #4] - 8003448: 681b ldr r3, [r3, #0] - 800344a: 697a ldr r2, [r7, #20] - 800344c: 609a str r2, [r3, #8] + 800350e: 687b ldr r3, [r7, #4] + 8003510: 681b ldr r3, [r3, #0] + 8003512: 697a ldr r2, [r7, #20] + 8003514: 609a str r2, [r3, #8] /* Write to TIMx CCMR1 */ htim->Instance->CCMR1 = tmpccmr1; - 800344e: 687b ldr r3, [r7, #4] - 8003450: 681b ldr r3, [r3, #0] - 8003452: 693a ldr r2, [r7, #16] - 8003454: 619a str r2, [r3, #24] + 8003516: 687b ldr r3, [r7, #4] + 8003518: 681b ldr r3, [r3, #0] + 800351a: 693a ldr r2, [r7, #16] + 800351c: 619a str r2, [r3, #24] /* Write to TIMx CCER */ htim->Instance->CCER = tmpccer; - 8003456: 687b ldr r3, [r7, #4] - 8003458: 681b ldr r3, [r3, #0] - 800345a: 68fa ldr r2, [r7, #12] - 800345c: 621a str r2, [r3, #32] + 800351e: 687b ldr r3, [r7, #4] + 8003520: 681b ldr r3, [r3, #0] + 8003522: 68fa ldr r2, [r7, #12] + 8003524: 621a str r2, [r3, #32] /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 800345e: 687b ldr r3, [r7, #4] - 8003460: 2201 movs r2, #1 - 8003462: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003526: 687b ldr r3, [r7, #4] + 8003528: 2201 movs r2, #1 + 800352a: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 8003466: 2300 movs r3, #0 + 800352e: 2300 movs r3, #0 } - 8003468: 4618 mov r0, r3 - 800346a: 3718 adds r7, #24 - 800346c: 46bd mov sp, r7 - 800346e: bd80 pop {r7, pc} - 8003470: fffebff8 .word 0xfffebff8 - 8003474: fffffcfc .word 0xfffffcfc - 8003478: fffff3f3 .word 0xfffff3f3 - 800347c: ffff0f0f .word 0xffff0f0f - -08003480 : + 8003530: 4618 mov r0, r3 + 8003532: 3718 adds r7, #24 + 8003534: 46bd mov sp, r7 + 8003536: bd80 pop {r7, pc} + 8003538: fffebff8 .word 0xfffebff8 + 800353c: fffffcfc .word 0xfffffcfc + 8003540: fffff3f3 .word 0xfffff3f3 + 8003544: ffff0f0f .word 0xffff0f0f + +08003548 : * @arg TIM_CHANNEL_2: TIM Channel 2 selected * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel) { - 8003480: b580 push {r7, lr} - 8003482: b082 sub sp, #8 - 8003484: af00 add r7, sp, #0 - 8003486: 6078 str r0, [r7, #4] - 8003488: 6039 str r1, [r7, #0] + 8003548: b580 push {r7, lr} + 800354a: b082 sub sp, #8 + 800354c: af00 add r7, sp, #0 + 800354e: 6078 str r0, [r7, #4] + 8003550: 6039 str r1, [r7, #0] /* Check the parameters */ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); /* Enable the encoder interface channels */ switch (Channel) - 800348a: 683b ldr r3, [r7, #0] - 800348c: 2b00 cmp r3, #0 - 800348e: d002 beq.n 8003496 - 8003490: 2b04 cmp r3, #4 - 8003492: d008 beq.n 80034a6 - 8003494: e00f b.n 80034b6 + 8003552: 683b ldr r3, [r7, #0] + 8003554: 2b00 cmp r3, #0 + 8003556: d002 beq.n 800355e + 8003558: 2b04 cmp r3, #4 + 800355a: d008 beq.n 800356e + 800355c: e00f b.n 800357e { case TIM_CHANNEL_1: { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - 8003496: 687b ldr r3, [r7, #4] - 8003498: 681b ldr r3, [r3, #0] - 800349a: 2201 movs r2, #1 - 800349c: 2100 movs r1, #0 - 800349e: 4618 mov r0, r3 - 80034a0: f000 fed6 bl 8004250 + 800355e: 687b ldr r3, [r7, #4] + 8003560: 681b ldr r3, [r3, #0] + 8003562: 2201 movs r2, #1 + 8003564: 2100 movs r1, #0 + 8003566: 4618 mov r0, r3 + 8003568: f000 fed6 bl 8004318 break; - 80034a4: e016 b.n 80034d4 + 800356c: e016 b.n 800359c } case TIM_CHANNEL_2: { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - 80034a6: 687b ldr r3, [r7, #4] - 80034a8: 681b ldr r3, [r3, #0] - 80034aa: 2201 movs r2, #1 - 80034ac: 2104 movs r1, #4 - 80034ae: 4618 mov r0, r3 - 80034b0: f000 fece bl 8004250 + 800356e: 687b ldr r3, [r7, #4] + 8003570: 681b ldr r3, [r3, #0] + 8003572: 2201 movs r2, #1 + 8003574: 2104 movs r1, #4 + 8003576: 4618 mov r0, r3 + 8003578: f000 fece bl 8004318 break; - 80034b4: e00e b.n 80034d4 + 800357c: e00e b.n 800359c } default : { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - 80034b6: 687b ldr r3, [r7, #4] - 80034b8: 681b ldr r3, [r3, #0] - 80034ba: 2201 movs r2, #1 - 80034bc: 2100 movs r1, #0 - 80034be: 4618 mov r0, r3 - 80034c0: f000 fec6 bl 8004250 + 800357e: 687b ldr r3, [r7, #4] + 8003580: 681b ldr r3, [r3, #0] + 8003582: 2201 movs r2, #1 + 8003584: 2100 movs r1, #0 + 8003586: 4618 mov r0, r3 + 8003588: f000 fec6 bl 8004318 TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - 80034c4: 687b ldr r3, [r7, #4] - 80034c6: 681b ldr r3, [r3, #0] - 80034c8: 2201 movs r2, #1 - 80034ca: 2104 movs r1, #4 - 80034cc: 4618 mov r0, r3 - 80034ce: f000 febf bl 8004250 + 800358c: 687b ldr r3, [r7, #4] + 800358e: 681b ldr r3, [r3, #0] + 8003590: 2201 movs r2, #1 + 8003592: 2104 movs r1, #4 + 8003594: 4618 mov r0, r3 + 8003596: f000 febf bl 8004318 break; - 80034d2: bf00 nop + 800359a: bf00 nop } } /* Enable the Peripheral */ __HAL_TIM_ENABLE(htim); - 80034d4: 687b ldr r3, [r7, #4] - 80034d6: 681b ldr r3, [r3, #0] - 80034d8: 681a ldr r2, [r3, #0] - 80034da: 687b ldr r3, [r7, #4] - 80034dc: 681b ldr r3, [r3, #0] - 80034de: f042 0201 orr.w r2, r2, #1 - 80034e2: 601a str r2, [r3, #0] + 800359c: 687b ldr r3, [r7, #4] + 800359e: 681b ldr r3, [r3, #0] + 80035a0: 681a ldr r2, [r3, #0] + 80035a2: 687b ldr r3, [r7, #4] + 80035a4: 681b ldr r3, [r3, #0] + 80035a6: f042 0201 orr.w r2, r2, #1 + 80035aa: 601a str r2, [r3, #0] /* Return function status */ return HAL_OK; - 80034e4: 2300 movs r3, #0 + 80035ac: 2300 movs r3, #0 } - 80034e6: 4618 mov r0, r3 - 80034e8: 3708 adds r7, #8 - 80034ea: 46bd mov sp, r7 - 80034ec: bd80 pop {r7, pc} + 80035ae: 4618 mov r0, r3 + 80035b0: 3708 adds r7, #8 + 80035b2: 46bd mov sp, r7 + 80035b4: bd80 pop {r7, pc} -080034ee : +080035b6 : * @brief This function handles TIM interrupts requests. * @param htim TIM handle * @retval None */ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) { - 80034ee: b580 push {r7, lr} - 80034f0: b082 sub sp, #8 - 80034f2: af00 add r7, sp, #0 - 80034f4: 6078 str r0, [r7, #4] + 80035b6: b580 push {r7, lr} + 80035b8: b082 sub sp, #8 + 80035ba: af00 add r7, sp, #0 + 80035bc: 6078 str r0, [r7, #4] /* Capture compare 1 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) - 80034f6: 687b ldr r3, [r7, #4] - 80034f8: 681b ldr r3, [r3, #0] - 80034fa: 691b ldr r3, [r3, #16] - 80034fc: f003 0302 and.w r3, r3, #2 - 8003500: 2b02 cmp r3, #2 - 8003502: d122 bne.n 800354a + 80035be: 687b ldr r3, [r7, #4] + 80035c0: 681b ldr r3, [r3, #0] + 80035c2: 691b ldr r3, [r3, #16] + 80035c4: f003 0302 and.w r3, r3, #2 + 80035c8: 2b02 cmp r3, #2 + 80035ca: d122 bne.n 8003612 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) - 8003504: 687b ldr r3, [r7, #4] - 8003506: 681b ldr r3, [r3, #0] - 8003508: 68db ldr r3, [r3, #12] - 800350a: f003 0302 and.w r3, r3, #2 - 800350e: 2b02 cmp r3, #2 - 8003510: d11b bne.n 800354a + 80035cc: 687b ldr r3, [r7, #4] + 80035ce: 681b ldr r3, [r3, #0] + 80035d0: 68db ldr r3, [r3, #12] + 80035d2: f003 0302 and.w r3, r3, #2 + 80035d6: 2b02 cmp r3, #2 + 80035d8: d11b bne.n 8003612 { { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); - 8003512: 687b ldr r3, [r7, #4] - 8003514: 681b ldr r3, [r3, #0] - 8003516: f06f 0202 mvn.w r2, #2 - 800351a: 611a str r2, [r3, #16] + 80035da: 687b ldr r3, [r7, #4] + 80035dc: 681b ldr r3, [r3, #0] + 80035de: f06f 0202 mvn.w r2, #2 + 80035e2: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - 800351c: 687b ldr r3, [r7, #4] - 800351e: 2201 movs r2, #1 - 8003520: 771a strb r2, [r3, #28] + 80035e4: 687b ldr r3, [r7, #4] + 80035e6: 2201 movs r2, #1 + 80035e8: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) - 8003522: 687b ldr r3, [r7, #4] - 8003524: 681b ldr r3, [r3, #0] - 8003526: 699b ldr r3, [r3, #24] - 8003528: f003 0303 and.w r3, r3, #3 - 800352c: 2b00 cmp r3, #0 - 800352e: d003 beq.n 8003538 + 80035ea: 687b ldr r3, [r7, #4] + 80035ec: 681b ldr r3, [r3, #0] + 80035ee: 699b ldr r3, [r3, #24] + 80035f0: f003 0303 and.w r3, r3, #3 + 80035f4: 2b00 cmp r3, #0 + 80035f6: d003 beq.n 8003600 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 8003530: 6878 ldr r0, [r7, #4] - 8003532: f000 fad7 bl 8003ae4 - 8003536: e005 b.n 8003544 + 80035f8: 6878 ldr r0, [r7, #4] + 80035fa: f000 fad7 bl 8003bac + 80035fe: e005 b.n 800360c { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 8003538: 6878 ldr r0, [r7, #4] - 800353a: f000 fac9 bl 8003ad0 + 8003600: 6878 ldr r0, [r7, #4] + 8003602: f000 fac9 bl 8003b98 HAL_TIM_PWM_PulseFinishedCallback(htim); - 800353e: 6878 ldr r0, [r7, #4] - 8003540: f000 fada bl 8003af8 + 8003606: 6878 ldr r0, [r7, #4] + 8003608: f000 fada bl 8003bc0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 8003544: 687b ldr r3, [r7, #4] - 8003546: 2200 movs r2, #0 - 8003548: 771a strb r2, [r3, #28] + 800360c: 687b ldr r3, [r7, #4] + 800360e: 2200 movs r2, #0 + 8003610: 771a strb r2, [r3, #28] } } } /* Capture compare 2 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) - 800354a: 687b ldr r3, [r7, #4] - 800354c: 681b ldr r3, [r3, #0] - 800354e: 691b ldr r3, [r3, #16] - 8003550: f003 0304 and.w r3, r3, #4 - 8003554: 2b04 cmp r3, #4 - 8003556: d122 bne.n 800359e + 8003612: 687b ldr r3, [r7, #4] + 8003614: 681b ldr r3, [r3, #0] + 8003616: 691b ldr r3, [r3, #16] + 8003618: f003 0304 and.w r3, r3, #4 + 800361c: 2b04 cmp r3, #4 + 800361e: d122 bne.n 8003666 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) - 8003558: 687b ldr r3, [r7, #4] - 800355a: 681b ldr r3, [r3, #0] - 800355c: 68db ldr r3, [r3, #12] - 800355e: f003 0304 and.w r3, r3, #4 - 8003562: 2b04 cmp r3, #4 - 8003564: d11b bne.n 800359e + 8003620: 687b ldr r3, [r7, #4] + 8003622: 681b ldr r3, [r3, #0] + 8003624: 68db ldr r3, [r3, #12] + 8003626: f003 0304 and.w r3, r3, #4 + 800362a: 2b04 cmp r3, #4 + 800362c: d11b bne.n 8003666 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); - 8003566: 687b ldr r3, [r7, #4] - 8003568: 681b ldr r3, [r3, #0] - 800356a: f06f 0204 mvn.w r2, #4 - 800356e: 611a str r2, [r3, #16] + 800362e: 687b ldr r3, [r7, #4] + 8003630: 681b ldr r3, [r3, #0] + 8003632: f06f 0204 mvn.w r2, #4 + 8003636: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - 8003570: 687b ldr r3, [r7, #4] - 8003572: 2202 movs r2, #2 - 8003574: 771a strb r2, [r3, #28] + 8003638: 687b ldr r3, [r7, #4] + 800363a: 2202 movs r2, #2 + 800363c: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) - 8003576: 687b ldr r3, [r7, #4] - 8003578: 681b ldr r3, [r3, #0] - 800357a: 699b ldr r3, [r3, #24] - 800357c: f403 7340 and.w r3, r3, #768 ; 0x300 - 8003580: 2b00 cmp r3, #0 - 8003582: d003 beq.n 800358c + 800363e: 687b ldr r3, [r7, #4] + 8003640: 681b ldr r3, [r3, #0] + 8003642: 699b ldr r3, [r3, #24] + 8003644: f403 7340 and.w r3, r3, #768 ; 0x300 + 8003648: 2b00 cmp r3, #0 + 800364a: d003 beq.n 8003654 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 8003584: 6878 ldr r0, [r7, #4] - 8003586: f000 faad bl 8003ae4 - 800358a: e005 b.n 8003598 + 800364c: 6878 ldr r0, [r7, #4] + 800364e: f000 faad bl 8003bac + 8003652: e005 b.n 8003660 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 800358c: 6878 ldr r0, [r7, #4] - 800358e: f000 fa9f bl 8003ad0 + 8003654: 6878 ldr r0, [r7, #4] + 8003656: f000 fa9f bl 8003b98 HAL_TIM_PWM_PulseFinishedCallback(htim); - 8003592: 6878 ldr r0, [r7, #4] - 8003594: f000 fab0 bl 8003af8 + 800365a: 6878 ldr r0, [r7, #4] + 800365c: f000 fab0 bl 8003bc0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 8003598: 687b ldr r3, [r7, #4] - 800359a: 2200 movs r2, #0 - 800359c: 771a strb r2, [r3, #28] + 8003660: 687b ldr r3, [r7, #4] + 8003662: 2200 movs r2, #0 + 8003664: 771a strb r2, [r3, #28] } } /* Capture compare 3 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) - 800359e: 687b ldr r3, [r7, #4] - 80035a0: 681b ldr r3, [r3, #0] - 80035a2: 691b ldr r3, [r3, #16] - 80035a4: f003 0308 and.w r3, r3, #8 - 80035a8: 2b08 cmp r3, #8 - 80035aa: d122 bne.n 80035f2 + 8003666: 687b ldr r3, [r7, #4] + 8003668: 681b ldr r3, [r3, #0] + 800366a: 691b ldr r3, [r3, #16] + 800366c: f003 0308 and.w r3, r3, #8 + 8003670: 2b08 cmp r3, #8 + 8003672: d122 bne.n 80036ba { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) - 80035ac: 687b ldr r3, [r7, #4] - 80035ae: 681b ldr r3, [r3, #0] - 80035b0: 68db ldr r3, [r3, #12] - 80035b2: f003 0308 and.w r3, r3, #8 - 80035b6: 2b08 cmp r3, #8 - 80035b8: d11b bne.n 80035f2 + 8003674: 687b ldr r3, [r7, #4] + 8003676: 681b ldr r3, [r3, #0] + 8003678: 68db ldr r3, [r3, #12] + 800367a: f003 0308 and.w r3, r3, #8 + 800367e: 2b08 cmp r3, #8 + 8003680: d11b bne.n 80036ba { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); - 80035ba: 687b ldr r3, [r7, #4] - 80035bc: 681b ldr r3, [r3, #0] - 80035be: f06f 0208 mvn.w r2, #8 - 80035c2: 611a str r2, [r3, #16] + 8003682: 687b ldr r3, [r7, #4] + 8003684: 681b ldr r3, [r3, #0] + 8003686: f06f 0208 mvn.w r2, #8 + 800368a: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - 80035c4: 687b ldr r3, [r7, #4] - 80035c6: 2204 movs r2, #4 - 80035c8: 771a strb r2, [r3, #28] + 800368c: 687b ldr r3, [r7, #4] + 800368e: 2204 movs r2, #4 + 8003690: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) - 80035ca: 687b ldr r3, [r7, #4] - 80035cc: 681b ldr r3, [r3, #0] - 80035ce: 69db ldr r3, [r3, #28] - 80035d0: f003 0303 and.w r3, r3, #3 - 80035d4: 2b00 cmp r3, #0 - 80035d6: d003 beq.n 80035e0 + 8003692: 687b ldr r3, [r7, #4] + 8003694: 681b ldr r3, [r3, #0] + 8003696: 69db ldr r3, [r3, #28] + 8003698: f003 0303 and.w r3, r3, #3 + 800369c: 2b00 cmp r3, #0 + 800369e: d003 beq.n 80036a8 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 80035d8: 6878 ldr r0, [r7, #4] - 80035da: f000 fa83 bl 8003ae4 - 80035de: e005 b.n 80035ec + 80036a0: 6878 ldr r0, [r7, #4] + 80036a2: f000 fa83 bl 8003bac + 80036a6: e005 b.n 80036b4 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 80035e0: 6878 ldr r0, [r7, #4] - 80035e2: f000 fa75 bl 8003ad0 + 80036a8: 6878 ldr r0, [r7, #4] + 80036aa: f000 fa75 bl 8003b98 HAL_TIM_PWM_PulseFinishedCallback(htim); - 80035e6: 6878 ldr r0, [r7, #4] - 80035e8: f000 fa86 bl 8003af8 + 80036ae: 6878 ldr r0, [r7, #4] + 80036b0: f000 fa86 bl 8003bc0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 80035ec: 687b ldr r3, [r7, #4] - 80035ee: 2200 movs r2, #0 - 80035f0: 771a strb r2, [r3, #28] + 80036b4: 687b ldr r3, [r7, #4] + 80036b6: 2200 movs r2, #0 + 80036b8: 771a strb r2, [r3, #28] } } /* Capture compare 4 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) - 80035f2: 687b ldr r3, [r7, #4] - 80035f4: 681b ldr r3, [r3, #0] - 80035f6: 691b ldr r3, [r3, #16] - 80035f8: f003 0310 and.w r3, r3, #16 - 80035fc: 2b10 cmp r3, #16 - 80035fe: d122 bne.n 8003646 + 80036ba: 687b ldr r3, [r7, #4] + 80036bc: 681b ldr r3, [r3, #0] + 80036be: 691b ldr r3, [r3, #16] + 80036c0: f003 0310 and.w r3, r3, #16 + 80036c4: 2b10 cmp r3, #16 + 80036c6: d122 bne.n 800370e { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) - 8003600: 687b ldr r3, [r7, #4] - 8003602: 681b ldr r3, [r3, #0] - 8003604: 68db ldr r3, [r3, #12] - 8003606: f003 0310 and.w r3, r3, #16 - 800360a: 2b10 cmp r3, #16 - 800360c: d11b bne.n 8003646 + 80036c8: 687b ldr r3, [r7, #4] + 80036ca: 681b ldr r3, [r3, #0] + 80036cc: 68db ldr r3, [r3, #12] + 80036ce: f003 0310 and.w r3, r3, #16 + 80036d2: 2b10 cmp r3, #16 + 80036d4: d11b bne.n 800370e { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); - 800360e: 687b ldr r3, [r7, #4] - 8003610: 681b ldr r3, [r3, #0] - 8003612: f06f 0210 mvn.w r2, #16 - 8003616: 611a str r2, [r3, #16] + 80036d6: 687b ldr r3, [r7, #4] + 80036d8: 681b ldr r3, [r3, #0] + 80036da: f06f 0210 mvn.w r2, #16 + 80036de: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - 8003618: 687b ldr r3, [r7, #4] - 800361a: 2208 movs r2, #8 - 800361c: 771a strb r2, [r3, #28] + 80036e0: 687b ldr r3, [r7, #4] + 80036e2: 2208 movs r2, #8 + 80036e4: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) - 800361e: 687b ldr r3, [r7, #4] - 8003620: 681b ldr r3, [r3, #0] - 8003622: 69db ldr r3, [r3, #28] - 8003624: f403 7340 and.w r3, r3, #768 ; 0x300 - 8003628: 2b00 cmp r3, #0 - 800362a: d003 beq.n 8003634 + 80036e6: 687b ldr r3, [r7, #4] + 80036e8: 681b ldr r3, [r3, #0] + 80036ea: 69db ldr r3, [r3, #28] + 80036ec: f403 7340 and.w r3, r3, #768 ; 0x300 + 80036f0: 2b00 cmp r3, #0 + 80036f2: d003 beq.n 80036fc { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 800362c: 6878 ldr r0, [r7, #4] - 800362e: f000 fa59 bl 8003ae4 - 8003632: e005 b.n 8003640 + 80036f4: 6878 ldr r0, [r7, #4] + 80036f6: f000 fa59 bl 8003bac + 80036fa: e005 b.n 8003708 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 8003634: 6878 ldr r0, [r7, #4] - 8003636: f000 fa4b bl 8003ad0 + 80036fc: 6878 ldr r0, [r7, #4] + 80036fe: f000 fa4b bl 8003b98 HAL_TIM_PWM_PulseFinishedCallback(htim); - 800363a: 6878 ldr r0, [r7, #4] - 800363c: f000 fa5c bl 8003af8 + 8003702: 6878 ldr r0, [r7, #4] + 8003704: f000 fa5c bl 8003bc0 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 8003640: 687b ldr r3, [r7, #4] - 8003642: 2200 movs r2, #0 - 8003644: 771a strb r2, [r3, #28] + 8003708: 687b ldr r3, [r7, #4] + 800370a: 2200 movs r2, #0 + 800370c: 771a strb r2, [r3, #28] } } /* TIM Update event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) - 8003646: 687b ldr r3, [r7, #4] - 8003648: 681b ldr r3, [r3, #0] - 800364a: 691b ldr r3, [r3, #16] - 800364c: f003 0301 and.w r3, r3, #1 - 8003650: 2b01 cmp r3, #1 - 8003652: d10e bne.n 8003672 + 800370e: 687b ldr r3, [r7, #4] + 8003710: 681b ldr r3, [r3, #0] + 8003712: 691b ldr r3, [r3, #16] + 8003714: f003 0301 and.w r3, r3, #1 + 8003718: 2b01 cmp r3, #1 + 800371a: d10e bne.n 800373a { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) - 8003654: 687b ldr r3, [r7, #4] - 8003656: 681b ldr r3, [r3, #0] - 8003658: 68db ldr r3, [r3, #12] - 800365a: f003 0301 and.w r3, r3, #1 - 800365e: 2b01 cmp r3, #1 - 8003660: d107 bne.n 8003672 + 800371c: 687b ldr r3, [r7, #4] + 800371e: 681b ldr r3, [r3, #0] + 8003720: 68db ldr r3, [r3, #12] + 8003722: f003 0301 and.w r3, r3, #1 + 8003726: 2b01 cmp r3, #1 + 8003728: d107 bne.n 800373a { __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); - 8003662: 687b ldr r3, [r7, #4] - 8003664: 681b ldr r3, [r3, #0] - 8003666: f06f 0201 mvn.w r2, #1 - 800366a: 611a str r2, [r3, #16] + 800372a: 687b ldr r3, [r7, #4] + 800372c: 681b ldr r3, [r3, #0] + 800372e: f06f 0201 mvn.w r2, #1 + 8003732: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->PeriodElapsedCallback(htim); #else HAL_TIM_PeriodElapsedCallback(htim); - 800366c: 6878 ldr r0, [r7, #4] - 800366e: f7fd fe3b bl 80012e8 + 8003734: 6878 ldr r0, [r7, #4] + 8003736: f7fd fe2b bl 8001390 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Break input event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) - 8003672: 687b ldr r3, [r7, #4] - 8003674: 681b ldr r3, [r3, #0] - 8003676: 691b ldr r3, [r3, #16] - 8003678: f003 0380 and.w r3, r3, #128 ; 0x80 - 800367c: 2b80 cmp r3, #128 ; 0x80 - 800367e: d10e bne.n 800369e + 800373a: 687b ldr r3, [r7, #4] + 800373c: 681b ldr r3, [r3, #0] + 800373e: 691b ldr r3, [r3, #16] + 8003740: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003744: 2b80 cmp r3, #128 ; 0x80 + 8003746: d10e bne.n 8003766 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - 8003680: 687b ldr r3, [r7, #4] - 8003682: 681b ldr r3, [r3, #0] - 8003684: 68db ldr r3, [r3, #12] - 8003686: f003 0380 and.w r3, r3, #128 ; 0x80 - 800368a: 2b80 cmp r3, #128 ; 0x80 - 800368c: d107 bne.n 800369e + 8003748: 687b ldr r3, [r7, #4] + 800374a: 681b ldr r3, [r3, #0] + 800374c: 68db ldr r3, [r3, #12] + 800374e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003752: 2b80 cmp r3, #128 ; 0x80 + 8003754: d107 bne.n 8003766 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); - 800368e: 687b ldr r3, [r7, #4] - 8003690: 681b ldr r3, [r3, #0] - 8003692: f06f 0280 mvn.w r2, #128 ; 0x80 - 8003696: 611a str r2, [r3, #16] + 8003756: 687b ldr r3, [r7, #4] + 8003758: 681b ldr r3, [r3, #0] + 800375a: f06f 0280 mvn.w r2, #128 ; 0x80 + 800375e: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->BreakCallback(htim); #else HAL_TIMEx_BreakCallback(htim); - 8003698: 6878 ldr r0, [r7, #4] - 800369a: f000 fe65 bl 8004368 + 8003760: 6878 ldr r0, [r7, #4] + 8003762: f000 fe65 bl 8004430 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Break2 input event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK2) != RESET) - 800369e: 687b ldr r3, [r7, #4] - 80036a0: 681b ldr r3, [r3, #0] - 80036a2: 691b ldr r3, [r3, #16] - 80036a4: f403 7380 and.w r3, r3, #256 ; 0x100 - 80036a8: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 80036ac: d10e bne.n 80036cc + 8003766: 687b ldr r3, [r7, #4] + 8003768: 681b ldr r3, [r3, #0] + 800376a: 691b ldr r3, [r3, #16] + 800376c: f403 7380 and.w r3, r3, #256 ; 0x100 + 8003770: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8003774: d10e bne.n 8003794 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - 80036ae: 687b ldr r3, [r7, #4] - 80036b0: 681b ldr r3, [r3, #0] - 80036b2: 68db ldr r3, [r3, #12] - 80036b4: f003 0380 and.w r3, r3, #128 ; 0x80 - 80036b8: 2b80 cmp r3, #128 ; 0x80 - 80036ba: d107 bne.n 80036cc + 8003776: 687b ldr r3, [r7, #4] + 8003778: 681b ldr r3, [r3, #0] + 800377a: 68db ldr r3, [r3, #12] + 800377c: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003780: 2b80 cmp r3, #128 ; 0x80 + 8003782: d107 bne.n 8003794 { __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_BREAK2); - 80036bc: 687b ldr r3, [r7, #4] - 80036be: 681b ldr r3, [r3, #0] - 80036c0: f46f 7280 mvn.w r2, #256 ; 0x100 - 80036c4: 611a str r2, [r3, #16] + 8003784: 687b ldr r3, [r7, #4] + 8003786: 681b ldr r3, [r3, #0] + 8003788: f46f 7280 mvn.w r2, #256 ; 0x100 + 800378c: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->Break2Callback(htim); #else HAL_TIMEx_Break2Callback(htim); - 80036c6: 6878 ldr r0, [r7, #4] - 80036c8: f000 fe58 bl 800437c + 800378e: 6878 ldr r0, [r7, #4] + 8003790: f000 fe58 bl 8004444 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Trigger detection event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) - 80036cc: 687b ldr r3, [r7, #4] - 80036ce: 681b ldr r3, [r3, #0] - 80036d0: 691b ldr r3, [r3, #16] - 80036d2: f003 0340 and.w r3, r3, #64 ; 0x40 - 80036d6: 2b40 cmp r3, #64 ; 0x40 - 80036d8: d10e bne.n 80036f8 + 8003794: 687b ldr r3, [r7, #4] + 8003796: 681b ldr r3, [r3, #0] + 8003798: 691b ldr r3, [r3, #16] + 800379a: f003 0340 and.w r3, r3, #64 ; 0x40 + 800379e: 2b40 cmp r3, #64 ; 0x40 + 80037a0: d10e bne.n 80037c0 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) - 80036da: 687b ldr r3, [r7, #4] - 80036dc: 681b ldr r3, [r3, #0] - 80036de: 68db ldr r3, [r3, #12] - 80036e0: f003 0340 and.w r3, r3, #64 ; 0x40 - 80036e4: 2b40 cmp r3, #64 ; 0x40 - 80036e6: d107 bne.n 80036f8 + 80037a2: 687b ldr r3, [r7, #4] + 80037a4: 681b ldr r3, [r3, #0] + 80037a6: 68db ldr r3, [r3, #12] + 80037a8: f003 0340 and.w r3, r3, #64 ; 0x40 + 80037ac: 2b40 cmp r3, #64 ; 0x40 + 80037ae: d107 bne.n 80037c0 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); - 80036e8: 687b ldr r3, [r7, #4] - 80036ea: 681b ldr r3, [r3, #0] - 80036ec: f06f 0240 mvn.w r2, #64 ; 0x40 - 80036f0: 611a str r2, [r3, #16] + 80037b0: 687b ldr r3, [r7, #4] + 80037b2: 681b ldr r3, [r3, #0] + 80037b4: f06f 0240 mvn.w r2, #64 ; 0x40 + 80037b8: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->TriggerCallback(htim); #else HAL_TIM_TriggerCallback(htim); - 80036f2: 6878 ldr r0, [r7, #4] - 80036f4: f000 fa0a bl 8003b0c + 80037ba: 6878 ldr r0, [r7, #4] + 80037bc: f000 fa0a bl 8003bd4 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM commutation event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) - 80036f8: 687b ldr r3, [r7, #4] - 80036fa: 681b ldr r3, [r3, #0] - 80036fc: 691b ldr r3, [r3, #16] - 80036fe: f003 0320 and.w r3, r3, #32 - 8003702: 2b20 cmp r3, #32 - 8003704: d10e bne.n 8003724 + 80037c0: 687b ldr r3, [r7, #4] + 80037c2: 681b ldr r3, [r3, #0] + 80037c4: 691b ldr r3, [r3, #16] + 80037c6: f003 0320 and.w r3, r3, #32 + 80037ca: 2b20 cmp r3, #32 + 80037cc: d10e bne.n 80037ec { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) - 8003706: 687b ldr r3, [r7, #4] - 8003708: 681b ldr r3, [r3, #0] - 800370a: 68db ldr r3, [r3, #12] - 800370c: f003 0320 and.w r3, r3, #32 - 8003710: 2b20 cmp r3, #32 - 8003712: d107 bne.n 8003724 + 80037ce: 687b ldr r3, [r7, #4] + 80037d0: 681b ldr r3, [r3, #0] + 80037d2: 68db ldr r3, [r3, #12] + 80037d4: f003 0320 and.w r3, r3, #32 + 80037d8: 2b20 cmp r3, #32 + 80037da: d107 bne.n 80037ec { __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); - 8003714: 687b ldr r3, [r7, #4] - 8003716: 681b ldr r3, [r3, #0] - 8003718: f06f 0220 mvn.w r2, #32 - 800371c: 611a str r2, [r3, #16] + 80037dc: 687b ldr r3, [r7, #4] + 80037de: 681b ldr r3, [r3, #0] + 80037e0: f06f 0220 mvn.w r2, #32 + 80037e4: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->CommutationCallback(htim); #else HAL_TIMEx_CommutCallback(htim); - 800371e: 6878 ldr r0, [r7, #4] - 8003720: f000 fe18 bl 8004354 + 80037e6: 6878 ldr r0, [r7, #4] + 80037e8: f000 fe18 bl 800441c #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } } - 8003724: bf00 nop - 8003726: 3708 adds r7, #8 - 8003728: 46bd mov sp, r7 - 800372a: bd80 pop {r7, pc} + 80037ec: bf00 nop + 80037ee: 3708 adds r7, #8 + 80037f0: 46bd mov sp, r7 + 80037f2: bd80 pop {r7, pc} -0800372c : +080037f4 : * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel) { - 800372c: b580 push {r7, lr} - 800372e: b084 sub sp, #16 - 8003730: af00 add r7, sp, #0 - 8003732: 60f8 str r0, [r7, #12] - 8003734: 60b9 str r1, [r7, #8] - 8003736: 607a str r2, [r7, #4] + 80037f4: b580 push {r7, lr} + 80037f6: b084 sub sp, #16 + 80037f8: af00 add r7, sp, #0 + 80037fa: 60f8 str r0, [r7, #12] + 80037fc: 60b9 str r1, [r7, #8] + 80037fe: 607a str r2, [r7, #4] assert_param(IS_TIM_PWM_MODE(sConfig->OCMode)); assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode)); /* Process Locked */ __HAL_LOCK(htim); - 8003738: 68fb ldr r3, [r7, #12] - 800373a: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 800373e: 2b01 cmp r3, #1 - 8003740: d101 bne.n 8003746 - 8003742: 2302 movs r3, #2 - 8003744: e105 b.n 8003952 - 8003746: 68fb ldr r3, [r7, #12] - 8003748: 2201 movs r2, #1 - 800374a: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003800: 68fb ldr r3, [r7, #12] + 8003802: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8003806: 2b01 cmp r3, #1 + 8003808: d101 bne.n 800380e + 800380a: 2302 movs r3, #2 + 800380c: e105 b.n 8003a1a + 800380e: 68fb ldr r3, [r7, #12] + 8003810: 2201 movs r2, #1 + 8003812: f883 203c strb.w r2, [r3, #60] ; 0x3c htim->State = HAL_TIM_STATE_BUSY; - 800374e: 68fb ldr r3, [r7, #12] - 8003750: 2202 movs r2, #2 - 8003752: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003816: 68fb ldr r3, [r7, #12] + 8003818: 2202 movs r2, #2 + 800381a: f883 203d strb.w r2, [r3, #61] ; 0x3d switch (Channel) - 8003756: 687b ldr r3, [r7, #4] - 8003758: 2b14 cmp r3, #20 - 800375a: f200 80f0 bhi.w 800393e - 800375e: a201 add r2, pc, #4 ; (adr r2, 8003764 ) - 8003760: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8003764: 080037b9 .word 0x080037b9 - 8003768: 0800393f .word 0x0800393f - 800376c: 0800393f .word 0x0800393f - 8003770: 0800393f .word 0x0800393f - 8003774: 080037f9 .word 0x080037f9 - 8003778: 0800393f .word 0x0800393f - 800377c: 0800393f .word 0x0800393f - 8003780: 0800393f .word 0x0800393f - 8003784: 0800383b .word 0x0800383b - 8003788: 0800393f .word 0x0800393f - 800378c: 0800393f .word 0x0800393f - 8003790: 0800393f .word 0x0800393f - 8003794: 0800387b .word 0x0800387b - 8003798: 0800393f .word 0x0800393f - 800379c: 0800393f .word 0x0800393f - 80037a0: 0800393f .word 0x0800393f - 80037a4: 080038bd .word 0x080038bd - 80037a8: 0800393f .word 0x0800393f - 80037ac: 0800393f .word 0x0800393f - 80037b0: 0800393f .word 0x0800393f - 80037b4: 080038fd .word 0x080038fd + 800381e: 687b ldr r3, [r7, #4] + 8003820: 2b14 cmp r3, #20 + 8003822: f200 80f0 bhi.w 8003a06 + 8003826: a201 add r2, pc, #4 ; (adr r2, 800382c ) + 8003828: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 800382c: 08003881 .word 0x08003881 + 8003830: 08003a07 .word 0x08003a07 + 8003834: 08003a07 .word 0x08003a07 + 8003838: 08003a07 .word 0x08003a07 + 800383c: 080038c1 .word 0x080038c1 + 8003840: 08003a07 .word 0x08003a07 + 8003844: 08003a07 .word 0x08003a07 + 8003848: 08003a07 .word 0x08003a07 + 800384c: 08003903 .word 0x08003903 + 8003850: 08003a07 .word 0x08003a07 + 8003854: 08003a07 .word 0x08003a07 + 8003858: 08003a07 .word 0x08003a07 + 800385c: 08003943 .word 0x08003943 + 8003860: 08003a07 .word 0x08003a07 + 8003864: 08003a07 .word 0x08003a07 + 8003868: 08003a07 .word 0x08003a07 + 800386c: 08003985 .word 0x08003985 + 8003870: 08003a07 .word 0x08003a07 + 8003874: 08003a07 .word 0x08003a07 + 8003878: 08003a07 .word 0x08003a07 + 800387c: 080039c5 .word 0x080039c5 { /* Check the parameters */ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); /* Configure the Channel 1 in PWM mode */ TIM_OC1_SetConfig(htim->Instance, sConfig); - 80037b8: 68fb ldr r3, [r7, #12] - 80037ba: 681b ldr r3, [r3, #0] - 80037bc: 68b9 ldr r1, [r7, #8] - 80037be: 4618 mov r0, r3 - 80037c0: f000 fa4e bl 8003c60 + 8003880: 68fb ldr r3, [r7, #12] + 8003882: 681b ldr r3, [r3, #0] + 8003884: 68b9 ldr r1, [r7, #8] + 8003886: 4618 mov r0, r3 + 8003888: f000 fa4e bl 8003d28 /* Set the Preload enable bit for channel1 */ htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; - 80037c4: 68fb ldr r3, [r7, #12] - 80037c6: 681b ldr r3, [r3, #0] - 80037c8: 699a ldr r2, [r3, #24] - 80037ca: 68fb ldr r3, [r7, #12] - 80037cc: 681b ldr r3, [r3, #0] - 80037ce: f042 0208 orr.w r2, r2, #8 - 80037d2: 619a str r2, [r3, #24] + 800388c: 68fb ldr r3, [r7, #12] + 800388e: 681b ldr r3, [r3, #0] + 8003890: 699a ldr r2, [r3, #24] + 8003892: 68fb ldr r3, [r7, #12] + 8003894: 681b ldr r3, [r3, #0] + 8003896: f042 0208 orr.w r2, r2, #8 + 800389a: 619a str r2, [r3, #24] /* Configure the Output Fast mode */ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; - 80037d4: 68fb ldr r3, [r7, #12] - 80037d6: 681b ldr r3, [r3, #0] - 80037d8: 699a ldr r2, [r3, #24] - 80037da: 68fb ldr r3, [r7, #12] - 80037dc: 681b ldr r3, [r3, #0] - 80037de: f022 0204 bic.w r2, r2, #4 - 80037e2: 619a str r2, [r3, #24] + 800389c: 68fb ldr r3, [r7, #12] + 800389e: 681b ldr r3, [r3, #0] + 80038a0: 699a ldr r2, [r3, #24] + 80038a2: 68fb ldr r3, [r7, #12] + 80038a4: 681b ldr r3, [r3, #0] + 80038a6: f022 0204 bic.w r2, r2, #4 + 80038aa: 619a str r2, [r3, #24] htim->Instance->CCMR1 |= sConfig->OCFastMode; - 80037e4: 68fb ldr r3, [r7, #12] - 80037e6: 681b ldr r3, [r3, #0] - 80037e8: 6999 ldr r1, [r3, #24] - 80037ea: 68bb ldr r3, [r7, #8] - 80037ec: 691a ldr r2, [r3, #16] - 80037ee: 68fb ldr r3, [r7, #12] - 80037f0: 681b ldr r3, [r3, #0] - 80037f2: 430a orrs r2, r1 - 80037f4: 619a str r2, [r3, #24] + 80038ac: 68fb ldr r3, [r7, #12] + 80038ae: 681b ldr r3, [r3, #0] + 80038b0: 6999 ldr r1, [r3, #24] + 80038b2: 68bb ldr r3, [r7, #8] + 80038b4: 691a ldr r2, [r3, #16] + 80038b6: 68fb ldr r3, [r7, #12] + 80038b8: 681b ldr r3, [r3, #0] + 80038ba: 430a orrs r2, r1 + 80038bc: 619a str r2, [r3, #24] break; - 80037f6: e0a3 b.n 8003940 + 80038be: e0a3 b.n 8003a08 { /* Check the parameters */ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); /* Configure the Channel 2 in PWM mode */ TIM_OC2_SetConfig(htim->Instance, sConfig); - 80037f8: 68fb ldr r3, [r7, #12] - 80037fa: 681b ldr r3, [r3, #0] - 80037fc: 68b9 ldr r1, [r7, #8] - 80037fe: 4618 mov r0, r3 - 8003800: f000 faa0 bl 8003d44 + 80038c0: 68fb ldr r3, [r7, #12] + 80038c2: 681b ldr r3, [r3, #0] + 80038c4: 68b9 ldr r1, [r7, #8] + 80038c6: 4618 mov r0, r3 + 80038c8: f000 faa0 bl 8003e0c /* Set the Preload enable bit for channel2 */ htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; - 8003804: 68fb ldr r3, [r7, #12] - 8003806: 681b ldr r3, [r3, #0] - 8003808: 699a ldr r2, [r3, #24] - 800380a: 68fb ldr r3, [r7, #12] - 800380c: 681b ldr r3, [r3, #0] - 800380e: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003812: 619a str r2, [r3, #24] + 80038cc: 68fb ldr r3, [r7, #12] + 80038ce: 681b ldr r3, [r3, #0] + 80038d0: 699a ldr r2, [r3, #24] + 80038d2: 68fb ldr r3, [r7, #12] + 80038d4: 681b ldr r3, [r3, #0] + 80038d6: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 80038da: 619a str r2, [r3, #24] /* Configure the Output Fast mode */ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; - 8003814: 68fb ldr r3, [r7, #12] - 8003816: 681b ldr r3, [r3, #0] - 8003818: 699a ldr r2, [r3, #24] - 800381a: 68fb ldr r3, [r7, #12] - 800381c: 681b ldr r3, [r3, #0] - 800381e: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 8003822: 619a str r2, [r3, #24] + 80038dc: 68fb ldr r3, [r7, #12] + 80038de: 681b ldr r3, [r3, #0] + 80038e0: 699a ldr r2, [r3, #24] + 80038e2: 68fb ldr r3, [r7, #12] + 80038e4: 681b ldr r3, [r3, #0] + 80038e6: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 80038ea: 619a str r2, [r3, #24] htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; - 8003824: 68fb ldr r3, [r7, #12] - 8003826: 681b ldr r3, [r3, #0] - 8003828: 6999 ldr r1, [r3, #24] - 800382a: 68bb ldr r3, [r7, #8] - 800382c: 691b ldr r3, [r3, #16] - 800382e: 021a lsls r2, r3, #8 - 8003830: 68fb ldr r3, [r7, #12] - 8003832: 681b ldr r3, [r3, #0] - 8003834: 430a orrs r2, r1 - 8003836: 619a str r2, [r3, #24] + 80038ec: 68fb ldr r3, [r7, #12] + 80038ee: 681b ldr r3, [r3, #0] + 80038f0: 6999 ldr r1, [r3, #24] + 80038f2: 68bb ldr r3, [r7, #8] + 80038f4: 691b ldr r3, [r3, #16] + 80038f6: 021a lsls r2, r3, #8 + 80038f8: 68fb ldr r3, [r7, #12] + 80038fa: 681b ldr r3, [r3, #0] + 80038fc: 430a orrs r2, r1 + 80038fe: 619a str r2, [r3, #24] break; - 8003838: e082 b.n 8003940 + 8003900: e082 b.n 8003a08 { /* Check the parameters */ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); /* Configure the Channel 3 in PWM mode */ TIM_OC3_SetConfig(htim->Instance, sConfig); - 800383a: 68fb ldr r3, [r7, #12] - 800383c: 681b ldr r3, [r3, #0] - 800383e: 68b9 ldr r1, [r7, #8] - 8003840: 4618 mov r0, r3 - 8003842: f000 faf7 bl 8003e34 + 8003902: 68fb ldr r3, [r7, #12] + 8003904: 681b ldr r3, [r3, #0] + 8003906: 68b9 ldr r1, [r7, #8] + 8003908: 4618 mov r0, r3 + 800390a: f000 faf7 bl 8003efc /* Set the Preload enable bit for channel3 */ htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; - 8003846: 68fb ldr r3, [r7, #12] - 8003848: 681b ldr r3, [r3, #0] - 800384a: 69da ldr r2, [r3, #28] - 800384c: 68fb ldr r3, [r7, #12] - 800384e: 681b ldr r3, [r3, #0] - 8003850: f042 0208 orr.w r2, r2, #8 - 8003854: 61da str r2, [r3, #28] + 800390e: 68fb ldr r3, [r7, #12] + 8003910: 681b ldr r3, [r3, #0] + 8003912: 69da ldr r2, [r3, #28] + 8003914: 68fb ldr r3, [r7, #12] + 8003916: 681b ldr r3, [r3, #0] + 8003918: f042 0208 orr.w r2, r2, #8 + 800391c: 61da str r2, [r3, #28] /* Configure the Output Fast mode */ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; - 8003856: 68fb ldr r3, [r7, #12] - 8003858: 681b ldr r3, [r3, #0] - 800385a: 69da ldr r2, [r3, #28] - 800385c: 68fb ldr r3, [r7, #12] - 800385e: 681b ldr r3, [r3, #0] - 8003860: f022 0204 bic.w r2, r2, #4 - 8003864: 61da str r2, [r3, #28] + 800391e: 68fb ldr r3, [r7, #12] + 8003920: 681b ldr r3, [r3, #0] + 8003922: 69da ldr r2, [r3, #28] + 8003924: 68fb ldr r3, [r7, #12] + 8003926: 681b ldr r3, [r3, #0] + 8003928: f022 0204 bic.w r2, r2, #4 + 800392c: 61da str r2, [r3, #28] htim->Instance->CCMR2 |= sConfig->OCFastMode; - 8003866: 68fb ldr r3, [r7, #12] - 8003868: 681b ldr r3, [r3, #0] - 800386a: 69d9 ldr r1, [r3, #28] - 800386c: 68bb ldr r3, [r7, #8] - 800386e: 691a ldr r2, [r3, #16] - 8003870: 68fb ldr r3, [r7, #12] - 8003872: 681b ldr r3, [r3, #0] - 8003874: 430a orrs r2, r1 - 8003876: 61da str r2, [r3, #28] + 800392e: 68fb ldr r3, [r7, #12] + 8003930: 681b ldr r3, [r3, #0] + 8003932: 69d9 ldr r1, [r3, #28] + 8003934: 68bb ldr r3, [r7, #8] + 8003936: 691a ldr r2, [r3, #16] + 8003938: 68fb ldr r3, [r7, #12] + 800393a: 681b ldr r3, [r3, #0] + 800393c: 430a orrs r2, r1 + 800393e: 61da str r2, [r3, #28] break; - 8003878: e062 b.n 8003940 + 8003940: e062 b.n 8003a08 { /* Check the parameters */ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); /* Configure the Channel 4 in PWM mode */ TIM_OC4_SetConfig(htim->Instance, sConfig); - 800387a: 68fb ldr r3, [r7, #12] - 800387c: 681b ldr r3, [r3, #0] - 800387e: 68b9 ldr r1, [r7, #8] - 8003880: 4618 mov r0, r3 - 8003882: f000 fb4d bl 8003f20 + 8003942: 68fb ldr r3, [r7, #12] + 8003944: 681b ldr r3, [r3, #0] + 8003946: 68b9 ldr r1, [r7, #8] + 8003948: 4618 mov r0, r3 + 800394a: f000 fb4d bl 8003fe8 /* Set the Preload enable bit for channel4 */ htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; - 8003886: 68fb ldr r3, [r7, #12] - 8003888: 681b ldr r3, [r3, #0] - 800388a: 69da ldr r2, [r3, #28] - 800388c: 68fb ldr r3, [r7, #12] - 800388e: 681b ldr r3, [r3, #0] - 8003890: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003894: 61da str r2, [r3, #28] + 800394e: 68fb ldr r3, [r7, #12] + 8003950: 681b ldr r3, [r3, #0] + 8003952: 69da ldr r2, [r3, #28] + 8003954: 68fb ldr r3, [r7, #12] + 8003956: 681b ldr r3, [r3, #0] + 8003958: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 800395c: 61da str r2, [r3, #28] /* Configure the Output Fast mode */ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; - 8003896: 68fb ldr r3, [r7, #12] - 8003898: 681b ldr r3, [r3, #0] - 800389a: 69da ldr r2, [r3, #28] - 800389c: 68fb ldr r3, [r7, #12] - 800389e: 681b ldr r3, [r3, #0] - 80038a0: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 80038a4: 61da str r2, [r3, #28] + 800395e: 68fb ldr r3, [r7, #12] + 8003960: 681b ldr r3, [r3, #0] + 8003962: 69da ldr r2, [r3, #28] + 8003964: 68fb ldr r3, [r7, #12] + 8003966: 681b ldr r3, [r3, #0] + 8003968: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 800396c: 61da str r2, [r3, #28] htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; - 80038a6: 68fb ldr r3, [r7, #12] - 80038a8: 681b ldr r3, [r3, #0] - 80038aa: 69d9 ldr r1, [r3, #28] - 80038ac: 68bb ldr r3, [r7, #8] - 80038ae: 691b ldr r3, [r3, #16] - 80038b0: 021a lsls r2, r3, #8 - 80038b2: 68fb ldr r3, [r7, #12] - 80038b4: 681b ldr r3, [r3, #0] - 80038b6: 430a orrs r2, r1 - 80038b8: 61da str r2, [r3, #28] + 800396e: 68fb ldr r3, [r7, #12] + 8003970: 681b ldr r3, [r3, #0] + 8003972: 69d9 ldr r1, [r3, #28] + 8003974: 68bb ldr r3, [r7, #8] + 8003976: 691b ldr r3, [r3, #16] + 8003978: 021a lsls r2, r3, #8 + 800397a: 68fb ldr r3, [r7, #12] + 800397c: 681b ldr r3, [r3, #0] + 800397e: 430a orrs r2, r1 + 8003980: 61da str r2, [r3, #28] break; - 80038ba: e041 b.n 8003940 + 8003982: e041 b.n 8003a08 { /* Check the parameters */ assert_param(IS_TIM_CC5_INSTANCE(htim->Instance)); /* Configure the Channel 5 in PWM mode */ TIM_OC5_SetConfig(htim->Instance, sConfig); - 80038bc: 68fb ldr r3, [r7, #12] - 80038be: 681b ldr r3, [r3, #0] - 80038c0: 68b9 ldr r1, [r7, #8] - 80038c2: 4618 mov r0, r3 - 80038c4: f000 fb84 bl 8003fd0 + 8003984: 68fb ldr r3, [r7, #12] + 8003986: 681b ldr r3, [r3, #0] + 8003988: 68b9 ldr r1, [r7, #8] + 800398a: 4618 mov r0, r3 + 800398c: f000 fb84 bl 8004098 /* Set the Preload enable bit for channel5*/ htim->Instance->CCMR3 |= TIM_CCMR3_OC5PE; - 80038c8: 68fb ldr r3, [r7, #12] - 80038ca: 681b ldr r3, [r3, #0] - 80038cc: 6d5a ldr r2, [r3, #84] ; 0x54 - 80038ce: 68fb ldr r3, [r7, #12] - 80038d0: 681b ldr r3, [r3, #0] - 80038d2: f042 0208 orr.w r2, r2, #8 - 80038d6: 655a str r2, [r3, #84] ; 0x54 + 8003990: 68fb ldr r3, [r7, #12] + 8003992: 681b ldr r3, [r3, #0] + 8003994: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003996: 68fb ldr r3, [r7, #12] + 8003998: 681b ldr r3, [r3, #0] + 800399a: f042 0208 orr.w r2, r2, #8 + 800399e: 655a str r2, [r3, #84] ; 0x54 /* Configure the Output Fast mode */ htim->Instance->CCMR3 &= ~TIM_CCMR3_OC5FE; - 80038d8: 68fb ldr r3, [r7, #12] - 80038da: 681b ldr r3, [r3, #0] - 80038dc: 6d5a ldr r2, [r3, #84] ; 0x54 - 80038de: 68fb ldr r3, [r7, #12] - 80038e0: 681b ldr r3, [r3, #0] - 80038e2: f022 0204 bic.w r2, r2, #4 - 80038e6: 655a str r2, [r3, #84] ; 0x54 + 80039a0: 68fb ldr r3, [r7, #12] + 80039a2: 681b ldr r3, [r3, #0] + 80039a4: 6d5a ldr r2, [r3, #84] ; 0x54 + 80039a6: 68fb ldr r3, [r7, #12] + 80039a8: 681b ldr r3, [r3, #0] + 80039aa: f022 0204 bic.w r2, r2, #4 + 80039ae: 655a str r2, [r3, #84] ; 0x54 htim->Instance->CCMR3 |= sConfig->OCFastMode; - 80038e8: 68fb ldr r3, [r7, #12] - 80038ea: 681b ldr r3, [r3, #0] - 80038ec: 6d59 ldr r1, [r3, #84] ; 0x54 - 80038ee: 68bb ldr r3, [r7, #8] - 80038f0: 691a ldr r2, [r3, #16] - 80038f2: 68fb ldr r3, [r7, #12] - 80038f4: 681b ldr r3, [r3, #0] - 80038f6: 430a orrs r2, r1 - 80038f8: 655a str r2, [r3, #84] ; 0x54 + 80039b0: 68fb ldr r3, [r7, #12] + 80039b2: 681b ldr r3, [r3, #0] + 80039b4: 6d59 ldr r1, [r3, #84] ; 0x54 + 80039b6: 68bb ldr r3, [r7, #8] + 80039b8: 691a ldr r2, [r3, #16] + 80039ba: 68fb ldr r3, [r7, #12] + 80039bc: 681b ldr r3, [r3, #0] + 80039be: 430a orrs r2, r1 + 80039c0: 655a str r2, [r3, #84] ; 0x54 break; - 80038fa: e021 b.n 8003940 + 80039c2: e021 b.n 8003a08 { /* Check the parameters */ assert_param(IS_TIM_CC6_INSTANCE(htim->Instance)); /* Configure the Channel 6 in PWM mode */ TIM_OC6_SetConfig(htim->Instance, sConfig); - 80038fc: 68fb ldr r3, [r7, #12] - 80038fe: 681b ldr r3, [r3, #0] - 8003900: 68b9 ldr r1, [r7, #8] - 8003902: 4618 mov r0, r3 - 8003904: f000 fbb6 bl 8004074 + 80039c4: 68fb ldr r3, [r7, #12] + 80039c6: 681b ldr r3, [r3, #0] + 80039c8: 68b9 ldr r1, [r7, #8] + 80039ca: 4618 mov r0, r3 + 80039cc: f000 fbb6 bl 800413c /* Set the Preload enable bit for channel6 */ htim->Instance->CCMR3 |= TIM_CCMR3_OC6PE; - 8003908: 68fb ldr r3, [r7, #12] - 800390a: 681b ldr r3, [r3, #0] - 800390c: 6d5a ldr r2, [r3, #84] ; 0x54 - 800390e: 68fb ldr r3, [r7, #12] - 8003910: 681b ldr r3, [r3, #0] - 8003912: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003916: 655a str r2, [r3, #84] ; 0x54 + 80039d0: 68fb ldr r3, [r7, #12] + 80039d2: 681b ldr r3, [r3, #0] + 80039d4: 6d5a ldr r2, [r3, #84] ; 0x54 + 80039d6: 68fb ldr r3, [r7, #12] + 80039d8: 681b ldr r3, [r3, #0] + 80039da: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 80039de: 655a str r2, [r3, #84] ; 0x54 /* Configure the Output Fast mode */ htim->Instance->CCMR3 &= ~TIM_CCMR3_OC6FE; - 8003918: 68fb ldr r3, [r7, #12] - 800391a: 681b ldr r3, [r3, #0] - 800391c: 6d5a ldr r2, [r3, #84] ; 0x54 - 800391e: 68fb ldr r3, [r7, #12] - 8003920: 681b ldr r3, [r3, #0] - 8003922: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 8003926: 655a str r2, [r3, #84] ; 0x54 + 80039e0: 68fb ldr r3, [r7, #12] + 80039e2: 681b ldr r3, [r3, #0] + 80039e4: 6d5a ldr r2, [r3, #84] ; 0x54 + 80039e6: 68fb ldr r3, [r7, #12] + 80039e8: 681b ldr r3, [r3, #0] + 80039ea: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 80039ee: 655a str r2, [r3, #84] ; 0x54 htim->Instance->CCMR3 |= sConfig->OCFastMode << 8U; - 8003928: 68fb ldr r3, [r7, #12] - 800392a: 681b ldr r3, [r3, #0] - 800392c: 6d59 ldr r1, [r3, #84] ; 0x54 - 800392e: 68bb ldr r3, [r7, #8] - 8003930: 691b ldr r3, [r3, #16] - 8003932: 021a lsls r2, r3, #8 - 8003934: 68fb ldr r3, [r7, #12] - 8003936: 681b ldr r3, [r3, #0] - 8003938: 430a orrs r2, r1 - 800393a: 655a str r2, [r3, #84] ; 0x54 + 80039f0: 68fb ldr r3, [r7, #12] + 80039f2: 681b ldr r3, [r3, #0] + 80039f4: 6d59 ldr r1, [r3, #84] ; 0x54 + 80039f6: 68bb ldr r3, [r7, #8] + 80039f8: 691b ldr r3, [r3, #16] + 80039fa: 021a lsls r2, r3, #8 + 80039fc: 68fb ldr r3, [r7, #12] + 80039fe: 681b ldr r3, [r3, #0] + 8003a00: 430a orrs r2, r1 + 8003a02: 655a str r2, [r3, #84] ; 0x54 break; - 800393c: e000 b.n 8003940 + 8003a04: e000 b.n 8003a08 } default: break; - 800393e: bf00 nop + 8003a06: bf00 nop } htim->State = HAL_TIM_STATE_READY; - 8003940: 68fb ldr r3, [r7, #12] - 8003942: 2201 movs r2, #1 - 8003944: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003a08: 68fb ldr r3, [r7, #12] + 8003a0a: 2201 movs r2, #1 + 8003a0c: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 8003948: 68fb ldr r3, [r7, #12] - 800394a: 2200 movs r2, #0 - 800394c: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003a10: 68fb ldr r3, [r7, #12] + 8003a12: 2200 movs r2, #0 + 8003a14: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 8003950: 2300 movs r3, #0 + 8003a18: 2300 movs r3, #0 } - 8003952: 4618 mov r0, r3 - 8003954: 3710 adds r7, #16 - 8003956: 46bd mov sp, r7 - 8003958: bd80 pop {r7, pc} - 800395a: bf00 nop + 8003a1a: 4618 mov r0, r3 + 8003a1c: 3710 adds r7, #16 + 8003a1e: 46bd mov sp, r7 + 8003a20: bd80 pop {r7, pc} + 8003a22: bf00 nop -0800395c : +08003a24 : * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that * contains the clock source information for the TIM peripheral. * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig) { - 800395c: b580 push {r7, lr} - 800395e: b084 sub sp, #16 - 8003960: af00 add r7, sp, #0 - 8003962: 6078 str r0, [r7, #4] - 8003964: 6039 str r1, [r7, #0] + 8003a24: b580 push {r7, lr} + 8003a26: b084 sub sp, #16 + 8003a28: af00 add r7, sp, #0 + 8003a2a: 6078 str r0, [r7, #4] + 8003a2c: 6039 str r1, [r7, #0] uint32_t tmpsmcr; /* Process Locked */ __HAL_LOCK(htim); - 8003966: 687b ldr r3, [r7, #4] - 8003968: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 800396c: 2b01 cmp r3, #1 - 800396e: d101 bne.n 8003974 - 8003970: 2302 movs r3, #2 - 8003972: e0a6 b.n 8003ac2 - 8003974: 687b ldr r3, [r7, #4] - 8003976: 2201 movs r2, #1 - 8003978: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003a2e: 687b ldr r3, [r7, #4] + 8003a30: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8003a34: 2b01 cmp r3, #1 + 8003a36: d101 bne.n 8003a3c + 8003a38: 2302 movs r3, #2 + 8003a3a: e0a6 b.n 8003b8a + 8003a3c: 687b ldr r3, [r7, #4] + 8003a3e: 2201 movs r2, #1 + 8003a40: f883 203c strb.w r2, [r3, #60] ; 0x3c htim->State = HAL_TIM_STATE_BUSY; - 800397c: 687b ldr r3, [r7, #4] - 800397e: 2202 movs r2, #2 - 8003980: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003a44: 687b ldr r3, [r7, #4] + 8003a46: 2202 movs r2, #2 + 8003a48: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Check the parameters */ assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource)); /* Reset the SMS, TS, ECE, ETPS and ETRF bits */ tmpsmcr = htim->Instance->SMCR; - 8003984: 687b ldr r3, [r7, #4] - 8003986: 681b ldr r3, [r3, #0] - 8003988: 689b ldr r3, [r3, #8] - 800398a: 60fb str r3, [r7, #12] + 8003a4c: 687b ldr r3, [r7, #4] + 8003a4e: 681b ldr r3, [r3, #0] + 8003a50: 689b ldr r3, [r3, #8] + 8003a52: 60fb str r3, [r7, #12] tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); - 800398c: 68fa ldr r2, [r7, #12] - 800398e: 4b4f ldr r3, [pc, #316] ; (8003acc ) - 8003990: 4013 ands r3, r2 - 8003992: 60fb str r3, [r7, #12] + 8003a54: 68fa ldr r2, [r7, #12] + 8003a56: 4b4f ldr r3, [pc, #316] ; (8003b94 ) + 8003a58: 4013 ands r3, r2 + 8003a5a: 60fb str r3, [r7, #12] tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - 8003994: 68fb ldr r3, [r7, #12] - 8003996: f423 437f bic.w r3, r3, #65280 ; 0xff00 - 800399a: 60fb str r3, [r7, #12] + 8003a5c: 68fb ldr r3, [r7, #12] + 8003a5e: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 8003a62: 60fb str r3, [r7, #12] htim->Instance->SMCR = tmpsmcr; - 800399c: 687b ldr r3, [r7, #4] - 800399e: 681b ldr r3, [r3, #0] - 80039a0: 68fa ldr r2, [r7, #12] - 80039a2: 609a str r2, [r3, #8] + 8003a64: 687b ldr r3, [r7, #4] + 8003a66: 681b ldr r3, [r3, #0] + 8003a68: 68fa ldr r2, [r7, #12] + 8003a6a: 609a str r2, [r3, #8] switch (sClockSourceConfig->ClockSource) - 80039a4: 683b ldr r3, [r7, #0] - 80039a6: 681b ldr r3, [r3, #0] - 80039a8: 2b40 cmp r3, #64 ; 0x40 - 80039aa: d067 beq.n 8003a7c - 80039ac: 2b40 cmp r3, #64 ; 0x40 - 80039ae: d80b bhi.n 80039c8 - 80039b0: 2b10 cmp r3, #16 - 80039b2: d073 beq.n 8003a9c - 80039b4: 2b10 cmp r3, #16 - 80039b6: d802 bhi.n 80039be - 80039b8: 2b00 cmp r3, #0 - 80039ba: d06f beq.n 8003a9c + 8003a6c: 683b ldr r3, [r7, #0] + 8003a6e: 681b ldr r3, [r3, #0] + 8003a70: 2b40 cmp r3, #64 ; 0x40 + 8003a72: d067 beq.n 8003b44 + 8003a74: 2b40 cmp r3, #64 ; 0x40 + 8003a76: d80b bhi.n 8003a90 + 8003a78: 2b10 cmp r3, #16 + 8003a7a: d073 beq.n 8003b64 + 8003a7c: 2b10 cmp r3, #16 + 8003a7e: d802 bhi.n 8003a86 + 8003a80: 2b00 cmp r3, #0 + 8003a82: d06f beq.n 8003b64 TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); break; } default: break; - 80039bc: e078 b.n 8003ab0 + 8003a84: e078 b.n 8003b78 switch (sClockSourceConfig->ClockSource) - 80039be: 2b20 cmp r3, #32 - 80039c0: d06c beq.n 8003a9c - 80039c2: 2b30 cmp r3, #48 ; 0x30 - 80039c4: d06a beq.n 8003a9c + 8003a86: 2b20 cmp r3, #32 + 8003a88: d06c beq.n 8003b64 + 8003a8a: 2b30 cmp r3, #48 ; 0x30 + 8003a8c: d06a beq.n 8003b64 break; - 80039c6: e073 b.n 8003ab0 + 8003a8e: e073 b.n 8003b78 switch (sClockSourceConfig->ClockSource) - 80039c8: 2b70 cmp r3, #112 ; 0x70 - 80039ca: d00d beq.n 80039e8 - 80039cc: 2b70 cmp r3, #112 ; 0x70 - 80039ce: d804 bhi.n 80039da - 80039d0: 2b50 cmp r3, #80 ; 0x50 - 80039d2: d033 beq.n 8003a3c - 80039d4: 2b60 cmp r3, #96 ; 0x60 - 80039d6: d041 beq.n 8003a5c + 8003a90: 2b70 cmp r3, #112 ; 0x70 + 8003a92: d00d beq.n 8003ab0 + 8003a94: 2b70 cmp r3, #112 ; 0x70 + 8003a96: d804 bhi.n 8003aa2 + 8003a98: 2b50 cmp r3, #80 ; 0x50 + 8003a9a: d033 beq.n 8003b04 + 8003a9c: 2b60 cmp r3, #96 ; 0x60 + 8003a9e: d041 beq.n 8003b24 break; - 80039d8: e06a b.n 8003ab0 + 8003aa0: e06a b.n 8003b78 switch (sClockSourceConfig->ClockSource) - 80039da: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 80039de: d066 beq.n 8003aae - 80039e0: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 80039e4: d017 beq.n 8003a16 + 8003aa2: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8003aa6: d066 beq.n 8003b76 + 8003aa8: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8003aac: d017 beq.n 8003ade break; - 80039e6: e063 b.n 8003ab0 + 8003aae: e063 b.n 8003b78 TIM_ETR_SetConfig(htim->Instance, - 80039e8: 687b ldr r3, [r7, #4] - 80039ea: 6818 ldr r0, [r3, #0] - 80039ec: 683b ldr r3, [r7, #0] - 80039ee: 6899 ldr r1, [r3, #8] - 80039f0: 683b ldr r3, [r7, #0] - 80039f2: 685a ldr r2, [r3, #4] - 80039f4: 683b ldr r3, [r7, #0] - 80039f6: 68db ldr r3, [r3, #12] - 80039f8: f000 fc0a bl 8004210 + 8003ab0: 687b ldr r3, [r7, #4] + 8003ab2: 6818 ldr r0, [r3, #0] + 8003ab4: 683b ldr r3, [r7, #0] + 8003ab6: 6899 ldr r1, [r3, #8] + 8003ab8: 683b ldr r3, [r7, #0] + 8003aba: 685a ldr r2, [r3, #4] + 8003abc: 683b ldr r3, [r7, #0] + 8003abe: 68db ldr r3, [r3, #12] + 8003ac0: f000 fc0a bl 80042d8 tmpsmcr = htim->Instance->SMCR; - 80039fc: 687b ldr r3, [r7, #4] - 80039fe: 681b ldr r3, [r3, #0] - 8003a00: 689b ldr r3, [r3, #8] - 8003a02: 60fb str r3, [r7, #12] + 8003ac4: 687b ldr r3, [r7, #4] + 8003ac6: 681b ldr r3, [r3, #0] + 8003ac8: 689b ldr r3, [r3, #8] + 8003aca: 60fb str r3, [r7, #12] tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); - 8003a04: 68fb ldr r3, [r7, #12] - 8003a06: f043 0377 orr.w r3, r3, #119 ; 0x77 - 8003a0a: 60fb str r3, [r7, #12] + 8003acc: 68fb ldr r3, [r7, #12] + 8003ace: f043 0377 orr.w r3, r3, #119 ; 0x77 + 8003ad2: 60fb str r3, [r7, #12] htim->Instance->SMCR = tmpsmcr; - 8003a0c: 687b ldr r3, [r7, #4] - 8003a0e: 681b ldr r3, [r3, #0] - 8003a10: 68fa ldr r2, [r7, #12] - 8003a12: 609a str r2, [r3, #8] + 8003ad4: 687b ldr r3, [r7, #4] + 8003ad6: 681b ldr r3, [r3, #0] + 8003ad8: 68fa ldr r2, [r7, #12] + 8003ada: 609a str r2, [r3, #8] break; - 8003a14: e04c b.n 8003ab0 + 8003adc: e04c b.n 8003b78 TIM_ETR_SetConfig(htim->Instance, - 8003a16: 687b ldr r3, [r7, #4] - 8003a18: 6818 ldr r0, [r3, #0] - 8003a1a: 683b ldr r3, [r7, #0] - 8003a1c: 6899 ldr r1, [r3, #8] - 8003a1e: 683b ldr r3, [r7, #0] - 8003a20: 685a ldr r2, [r3, #4] - 8003a22: 683b ldr r3, [r7, #0] - 8003a24: 68db ldr r3, [r3, #12] - 8003a26: f000 fbf3 bl 8004210 + 8003ade: 687b ldr r3, [r7, #4] + 8003ae0: 6818 ldr r0, [r3, #0] + 8003ae2: 683b ldr r3, [r7, #0] + 8003ae4: 6899 ldr r1, [r3, #8] + 8003ae6: 683b ldr r3, [r7, #0] + 8003ae8: 685a ldr r2, [r3, #4] + 8003aea: 683b ldr r3, [r7, #0] + 8003aec: 68db ldr r3, [r3, #12] + 8003aee: f000 fbf3 bl 80042d8 htim->Instance->SMCR |= TIM_SMCR_ECE; - 8003a2a: 687b ldr r3, [r7, #4] - 8003a2c: 681b ldr r3, [r3, #0] - 8003a2e: 689a ldr r2, [r3, #8] - 8003a30: 687b ldr r3, [r7, #4] - 8003a32: 681b ldr r3, [r3, #0] - 8003a34: f442 4280 orr.w r2, r2, #16384 ; 0x4000 - 8003a38: 609a str r2, [r3, #8] + 8003af2: 687b ldr r3, [r7, #4] + 8003af4: 681b ldr r3, [r3, #0] + 8003af6: 689a ldr r2, [r3, #8] + 8003af8: 687b ldr r3, [r7, #4] + 8003afa: 681b ldr r3, [r3, #0] + 8003afc: f442 4280 orr.w r2, r2, #16384 ; 0x4000 + 8003b00: 609a str r2, [r3, #8] break; - 8003a3a: e039 b.n 8003ab0 + 8003b02: e039 b.n 8003b78 TIM_TI1_ConfigInputStage(htim->Instance, - 8003a3c: 687b ldr r3, [r7, #4] - 8003a3e: 6818 ldr r0, [r3, #0] - 8003a40: 683b ldr r3, [r7, #0] - 8003a42: 6859 ldr r1, [r3, #4] - 8003a44: 683b ldr r3, [r7, #0] - 8003a46: 68db ldr r3, [r3, #12] - 8003a48: 461a mov r2, r3 - 8003a4a: f000 fb67 bl 800411c + 8003b04: 687b ldr r3, [r7, #4] + 8003b06: 6818 ldr r0, [r3, #0] + 8003b08: 683b ldr r3, [r7, #0] + 8003b0a: 6859 ldr r1, [r3, #4] + 8003b0c: 683b ldr r3, [r7, #0] + 8003b0e: 68db ldr r3, [r3, #12] + 8003b10: 461a mov r2, r3 + 8003b12: f000 fb67 bl 80041e4 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); - 8003a4e: 687b ldr r3, [r7, #4] - 8003a50: 681b ldr r3, [r3, #0] - 8003a52: 2150 movs r1, #80 ; 0x50 - 8003a54: 4618 mov r0, r3 - 8003a56: f000 fbc0 bl 80041da + 8003b16: 687b ldr r3, [r7, #4] + 8003b18: 681b ldr r3, [r3, #0] + 8003b1a: 2150 movs r1, #80 ; 0x50 + 8003b1c: 4618 mov r0, r3 + 8003b1e: f000 fbc0 bl 80042a2 break; - 8003a5a: e029 b.n 8003ab0 + 8003b22: e029 b.n 8003b78 TIM_TI2_ConfigInputStage(htim->Instance, - 8003a5c: 687b ldr r3, [r7, #4] - 8003a5e: 6818 ldr r0, [r3, #0] - 8003a60: 683b ldr r3, [r7, #0] - 8003a62: 6859 ldr r1, [r3, #4] - 8003a64: 683b ldr r3, [r7, #0] - 8003a66: 68db ldr r3, [r3, #12] - 8003a68: 461a mov r2, r3 - 8003a6a: f000 fb86 bl 800417a + 8003b24: 687b ldr r3, [r7, #4] + 8003b26: 6818 ldr r0, [r3, #0] + 8003b28: 683b ldr r3, [r7, #0] + 8003b2a: 6859 ldr r1, [r3, #4] + 8003b2c: 683b ldr r3, [r7, #0] + 8003b2e: 68db ldr r3, [r3, #12] + 8003b30: 461a mov r2, r3 + 8003b32: f000 fb86 bl 8004242 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); - 8003a6e: 687b ldr r3, [r7, #4] - 8003a70: 681b ldr r3, [r3, #0] - 8003a72: 2160 movs r1, #96 ; 0x60 - 8003a74: 4618 mov r0, r3 - 8003a76: f000 fbb0 bl 80041da + 8003b36: 687b ldr r3, [r7, #4] + 8003b38: 681b ldr r3, [r3, #0] + 8003b3a: 2160 movs r1, #96 ; 0x60 + 8003b3c: 4618 mov r0, r3 + 8003b3e: f000 fbb0 bl 80042a2 break; - 8003a7a: e019 b.n 8003ab0 + 8003b42: e019 b.n 8003b78 TIM_TI1_ConfigInputStage(htim->Instance, - 8003a7c: 687b ldr r3, [r7, #4] - 8003a7e: 6818 ldr r0, [r3, #0] - 8003a80: 683b ldr r3, [r7, #0] - 8003a82: 6859 ldr r1, [r3, #4] - 8003a84: 683b ldr r3, [r7, #0] - 8003a86: 68db ldr r3, [r3, #12] - 8003a88: 461a mov r2, r3 - 8003a8a: f000 fb47 bl 800411c + 8003b44: 687b ldr r3, [r7, #4] + 8003b46: 6818 ldr r0, [r3, #0] + 8003b48: 683b ldr r3, [r7, #0] + 8003b4a: 6859 ldr r1, [r3, #4] + 8003b4c: 683b ldr r3, [r7, #0] + 8003b4e: 68db ldr r3, [r3, #12] + 8003b50: 461a mov r2, r3 + 8003b52: f000 fb47 bl 80041e4 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); - 8003a8e: 687b ldr r3, [r7, #4] - 8003a90: 681b ldr r3, [r3, #0] - 8003a92: 2140 movs r1, #64 ; 0x40 - 8003a94: 4618 mov r0, r3 - 8003a96: f000 fba0 bl 80041da + 8003b56: 687b ldr r3, [r7, #4] + 8003b58: 681b ldr r3, [r3, #0] + 8003b5a: 2140 movs r1, #64 ; 0x40 + 8003b5c: 4618 mov r0, r3 + 8003b5e: f000 fba0 bl 80042a2 break; - 8003a9a: e009 b.n 8003ab0 + 8003b62: e009 b.n 8003b78 TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); - 8003a9c: 687b ldr r3, [r7, #4] - 8003a9e: 681a ldr r2, [r3, #0] - 8003aa0: 683b ldr r3, [r7, #0] - 8003aa2: 681b ldr r3, [r3, #0] - 8003aa4: 4619 mov r1, r3 - 8003aa6: 4610 mov r0, r2 - 8003aa8: f000 fb97 bl 80041da + 8003b64: 687b ldr r3, [r7, #4] + 8003b66: 681a ldr r2, [r3, #0] + 8003b68: 683b ldr r3, [r7, #0] + 8003b6a: 681b ldr r3, [r3, #0] + 8003b6c: 4619 mov r1, r3 + 8003b6e: 4610 mov r0, r2 + 8003b70: f000 fb97 bl 80042a2 break; - 8003aac: e000 b.n 8003ab0 + 8003b74: e000 b.n 8003b78 break; - 8003aae: bf00 nop + 8003b76: bf00 nop } htim->State = HAL_TIM_STATE_READY; - 8003ab0: 687b ldr r3, [r7, #4] - 8003ab2: 2201 movs r2, #1 - 8003ab4: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003b78: 687b ldr r3, [r7, #4] + 8003b7a: 2201 movs r2, #1 + 8003b7c: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 8003ab8: 687b ldr r3, [r7, #4] - 8003aba: 2200 movs r2, #0 - 8003abc: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003b80: 687b ldr r3, [r7, #4] + 8003b82: 2200 movs r2, #0 + 8003b84: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 8003ac0: 2300 movs r3, #0 + 8003b88: 2300 movs r3, #0 } - 8003ac2: 4618 mov r0, r3 - 8003ac4: 3710 adds r7, #16 - 8003ac6: 46bd mov sp, r7 - 8003ac8: bd80 pop {r7, pc} - 8003aca: bf00 nop - 8003acc: fffeff88 .word 0xfffeff88 - -08003ad0 : + 8003b8a: 4618 mov r0, r3 + 8003b8c: 3710 adds r7, #16 + 8003b8e: 46bd mov sp, r7 + 8003b90: bd80 pop {r7, pc} + 8003b92: bf00 nop + 8003b94: fffeff88 .word 0xfffeff88 + +08003b98 : * @brief Output Compare callback in non-blocking mode * @param htim TIM OC handle * @retval None */ __weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) { - 8003ad0: b480 push {r7} - 8003ad2: b083 sub sp, #12 - 8003ad4: af00 add r7, sp, #0 - 8003ad6: 6078 str r0, [r7, #4] + 8003b98: b480 push {r7} + 8003b9a: b083 sub sp, #12 + 8003b9c: af00 add r7, sp, #0 + 8003b9e: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file */ } - 8003ad8: bf00 nop - 8003ada: 370c adds r7, #12 - 8003adc: 46bd mov sp, r7 - 8003ade: f85d 7b04 ldr.w r7, [sp], #4 - 8003ae2: 4770 bx lr + 8003ba0: bf00 nop + 8003ba2: 370c adds r7, #12 + 8003ba4: 46bd mov sp, r7 + 8003ba6: f85d 7b04 ldr.w r7, [sp], #4 + 8003baa: 4770 bx lr -08003ae4 : +08003bac : * @brief Input Capture callback in non-blocking mode * @param htim TIM IC handle * @retval None */ __weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) { - 8003ae4: b480 push {r7} - 8003ae6: b083 sub sp, #12 - 8003ae8: af00 add r7, sp, #0 - 8003aea: 6078 str r0, [r7, #4] + 8003bac: b480 push {r7} + 8003bae: b083 sub sp, #12 + 8003bb0: af00 add r7, sp, #0 + 8003bb2: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIM_IC_CaptureCallback could be implemented in the user file */ } - 8003aec: bf00 nop - 8003aee: 370c adds r7, #12 - 8003af0: 46bd mov sp, r7 - 8003af2: f85d 7b04 ldr.w r7, [sp], #4 - 8003af6: 4770 bx lr + 8003bb4: bf00 nop + 8003bb6: 370c adds r7, #12 + 8003bb8: 46bd mov sp, r7 + 8003bba: f85d 7b04 ldr.w r7, [sp], #4 + 8003bbe: 4770 bx lr -08003af8 : +08003bc0 : * @brief PWM Pulse finished callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) { - 8003af8: b480 push {r7} - 8003afa: b083 sub sp, #12 - 8003afc: af00 add r7, sp, #0 - 8003afe: 6078 str r0, [r7, #4] + 8003bc0: b480 push {r7} + 8003bc2: b083 sub sp, #12 + 8003bc4: af00 add r7, sp, #0 + 8003bc6: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file */ } - 8003b00: bf00 nop - 8003b02: 370c adds r7, #12 - 8003b04: 46bd mov sp, r7 - 8003b06: f85d 7b04 ldr.w r7, [sp], #4 - 8003b0a: 4770 bx lr + 8003bc8: bf00 nop + 8003bca: 370c adds r7, #12 + 8003bcc: 46bd mov sp, r7 + 8003bce: f85d 7b04 ldr.w r7, [sp], #4 + 8003bd2: 4770 bx lr -08003b0c : +08003bd4 : * @brief Hall Trigger detection callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) { - 8003b0c: b480 push {r7} - 8003b0e: b083 sub sp, #12 - 8003b10: af00 add r7, sp, #0 - 8003b12: 6078 str r0, [r7, #4] + 8003bd4: b480 push {r7} + 8003bd6: b083 sub sp, #12 + 8003bd8: af00 add r7, sp, #0 + 8003bda: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIM_TriggerCallback could be implemented in the user file */ } - 8003b14: bf00 nop - 8003b16: 370c adds r7, #12 - 8003b18: 46bd mov sp, r7 - 8003b1a: f85d 7b04 ldr.w r7, [sp], #4 - 8003b1e: 4770 bx lr + 8003bdc: bf00 nop + 8003bde: 370c adds r7, #12 + 8003be0: 46bd mov sp, r7 + 8003be2: f85d 7b04 ldr.w r7, [sp], #4 + 8003be6: 4770 bx lr -08003b20 : +08003be8 : * @param TIMx TIM peripheral * @param Structure TIM Base configuration structure * @retval None */ void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) { - 8003b20: b480 push {r7} - 8003b22: b085 sub sp, #20 - 8003b24: af00 add r7, sp, #0 - 8003b26: 6078 str r0, [r7, #4] - 8003b28: 6039 str r1, [r7, #0] + 8003be8: b480 push {r7} + 8003bea: b085 sub sp, #20 + 8003bec: af00 add r7, sp, #0 + 8003bee: 6078 str r0, [r7, #4] + 8003bf0: 6039 str r1, [r7, #0] uint32_t tmpcr1; tmpcr1 = TIMx->CR1; - 8003b2a: 687b ldr r3, [r7, #4] - 8003b2c: 681b ldr r3, [r3, #0] - 8003b2e: 60fb str r3, [r7, #12] + 8003bf2: 687b ldr r3, [r7, #4] + 8003bf4: 681b ldr r3, [r3, #0] + 8003bf6: 60fb str r3, [r7, #12] /* Set TIM Time Base Unit parameters ---------------------------------------*/ if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) - 8003b30: 687b ldr r3, [r7, #4] - 8003b32: 4a40 ldr r2, [pc, #256] ; (8003c34 ) - 8003b34: 4293 cmp r3, r2 - 8003b36: d013 beq.n 8003b60 - 8003b38: 687b ldr r3, [r7, #4] - 8003b3a: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 8003b3e: d00f beq.n 8003b60 - 8003b40: 687b ldr r3, [r7, #4] - 8003b42: 4a3d ldr r2, [pc, #244] ; (8003c38 ) - 8003b44: 4293 cmp r3, r2 - 8003b46: d00b beq.n 8003b60 - 8003b48: 687b ldr r3, [r7, #4] - 8003b4a: 4a3c ldr r2, [pc, #240] ; (8003c3c ) - 8003b4c: 4293 cmp r3, r2 - 8003b4e: d007 beq.n 8003b60 - 8003b50: 687b ldr r3, [r7, #4] - 8003b52: 4a3b ldr r2, [pc, #236] ; (8003c40 ) - 8003b54: 4293 cmp r3, r2 - 8003b56: d003 beq.n 8003b60 - 8003b58: 687b ldr r3, [r7, #4] - 8003b5a: 4a3a ldr r2, [pc, #232] ; (8003c44 ) - 8003b5c: 4293 cmp r3, r2 - 8003b5e: d108 bne.n 8003b72 + 8003bf8: 687b ldr r3, [r7, #4] + 8003bfa: 4a40 ldr r2, [pc, #256] ; (8003cfc ) + 8003bfc: 4293 cmp r3, r2 + 8003bfe: d013 beq.n 8003c28 + 8003c00: 687b ldr r3, [r7, #4] + 8003c02: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003c06: d00f beq.n 8003c28 + 8003c08: 687b ldr r3, [r7, #4] + 8003c0a: 4a3d ldr r2, [pc, #244] ; (8003d00 ) + 8003c0c: 4293 cmp r3, r2 + 8003c0e: d00b beq.n 8003c28 + 8003c10: 687b ldr r3, [r7, #4] + 8003c12: 4a3c ldr r2, [pc, #240] ; (8003d04 ) + 8003c14: 4293 cmp r3, r2 + 8003c16: d007 beq.n 8003c28 + 8003c18: 687b ldr r3, [r7, #4] + 8003c1a: 4a3b ldr r2, [pc, #236] ; (8003d08 ) + 8003c1c: 4293 cmp r3, r2 + 8003c1e: d003 beq.n 8003c28 + 8003c20: 687b ldr r3, [r7, #4] + 8003c22: 4a3a ldr r2, [pc, #232] ; (8003d0c ) + 8003c24: 4293 cmp r3, r2 + 8003c26: d108 bne.n 8003c3a { /* Select the Counter Mode */ tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); - 8003b60: 68fb ldr r3, [r7, #12] - 8003b62: f023 0370 bic.w r3, r3, #112 ; 0x70 - 8003b66: 60fb str r3, [r7, #12] + 8003c28: 68fb ldr r3, [r7, #12] + 8003c2a: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8003c2e: 60fb str r3, [r7, #12] tmpcr1 |= Structure->CounterMode; - 8003b68: 683b ldr r3, [r7, #0] - 8003b6a: 685b ldr r3, [r3, #4] - 8003b6c: 68fa ldr r2, [r7, #12] - 8003b6e: 4313 orrs r3, r2 - 8003b70: 60fb str r3, [r7, #12] + 8003c30: 683b ldr r3, [r7, #0] + 8003c32: 685b ldr r3, [r3, #4] + 8003c34: 68fa ldr r2, [r7, #12] + 8003c36: 4313 orrs r3, r2 + 8003c38: 60fb str r3, [r7, #12] } if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) - 8003b72: 687b ldr r3, [r7, #4] - 8003b74: 4a2f ldr r2, [pc, #188] ; (8003c34 ) - 8003b76: 4293 cmp r3, r2 - 8003b78: d02b beq.n 8003bd2 - 8003b7a: 687b ldr r3, [r7, #4] - 8003b7c: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 8003b80: d027 beq.n 8003bd2 - 8003b82: 687b ldr r3, [r7, #4] - 8003b84: 4a2c ldr r2, [pc, #176] ; (8003c38 ) - 8003b86: 4293 cmp r3, r2 - 8003b88: d023 beq.n 8003bd2 - 8003b8a: 687b ldr r3, [r7, #4] - 8003b8c: 4a2b ldr r2, [pc, #172] ; (8003c3c ) - 8003b8e: 4293 cmp r3, r2 - 8003b90: d01f beq.n 8003bd2 - 8003b92: 687b ldr r3, [r7, #4] - 8003b94: 4a2a ldr r2, [pc, #168] ; (8003c40 ) - 8003b96: 4293 cmp r3, r2 - 8003b98: d01b beq.n 8003bd2 - 8003b9a: 687b ldr r3, [r7, #4] - 8003b9c: 4a29 ldr r2, [pc, #164] ; (8003c44 ) - 8003b9e: 4293 cmp r3, r2 - 8003ba0: d017 beq.n 8003bd2 - 8003ba2: 687b ldr r3, [r7, #4] - 8003ba4: 4a28 ldr r2, [pc, #160] ; (8003c48 ) - 8003ba6: 4293 cmp r3, r2 - 8003ba8: d013 beq.n 8003bd2 - 8003baa: 687b ldr r3, [r7, #4] - 8003bac: 4a27 ldr r2, [pc, #156] ; (8003c4c ) - 8003bae: 4293 cmp r3, r2 - 8003bb0: d00f beq.n 8003bd2 - 8003bb2: 687b ldr r3, [r7, #4] - 8003bb4: 4a26 ldr r2, [pc, #152] ; (8003c50 ) - 8003bb6: 4293 cmp r3, r2 - 8003bb8: d00b beq.n 8003bd2 - 8003bba: 687b ldr r3, [r7, #4] - 8003bbc: 4a25 ldr r2, [pc, #148] ; (8003c54 ) - 8003bbe: 4293 cmp r3, r2 - 8003bc0: d007 beq.n 8003bd2 - 8003bc2: 687b ldr r3, [r7, #4] - 8003bc4: 4a24 ldr r2, [pc, #144] ; (8003c58 ) - 8003bc6: 4293 cmp r3, r2 - 8003bc8: d003 beq.n 8003bd2 - 8003bca: 687b ldr r3, [r7, #4] - 8003bcc: 4a23 ldr r2, [pc, #140] ; (8003c5c ) - 8003bce: 4293 cmp r3, r2 - 8003bd0: d108 bne.n 8003be4 + 8003c3a: 687b ldr r3, [r7, #4] + 8003c3c: 4a2f ldr r2, [pc, #188] ; (8003cfc ) + 8003c3e: 4293 cmp r3, r2 + 8003c40: d02b beq.n 8003c9a + 8003c42: 687b ldr r3, [r7, #4] + 8003c44: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003c48: d027 beq.n 8003c9a + 8003c4a: 687b ldr r3, [r7, #4] + 8003c4c: 4a2c ldr r2, [pc, #176] ; (8003d00 ) + 8003c4e: 4293 cmp r3, r2 + 8003c50: d023 beq.n 8003c9a + 8003c52: 687b ldr r3, [r7, #4] + 8003c54: 4a2b ldr r2, [pc, #172] ; (8003d04 ) + 8003c56: 4293 cmp r3, r2 + 8003c58: d01f beq.n 8003c9a + 8003c5a: 687b ldr r3, [r7, #4] + 8003c5c: 4a2a ldr r2, [pc, #168] ; (8003d08 ) + 8003c5e: 4293 cmp r3, r2 + 8003c60: d01b beq.n 8003c9a + 8003c62: 687b ldr r3, [r7, #4] + 8003c64: 4a29 ldr r2, [pc, #164] ; (8003d0c ) + 8003c66: 4293 cmp r3, r2 + 8003c68: d017 beq.n 8003c9a + 8003c6a: 687b ldr r3, [r7, #4] + 8003c6c: 4a28 ldr r2, [pc, #160] ; (8003d10 ) + 8003c6e: 4293 cmp r3, r2 + 8003c70: d013 beq.n 8003c9a + 8003c72: 687b ldr r3, [r7, #4] + 8003c74: 4a27 ldr r2, [pc, #156] ; (8003d14 ) + 8003c76: 4293 cmp r3, r2 + 8003c78: d00f beq.n 8003c9a + 8003c7a: 687b ldr r3, [r7, #4] + 8003c7c: 4a26 ldr r2, [pc, #152] ; (8003d18 ) + 8003c7e: 4293 cmp r3, r2 + 8003c80: d00b beq.n 8003c9a + 8003c82: 687b ldr r3, [r7, #4] + 8003c84: 4a25 ldr r2, [pc, #148] ; (8003d1c ) + 8003c86: 4293 cmp r3, r2 + 8003c88: d007 beq.n 8003c9a + 8003c8a: 687b ldr r3, [r7, #4] + 8003c8c: 4a24 ldr r2, [pc, #144] ; (8003d20 ) + 8003c8e: 4293 cmp r3, r2 + 8003c90: d003 beq.n 8003c9a + 8003c92: 687b ldr r3, [r7, #4] + 8003c94: 4a23 ldr r2, [pc, #140] ; (8003d24 ) + 8003c96: 4293 cmp r3, r2 + 8003c98: d108 bne.n 8003cac { /* Set the clock division */ tmpcr1 &= ~TIM_CR1_CKD; - 8003bd2: 68fb ldr r3, [r7, #12] - 8003bd4: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8003bd8: 60fb str r3, [r7, #12] + 8003c9a: 68fb ldr r3, [r7, #12] + 8003c9c: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003ca0: 60fb str r3, [r7, #12] tmpcr1 |= (uint32_t)Structure->ClockDivision; - 8003bda: 683b ldr r3, [r7, #0] - 8003bdc: 68db ldr r3, [r3, #12] - 8003bde: 68fa ldr r2, [r7, #12] - 8003be0: 4313 orrs r3, r2 - 8003be2: 60fb str r3, [r7, #12] + 8003ca2: 683b ldr r3, [r7, #0] + 8003ca4: 68db ldr r3, [r3, #12] + 8003ca6: 68fa ldr r2, [r7, #12] + 8003ca8: 4313 orrs r3, r2 + 8003caa: 60fb str r3, [r7, #12] } /* Set the auto-reload preload */ MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); - 8003be4: 68fb ldr r3, [r7, #12] - 8003be6: f023 0280 bic.w r2, r3, #128 ; 0x80 - 8003bea: 683b ldr r3, [r7, #0] - 8003bec: 695b ldr r3, [r3, #20] - 8003bee: 4313 orrs r3, r2 - 8003bf0: 60fb str r3, [r7, #12] + 8003cac: 68fb ldr r3, [r7, #12] + 8003cae: f023 0280 bic.w r2, r3, #128 ; 0x80 + 8003cb2: 683b ldr r3, [r7, #0] + 8003cb4: 695b ldr r3, [r3, #20] + 8003cb6: 4313 orrs r3, r2 + 8003cb8: 60fb str r3, [r7, #12] TIMx->CR1 = tmpcr1; - 8003bf2: 687b ldr r3, [r7, #4] - 8003bf4: 68fa ldr r2, [r7, #12] - 8003bf6: 601a str r2, [r3, #0] + 8003cba: 687b ldr r3, [r7, #4] + 8003cbc: 68fa ldr r2, [r7, #12] + 8003cbe: 601a str r2, [r3, #0] /* Set the Autoreload value */ TIMx->ARR = (uint32_t)Structure->Period ; - 8003bf8: 683b ldr r3, [r7, #0] - 8003bfa: 689a ldr r2, [r3, #8] - 8003bfc: 687b ldr r3, [r7, #4] - 8003bfe: 62da str r2, [r3, #44] ; 0x2c + 8003cc0: 683b ldr r3, [r7, #0] + 8003cc2: 689a ldr r2, [r3, #8] + 8003cc4: 687b ldr r3, [r7, #4] + 8003cc6: 62da str r2, [r3, #44] ; 0x2c /* Set the Prescaler value */ TIMx->PSC = Structure->Prescaler; - 8003c00: 683b ldr r3, [r7, #0] - 8003c02: 681a ldr r2, [r3, #0] - 8003c04: 687b ldr r3, [r7, #4] - 8003c06: 629a str r2, [r3, #40] ; 0x28 + 8003cc8: 683b ldr r3, [r7, #0] + 8003cca: 681a ldr r2, [r3, #0] + 8003ccc: 687b ldr r3, [r7, #4] + 8003cce: 629a str r2, [r3, #40] ; 0x28 if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) - 8003c08: 687b ldr r3, [r7, #4] - 8003c0a: 4a0a ldr r2, [pc, #40] ; (8003c34 ) - 8003c0c: 4293 cmp r3, r2 - 8003c0e: d003 beq.n 8003c18 - 8003c10: 687b ldr r3, [r7, #4] - 8003c12: 4a0c ldr r2, [pc, #48] ; (8003c44 ) - 8003c14: 4293 cmp r3, r2 - 8003c16: d103 bne.n 8003c20 + 8003cd0: 687b ldr r3, [r7, #4] + 8003cd2: 4a0a ldr r2, [pc, #40] ; (8003cfc ) + 8003cd4: 4293 cmp r3, r2 + 8003cd6: d003 beq.n 8003ce0 + 8003cd8: 687b ldr r3, [r7, #4] + 8003cda: 4a0c ldr r2, [pc, #48] ; (8003d0c ) + 8003cdc: 4293 cmp r3, r2 + 8003cde: d103 bne.n 8003ce8 { /* Set the Repetition Counter value */ TIMx->RCR = Structure->RepetitionCounter; - 8003c18: 683b ldr r3, [r7, #0] - 8003c1a: 691a ldr r2, [r3, #16] - 8003c1c: 687b ldr r3, [r7, #4] - 8003c1e: 631a str r2, [r3, #48] ; 0x30 + 8003ce0: 683b ldr r3, [r7, #0] + 8003ce2: 691a ldr r2, [r3, #16] + 8003ce4: 687b ldr r3, [r7, #4] + 8003ce6: 631a str r2, [r3, #48] ; 0x30 } /* Generate an update event to reload the Prescaler and the repetition counter (only for advanced timer) value immediately */ TIMx->EGR = TIM_EGR_UG; - 8003c20: 687b ldr r3, [r7, #4] - 8003c22: 2201 movs r2, #1 - 8003c24: 615a str r2, [r3, #20] + 8003ce8: 687b ldr r3, [r7, #4] + 8003cea: 2201 movs r2, #1 + 8003cec: 615a str r2, [r3, #20] } - 8003c26: bf00 nop - 8003c28: 3714 adds r7, #20 - 8003c2a: 46bd mov sp, r7 - 8003c2c: f85d 7b04 ldr.w r7, [sp], #4 - 8003c30: 4770 bx lr - 8003c32: bf00 nop - 8003c34: 40010000 .word 0x40010000 - 8003c38: 40000400 .word 0x40000400 - 8003c3c: 40000800 .word 0x40000800 - 8003c40: 40000c00 .word 0x40000c00 - 8003c44: 40010400 .word 0x40010400 - 8003c48: 40014000 .word 0x40014000 - 8003c4c: 40014400 .word 0x40014400 - 8003c50: 40014800 .word 0x40014800 - 8003c54: 40001800 .word 0x40001800 - 8003c58: 40001c00 .word 0x40001c00 - 8003c5c: 40002000 .word 0x40002000 - -08003c60 : + 8003cee: bf00 nop + 8003cf0: 3714 adds r7, #20 + 8003cf2: 46bd mov sp, r7 + 8003cf4: f85d 7b04 ldr.w r7, [sp], #4 + 8003cf8: 4770 bx lr + 8003cfa: bf00 nop + 8003cfc: 40010000 .word 0x40010000 + 8003d00: 40000400 .word 0x40000400 + 8003d04: 40000800 .word 0x40000800 + 8003d08: 40000c00 .word 0x40000c00 + 8003d0c: 40010400 .word 0x40010400 + 8003d10: 40014000 .word 0x40014000 + 8003d14: 40014400 .word 0x40014400 + 8003d18: 40014800 .word 0x40014800 + 8003d1c: 40001800 .word 0x40001800 + 8003d20: 40001c00 .word 0x40001c00 + 8003d24: 40002000 .word 0x40002000 + +08003d28 : * @param TIMx to select the TIM peripheral * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8003c60: b480 push {r7} - 8003c62: b087 sub sp, #28 - 8003c64: af00 add r7, sp, #0 - 8003c66: 6078 str r0, [r7, #4] - 8003c68: 6039 str r1, [r7, #0] + 8003d28: b480 push {r7} + 8003d2a: b087 sub sp, #28 + 8003d2c: af00 add r7, sp, #0 + 8003d2e: 6078 str r0, [r7, #4] + 8003d30: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the Channel 1: Reset the CC1E Bit */ TIMx->CCER &= ~TIM_CCER_CC1E; - 8003c6a: 687b ldr r3, [r7, #4] - 8003c6c: 6a1b ldr r3, [r3, #32] - 8003c6e: f023 0201 bic.w r2, r3, #1 - 8003c72: 687b ldr r3, [r7, #4] - 8003c74: 621a str r2, [r3, #32] + 8003d32: 687b ldr r3, [r7, #4] + 8003d34: 6a1b ldr r3, [r3, #32] + 8003d36: f023 0201 bic.w r2, r3, #1 + 8003d3a: 687b ldr r3, [r7, #4] + 8003d3c: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003c76: 687b ldr r3, [r7, #4] - 8003c78: 6a1b ldr r3, [r3, #32] - 8003c7a: 617b str r3, [r7, #20] + 8003d3e: 687b ldr r3, [r7, #4] + 8003d40: 6a1b ldr r3, [r3, #32] + 8003d42: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003c7c: 687b ldr r3, [r7, #4] - 8003c7e: 685b ldr r3, [r3, #4] - 8003c80: 613b str r3, [r7, #16] + 8003d44: 687b ldr r3, [r7, #4] + 8003d46: 685b ldr r3, [r3, #4] + 8003d48: 613b str r3, [r7, #16] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR1; - 8003c82: 687b ldr r3, [r7, #4] - 8003c84: 699b ldr r3, [r3, #24] - 8003c86: 60fb str r3, [r7, #12] + 8003d4a: 687b ldr r3, [r7, #4] + 8003d4c: 699b ldr r3, [r3, #24] + 8003d4e: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~TIM_CCMR1_OC1M; - 8003c88: 68fa ldr r2, [r7, #12] - 8003c8a: 4b2b ldr r3, [pc, #172] ; (8003d38 ) - 8003c8c: 4013 ands r3, r2 - 8003c8e: 60fb str r3, [r7, #12] + 8003d50: 68fa ldr r2, [r7, #12] + 8003d52: 4b2b ldr r3, [pc, #172] ; (8003e00 ) + 8003d54: 4013 ands r3, r2 + 8003d56: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR1_CC1S; - 8003c90: 68fb ldr r3, [r7, #12] - 8003c92: f023 0303 bic.w r3, r3, #3 - 8003c96: 60fb str r3, [r7, #12] + 8003d58: 68fb ldr r3, [r7, #12] + 8003d5a: f023 0303 bic.w r3, r3, #3 + 8003d5e: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8003c98: 683b ldr r3, [r7, #0] - 8003c9a: 681b ldr r3, [r3, #0] - 8003c9c: 68fa ldr r2, [r7, #12] - 8003c9e: 4313 orrs r3, r2 - 8003ca0: 60fb str r3, [r7, #12] + 8003d60: 683b ldr r3, [r7, #0] + 8003d62: 681b ldr r3, [r3, #0] + 8003d64: 68fa ldr r2, [r7, #12] + 8003d66: 4313 orrs r3, r2 + 8003d68: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC1P; - 8003ca2: 697b ldr r3, [r7, #20] - 8003ca4: f023 0302 bic.w r3, r3, #2 - 8003ca8: 617b str r3, [r7, #20] + 8003d6a: 697b ldr r3, [r7, #20] + 8003d6c: f023 0302 bic.w r3, r3, #2 + 8003d70: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= OC_Config->OCPolarity; - 8003caa: 683b ldr r3, [r7, #0] - 8003cac: 689b ldr r3, [r3, #8] - 8003cae: 697a ldr r2, [r7, #20] - 8003cb0: 4313 orrs r3, r2 - 8003cb2: 617b str r3, [r7, #20] + 8003d72: 683b ldr r3, [r7, #0] + 8003d74: 689b ldr r3, [r3, #8] + 8003d76: 697a ldr r2, [r7, #20] + 8003d78: 4313 orrs r3, r2 + 8003d7a: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) - 8003cb4: 687b ldr r3, [r7, #4] - 8003cb6: 4a21 ldr r2, [pc, #132] ; (8003d3c ) - 8003cb8: 4293 cmp r3, r2 - 8003cba: d003 beq.n 8003cc4 - 8003cbc: 687b ldr r3, [r7, #4] - 8003cbe: 4a20 ldr r2, [pc, #128] ; (8003d40 ) - 8003cc0: 4293 cmp r3, r2 - 8003cc2: d10c bne.n 8003cde + 8003d7c: 687b ldr r3, [r7, #4] + 8003d7e: 4a21 ldr r2, [pc, #132] ; (8003e04 ) + 8003d80: 4293 cmp r3, r2 + 8003d82: d003 beq.n 8003d8c + 8003d84: 687b ldr r3, [r7, #4] + 8003d86: 4a20 ldr r2, [pc, #128] ; (8003e08 ) + 8003d88: 4293 cmp r3, r2 + 8003d8a: d10c bne.n 8003da6 { /* Check parameters */ assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC1NP; - 8003cc4: 697b ldr r3, [r7, #20] - 8003cc6: f023 0308 bic.w r3, r3, #8 - 8003cca: 617b str r3, [r7, #20] + 8003d8c: 697b ldr r3, [r7, #20] + 8003d8e: f023 0308 bic.w r3, r3, #8 + 8003d92: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= OC_Config->OCNPolarity; - 8003ccc: 683b ldr r3, [r7, #0] - 8003cce: 68db ldr r3, [r3, #12] - 8003cd0: 697a ldr r2, [r7, #20] - 8003cd2: 4313 orrs r3, r2 - 8003cd4: 617b str r3, [r7, #20] + 8003d94: 683b ldr r3, [r7, #0] + 8003d96: 68db ldr r3, [r3, #12] + 8003d98: 697a ldr r2, [r7, #20] + 8003d9a: 4313 orrs r3, r2 + 8003d9c: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC1NE; - 8003cd6: 697b ldr r3, [r7, #20] - 8003cd8: f023 0304 bic.w r3, r3, #4 - 8003cdc: 617b str r3, [r7, #20] + 8003d9e: 697b ldr r3, [r7, #20] + 8003da0: f023 0304 bic.w r3, r3, #4 + 8003da4: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8003cde: 687b ldr r3, [r7, #4] - 8003ce0: 4a16 ldr r2, [pc, #88] ; (8003d3c ) - 8003ce2: 4293 cmp r3, r2 - 8003ce4: d003 beq.n 8003cee - 8003ce6: 687b ldr r3, [r7, #4] - 8003ce8: 4a15 ldr r2, [pc, #84] ; (8003d40 ) - 8003cea: 4293 cmp r3, r2 - 8003cec: d111 bne.n 8003d12 + 8003da6: 687b ldr r3, [r7, #4] + 8003da8: 4a16 ldr r2, [pc, #88] ; (8003e04 ) + 8003daa: 4293 cmp r3, r2 + 8003dac: d003 beq.n 8003db6 + 8003dae: 687b ldr r3, [r7, #4] + 8003db0: 4a15 ldr r2, [pc, #84] ; (8003e08 ) + 8003db2: 4293 cmp r3, r2 + 8003db4: d111 bne.n 8003dda /* Check parameters */ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); /* Reset the Output Compare and Output Compare N IDLE State */ tmpcr2 &= ~TIM_CR2_OIS1; - 8003cee: 693b ldr r3, [r7, #16] - 8003cf0: f423 7380 bic.w r3, r3, #256 ; 0x100 - 8003cf4: 613b str r3, [r7, #16] + 8003db6: 693b ldr r3, [r7, #16] + 8003db8: f423 7380 bic.w r3, r3, #256 ; 0x100 + 8003dbc: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS1N; - 8003cf6: 693b ldr r3, [r7, #16] - 8003cf8: f423 7300 bic.w r3, r3, #512 ; 0x200 - 8003cfc: 613b str r3, [r7, #16] + 8003dbe: 693b ldr r3, [r7, #16] + 8003dc0: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8003dc4: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= OC_Config->OCIdleState; - 8003cfe: 683b ldr r3, [r7, #0] - 8003d00: 695b ldr r3, [r3, #20] - 8003d02: 693a ldr r2, [r7, #16] - 8003d04: 4313 orrs r3, r2 - 8003d06: 613b str r3, [r7, #16] + 8003dc6: 683b ldr r3, [r7, #0] + 8003dc8: 695b ldr r3, [r3, #20] + 8003dca: 693a ldr r2, [r7, #16] + 8003dcc: 4313 orrs r3, r2 + 8003dce: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= OC_Config->OCNIdleState; - 8003d08: 683b ldr r3, [r7, #0] - 8003d0a: 699b ldr r3, [r3, #24] - 8003d0c: 693a ldr r2, [r7, #16] - 8003d0e: 4313 orrs r3, r2 - 8003d10: 613b str r3, [r7, #16] + 8003dd0: 683b ldr r3, [r7, #0] + 8003dd2: 699b ldr r3, [r3, #24] + 8003dd4: 693a ldr r2, [r7, #16] + 8003dd6: 4313 orrs r3, r2 + 8003dd8: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8003d12: 687b ldr r3, [r7, #4] - 8003d14: 693a ldr r2, [r7, #16] - 8003d16: 605a str r2, [r3, #4] + 8003dda: 687b ldr r3, [r7, #4] + 8003ddc: 693a ldr r2, [r7, #16] + 8003dde: 605a str r2, [r3, #4] /* Write to TIMx CCMR1 */ TIMx->CCMR1 = tmpccmrx; - 8003d18: 687b ldr r3, [r7, #4] - 8003d1a: 68fa ldr r2, [r7, #12] - 8003d1c: 619a str r2, [r3, #24] + 8003de0: 687b ldr r3, [r7, #4] + 8003de2: 68fa ldr r2, [r7, #12] + 8003de4: 619a str r2, [r3, #24] /* Set the Capture Compare Register value */ TIMx->CCR1 = OC_Config->Pulse; - 8003d1e: 683b ldr r3, [r7, #0] - 8003d20: 685a ldr r2, [r3, #4] - 8003d22: 687b ldr r3, [r7, #4] - 8003d24: 635a str r2, [r3, #52] ; 0x34 + 8003de6: 683b ldr r3, [r7, #0] + 8003de8: 685a ldr r2, [r3, #4] + 8003dea: 687b ldr r3, [r7, #4] + 8003dec: 635a str r2, [r3, #52] ; 0x34 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8003d26: 687b ldr r3, [r7, #4] - 8003d28: 697a ldr r2, [r7, #20] - 8003d2a: 621a str r2, [r3, #32] + 8003dee: 687b ldr r3, [r7, #4] + 8003df0: 697a ldr r2, [r7, #20] + 8003df2: 621a str r2, [r3, #32] } - 8003d2c: bf00 nop - 8003d2e: 371c adds r7, #28 - 8003d30: 46bd mov sp, r7 - 8003d32: f85d 7b04 ldr.w r7, [sp], #4 - 8003d36: 4770 bx lr - 8003d38: fffeff8f .word 0xfffeff8f - 8003d3c: 40010000 .word 0x40010000 - 8003d40: 40010400 .word 0x40010400 - -08003d44 : + 8003df4: bf00 nop + 8003df6: 371c adds r7, #28 + 8003df8: 46bd mov sp, r7 + 8003dfa: f85d 7b04 ldr.w r7, [sp], #4 + 8003dfe: 4770 bx lr + 8003e00: fffeff8f .word 0xfffeff8f + 8003e04: 40010000 .word 0x40010000 + 8003e08: 40010400 .word 0x40010400 + +08003e0c : * @param TIMx to select the TIM peripheral * @param OC_Config The ouput configuration structure * @retval None */ void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8003d44: b480 push {r7} - 8003d46: b087 sub sp, #28 - 8003d48: af00 add r7, sp, #0 - 8003d4a: 6078 str r0, [r7, #4] - 8003d4c: 6039 str r1, [r7, #0] + 8003e0c: b480 push {r7} + 8003e0e: b087 sub sp, #28 + 8003e10: af00 add r7, sp, #0 + 8003e12: 6078 str r0, [r7, #4] + 8003e14: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the Channel 2: Reset the CC2E Bit */ TIMx->CCER &= ~TIM_CCER_CC2E; - 8003d4e: 687b ldr r3, [r7, #4] - 8003d50: 6a1b ldr r3, [r3, #32] - 8003d52: f023 0210 bic.w r2, r3, #16 - 8003d56: 687b ldr r3, [r7, #4] - 8003d58: 621a str r2, [r3, #32] + 8003e16: 687b ldr r3, [r7, #4] + 8003e18: 6a1b ldr r3, [r3, #32] + 8003e1a: f023 0210 bic.w r2, r3, #16 + 8003e1e: 687b ldr r3, [r7, #4] + 8003e20: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003d5a: 687b ldr r3, [r7, #4] - 8003d5c: 6a1b ldr r3, [r3, #32] - 8003d5e: 617b str r3, [r7, #20] + 8003e22: 687b ldr r3, [r7, #4] + 8003e24: 6a1b ldr r3, [r3, #32] + 8003e26: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003d60: 687b ldr r3, [r7, #4] - 8003d62: 685b ldr r3, [r3, #4] - 8003d64: 613b str r3, [r7, #16] + 8003e28: 687b ldr r3, [r7, #4] + 8003e2a: 685b ldr r3, [r3, #4] + 8003e2c: 613b str r3, [r7, #16] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR1; - 8003d66: 687b ldr r3, [r7, #4] - 8003d68: 699b ldr r3, [r3, #24] - 8003d6a: 60fb str r3, [r7, #12] + 8003e2e: 687b ldr r3, [r7, #4] + 8003e30: 699b ldr r3, [r3, #24] + 8003e32: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR1_OC2M; - 8003d6c: 68fa ldr r2, [r7, #12] - 8003d6e: 4b2e ldr r3, [pc, #184] ; (8003e28 ) - 8003d70: 4013 ands r3, r2 - 8003d72: 60fb str r3, [r7, #12] + 8003e34: 68fa ldr r2, [r7, #12] + 8003e36: 4b2e ldr r3, [pc, #184] ; (8003ef0 ) + 8003e38: 4013 ands r3, r2 + 8003e3a: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR1_CC2S; - 8003d74: 68fb ldr r3, [r7, #12] - 8003d76: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8003d7a: 60fb str r3, [r7, #12] + 8003e3c: 68fb ldr r3, [r7, #12] + 8003e3e: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003e42: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 8003d7c: 683b ldr r3, [r7, #0] - 8003d7e: 681b ldr r3, [r3, #0] - 8003d80: 021b lsls r3, r3, #8 - 8003d82: 68fa ldr r2, [r7, #12] - 8003d84: 4313 orrs r3, r2 - 8003d86: 60fb str r3, [r7, #12] + 8003e44: 683b ldr r3, [r7, #0] + 8003e46: 681b ldr r3, [r3, #0] + 8003e48: 021b lsls r3, r3, #8 + 8003e4a: 68fa ldr r2, [r7, #12] + 8003e4c: 4313 orrs r3, r2 + 8003e4e: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC2P; - 8003d88: 697b ldr r3, [r7, #20] - 8003d8a: f023 0320 bic.w r3, r3, #32 - 8003d8e: 617b str r3, [r7, #20] + 8003e50: 697b ldr r3, [r7, #20] + 8003e52: f023 0320 bic.w r3, r3, #32 + 8003e56: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 4U); - 8003d90: 683b ldr r3, [r7, #0] - 8003d92: 689b ldr r3, [r3, #8] - 8003d94: 011b lsls r3, r3, #4 - 8003d96: 697a ldr r2, [r7, #20] - 8003d98: 4313 orrs r3, r2 - 8003d9a: 617b str r3, [r7, #20] + 8003e58: 683b ldr r3, [r7, #0] + 8003e5a: 689b ldr r3, [r3, #8] + 8003e5c: 011b lsls r3, r3, #4 + 8003e5e: 697a ldr r2, [r7, #20] + 8003e60: 4313 orrs r3, r2 + 8003e62: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) - 8003d9c: 687b ldr r3, [r7, #4] - 8003d9e: 4a23 ldr r2, [pc, #140] ; (8003e2c ) - 8003da0: 4293 cmp r3, r2 - 8003da2: d003 beq.n 8003dac - 8003da4: 687b ldr r3, [r7, #4] - 8003da6: 4a22 ldr r2, [pc, #136] ; (8003e30 ) - 8003da8: 4293 cmp r3, r2 - 8003daa: d10d bne.n 8003dc8 + 8003e64: 687b ldr r3, [r7, #4] + 8003e66: 4a23 ldr r2, [pc, #140] ; (8003ef4 ) + 8003e68: 4293 cmp r3, r2 + 8003e6a: d003 beq.n 8003e74 + 8003e6c: 687b ldr r3, [r7, #4] + 8003e6e: 4a22 ldr r2, [pc, #136] ; (8003ef8 ) + 8003e70: 4293 cmp r3, r2 + 8003e72: d10d bne.n 8003e90 { assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC2NP; - 8003dac: 697b ldr r3, [r7, #20] - 8003dae: f023 0380 bic.w r3, r3, #128 ; 0x80 - 8003db2: 617b str r3, [r7, #20] + 8003e74: 697b ldr r3, [r7, #20] + 8003e76: f023 0380 bic.w r3, r3, #128 ; 0x80 + 8003e7a: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= (OC_Config->OCNPolarity << 4U); - 8003db4: 683b ldr r3, [r7, #0] - 8003db6: 68db ldr r3, [r3, #12] - 8003db8: 011b lsls r3, r3, #4 - 8003dba: 697a ldr r2, [r7, #20] - 8003dbc: 4313 orrs r3, r2 - 8003dbe: 617b str r3, [r7, #20] + 8003e7c: 683b ldr r3, [r7, #0] + 8003e7e: 68db ldr r3, [r3, #12] + 8003e80: 011b lsls r3, r3, #4 + 8003e82: 697a ldr r2, [r7, #20] + 8003e84: 4313 orrs r3, r2 + 8003e86: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC2NE; - 8003dc0: 697b ldr r3, [r7, #20] - 8003dc2: f023 0340 bic.w r3, r3, #64 ; 0x40 - 8003dc6: 617b str r3, [r7, #20] + 8003e88: 697b ldr r3, [r7, #20] + 8003e8a: f023 0340 bic.w r3, r3, #64 ; 0x40 + 8003e8e: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8003dc8: 687b ldr r3, [r7, #4] - 8003dca: 4a18 ldr r2, [pc, #96] ; (8003e2c ) - 8003dcc: 4293 cmp r3, r2 - 8003dce: d003 beq.n 8003dd8 - 8003dd0: 687b ldr r3, [r7, #4] - 8003dd2: 4a17 ldr r2, [pc, #92] ; (8003e30 ) - 8003dd4: 4293 cmp r3, r2 - 8003dd6: d113 bne.n 8003e00 + 8003e90: 687b ldr r3, [r7, #4] + 8003e92: 4a18 ldr r2, [pc, #96] ; (8003ef4 ) + 8003e94: 4293 cmp r3, r2 + 8003e96: d003 beq.n 8003ea0 + 8003e98: 687b ldr r3, [r7, #4] + 8003e9a: 4a17 ldr r2, [pc, #92] ; (8003ef8 ) + 8003e9c: 4293 cmp r3, r2 + 8003e9e: d113 bne.n 8003ec8 /* Check parameters */ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); /* Reset the Output Compare and Output Compare N IDLE State */ tmpcr2 &= ~TIM_CR2_OIS2; - 8003dd8: 693b ldr r3, [r7, #16] - 8003dda: f423 6380 bic.w r3, r3, #1024 ; 0x400 - 8003dde: 613b str r3, [r7, #16] + 8003ea0: 693b ldr r3, [r7, #16] + 8003ea2: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 8003ea6: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS2N; - 8003de0: 693b ldr r3, [r7, #16] - 8003de2: f423 6300 bic.w r3, r3, #2048 ; 0x800 - 8003de6: 613b str r3, [r7, #16] + 8003ea8: 693b ldr r3, [r7, #16] + 8003eaa: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 8003eae: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 2U); - 8003de8: 683b ldr r3, [r7, #0] - 8003dea: 695b ldr r3, [r3, #20] - 8003dec: 009b lsls r3, r3, #2 - 8003dee: 693a ldr r2, [r7, #16] - 8003df0: 4313 orrs r3, r2 - 8003df2: 613b str r3, [r7, #16] + 8003eb0: 683b ldr r3, [r7, #0] + 8003eb2: 695b ldr r3, [r3, #20] + 8003eb4: 009b lsls r3, r3, #2 + 8003eb6: 693a ldr r2, [r7, #16] + 8003eb8: 4313 orrs r3, r2 + 8003eba: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= (OC_Config->OCNIdleState << 2U); - 8003df4: 683b ldr r3, [r7, #0] - 8003df6: 699b ldr r3, [r3, #24] - 8003df8: 009b lsls r3, r3, #2 - 8003dfa: 693a ldr r2, [r7, #16] - 8003dfc: 4313 orrs r3, r2 - 8003dfe: 613b str r3, [r7, #16] + 8003ebc: 683b ldr r3, [r7, #0] + 8003ebe: 699b ldr r3, [r3, #24] + 8003ec0: 009b lsls r3, r3, #2 + 8003ec2: 693a ldr r2, [r7, #16] + 8003ec4: 4313 orrs r3, r2 + 8003ec6: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8003e00: 687b ldr r3, [r7, #4] - 8003e02: 693a ldr r2, [r7, #16] - 8003e04: 605a str r2, [r3, #4] + 8003ec8: 687b ldr r3, [r7, #4] + 8003eca: 693a ldr r2, [r7, #16] + 8003ecc: 605a str r2, [r3, #4] /* Write to TIMx CCMR1 */ TIMx->CCMR1 = tmpccmrx; - 8003e06: 687b ldr r3, [r7, #4] - 8003e08: 68fa ldr r2, [r7, #12] - 8003e0a: 619a str r2, [r3, #24] + 8003ece: 687b ldr r3, [r7, #4] + 8003ed0: 68fa ldr r2, [r7, #12] + 8003ed2: 619a str r2, [r3, #24] /* Set the Capture Compare Register value */ TIMx->CCR2 = OC_Config->Pulse; - 8003e0c: 683b ldr r3, [r7, #0] - 8003e0e: 685a ldr r2, [r3, #4] - 8003e10: 687b ldr r3, [r7, #4] - 8003e12: 639a str r2, [r3, #56] ; 0x38 + 8003ed4: 683b ldr r3, [r7, #0] + 8003ed6: 685a ldr r2, [r3, #4] + 8003ed8: 687b ldr r3, [r7, #4] + 8003eda: 639a str r2, [r3, #56] ; 0x38 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8003e14: 687b ldr r3, [r7, #4] - 8003e16: 697a ldr r2, [r7, #20] - 8003e18: 621a str r2, [r3, #32] + 8003edc: 687b ldr r3, [r7, #4] + 8003ede: 697a ldr r2, [r7, #20] + 8003ee0: 621a str r2, [r3, #32] } - 8003e1a: bf00 nop - 8003e1c: 371c adds r7, #28 - 8003e1e: 46bd mov sp, r7 - 8003e20: f85d 7b04 ldr.w r7, [sp], #4 - 8003e24: 4770 bx lr - 8003e26: bf00 nop - 8003e28: feff8fff .word 0xfeff8fff - 8003e2c: 40010000 .word 0x40010000 - 8003e30: 40010400 .word 0x40010400 - -08003e34 : + 8003ee2: bf00 nop + 8003ee4: 371c adds r7, #28 + 8003ee6: 46bd mov sp, r7 + 8003ee8: f85d 7b04 ldr.w r7, [sp], #4 + 8003eec: 4770 bx lr + 8003eee: bf00 nop + 8003ef0: feff8fff .word 0xfeff8fff + 8003ef4: 40010000 .word 0x40010000 + 8003ef8: 40010400 .word 0x40010400 + +08003efc : * @param TIMx to select the TIM peripheral * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8003e34: b480 push {r7} - 8003e36: b087 sub sp, #28 - 8003e38: af00 add r7, sp, #0 - 8003e3a: 6078 str r0, [r7, #4] - 8003e3c: 6039 str r1, [r7, #0] + 8003efc: b480 push {r7} + 8003efe: b087 sub sp, #28 + 8003f00: af00 add r7, sp, #0 + 8003f02: 6078 str r0, [r7, #4] + 8003f04: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the Channel 3: Reset the CC2E Bit */ TIMx->CCER &= ~TIM_CCER_CC3E; - 8003e3e: 687b ldr r3, [r7, #4] - 8003e40: 6a1b ldr r3, [r3, #32] - 8003e42: f423 7280 bic.w r2, r3, #256 ; 0x100 - 8003e46: 687b ldr r3, [r7, #4] - 8003e48: 621a str r2, [r3, #32] + 8003f06: 687b ldr r3, [r7, #4] + 8003f08: 6a1b ldr r3, [r3, #32] + 8003f0a: f423 7280 bic.w r2, r3, #256 ; 0x100 + 8003f0e: 687b ldr r3, [r7, #4] + 8003f10: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003e4a: 687b ldr r3, [r7, #4] - 8003e4c: 6a1b ldr r3, [r3, #32] - 8003e4e: 617b str r3, [r7, #20] + 8003f12: 687b ldr r3, [r7, #4] + 8003f14: 6a1b ldr r3, [r3, #32] + 8003f16: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003e50: 687b ldr r3, [r7, #4] - 8003e52: 685b ldr r3, [r3, #4] - 8003e54: 613b str r3, [r7, #16] + 8003f18: 687b ldr r3, [r7, #4] + 8003f1a: 685b ldr r3, [r3, #4] + 8003f1c: 613b str r3, [r7, #16] /* Get the TIMx CCMR2 register value */ tmpccmrx = TIMx->CCMR2; - 8003e56: 687b ldr r3, [r7, #4] - 8003e58: 69db ldr r3, [r3, #28] - 8003e5a: 60fb str r3, [r7, #12] + 8003f1e: 687b ldr r3, [r7, #4] + 8003f20: 69db ldr r3, [r3, #28] + 8003f22: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR2_OC3M; - 8003e5c: 68fa ldr r2, [r7, #12] - 8003e5e: 4b2d ldr r3, [pc, #180] ; (8003f14 ) - 8003e60: 4013 ands r3, r2 - 8003e62: 60fb str r3, [r7, #12] + 8003f24: 68fa ldr r2, [r7, #12] + 8003f26: 4b2d ldr r3, [pc, #180] ; (8003fdc ) + 8003f28: 4013 ands r3, r2 + 8003f2a: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR2_CC3S; - 8003e64: 68fb ldr r3, [r7, #12] - 8003e66: f023 0303 bic.w r3, r3, #3 - 8003e6a: 60fb str r3, [r7, #12] + 8003f2c: 68fb ldr r3, [r7, #12] + 8003f2e: f023 0303 bic.w r3, r3, #3 + 8003f32: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8003e6c: 683b ldr r3, [r7, #0] - 8003e6e: 681b ldr r3, [r3, #0] - 8003e70: 68fa ldr r2, [r7, #12] - 8003e72: 4313 orrs r3, r2 - 8003e74: 60fb str r3, [r7, #12] + 8003f34: 683b ldr r3, [r7, #0] + 8003f36: 681b ldr r3, [r3, #0] + 8003f38: 68fa ldr r2, [r7, #12] + 8003f3a: 4313 orrs r3, r2 + 8003f3c: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC3P; - 8003e76: 697b ldr r3, [r7, #20] - 8003e78: f423 7300 bic.w r3, r3, #512 ; 0x200 - 8003e7c: 617b str r3, [r7, #20] + 8003f3e: 697b ldr r3, [r7, #20] + 8003f40: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8003f44: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 8U); - 8003e7e: 683b ldr r3, [r7, #0] - 8003e80: 689b ldr r3, [r3, #8] - 8003e82: 021b lsls r3, r3, #8 - 8003e84: 697a ldr r2, [r7, #20] - 8003e86: 4313 orrs r3, r2 - 8003e88: 617b str r3, [r7, #20] + 8003f46: 683b ldr r3, [r7, #0] + 8003f48: 689b ldr r3, [r3, #8] + 8003f4a: 021b lsls r3, r3, #8 + 8003f4c: 697a ldr r2, [r7, #20] + 8003f4e: 4313 orrs r3, r2 + 8003f50: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) - 8003e8a: 687b ldr r3, [r7, #4] - 8003e8c: 4a22 ldr r2, [pc, #136] ; (8003f18 ) - 8003e8e: 4293 cmp r3, r2 - 8003e90: d003 beq.n 8003e9a - 8003e92: 687b ldr r3, [r7, #4] - 8003e94: 4a21 ldr r2, [pc, #132] ; (8003f1c ) - 8003e96: 4293 cmp r3, r2 - 8003e98: d10d bne.n 8003eb6 + 8003f52: 687b ldr r3, [r7, #4] + 8003f54: 4a22 ldr r2, [pc, #136] ; (8003fe0 ) + 8003f56: 4293 cmp r3, r2 + 8003f58: d003 beq.n 8003f62 + 8003f5a: 687b ldr r3, [r7, #4] + 8003f5c: 4a21 ldr r2, [pc, #132] ; (8003fe4 ) + 8003f5e: 4293 cmp r3, r2 + 8003f60: d10d bne.n 8003f7e { assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC3NP; - 8003e9a: 697b ldr r3, [r7, #20] - 8003e9c: f423 6300 bic.w r3, r3, #2048 ; 0x800 - 8003ea0: 617b str r3, [r7, #20] + 8003f62: 697b ldr r3, [r7, #20] + 8003f64: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 8003f68: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= (OC_Config->OCNPolarity << 8U); - 8003ea2: 683b ldr r3, [r7, #0] - 8003ea4: 68db ldr r3, [r3, #12] - 8003ea6: 021b lsls r3, r3, #8 - 8003ea8: 697a ldr r2, [r7, #20] - 8003eaa: 4313 orrs r3, r2 - 8003eac: 617b str r3, [r7, #20] + 8003f6a: 683b ldr r3, [r7, #0] + 8003f6c: 68db ldr r3, [r3, #12] + 8003f6e: 021b lsls r3, r3, #8 + 8003f70: 697a ldr r2, [r7, #20] + 8003f72: 4313 orrs r3, r2 + 8003f74: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC3NE; - 8003eae: 697b ldr r3, [r7, #20] - 8003eb0: f423 6380 bic.w r3, r3, #1024 ; 0x400 - 8003eb4: 617b str r3, [r7, #20] + 8003f76: 697b ldr r3, [r7, #20] + 8003f78: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 8003f7c: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8003eb6: 687b ldr r3, [r7, #4] - 8003eb8: 4a17 ldr r2, [pc, #92] ; (8003f18 ) - 8003eba: 4293 cmp r3, r2 - 8003ebc: d003 beq.n 8003ec6 - 8003ebe: 687b ldr r3, [r7, #4] - 8003ec0: 4a16 ldr r2, [pc, #88] ; (8003f1c ) - 8003ec2: 4293 cmp r3, r2 - 8003ec4: d113 bne.n 8003eee + 8003f7e: 687b ldr r3, [r7, #4] + 8003f80: 4a17 ldr r2, [pc, #92] ; (8003fe0 ) + 8003f82: 4293 cmp r3, r2 + 8003f84: d003 beq.n 8003f8e + 8003f86: 687b ldr r3, [r7, #4] + 8003f88: 4a16 ldr r2, [pc, #88] ; (8003fe4 ) + 8003f8a: 4293 cmp r3, r2 + 8003f8c: d113 bne.n 8003fb6 /* Check parameters */ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); /* Reset the Output Compare and Output Compare N IDLE State */ tmpcr2 &= ~TIM_CR2_OIS3; - 8003ec6: 693b ldr r3, [r7, #16] - 8003ec8: f423 5380 bic.w r3, r3, #4096 ; 0x1000 - 8003ecc: 613b str r3, [r7, #16] + 8003f8e: 693b ldr r3, [r7, #16] + 8003f90: f423 5380 bic.w r3, r3, #4096 ; 0x1000 + 8003f94: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS3N; - 8003ece: 693b ldr r3, [r7, #16] - 8003ed0: f423 5300 bic.w r3, r3, #8192 ; 0x2000 - 8003ed4: 613b str r3, [r7, #16] + 8003f96: 693b ldr r3, [r7, #16] + 8003f98: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 8003f9c: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 4U); - 8003ed6: 683b ldr r3, [r7, #0] - 8003ed8: 695b ldr r3, [r3, #20] - 8003eda: 011b lsls r3, r3, #4 - 8003edc: 693a ldr r2, [r7, #16] - 8003ede: 4313 orrs r3, r2 - 8003ee0: 613b str r3, [r7, #16] + 8003f9e: 683b ldr r3, [r7, #0] + 8003fa0: 695b ldr r3, [r3, #20] + 8003fa2: 011b lsls r3, r3, #4 + 8003fa4: 693a ldr r2, [r7, #16] + 8003fa6: 4313 orrs r3, r2 + 8003fa8: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= (OC_Config->OCNIdleState << 4U); - 8003ee2: 683b ldr r3, [r7, #0] - 8003ee4: 699b ldr r3, [r3, #24] - 8003ee6: 011b lsls r3, r3, #4 - 8003ee8: 693a ldr r2, [r7, #16] - 8003eea: 4313 orrs r3, r2 - 8003eec: 613b str r3, [r7, #16] + 8003faa: 683b ldr r3, [r7, #0] + 8003fac: 699b ldr r3, [r3, #24] + 8003fae: 011b lsls r3, r3, #4 + 8003fb0: 693a ldr r2, [r7, #16] + 8003fb2: 4313 orrs r3, r2 + 8003fb4: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8003eee: 687b ldr r3, [r7, #4] - 8003ef0: 693a ldr r2, [r7, #16] - 8003ef2: 605a str r2, [r3, #4] + 8003fb6: 687b ldr r3, [r7, #4] + 8003fb8: 693a ldr r2, [r7, #16] + 8003fba: 605a str r2, [r3, #4] /* Write to TIMx CCMR2 */ TIMx->CCMR2 = tmpccmrx; - 8003ef4: 687b ldr r3, [r7, #4] - 8003ef6: 68fa ldr r2, [r7, #12] - 8003ef8: 61da str r2, [r3, #28] + 8003fbc: 687b ldr r3, [r7, #4] + 8003fbe: 68fa ldr r2, [r7, #12] + 8003fc0: 61da str r2, [r3, #28] /* Set the Capture Compare Register value */ TIMx->CCR3 = OC_Config->Pulse; - 8003efa: 683b ldr r3, [r7, #0] - 8003efc: 685a ldr r2, [r3, #4] - 8003efe: 687b ldr r3, [r7, #4] - 8003f00: 63da str r2, [r3, #60] ; 0x3c + 8003fc2: 683b ldr r3, [r7, #0] + 8003fc4: 685a ldr r2, [r3, #4] + 8003fc6: 687b ldr r3, [r7, #4] + 8003fc8: 63da str r2, [r3, #60] ; 0x3c /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8003f02: 687b ldr r3, [r7, #4] - 8003f04: 697a ldr r2, [r7, #20] - 8003f06: 621a str r2, [r3, #32] + 8003fca: 687b ldr r3, [r7, #4] + 8003fcc: 697a ldr r2, [r7, #20] + 8003fce: 621a str r2, [r3, #32] } - 8003f08: bf00 nop - 8003f0a: 371c adds r7, #28 - 8003f0c: 46bd mov sp, r7 - 8003f0e: f85d 7b04 ldr.w r7, [sp], #4 - 8003f12: 4770 bx lr - 8003f14: fffeff8f .word 0xfffeff8f - 8003f18: 40010000 .word 0x40010000 - 8003f1c: 40010400 .word 0x40010400 - -08003f20 : + 8003fd0: bf00 nop + 8003fd2: 371c adds r7, #28 + 8003fd4: 46bd mov sp, r7 + 8003fd6: f85d 7b04 ldr.w r7, [sp], #4 + 8003fda: 4770 bx lr + 8003fdc: fffeff8f .word 0xfffeff8f + 8003fe0: 40010000 .word 0x40010000 + 8003fe4: 40010400 .word 0x40010400 + +08003fe8 : * @param TIMx to select the TIM peripheral * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8003f20: b480 push {r7} - 8003f22: b087 sub sp, #28 - 8003f24: af00 add r7, sp, #0 - 8003f26: 6078 str r0, [r7, #4] - 8003f28: 6039 str r1, [r7, #0] + 8003fe8: b480 push {r7} + 8003fea: b087 sub sp, #28 + 8003fec: af00 add r7, sp, #0 + 8003fee: 6078 str r0, [r7, #4] + 8003ff0: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the Channel 4: Reset the CC4E Bit */ TIMx->CCER &= ~TIM_CCER_CC4E; - 8003f2a: 687b ldr r3, [r7, #4] - 8003f2c: 6a1b ldr r3, [r3, #32] - 8003f2e: f423 5280 bic.w r2, r3, #4096 ; 0x1000 - 8003f32: 687b ldr r3, [r7, #4] - 8003f34: 621a str r2, [r3, #32] + 8003ff2: 687b ldr r3, [r7, #4] + 8003ff4: 6a1b ldr r3, [r3, #32] + 8003ff6: f423 5280 bic.w r2, r3, #4096 ; 0x1000 + 8003ffa: 687b ldr r3, [r7, #4] + 8003ffc: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003f36: 687b ldr r3, [r7, #4] - 8003f38: 6a1b ldr r3, [r3, #32] - 8003f3a: 613b str r3, [r7, #16] + 8003ffe: 687b ldr r3, [r7, #4] + 8004000: 6a1b ldr r3, [r3, #32] + 8004002: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003f3c: 687b ldr r3, [r7, #4] - 8003f3e: 685b ldr r3, [r3, #4] - 8003f40: 617b str r3, [r7, #20] + 8004004: 687b ldr r3, [r7, #4] + 8004006: 685b ldr r3, [r3, #4] + 8004008: 617b str r3, [r7, #20] /* Get the TIMx CCMR2 register value */ tmpccmrx = TIMx->CCMR2; - 8003f42: 687b ldr r3, [r7, #4] - 8003f44: 69db ldr r3, [r3, #28] - 8003f46: 60fb str r3, [r7, #12] + 800400a: 687b ldr r3, [r7, #4] + 800400c: 69db ldr r3, [r3, #28] + 800400e: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR2_OC4M; - 8003f48: 68fa ldr r2, [r7, #12] - 8003f4a: 4b1e ldr r3, [pc, #120] ; (8003fc4 ) - 8003f4c: 4013 ands r3, r2 - 8003f4e: 60fb str r3, [r7, #12] + 8004010: 68fa ldr r2, [r7, #12] + 8004012: 4b1e ldr r3, [pc, #120] ; (800408c ) + 8004014: 4013 ands r3, r2 + 8004016: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR2_CC4S; - 8003f50: 68fb ldr r3, [r7, #12] - 8003f52: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8003f56: 60fb str r3, [r7, #12] + 8004018: 68fb ldr r3, [r7, #12] + 800401a: f423 7340 bic.w r3, r3, #768 ; 0x300 + 800401e: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 8003f58: 683b ldr r3, [r7, #0] - 8003f5a: 681b ldr r3, [r3, #0] - 8003f5c: 021b lsls r3, r3, #8 - 8003f5e: 68fa ldr r2, [r7, #12] - 8003f60: 4313 orrs r3, r2 - 8003f62: 60fb str r3, [r7, #12] + 8004020: 683b ldr r3, [r7, #0] + 8004022: 681b ldr r3, [r3, #0] + 8004024: 021b lsls r3, r3, #8 + 8004026: 68fa ldr r2, [r7, #12] + 8004028: 4313 orrs r3, r2 + 800402a: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC4P; - 8003f64: 693b ldr r3, [r7, #16] - 8003f66: f423 5300 bic.w r3, r3, #8192 ; 0x2000 - 8003f6a: 613b str r3, [r7, #16] + 800402c: 693b ldr r3, [r7, #16] + 800402e: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 8004032: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 12U); - 8003f6c: 683b ldr r3, [r7, #0] - 8003f6e: 689b ldr r3, [r3, #8] - 8003f70: 031b lsls r3, r3, #12 - 8003f72: 693a ldr r2, [r7, #16] - 8003f74: 4313 orrs r3, r2 - 8003f76: 613b str r3, [r7, #16] + 8004034: 683b ldr r3, [r7, #0] + 8004036: 689b ldr r3, [r3, #8] + 8004038: 031b lsls r3, r3, #12 + 800403a: 693a ldr r2, [r7, #16] + 800403c: 4313 orrs r3, r2 + 800403e: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8003f78: 687b ldr r3, [r7, #4] - 8003f7a: 4a13 ldr r2, [pc, #76] ; (8003fc8 ) - 8003f7c: 4293 cmp r3, r2 - 8003f7e: d003 beq.n 8003f88 - 8003f80: 687b ldr r3, [r7, #4] - 8003f82: 4a12 ldr r2, [pc, #72] ; (8003fcc ) - 8003f84: 4293 cmp r3, r2 - 8003f86: d109 bne.n 8003f9c + 8004040: 687b ldr r3, [r7, #4] + 8004042: 4a13 ldr r2, [pc, #76] ; (8004090 ) + 8004044: 4293 cmp r3, r2 + 8004046: d003 beq.n 8004050 + 8004048: 687b ldr r3, [r7, #4] + 800404a: 4a12 ldr r2, [pc, #72] ; (8004094 ) + 800404c: 4293 cmp r3, r2 + 800404e: d109 bne.n 8004064 { /* Check parameters */ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS4; - 8003f88: 697b ldr r3, [r7, #20] - 8003f8a: f423 4380 bic.w r3, r3, #16384 ; 0x4000 - 8003f8e: 617b str r3, [r7, #20] + 8004050: 697b ldr r3, [r7, #20] + 8004052: f423 4380 bic.w r3, r3, #16384 ; 0x4000 + 8004056: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 6U); - 8003f90: 683b ldr r3, [r7, #0] - 8003f92: 695b ldr r3, [r3, #20] - 8003f94: 019b lsls r3, r3, #6 - 8003f96: 697a ldr r2, [r7, #20] - 8003f98: 4313 orrs r3, r2 - 8003f9a: 617b str r3, [r7, #20] + 8004058: 683b ldr r3, [r7, #0] + 800405a: 695b ldr r3, [r3, #20] + 800405c: 019b lsls r3, r3, #6 + 800405e: 697a ldr r2, [r7, #20] + 8004060: 4313 orrs r3, r2 + 8004062: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8003f9c: 687b ldr r3, [r7, #4] - 8003f9e: 697a ldr r2, [r7, #20] - 8003fa0: 605a str r2, [r3, #4] + 8004064: 687b ldr r3, [r7, #4] + 8004066: 697a ldr r2, [r7, #20] + 8004068: 605a str r2, [r3, #4] /* Write to TIMx CCMR2 */ TIMx->CCMR2 = tmpccmrx; - 8003fa2: 687b ldr r3, [r7, #4] - 8003fa4: 68fa ldr r2, [r7, #12] - 8003fa6: 61da str r2, [r3, #28] + 800406a: 687b ldr r3, [r7, #4] + 800406c: 68fa ldr r2, [r7, #12] + 800406e: 61da str r2, [r3, #28] /* Set the Capture Compare Register value */ TIMx->CCR4 = OC_Config->Pulse; - 8003fa8: 683b ldr r3, [r7, #0] - 8003faa: 685a ldr r2, [r3, #4] - 8003fac: 687b ldr r3, [r7, #4] - 8003fae: 641a str r2, [r3, #64] ; 0x40 + 8004070: 683b ldr r3, [r7, #0] + 8004072: 685a ldr r2, [r3, #4] + 8004074: 687b ldr r3, [r7, #4] + 8004076: 641a str r2, [r3, #64] ; 0x40 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8003fb0: 687b ldr r3, [r7, #4] - 8003fb2: 693a ldr r2, [r7, #16] - 8003fb4: 621a str r2, [r3, #32] + 8004078: 687b ldr r3, [r7, #4] + 800407a: 693a ldr r2, [r7, #16] + 800407c: 621a str r2, [r3, #32] } - 8003fb6: bf00 nop - 8003fb8: 371c adds r7, #28 - 8003fba: 46bd mov sp, r7 - 8003fbc: f85d 7b04 ldr.w r7, [sp], #4 - 8003fc0: 4770 bx lr - 8003fc2: bf00 nop - 8003fc4: feff8fff .word 0xfeff8fff - 8003fc8: 40010000 .word 0x40010000 - 8003fcc: 40010400 .word 0x40010400 - -08003fd0 : + 800407e: bf00 nop + 8004080: 371c adds r7, #28 + 8004082: 46bd mov sp, r7 + 8004084: f85d 7b04 ldr.w r7, [sp], #4 + 8004088: 4770 bx lr + 800408a: bf00 nop + 800408c: feff8fff .word 0xfeff8fff + 8004090: 40010000 .word 0x40010000 + 8004094: 40010400 .word 0x40010400 + +08004098 : * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC5_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8003fd0: b480 push {r7} - 8003fd2: b087 sub sp, #28 - 8003fd4: af00 add r7, sp, #0 - 8003fd6: 6078 str r0, [r7, #4] - 8003fd8: 6039 str r1, [r7, #0] + 8004098: b480 push {r7} + 800409a: b087 sub sp, #28 + 800409c: af00 add r7, sp, #0 + 800409e: 6078 str r0, [r7, #4] + 80040a0: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the output: Reset the CCxE Bit */ TIMx->CCER &= ~TIM_CCER_CC5E; - 8003fda: 687b ldr r3, [r7, #4] - 8003fdc: 6a1b ldr r3, [r3, #32] - 8003fde: f423 3280 bic.w r2, r3, #65536 ; 0x10000 - 8003fe2: 687b ldr r3, [r7, #4] - 8003fe4: 621a str r2, [r3, #32] + 80040a2: 687b ldr r3, [r7, #4] + 80040a4: 6a1b ldr r3, [r3, #32] + 80040a6: f423 3280 bic.w r2, r3, #65536 ; 0x10000 + 80040aa: 687b ldr r3, [r7, #4] + 80040ac: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003fe6: 687b ldr r3, [r7, #4] - 8003fe8: 6a1b ldr r3, [r3, #32] - 8003fea: 613b str r3, [r7, #16] + 80040ae: 687b ldr r3, [r7, #4] + 80040b0: 6a1b ldr r3, [r3, #32] + 80040b2: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003fec: 687b ldr r3, [r7, #4] - 8003fee: 685b ldr r3, [r3, #4] - 8003ff0: 617b str r3, [r7, #20] + 80040b4: 687b ldr r3, [r7, #4] + 80040b6: 685b ldr r3, [r3, #4] + 80040b8: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR3; - 8003ff2: 687b ldr r3, [r7, #4] - 8003ff4: 6d5b ldr r3, [r3, #84] ; 0x54 - 8003ff6: 60fb str r3, [r7, #12] + 80040ba: 687b ldr r3, [r7, #4] + 80040bc: 6d5b ldr r3, [r3, #84] ; 0x54 + 80040be: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~(TIM_CCMR3_OC5M); - 8003ff8: 68fa ldr r2, [r7, #12] - 8003ffa: 4b1b ldr r3, [pc, #108] ; (8004068 ) - 8003ffc: 4013 ands r3, r2 - 8003ffe: 60fb str r3, [r7, #12] + 80040c0: 68fa ldr r2, [r7, #12] + 80040c2: 4b1b ldr r3, [pc, #108] ; (8004130 ) + 80040c4: 4013 ands r3, r2 + 80040c6: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8004000: 683b ldr r3, [r7, #0] - 8004002: 681b ldr r3, [r3, #0] - 8004004: 68fa ldr r2, [r7, #12] - 8004006: 4313 orrs r3, r2 - 8004008: 60fb str r3, [r7, #12] + 80040c8: 683b ldr r3, [r7, #0] + 80040ca: 681b ldr r3, [r3, #0] + 80040cc: 68fa ldr r2, [r7, #12] + 80040ce: 4313 orrs r3, r2 + 80040d0: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC5P; - 800400a: 693b ldr r3, [r7, #16] - 800400c: f423 3300 bic.w r3, r3, #131072 ; 0x20000 - 8004010: 613b str r3, [r7, #16] + 80040d2: 693b ldr r3, [r7, #16] + 80040d4: f423 3300 bic.w r3, r3, #131072 ; 0x20000 + 80040d8: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 16U); - 8004012: 683b ldr r3, [r7, #0] - 8004014: 689b ldr r3, [r3, #8] - 8004016: 041b lsls r3, r3, #16 - 8004018: 693a ldr r2, [r7, #16] - 800401a: 4313 orrs r3, r2 - 800401c: 613b str r3, [r7, #16] + 80040da: 683b ldr r3, [r7, #0] + 80040dc: 689b ldr r3, [r3, #8] + 80040de: 041b lsls r3, r3, #16 + 80040e0: 693a ldr r2, [r7, #16] + 80040e2: 4313 orrs r3, r2 + 80040e4: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 800401e: 687b ldr r3, [r7, #4] - 8004020: 4a12 ldr r2, [pc, #72] ; (800406c ) - 8004022: 4293 cmp r3, r2 - 8004024: d003 beq.n 800402e - 8004026: 687b ldr r3, [r7, #4] - 8004028: 4a11 ldr r2, [pc, #68] ; (8004070 ) - 800402a: 4293 cmp r3, r2 - 800402c: d109 bne.n 8004042 + 80040e6: 687b ldr r3, [r7, #4] + 80040e8: 4a12 ldr r2, [pc, #72] ; (8004134 ) + 80040ea: 4293 cmp r3, r2 + 80040ec: d003 beq.n 80040f6 + 80040ee: 687b ldr r3, [r7, #4] + 80040f0: 4a11 ldr r2, [pc, #68] ; (8004138 ) + 80040f2: 4293 cmp r3, r2 + 80040f4: d109 bne.n 800410a { /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS5; - 800402e: 697b ldr r3, [r7, #20] - 8004030: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 8004034: 617b str r3, [r7, #20] + 80040f6: 697b ldr r3, [r7, #20] + 80040f8: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 80040fc: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 8U); - 8004036: 683b ldr r3, [r7, #0] - 8004038: 695b ldr r3, [r3, #20] - 800403a: 021b lsls r3, r3, #8 - 800403c: 697a ldr r2, [r7, #20] - 800403e: 4313 orrs r3, r2 - 8004040: 617b str r3, [r7, #20] + 80040fe: 683b ldr r3, [r7, #0] + 8004100: 695b ldr r3, [r3, #20] + 8004102: 021b lsls r3, r3, #8 + 8004104: 697a ldr r2, [r7, #20] + 8004106: 4313 orrs r3, r2 + 8004108: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8004042: 687b ldr r3, [r7, #4] - 8004044: 697a ldr r2, [r7, #20] - 8004046: 605a str r2, [r3, #4] + 800410a: 687b ldr r3, [r7, #4] + 800410c: 697a ldr r2, [r7, #20] + 800410e: 605a str r2, [r3, #4] /* Write to TIMx CCMR3 */ TIMx->CCMR3 = tmpccmrx; - 8004048: 687b ldr r3, [r7, #4] - 800404a: 68fa ldr r2, [r7, #12] - 800404c: 655a str r2, [r3, #84] ; 0x54 + 8004110: 687b ldr r3, [r7, #4] + 8004112: 68fa ldr r2, [r7, #12] + 8004114: 655a str r2, [r3, #84] ; 0x54 /* Set the Capture Compare Register value */ TIMx->CCR5 = OC_Config->Pulse; - 800404e: 683b ldr r3, [r7, #0] - 8004050: 685a ldr r2, [r3, #4] - 8004052: 687b ldr r3, [r7, #4] - 8004054: 659a str r2, [r3, #88] ; 0x58 + 8004116: 683b ldr r3, [r7, #0] + 8004118: 685a ldr r2, [r3, #4] + 800411a: 687b ldr r3, [r7, #4] + 800411c: 659a str r2, [r3, #88] ; 0x58 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8004056: 687b ldr r3, [r7, #4] - 8004058: 693a ldr r2, [r7, #16] - 800405a: 621a str r2, [r3, #32] + 800411e: 687b ldr r3, [r7, #4] + 8004120: 693a ldr r2, [r7, #16] + 8004122: 621a str r2, [r3, #32] } - 800405c: bf00 nop - 800405e: 371c adds r7, #28 - 8004060: 46bd mov sp, r7 - 8004062: f85d 7b04 ldr.w r7, [sp], #4 - 8004066: 4770 bx lr - 8004068: fffeff8f .word 0xfffeff8f - 800406c: 40010000 .word 0x40010000 - 8004070: 40010400 .word 0x40010400 - -08004074 : + 8004124: bf00 nop + 8004126: 371c adds r7, #28 + 8004128: 46bd mov sp, r7 + 800412a: f85d 7b04 ldr.w r7, [sp], #4 + 800412e: 4770 bx lr + 8004130: fffeff8f .word 0xfffeff8f + 8004134: 40010000 .word 0x40010000 + 8004138: 40010400 .word 0x40010400 + +0800413c : * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC6_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8004074: b480 push {r7} - 8004076: b087 sub sp, #28 - 8004078: af00 add r7, sp, #0 - 800407a: 6078 str r0, [r7, #4] - 800407c: 6039 str r1, [r7, #0] + 800413c: b480 push {r7} + 800413e: b087 sub sp, #28 + 8004140: af00 add r7, sp, #0 + 8004142: 6078 str r0, [r7, #4] + 8004144: 6039 str r1, [r7, #0] uint32_t tmpccmrx; uint32_t tmpccer; uint32_t tmpcr2; /* Disable the output: Reset the CCxE Bit */ TIMx->CCER &= ~TIM_CCER_CC6E; - 800407e: 687b ldr r3, [r7, #4] - 8004080: 6a1b ldr r3, [r3, #32] - 8004082: f423 1280 bic.w r2, r3, #1048576 ; 0x100000 - 8004086: 687b ldr r3, [r7, #4] - 8004088: 621a str r2, [r3, #32] + 8004146: 687b ldr r3, [r7, #4] + 8004148: 6a1b ldr r3, [r3, #32] + 800414a: f423 1280 bic.w r2, r3, #1048576 ; 0x100000 + 800414e: 687b ldr r3, [r7, #4] + 8004150: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 800408a: 687b ldr r3, [r7, #4] - 800408c: 6a1b ldr r3, [r3, #32] - 800408e: 613b str r3, [r7, #16] + 8004152: 687b ldr r3, [r7, #4] + 8004154: 6a1b ldr r3, [r3, #32] + 8004156: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8004090: 687b ldr r3, [r7, #4] - 8004092: 685b ldr r3, [r3, #4] - 8004094: 617b str r3, [r7, #20] + 8004158: 687b ldr r3, [r7, #4] + 800415a: 685b ldr r3, [r3, #4] + 800415c: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR3; - 8004096: 687b ldr r3, [r7, #4] - 8004098: 6d5b ldr r3, [r3, #84] ; 0x54 - 800409a: 60fb str r3, [r7, #12] + 800415e: 687b ldr r3, [r7, #4] + 8004160: 6d5b ldr r3, [r3, #84] ; 0x54 + 8004162: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~(TIM_CCMR3_OC6M); - 800409c: 68fa ldr r2, [r7, #12] - 800409e: 4b1c ldr r3, [pc, #112] ; (8004110 ) - 80040a0: 4013 ands r3, r2 - 80040a2: 60fb str r3, [r7, #12] + 8004164: 68fa ldr r2, [r7, #12] + 8004166: 4b1c ldr r3, [pc, #112] ; (80041d8 ) + 8004168: 4013 ands r3, r2 + 800416a: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 80040a4: 683b ldr r3, [r7, #0] - 80040a6: 681b ldr r3, [r3, #0] - 80040a8: 021b lsls r3, r3, #8 - 80040aa: 68fa ldr r2, [r7, #12] - 80040ac: 4313 orrs r3, r2 - 80040ae: 60fb str r3, [r7, #12] + 800416c: 683b ldr r3, [r7, #0] + 800416e: 681b ldr r3, [r3, #0] + 8004170: 021b lsls r3, r3, #8 + 8004172: 68fa ldr r2, [r7, #12] + 8004174: 4313 orrs r3, r2 + 8004176: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= (uint32_t)~TIM_CCER_CC6P; - 80040b0: 693b ldr r3, [r7, #16] - 80040b2: f423 1300 bic.w r3, r3, #2097152 ; 0x200000 - 80040b6: 613b str r3, [r7, #16] + 8004178: 693b ldr r3, [r7, #16] + 800417a: f423 1300 bic.w r3, r3, #2097152 ; 0x200000 + 800417e: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 20U); - 80040b8: 683b ldr r3, [r7, #0] - 80040ba: 689b ldr r3, [r3, #8] - 80040bc: 051b lsls r3, r3, #20 - 80040be: 693a ldr r2, [r7, #16] - 80040c0: 4313 orrs r3, r2 - 80040c2: 613b str r3, [r7, #16] + 8004180: 683b ldr r3, [r7, #0] + 8004182: 689b ldr r3, [r3, #8] + 8004184: 051b lsls r3, r3, #20 + 8004186: 693a ldr r2, [r7, #16] + 8004188: 4313 orrs r3, r2 + 800418a: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 80040c4: 687b ldr r3, [r7, #4] - 80040c6: 4a13 ldr r2, [pc, #76] ; (8004114 ) - 80040c8: 4293 cmp r3, r2 - 80040ca: d003 beq.n 80040d4 - 80040cc: 687b ldr r3, [r7, #4] - 80040ce: 4a12 ldr r2, [pc, #72] ; (8004118 ) - 80040d0: 4293 cmp r3, r2 - 80040d2: d109 bne.n 80040e8 + 800418c: 687b ldr r3, [r7, #4] + 800418e: 4a13 ldr r2, [pc, #76] ; (80041dc ) + 8004190: 4293 cmp r3, r2 + 8004192: d003 beq.n 800419c + 8004194: 687b ldr r3, [r7, #4] + 8004196: 4a12 ldr r2, [pc, #72] ; (80041e0 ) + 8004198: 4293 cmp r3, r2 + 800419a: d109 bne.n 80041b0 { /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS6; - 80040d4: 697b ldr r3, [r7, #20] - 80040d6: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 80040da: 617b str r3, [r7, #20] + 800419c: 697b ldr r3, [r7, #20] + 800419e: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 80041a2: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 10U); - 80040dc: 683b ldr r3, [r7, #0] - 80040de: 695b ldr r3, [r3, #20] - 80040e0: 029b lsls r3, r3, #10 - 80040e2: 697a ldr r2, [r7, #20] - 80040e4: 4313 orrs r3, r2 - 80040e6: 617b str r3, [r7, #20] + 80041a4: 683b ldr r3, [r7, #0] + 80041a6: 695b ldr r3, [r3, #20] + 80041a8: 029b lsls r3, r3, #10 + 80041aa: 697a ldr r2, [r7, #20] + 80041ac: 4313 orrs r3, r2 + 80041ae: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 80040e8: 687b ldr r3, [r7, #4] - 80040ea: 697a ldr r2, [r7, #20] - 80040ec: 605a str r2, [r3, #4] + 80041b0: 687b ldr r3, [r7, #4] + 80041b2: 697a ldr r2, [r7, #20] + 80041b4: 605a str r2, [r3, #4] /* Write to TIMx CCMR3 */ TIMx->CCMR3 = tmpccmrx; - 80040ee: 687b ldr r3, [r7, #4] - 80040f0: 68fa ldr r2, [r7, #12] - 80040f2: 655a str r2, [r3, #84] ; 0x54 + 80041b6: 687b ldr r3, [r7, #4] + 80041b8: 68fa ldr r2, [r7, #12] + 80041ba: 655a str r2, [r3, #84] ; 0x54 /* Set the Capture Compare Register value */ TIMx->CCR6 = OC_Config->Pulse; - 80040f4: 683b ldr r3, [r7, #0] - 80040f6: 685a ldr r2, [r3, #4] - 80040f8: 687b ldr r3, [r7, #4] - 80040fa: 65da str r2, [r3, #92] ; 0x5c + 80041bc: 683b ldr r3, [r7, #0] + 80041be: 685a ldr r2, [r3, #4] + 80041c0: 687b ldr r3, [r7, #4] + 80041c2: 65da str r2, [r3, #92] ; 0x5c /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 80040fc: 687b ldr r3, [r7, #4] - 80040fe: 693a ldr r2, [r7, #16] - 8004100: 621a str r2, [r3, #32] + 80041c4: 687b ldr r3, [r7, #4] + 80041c6: 693a ldr r2, [r7, #16] + 80041c8: 621a str r2, [r3, #32] } - 8004102: bf00 nop - 8004104: 371c adds r7, #28 - 8004106: 46bd mov sp, r7 - 8004108: f85d 7b04 ldr.w r7, [sp], #4 - 800410c: 4770 bx lr - 800410e: bf00 nop - 8004110: feff8fff .word 0xfeff8fff - 8004114: 40010000 .word 0x40010000 - 8004118: 40010400 .word 0x40010400 - -0800411c : + 80041ca: bf00 nop + 80041cc: 371c adds r7, #28 + 80041ce: 46bd mov sp, r7 + 80041d0: f85d 7b04 ldr.w r7, [sp], #4 + 80041d4: 4770 bx lr + 80041d6: bf00 nop + 80041d8: feff8fff .word 0xfeff8fff + 80041dc: 40010000 .word 0x40010000 + 80041e0: 40010400 .word 0x40010400 + +080041e4 : * @param TIM_ICFilter Specifies the Input Capture Filter. * This parameter must be a value between 0x00 and 0x0F. * @retval None */ static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) { - 800411c: b480 push {r7} - 800411e: b087 sub sp, #28 - 8004120: af00 add r7, sp, #0 - 8004122: 60f8 str r0, [r7, #12] - 8004124: 60b9 str r1, [r7, #8] - 8004126: 607a str r2, [r7, #4] + 80041e4: b480 push {r7} + 80041e6: b087 sub sp, #28 + 80041e8: af00 add r7, sp, #0 + 80041ea: 60f8 str r0, [r7, #12] + 80041ec: 60b9 str r1, [r7, #8] + 80041ee: 607a str r2, [r7, #4] uint32_t tmpccmr1; uint32_t tmpccer; /* Disable the Channel 1: Reset the CC1E Bit */ tmpccer = TIMx->CCER; - 8004128: 68fb ldr r3, [r7, #12] - 800412a: 6a1b ldr r3, [r3, #32] - 800412c: 617b str r3, [r7, #20] + 80041f0: 68fb ldr r3, [r7, #12] + 80041f2: 6a1b ldr r3, [r3, #32] + 80041f4: 617b str r3, [r7, #20] TIMx->CCER &= ~TIM_CCER_CC1E; - 800412e: 68fb ldr r3, [r7, #12] - 8004130: 6a1b ldr r3, [r3, #32] - 8004132: f023 0201 bic.w r2, r3, #1 - 8004136: 68fb ldr r3, [r7, #12] - 8004138: 621a str r2, [r3, #32] + 80041f6: 68fb ldr r3, [r7, #12] + 80041f8: 6a1b ldr r3, [r3, #32] + 80041fa: f023 0201 bic.w r2, r3, #1 + 80041fe: 68fb ldr r3, [r7, #12] + 8004200: 621a str r2, [r3, #32] tmpccmr1 = TIMx->CCMR1; - 800413a: 68fb ldr r3, [r7, #12] - 800413c: 699b ldr r3, [r3, #24] - 800413e: 613b str r3, [r7, #16] + 8004202: 68fb ldr r3, [r7, #12] + 8004204: 699b ldr r3, [r3, #24] + 8004206: 613b str r3, [r7, #16] /* Set the filter */ tmpccmr1 &= ~TIM_CCMR1_IC1F; - 8004140: 693b ldr r3, [r7, #16] - 8004142: f023 03f0 bic.w r3, r3, #240 ; 0xf0 - 8004146: 613b str r3, [r7, #16] + 8004208: 693b ldr r3, [r7, #16] + 800420a: f023 03f0 bic.w r3, r3, #240 ; 0xf0 + 800420e: 613b str r3, [r7, #16] tmpccmr1 |= (TIM_ICFilter << 4U); - 8004148: 687b ldr r3, [r7, #4] - 800414a: 011b lsls r3, r3, #4 - 800414c: 693a ldr r2, [r7, #16] - 800414e: 4313 orrs r3, r2 - 8004150: 613b str r3, [r7, #16] + 8004210: 687b ldr r3, [r7, #4] + 8004212: 011b lsls r3, r3, #4 + 8004214: 693a ldr r2, [r7, #16] + 8004216: 4313 orrs r3, r2 + 8004218: 613b str r3, [r7, #16] /* Select the Polarity and set the CC1E Bit */ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - 8004152: 697b ldr r3, [r7, #20] - 8004154: f023 030a bic.w r3, r3, #10 - 8004158: 617b str r3, [r7, #20] + 800421a: 697b ldr r3, [r7, #20] + 800421c: f023 030a bic.w r3, r3, #10 + 8004220: 617b str r3, [r7, #20] tmpccer |= TIM_ICPolarity; - 800415a: 697a ldr r2, [r7, #20] - 800415c: 68bb ldr r3, [r7, #8] - 800415e: 4313 orrs r3, r2 - 8004160: 617b str r3, [r7, #20] + 8004222: 697a ldr r2, [r7, #20] + 8004224: 68bb ldr r3, [r7, #8] + 8004226: 4313 orrs r3, r2 + 8004228: 617b str r3, [r7, #20] /* Write to TIMx CCMR1 and CCER registers */ TIMx->CCMR1 = tmpccmr1; - 8004162: 68fb ldr r3, [r7, #12] - 8004164: 693a ldr r2, [r7, #16] - 8004166: 619a str r2, [r3, #24] + 800422a: 68fb ldr r3, [r7, #12] + 800422c: 693a ldr r2, [r7, #16] + 800422e: 619a str r2, [r3, #24] TIMx->CCER = tmpccer; - 8004168: 68fb ldr r3, [r7, #12] - 800416a: 697a ldr r2, [r7, #20] - 800416c: 621a str r2, [r3, #32] + 8004230: 68fb ldr r3, [r7, #12] + 8004232: 697a ldr r2, [r7, #20] + 8004234: 621a str r2, [r3, #32] } - 800416e: bf00 nop - 8004170: 371c adds r7, #28 - 8004172: 46bd mov sp, r7 - 8004174: f85d 7b04 ldr.w r7, [sp], #4 - 8004178: 4770 bx lr + 8004236: bf00 nop + 8004238: 371c adds r7, #28 + 800423a: 46bd mov sp, r7 + 800423c: f85d 7b04 ldr.w r7, [sp], #4 + 8004240: 4770 bx lr -0800417a : +08004242 : * @param TIM_ICFilter Specifies the Input Capture Filter. * This parameter must be a value between 0x00 and 0x0F. * @retval None */ static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) { - 800417a: b480 push {r7} - 800417c: b087 sub sp, #28 - 800417e: af00 add r7, sp, #0 - 8004180: 60f8 str r0, [r7, #12] - 8004182: 60b9 str r1, [r7, #8] - 8004184: 607a str r2, [r7, #4] + 8004242: b480 push {r7} + 8004244: b087 sub sp, #28 + 8004246: af00 add r7, sp, #0 + 8004248: 60f8 str r0, [r7, #12] + 800424a: 60b9 str r1, [r7, #8] + 800424c: 607a str r2, [r7, #4] uint32_t tmpccmr1; uint32_t tmpccer; /* Disable the Channel 2: Reset the CC2E Bit */ TIMx->CCER &= ~TIM_CCER_CC2E; - 8004186: 68fb ldr r3, [r7, #12] - 8004188: 6a1b ldr r3, [r3, #32] - 800418a: f023 0210 bic.w r2, r3, #16 - 800418e: 68fb ldr r3, [r7, #12] - 8004190: 621a str r2, [r3, #32] + 800424e: 68fb ldr r3, [r7, #12] + 8004250: 6a1b ldr r3, [r3, #32] + 8004252: f023 0210 bic.w r2, r3, #16 + 8004256: 68fb ldr r3, [r7, #12] + 8004258: 621a str r2, [r3, #32] tmpccmr1 = TIMx->CCMR1; - 8004192: 68fb ldr r3, [r7, #12] - 8004194: 699b ldr r3, [r3, #24] - 8004196: 617b str r3, [r7, #20] + 800425a: 68fb ldr r3, [r7, #12] + 800425c: 699b ldr r3, [r3, #24] + 800425e: 617b str r3, [r7, #20] tmpccer = TIMx->CCER; - 8004198: 68fb ldr r3, [r7, #12] - 800419a: 6a1b ldr r3, [r3, #32] - 800419c: 613b str r3, [r7, #16] + 8004260: 68fb ldr r3, [r7, #12] + 8004262: 6a1b ldr r3, [r3, #32] + 8004264: 613b str r3, [r7, #16] /* Set the filter */ tmpccmr1 &= ~TIM_CCMR1_IC2F; - 800419e: 697b ldr r3, [r7, #20] - 80041a0: f423 4370 bic.w r3, r3, #61440 ; 0xf000 - 80041a4: 617b str r3, [r7, #20] + 8004266: 697b ldr r3, [r7, #20] + 8004268: f423 4370 bic.w r3, r3, #61440 ; 0xf000 + 800426c: 617b str r3, [r7, #20] tmpccmr1 |= (TIM_ICFilter << 12U); - 80041a6: 687b ldr r3, [r7, #4] - 80041a8: 031b lsls r3, r3, #12 - 80041aa: 697a ldr r2, [r7, #20] - 80041ac: 4313 orrs r3, r2 - 80041ae: 617b str r3, [r7, #20] + 800426e: 687b ldr r3, [r7, #4] + 8004270: 031b lsls r3, r3, #12 + 8004272: 697a ldr r2, [r7, #20] + 8004274: 4313 orrs r3, r2 + 8004276: 617b str r3, [r7, #20] /* Select the Polarity and set the CC2E Bit */ tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - 80041b0: 693b ldr r3, [r7, #16] - 80041b2: f023 03a0 bic.w r3, r3, #160 ; 0xa0 - 80041b6: 613b str r3, [r7, #16] + 8004278: 693b ldr r3, [r7, #16] + 800427a: f023 03a0 bic.w r3, r3, #160 ; 0xa0 + 800427e: 613b str r3, [r7, #16] tmpccer |= (TIM_ICPolarity << 4U); - 80041b8: 68bb ldr r3, [r7, #8] - 80041ba: 011b lsls r3, r3, #4 - 80041bc: 693a ldr r2, [r7, #16] - 80041be: 4313 orrs r3, r2 - 80041c0: 613b str r3, [r7, #16] + 8004280: 68bb ldr r3, [r7, #8] + 8004282: 011b lsls r3, r3, #4 + 8004284: 693a ldr r2, [r7, #16] + 8004286: 4313 orrs r3, r2 + 8004288: 613b str r3, [r7, #16] /* Write to TIMx CCMR1 and CCER registers */ TIMx->CCMR1 = tmpccmr1 ; - 80041c2: 68fb ldr r3, [r7, #12] - 80041c4: 697a ldr r2, [r7, #20] - 80041c6: 619a str r2, [r3, #24] + 800428a: 68fb ldr r3, [r7, #12] + 800428c: 697a ldr r2, [r7, #20] + 800428e: 619a str r2, [r3, #24] TIMx->CCER = tmpccer; - 80041c8: 68fb ldr r3, [r7, #12] - 80041ca: 693a ldr r2, [r7, #16] - 80041cc: 621a str r2, [r3, #32] + 8004290: 68fb ldr r3, [r7, #12] + 8004292: 693a ldr r2, [r7, #16] + 8004294: 621a str r2, [r3, #32] } - 80041ce: bf00 nop - 80041d0: 371c adds r7, #28 - 80041d2: 46bd mov sp, r7 - 80041d4: f85d 7b04 ldr.w r7, [sp], #4 - 80041d8: 4770 bx lr + 8004296: bf00 nop + 8004298: 371c adds r7, #28 + 800429a: 46bd mov sp, r7 + 800429c: f85d 7b04 ldr.w r7, [sp], #4 + 80042a0: 4770 bx lr -080041da : +080042a2 : * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 * @arg TIM_TS_ETRF: External Trigger input * @retval None */ static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource) { - 80041da: b480 push {r7} - 80041dc: b085 sub sp, #20 - 80041de: af00 add r7, sp, #0 - 80041e0: 6078 str r0, [r7, #4] - 80041e2: 6039 str r1, [r7, #0] + 80042a2: b480 push {r7} + 80042a4: b085 sub sp, #20 + 80042a6: af00 add r7, sp, #0 + 80042a8: 6078 str r0, [r7, #4] + 80042aa: 6039 str r1, [r7, #0] uint32_t tmpsmcr; /* Get the TIMx SMCR register value */ tmpsmcr = TIMx->SMCR; - 80041e4: 687b ldr r3, [r7, #4] - 80041e6: 689b ldr r3, [r3, #8] - 80041e8: 60fb str r3, [r7, #12] + 80042ac: 687b ldr r3, [r7, #4] + 80042ae: 689b ldr r3, [r3, #8] + 80042b0: 60fb str r3, [r7, #12] /* Reset the TS Bits */ tmpsmcr &= ~TIM_SMCR_TS; - 80041ea: 68fb ldr r3, [r7, #12] - 80041ec: f023 0370 bic.w r3, r3, #112 ; 0x70 - 80041f0: 60fb str r3, [r7, #12] + 80042b2: 68fb ldr r3, [r7, #12] + 80042b4: f023 0370 bic.w r3, r3, #112 ; 0x70 + 80042b8: 60fb str r3, [r7, #12] /* Set the Input Trigger source and the slave mode*/ tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); - 80041f2: 683a ldr r2, [r7, #0] - 80041f4: 68fb ldr r3, [r7, #12] - 80041f6: 4313 orrs r3, r2 - 80041f8: f043 0307 orr.w r3, r3, #7 - 80041fc: 60fb str r3, [r7, #12] + 80042ba: 683a ldr r2, [r7, #0] + 80042bc: 68fb ldr r3, [r7, #12] + 80042be: 4313 orrs r3, r2 + 80042c0: f043 0307 orr.w r3, r3, #7 + 80042c4: 60fb str r3, [r7, #12] /* Write to TIMx SMCR */ TIMx->SMCR = tmpsmcr; - 80041fe: 687b ldr r3, [r7, #4] - 8004200: 68fa ldr r2, [r7, #12] - 8004202: 609a str r2, [r3, #8] + 80042c6: 687b ldr r3, [r7, #4] + 80042c8: 68fa ldr r2, [r7, #12] + 80042ca: 609a str r2, [r3, #8] } - 8004204: bf00 nop - 8004206: 3714 adds r7, #20 - 8004208: 46bd mov sp, r7 - 800420a: f85d 7b04 ldr.w r7, [sp], #4 - 800420e: 4770 bx lr + 80042cc: bf00 nop + 80042ce: 3714 adds r7, #20 + 80042d0: 46bd mov sp, r7 + 80042d2: f85d 7b04 ldr.w r7, [sp], #4 + 80042d6: 4770 bx lr -08004210 : +080042d8 : * This parameter must be a value between 0x00 and 0x0F * @retval None */ void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter) { - 8004210: b480 push {r7} - 8004212: b087 sub sp, #28 - 8004214: af00 add r7, sp, #0 - 8004216: 60f8 str r0, [r7, #12] - 8004218: 60b9 str r1, [r7, #8] - 800421a: 607a str r2, [r7, #4] - 800421c: 603b str r3, [r7, #0] + 80042d8: b480 push {r7} + 80042da: b087 sub sp, #28 + 80042dc: af00 add r7, sp, #0 + 80042de: 60f8 str r0, [r7, #12] + 80042e0: 60b9 str r1, [r7, #8] + 80042e2: 607a str r2, [r7, #4] + 80042e4: 603b str r3, [r7, #0] uint32_t tmpsmcr; tmpsmcr = TIMx->SMCR; - 800421e: 68fb ldr r3, [r7, #12] - 8004220: 689b ldr r3, [r3, #8] - 8004222: 617b str r3, [r7, #20] + 80042e6: 68fb ldr r3, [r7, #12] + 80042e8: 689b ldr r3, [r3, #8] + 80042ea: 617b str r3, [r7, #20] /* Reset the ETR Bits */ tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - 8004224: 697b ldr r3, [r7, #20] - 8004226: f423 437f bic.w r3, r3, #65280 ; 0xff00 - 800422a: 617b str r3, [r7, #20] + 80042ec: 697b ldr r3, [r7, #20] + 80042ee: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 80042f2: 617b str r3, [r7, #20] /* Set the Prescaler, the Filter value and the Polarity */ tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); - 800422c: 683b ldr r3, [r7, #0] - 800422e: 021a lsls r2, r3, #8 - 8004230: 687b ldr r3, [r7, #4] - 8004232: 431a orrs r2, r3 - 8004234: 68bb ldr r3, [r7, #8] - 8004236: 4313 orrs r3, r2 - 8004238: 697a ldr r2, [r7, #20] - 800423a: 4313 orrs r3, r2 - 800423c: 617b str r3, [r7, #20] + 80042f4: 683b ldr r3, [r7, #0] + 80042f6: 021a lsls r2, r3, #8 + 80042f8: 687b ldr r3, [r7, #4] + 80042fa: 431a orrs r2, r3 + 80042fc: 68bb ldr r3, [r7, #8] + 80042fe: 4313 orrs r3, r2 + 8004300: 697a ldr r2, [r7, #20] + 8004302: 4313 orrs r3, r2 + 8004304: 617b str r3, [r7, #20] /* Write to TIMx SMCR */ TIMx->SMCR = tmpsmcr; - 800423e: 68fb ldr r3, [r7, #12] - 8004240: 697a ldr r2, [r7, #20] - 8004242: 609a str r2, [r3, #8] + 8004306: 68fb ldr r3, [r7, #12] + 8004308: 697a ldr r2, [r7, #20] + 800430a: 609a str r2, [r3, #8] } - 8004244: bf00 nop - 8004246: 371c adds r7, #28 - 8004248: 46bd mov sp, r7 - 800424a: f85d 7b04 ldr.w r7, [sp], #4 - 800424e: 4770 bx lr + 800430c: bf00 nop + 800430e: 371c adds r7, #28 + 8004310: 46bd mov sp, r7 + 8004312: f85d 7b04 ldr.w r7, [sp], #4 + 8004316: 4770 bx lr -08004250 : +08004318 : * @param ChannelState specifies the TIM Channel CCxE bit new state. * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE. * @retval None */ void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState) { - 8004250: b480 push {r7} - 8004252: b087 sub sp, #28 - 8004254: af00 add r7, sp, #0 - 8004256: 60f8 str r0, [r7, #12] - 8004258: 60b9 str r1, [r7, #8] - 800425a: 607a str r2, [r7, #4] + 8004318: b480 push {r7} + 800431a: b087 sub sp, #28 + 800431c: af00 add r7, sp, #0 + 800431e: 60f8 str r0, [r7, #12] + 8004320: 60b9 str r1, [r7, #8] + 8004322: 607a str r2, [r7, #4] /* Check the parameters */ assert_param(IS_TIM_CC1_INSTANCE(TIMx)); assert_param(IS_TIM_CHANNELS(Channel)); tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ - 800425c: 68bb ldr r3, [r7, #8] - 800425e: f003 031f and.w r3, r3, #31 - 8004262: 2201 movs r2, #1 - 8004264: fa02 f303 lsl.w r3, r2, r3 - 8004268: 617b str r3, [r7, #20] + 8004324: 68bb ldr r3, [r7, #8] + 8004326: f003 031f and.w r3, r3, #31 + 800432a: 2201 movs r2, #1 + 800432c: fa02 f303 lsl.w r3, r2, r3 + 8004330: 617b str r3, [r7, #20] /* Reset the CCxE Bit */ TIMx->CCER &= ~tmp; - 800426a: 68fb ldr r3, [r7, #12] - 800426c: 6a1a ldr r2, [r3, #32] - 800426e: 697b ldr r3, [r7, #20] - 8004270: 43db mvns r3, r3 - 8004272: 401a ands r2, r3 - 8004274: 68fb ldr r3, [r7, #12] - 8004276: 621a str r2, [r3, #32] + 8004332: 68fb ldr r3, [r7, #12] + 8004334: 6a1a ldr r2, [r3, #32] + 8004336: 697b ldr r3, [r7, #20] + 8004338: 43db mvns r3, r3 + 800433a: 401a ands r2, r3 + 800433c: 68fb ldr r3, [r7, #12] + 800433e: 621a str r2, [r3, #32] /* Set or reset the CCxE Bit */ TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ - 8004278: 68fb ldr r3, [r7, #12] - 800427a: 6a1a ldr r2, [r3, #32] - 800427c: 68bb ldr r3, [r7, #8] - 800427e: f003 031f and.w r3, r3, #31 - 8004282: 6879 ldr r1, [r7, #4] - 8004284: fa01 f303 lsl.w r3, r1, r3 - 8004288: 431a orrs r2, r3 - 800428a: 68fb ldr r3, [r7, #12] - 800428c: 621a str r2, [r3, #32] + 8004340: 68fb ldr r3, [r7, #12] + 8004342: 6a1a ldr r2, [r3, #32] + 8004344: 68bb ldr r3, [r7, #8] + 8004346: f003 031f and.w r3, r3, #31 + 800434a: 6879 ldr r1, [r7, #4] + 800434c: fa01 f303 lsl.w r3, r1, r3 + 8004350: 431a orrs r2, r3 + 8004352: 68fb ldr r3, [r7, #12] + 8004354: 621a str r2, [r3, #32] } - 800428e: bf00 nop - 8004290: 371c adds r7, #28 - 8004292: 46bd mov sp, r7 - 8004294: f85d 7b04 ldr.w r7, [sp], #4 - 8004298: 4770 bx lr + 8004356: bf00 nop + 8004358: 371c adds r7, #28 + 800435a: 46bd mov sp, r7 + 800435c: f85d 7b04 ldr.w r7, [sp], #4 + 8004360: 4770 bx lr ... -0800429c : +08004364 : * mode. * @retval HAL status */ HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, TIM_MasterConfigTypeDef *sMasterConfig) { - 800429c: b480 push {r7} - 800429e: b085 sub sp, #20 - 80042a0: af00 add r7, sp, #0 - 80042a2: 6078 str r0, [r7, #4] - 80042a4: 6039 str r1, [r7, #0] + 8004364: b480 push {r7} + 8004366: b085 sub sp, #20 + 8004368: af00 add r7, sp, #0 + 800436a: 6078 str r0, [r7, #4] + 800436c: 6039 str r1, [r7, #0] assert_param(IS_TIM_SYNCHRO_INSTANCE(htim->Instance)); assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger)); assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode)); /* Check input state */ __HAL_LOCK(htim); - 80042a6: 687b ldr r3, [r7, #4] - 80042a8: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 80042ac: 2b01 cmp r3, #1 - 80042ae: d101 bne.n 80042b4 - 80042b0: 2302 movs r3, #2 - 80042b2: e045 b.n 8004340 - 80042b4: 687b ldr r3, [r7, #4] - 80042b6: 2201 movs r2, #1 - 80042b8: f883 203c strb.w r2, [r3, #60] ; 0x3c + 800436e: 687b ldr r3, [r7, #4] + 8004370: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8004374: 2b01 cmp r3, #1 + 8004376: d101 bne.n 800437c + 8004378: 2302 movs r3, #2 + 800437a: e045 b.n 8004408 + 800437c: 687b ldr r3, [r7, #4] + 800437e: 2201 movs r2, #1 + 8004380: f883 203c strb.w r2, [r3, #60] ; 0x3c /* Change the handler state */ htim->State = HAL_TIM_STATE_BUSY; - 80042bc: 687b ldr r3, [r7, #4] - 80042be: 2202 movs r2, #2 - 80042c0: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8004384: 687b ldr r3, [r7, #4] + 8004386: 2202 movs r2, #2 + 8004388: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Get the TIMx CR2 register value */ tmpcr2 = htim->Instance->CR2; - 80042c4: 687b ldr r3, [r7, #4] - 80042c6: 681b ldr r3, [r3, #0] - 80042c8: 685b ldr r3, [r3, #4] - 80042ca: 60fb str r3, [r7, #12] + 800438c: 687b ldr r3, [r7, #4] + 800438e: 681b ldr r3, [r3, #0] + 8004390: 685b ldr r3, [r3, #4] + 8004392: 60fb str r3, [r7, #12] /* Get the TIMx SMCR register value */ tmpsmcr = htim->Instance->SMCR; - 80042cc: 687b ldr r3, [r7, #4] - 80042ce: 681b ldr r3, [r3, #0] - 80042d0: 689b ldr r3, [r3, #8] - 80042d2: 60bb str r3, [r7, #8] + 8004394: 687b ldr r3, [r7, #4] + 8004396: 681b ldr r3, [r3, #0] + 8004398: 689b ldr r3, [r3, #8] + 800439a: 60bb str r3, [r7, #8] /* If the timer supports ADC synchronization through TRGO2, set the master mode selection 2 */ if (IS_TIM_TRGO2_INSTANCE(htim->Instance)) - 80042d4: 687b ldr r3, [r7, #4] - 80042d6: 681b ldr r3, [r3, #0] - 80042d8: 4a1c ldr r2, [pc, #112] ; (800434c ) - 80042da: 4293 cmp r3, r2 - 80042dc: d004 beq.n 80042e8 - 80042de: 687b ldr r3, [r7, #4] - 80042e0: 681b ldr r3, [r3, #0] - 80042e2: 4a1b ldr r2, [pc, #108] ; (8004350 ) - 80042e4: 4293 cmp r3, r2 - 80042e6: d108 bne.n 80042fa + 800439c: 687b ldr r3, [r7, #4] + 800439e: 681b ldr r3, [r3, #0] + 80043a0: 4a1c ldr r2, [pc, #112] ; (8004414 ) + 80043a2: 4293 cmp r3, r2 + 80043a4: d004 beq.n 80043b0 + 80043a6: 687b ldr r3, [r7, #4] + 80043a8: 681b ldr r3, [r3, #0] + 80043aa: 4a1b ldr r2, [pc, #108] ; (8004418 ) + 80043ac: 4293 cmp r3, r2 + 80043ae: d108 bne.n 80043c2 { /* Check the parameters */ assert_param(IS_TIM_TRGO2_SOURCE(sMasterConfig->MasterOutputTrigger2)); /* Clear the MMS2 bits */ tmpcr2 &= ~TIM_CR2_MMS2; - 80042e8: 68fb ldr r3, [r7, #12] - 80042ea: f423 0370 bic.w r3, r3, #15728640 ; 0xf00000 - 80042ee: 60fb str r3, [r7, #12] + 80043b0: 68fb ldr r3, [r7, #12] + 80043b2: f423 0370 bic.w r3, r3, #15728640 ; 0xf00000 + 80043b6: 60fb str r3, [r7, #12] /* Select the TRGO2 source*/ tmpcr2 |= sMasterConfig->MasterOutputTrigger2; - 80042f0: 683b ldr r3, [r7, #0] - 80042f2: 685b ldr r3, [r3, #4] - 80042f4: 68fa ldr r2, [r7, #12] - 80042f6: 4313 orrs r3, r2 - 80042f8: 60fb str r3, [r7, #12] + 80043b8: 683b ldr r3, [r7, #0] + 80043ba: 685b ldr r3, [r3, #4] + 80043bc: 68fa ldr r2, [r7, #12] + 80043be: 4313 orrs r3, r2 + 80043c0: 60fb str r3, [r7, #12] } /* Reset the MMS Bits */ tmpcr2 &= ~TIM_CR2_MMS; - 80042fa: 68fb ldr r3, [r7, #12] - 80042fc: f023 0370 bic.w r3, r3, #112 ; 0x70 - 8004300: 60fb str r3, [r7, #12] + 80043c2: 68fb ldr r3, [r7, #12] + 80043c4: f023 0370 bic.w r3, r3, #112 ; 0x70 + 80043c8: 60fb str r3, [r7, #12] /* Select the TRGO source */ tmpcr2 |= sMasterConfig->MasterOutputTrigger; - 8004302: 683b ldr r3, [r7, #0] - 8004304: 681b ldr r3, [r3, #0] - 8004306: 68fa ldr r2, [r7, #12] - 8004308: 4313 orrs r3, r2 - 800430a: 60fb str r3, [r7, #12] + 80043ca: 683b ldr r3, [r7, #0] + 80043cc: 681b ldr r3, [r3, #0] + 80043ce: 68fa ldr r2, [r7, #12] + 80043d0: 4313 orrs r3, r2 + 80043d2: 60fb str r3, [r7, #12] /* Reset the MSM Bit */ tmpsmcr &= ~TIM_SMCR_MSM; - 800430c: 68bb ldr r3, [r7, #8] - 800430e: f023 0380 bic.w r3, r3, #128 ; 0x80 - 8004312: 60bb str r3, [r7, #8] + 80043d4: 68bb ldr r3, [r7, #8] + 80043d6: f023 0380 bic.w r3, r3, #128 ; 0x80 + 80043da: 60bb str r3, [r7, #8] /* Set master mode */ tmpsmcr |= sMasterConfig->MasterSlaveMode; - 8004314: 683b ldr r3, [r7, #0] - 8004316: 689b ldr r3, [r3, #8] - 8004318: 68ba ldr r2, [r7, #8] - 800431a: 4313 orrs r3, r2 - 800431c: 60bb str r3, [r7, #8] + 80043dc: 683b ldr r3, [r7, #0] + 80043de: 689b ldr r3, [r3, #8] + 80043e0: 68ba ldr r2, [r7, #8] + 80043e2: 4313 orrs r3, r2 + 80043e4: 60bb str r3, [r7, #8] /* Update TIMx CR2 */ htim->Instance->CR2 = tmpcr2; - 800431e: 687b ldr r3, [r7, #4] - 8004320: 681b ldr r3, [r3, #0] - 8004322: 68fa ldr r2, [r7, #12] - 8004324: 605a str r2, [r3, #4] + 80043e6: 687b ldr r3, [r7, #4] + 80043e8: 681b ldr r3, [r3, #0] + 80043ea: 68fa ldr r2, [r7, #12] + 80043ec: 605a str r2, [r3, #4] /* Update TIMx SMCR */ htim->Instance->SMCR = tmpsmcr; - 8004326: 687b ldr r3, [r7, #4] - 8004328: 681b ldr r3, [r3, #0] - 800432a: 68ba ldr r2, [r7, #8] - 800432c: 609a str r2, [r3, #8] + 80043ee: 687b ldr r3, [r7, #4] + 80043f0: 681b ldr r3, [r3, #0] + 80043f2: 68ba ldr r2, [r7, #8] + 80043f4: 609a str r2, [r3, #8] /* Change the htim state */ htim->State = HAL_TIM_STATE_READY; - 800432e: 687b ldr r3, [r7, #4] - 8004330: 2201 movs r2, #1 - 8004332: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80043f6: 687b ldr r3, [r7, #4] + 80043f8: 2201 movs r2, #1 + 80043fa: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 8004336: 687b ldr r3, [r7, #4] - 8004338: 2200 movs r2, #0 - 800433a: f883 203c strb.w r2, [r3, #60] ; 0x3c + 80043fe: 687b ldr r3, [r7, #4] + 8004400: 2200 movs r2, #0 + 8004402: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 800433e: 2300 movs r3, #0 + 8004406: 2300 movs r3, #0 } - 8004340: 4618 mov r0, r3 - 8004342: 3714 adds r7, #20 - 8004344: 46bd mov sp, r7 - 8004346: f85d 7b04 ldr.w r7, [sp], #4 - 800434a: 4770 bx lr - 800434c: 40010000 .word 0x40010000 - 8004350: 40010400 .word 0x40010400 - -08004354 : + 8004408: 4618 mov r0, r3 + 800440a: 3714 adds r7, #20 + 800440c: 46bd mov sp, r7 + 800440e: f85d 7b04 ldr.w r7, [sp], #4 + 8004412: 4770 bx lr + 8004414: 40010000 .word 0x40010000 + 8004418: 40010400 .word 0x40010400 + +0800441c : * @brief Hall commutation changed callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) { - 8004354: b480 push {r7} - 8004356: b083 sub sp, #12 - 8004358: af00 add r7, sp, #0 - 800435a: 6078 str r0, [r7, #4] + 800441c: b480 push {r7} + 800441e: b083 sub sp, #12 + 8004420: af00 add r7, sp, #0 + 8004422: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIMEx_CommutCallback could be implemented in the user file */ } - 800435c: bf00 nop - 800435e: 370c adds r7, #12 - 8004360: 46bd mov sp, r7 - 8004362: f85d 7b04 ldr.w r7, [sp], #4 - 8004366: 4770 bx lr + 8004424: bf00 nop + 8004426: 370c adds r7, #12 + 8004428: 46bd mov sp, r7 + 800442a: f85d 7b04 ldr.w r7, [sp], #4 + 800442e: 4770 bx lr -08004368 : +08004430 : * @brief Hall Break detection callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) { - 8004368: b480 push {r7} - 800436a: b083 sub sp, #12 - 800436c: af00 add r7, sp, #0 - 800436e: 6078 str r0, [r7, #4] + 8004430: b480 push {r7} + 8004432: b083 sub sp, #12 + 8004434: af00 add r7, sp, #0 + 8004436: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function should not be modified, when the callback is needed, the HAL_TIMEx_BreakCallback could be implemented in the user file */ } - 8004370: bf00 nop - 8004372: 370c adds r7, #12 - 8004374: 46bd mov sp, r7 - 8004376: f85d 7b04 ldr.w r7, [sp], #4 - 800437a: 4770 bx lr + 8004438: bf00 nop + 800443a: 370c adds r7, #12 + 800443c: 46bd mov sp, r7 + 800443e: f85d 7b04 ldr.w r7, [sp], #4 + 8004442: 4770 bx lr -0800437c : +08004444 : * @brief Hall Break2 detection callback in non blocking mode * @param htim: TIM handle * @retval None */ __weak void HAL_TIMEx_Break2Callback(TIM_HandleTypeDef *htim) { - 800437c: b480 push {r7} - 800437e: b083 sub sp, #12 - 8004380: af00 add r7, sp, #0 - 8004382: 6078 str r0, [r7, #4] + 8004444: b480 push {r7} + 8004446: b083 sub sp, #12 + 8004448: af00 add r7, sp, #0 + 800444a: 6078 str r0, [r7, #4] UNUSED(htim); /* NOTE : This function Should not be modified, when the callback is needed, the HAL_TIMEx_Break2Callback could be implemented in the user file */ } - 8004384: bf00 nop - 8004386: 370c adds r7, #12 - 8004388: 46bd mov sp, r7 - 800438a: f85d 7b04 ldr.w r7, [sp], #4 - 800438e: 4770 bx lr + 800444c: bf00 nop + 800444e: 370c adds r7, #12 + 8004450: 46bd mov sp, r7 + 8004452: f85d 7b04 ldr.w r7, [sp], #4 + 8004456: 4770 bx lr -08004390 : +08004458 : * parameters in the UART_InitTypeDef and initialize the associated handle. * @param huart UART handle. * @retval HAL status */ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) { - 8004390: b580 push {r7, lr} - 8004392: b082 sub sp, #8 - 8004394: af00 add r7, sp, #0 - 8004396: 6078 str r0, [r7, #4] + 8004458: b580 push {r7, lr} + 800445a: b082 sub sp, #8 + 800445c: af00 add r7, sp, #0 + 800445e: 6078 str r0, [r7, #4] /* Check the UART handle allocation */ if (huart == NULL) - 8004398: 687b ldr r3, [r7, #4] - 800439a: 2b00 cmp r3, #0 - 800439c: d101 bne.n 80043a2 + 8004460: 687b ldr r3, [r7, #4] + 8004462: 2b00 cmp r3, #0 + 8004464: d101 bne.n 800446a { return HAL_ERROR; - 800439e: 2301 movs r3, #1 - 80043a0: e040 b.n 8004424 + 8004466: 2301 movs r3, #1 + 8004468: e040 b.n 80044ec { /* Check the parameters */ assert_param(IS_UART_INSTANCE(huart->Instance)); } if (huart->gState == HAL_UART_STATE_RESET) - 80043a2: 687b ldr r3, [r7, #4] - 80043a4: 6f5b ldr r3, [r3, #116] ; 0x74 - 80043a6: 2b00 cmp r3, #0 - 80043a8: d106 bne.n 80043b8 + 800446a: 687b ldr r3, [r7, #4] + 800446c: 6f5b ldr r3, [r3, #116] ; 0x74 + 800446e: 2b00 cmp r3, #0 + 8004470: d106 bne.n 8004480 { /* Allocate lock resource and initialize it */ huart->Lock = HAL_UNLOCKED; - 80043aa: 687b ldr r3, [r7, #4] - 80043ac: 2200 movs r2, #0 - 80043ae: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004472: 687b ldr r3, [r7, #4] + 8004474: 2200 movs r2, #0 + 8004476: f883 2070 strb.w r2, [r3, #112] ; 0x70 /* Init the low level hardware */ huart->MspInitCallback(huart); #else /* Init the low level hardware : GPIO, CLOCK */ HAL_UART_MspInit(huart); - 80043b2: 6878 ldr r0, [r7, #4] - 80043b4: f7fd fa38 bl 8001828 + 800447a: 6878 ldr r0, [r7, #4] + 800447c: f7fd fa38 bl 80018f0 #endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ } huart->gState = HAL_UART_STATE_BUSY; - 80043b8: 687b ldr r3, [r7, #4] - 80043ba: 2224 movs r2, #36 ; 0x24 - 80043bc: 675a str r2, [r3, #116] ; 0x74 + 8004480: 687b ldr r3, [r7, #4] + 8004482: 2224 movs r2, #36 ; 0x24 + 8004484: 675a str r2, [r3, #116] ; 0x74 /* Disable the Peripheral */ __HAL_UART_DISABLE(huart); - 80043be: 687b ldr r3, [r7, #4] - 80043c0: 681b ldr r3, [r3, #0] - 80043c2: 681a ldr r2, [r3, #0] - 80043c4: 687b ldr r3, [r7, #4] - 80043c6: 681b ldr r3, [r3, #0] - 80043c8: f022 0201 bic.w r2, r2, #1 - 80043cc: 601a str r2, [r3, #0] + 8004486: 687b ldr r3, [r7, #4] + 8004488: 681b ldr r3, [r3, #0] + 800448a: 681a ldr r2, [r3, #0] + 800448c: 687b ldr r3, [r7, #4] + 800448e: 681b ldr r3, [r3, #0] + 8004490: f022 0201 bic.w r2, r2, #1 + 8004494: 601a str r2, [r3, #0] /* Set the UART Communication parameters */ if (UART_SetConfig(huart) == HAL_ERROR) - 80043ce: 6878 ldr r0, [r7, #4] - 80043d0: f000 fa90 bl 80048f4 - 80043d4: 4603 mov r3, r0 - 80043d6: 2b01 cmp r3, #1 - 80043d8: d101 bne.n 80043de + 8004496: 6878 ldr r0, [r7, #4] + 8004498: f000 fa90 bl 80049bc + 800449c: 4603 mov r3, r0 + 800449e: 2b01 cmp r3, #1 + 80044a0: d101 bne.n 80044a6 { return HAL_ERROR; - 80043da: 2301 movs r3, #1 - 80043dc: e022 b.n 8004424 + 80044a2: 2301 movs r3, #1 + 80044a4: e022 b.n 80044ec } if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT) - 80043de: 687b ldr r3, [r7, #4] - 80043e0: 6a5b ldr r3, [r3, #36] ; 0x24 - 80043e2: 2b00 cmp r3, #0 - 80043e4: d002 beq.n 80043ec + 80044a6: 687b ldr r3, [r7, #4] + 80044a8: 6a5b ldr r3, [r3, #36] ; 0x24 + 80044aa: 2b00 cmp r3, #0 + 80044ac: d002 beq.n 80044b4 { UART_AdvFeatureConfig(huart); - 80043e6: 6878 ldr r0, [r7, #4] - 80043e8: f000 fd28 bl 8004e3c + 80044ae: 6878 ldr r0, [r7, #4] + 80044b0: f000 fd28 bl 8004f04 } /* In asynchronous mode, the following bits must be kept cleared: - LINEN and CLKEN bits in the USART_CR2 register, - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - 80043ec: 687b ldr r3, [r7, #4] - 80043ee: 681b ldr r3, [r3, #0] - 80043f0: 685a ldr r2, [r3, #4] - 80043f2: 687b ldr r3, [r7, #4] - 80043f4: 681b ldr r3, [r3, #0] - 80043f6: f422 4290 bic.w r2, r2, #18432 ; 0x4800 - 80043fa: 605a str r2, [r3, #4] + 80044b4: 687b ldr r3, [r7, #4] + 80044b6: 681b ldr r3, [r3, #0] + 80044b8: 685a ldr r2, [r3, #4] + 80044ba: 687b ldr r3, [r7, #4] + 80044bc: 681b ldr r3, [r3, #0] + 80044be: f422 4290 bic.w r2, r2, #18432 ; 0x4800 + 80044c2: 605a str r2, [r3, #4] CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - 80043fc: 687b ldr r3, [r7, #4] - 80043fe: 681b ldr r3, [r3, #0] - 8004400: 689a ldr r2, [r3, #8] - 8004402: 687b ldr r3, [r7, #4] - 8004404: 681b ldr r3, [r3, #0] - 8004406: f022 022a bic.w r2, r2, #42 ; 0x2a - 800440a: 609a str r2, [r3, #8] + 80044c4: 687b ldr r3, [r7, #4] + 80044c6: 681b ldr r3, [r3, #0] + 80044c8: 689a ldr r2, [r3, #8] + 80044ca: 687b ldr r3, [r7, #4] + 80044cc: 681b ldr r3, [r3, #0] + 80044ce: f022 022a bic.w r2, r2, #42 ; 0x2a + 80044d2: 609a str r2, [r3, #8] /* Enable the Peripheral */ __HAL_UART_ENABLE(huart); - 800440c: 687b ldr r3, [r7, #4] - 800440e: 681b ldr r3, [r3, #0] - 8004410: 681a ldr r2, [r3, #0] - 8004412: 687b ldr r3, [r7, #4] - 8004414: 681b ldr r3, [r3, #0] - 8004416: f042 0201 orr.w r2, r2, #1 - 800441a: 601a str r2, [r3, #0] + 80044d4: 687b ldr r3, [r7, #4] + 80044d6: 681b ldr r3, [r3, #0] + 80044d8: 681a ldr r2, [r3, #0] + 80044da: 687b ldr r3, [r7, #4] + 80044dc: 681b ldr r3, [r3, #0] + 80044de: f042 0201 orr.w r2, r2, #1 + 80044e2: 601a str r2, [r3, #0] /* TEACK and/or REACK to check before moving huart->gState and huart->RxState to Ready */ return (UART_CheckIdleState(huart)); - 800441c: 6878 ldr r0, [r7, #4] - 800441e: f000 fdaf bl 8004f80 - 8004422: 4603 mov r3, r0 + 80044e4: 6878 ldr r0, [r7, #4] + 80044e6: f000 fdaf bl 8005048 + 80044ea: 4603 mov r3, r0 } - 8004424: 4618 mov r0, r3 - 8004426: 3708 adds r7, #8 - 8004428: 46bd mov sp, r7 - 800442a: bd80 pop {r7, pc} + 80044ec: 4618 mov r0, r3 + 80044ee: 3708 adds r7, #8 + 80044f0: 46bd mov sp, r7 + 80044f2: bd80 pop {r7, pc} -0800442c : +080044f4 : * @param Size Amount of data to be sent. * @param Timeout Timeout duration. * @retval HAL status */ HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) { - 800442c: b580 push {r7, lr} - 800442e: b08a sub sp, #40 ; 0x28 - 8004430: af02 add r7, sp, #8 - 8004432: 60f8 str r0, [r7, #12] - 8004434: 60b9 str r1, [r7, #8] - 8004436: 603b str r3, [r7, #0] - 8004438: 4613 mov r3, r2 - 800443a: 80fb strh r3, [r7, #6] + 80044f4: b580 push {r7, lr} + 80044f6: b08a sub sp, #40 ; 0x28 + 80044f8: af02 add r7, sp, #8 + 80044fa: 60f8 str r0, [r7, #12] + 80044fc: 60b9 str r1, [r7, #8] + 80044fe: 603b str r3, [r7, #0] + 8004500: 4613 mov r3, r2 + 8004502: 80fb strh r3, [r7, #6] uint8_t *pdata8bits; uint16_t *pdata16bits; uint32_t tickstart; /* Check that a Tx process is not already ongoing */ if (huart->gState == HAL_UART_STATE_READY) - 800443c: 68fb ldr r3, [r7, #12] - 800443e: 6f5b ldr r3, [r3, #116] ; 0x74 - 8004440: 2b20 cmp r3, #32 - 8004442: d17f bne.n 8004544 + 8004504: 68fb ldr r3, [r7, #12] + 8004506: 6f5b ldr r3, [r3, #116] ; 0x74 + 8004508: 2b20 cmp r3, #32 + 800450a: d17f bne.n 800460c { if ((pData == NULL) || (Size == 0U)) - 8004444: 68bb ldr r3, [r7, #8] - 8004446: 2b00 cmp r3, #0 - 8004448: d002 beq.n 8004450 - 800444a: 88fb ldrh r3, [r7, #6] - 800444c: 2b00 cmp r3, #0 - 800444e: d101 bne.n 8004454 + 800450c: 68bb ldr r3, [r7, #8] + 800450e: 2b00 cmp r3, #0 + 8004510: d002 beq.n 8004518 + 8004512: 88fb ldrh r3, [r7, #6] + 8004514: 2b00 cmp r3, #0 + 8004516: d101 bne.n 800451c { return HAL_ERROR; - 8004450: 2301 movs r3, #1 - 8004452: e078 b.n 8004546 + 8004518: 2301 movs r3, #1 + 800451a: e078 b.n 800460e } /* Process Locked */ __HAL_LOCK(huart); - 8004454: 68fb ldr r3, [r7, #12] - 8004456: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 - 800445a: 2b01 cmp r3, #1 - 800445c: d101 bne.n 8004462 - 800445e: 2302 movs r3, #2 - 8004460: e071 b.n 8004546 - 8004462: 68fb ldr r3, [r7, #12] - 8004464: 2201 movs r2, #1 - 8004466: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 800451c: 68fb ldr r3, [r7, #12] + 800451e: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 + 8004522: 2b01 cmp r3, #1 + 8004524: d101 bne.n 800452a + 8004526: 2302 movs r3, #2 + 8004528: e071 b.n 800460e + 800452a: 68fb ldr r3, [r7, #12] + 800452c: 2201 movs r2, #1 + 800452e: f883 2070 strb.w r2, [r3, #112] ; 0x70 huart->ErrorCode = HAL_UART_ERROR_NONE; - 800446a: 68fb ldr r3, [r7, #12] - 800446c: 2200 movs r2, #0 - 800446e: 67da str r2, [r3, #124] ; 0x7c + 8004532: 68fb ldr r3, [r7, #12] + 8004534: 2200 movs r2, #0 + 8004536: 67da str r2, [r3, #124] ; 0x7c huart->gState = HAL_UART_STATE_BUSY_TX; - 8004470: 68fb ldr r3, [r7, #12] - 8004472: 2221 movs r2, #33 ; 0x21 - 8004474: 675a str r2, [r3, #116] ; 0x74 + 8004538: 68fb ldr r3, [r7, #12] + 800453a: 2221 movs r2, #33 ; 0x21 + 800453c: 675a str r2, [r3, #116] ; 0x74 /* Init tickstart for timeout managment*/ tickstart = HAL_GetTick(); - 8004476: f7fd fb1f bl 8001ab8 - 800447a: 6178 str r0, [r7, #20] + 800453e: f7fd fb1f bl 8001b80 + 8004542: 6178 str r0, [r7, #20] huart->TxXferSize = Size; - 800447c: 68fb ldr r3, [r7, #12] - 800447e: 88fa ldrh r2, [r7, #6] - 8004480: f8a3 2050 strh.w r2, [r3, #80] ; 0x50 + 8004544: 68fb ldr r3, [r7, #12] + 8004546: 88fa ldrh r2, [r7, #6] + 8004548: f8a3 2050 strh.w r2, [r3, #80] ; 0x50 huart->TxXferCount = Size; - 8004484: 68fb ldr r3, [r7, #12] - 8004486: 88fa ldrh r2, [r7, #6] - 8004488: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 800454c: 68fb ldr r3, [r7, #12] + 800454e: 88fa ldrh r2, [r7, #6] + 8004550: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - 800448c: 68fb ldr r3, [r7, #12] - 800448e: 689b ldr r3, [r3, #8] - 8004490: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004494: d108 bne.n 80044a8 - 8004496: 68fb ldr r3, [r7, #12] - 8004498: 691b ldr r3, [r3, #16] - 800449a: 2b00 cmp r3, #0 - 800449c: d104 bne.n 80044a8 + 8004554: 68fb ldr r3, [r7, #12] + 8004556: 689b ldr r3, [r3, #8] + 8004558: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 800455c: d108 bne.n 8004570 + 800455e: 68fb ldr r3, [r7, #12] + 8004560: 691b ldr r3, [r3, #16] + 8004562: 2b00 cmp r3, #0 + 8004564: d104 bne.n 8004570 { pdata8bits = NULL; - 800449e: 2300 movs r3, #0 - 80044a0: 61fb str r3, [r7, #28] + 8004566: 2300 movs r3, #0 + 8004568: 61fb str r3, [r7, #28] pdata16bits = (uint16_t *) pData; - 80044a2: 68bb ldr r3, [r7, #8] - 80044a4: 61bb str r3, [r7, #24] - 80044a6: e003 b.n 80044b0 + 800456a: 68bb ldr r3, [r7, #8] + 800456c: 61bb str r3, [r7, #24] + 800456e: e003 b.n 8004578 } else { pdata8bits = pData; - 80044a8: 68bb ldr r3, [r7, #8] - 80044aa: 61fb str r3, [r7, #28] + 8004570: 68bb ldr r3, [r7, #8] + 8004572: 61fb str r3, [r7, #28] pdata16bits = NULL; - 80044ac: 2300 movs r3, #0 - 80044ae: 61bb str r3, [r7, #24] + 8004574: 2300 movs r3, #0 + 8004576: 61bb str r3, [r7, #24] } while (huart->TxXferCount > 0U) - 80044b0: e02c b.n 800450c + 8004578: e02c b.n 80045d4 { if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - 80044b2: 683b ldr r3, [r7, #0] - 80044b4: 9300 str r3, [sp, #0] - 80044b6: 697b ldr r3, [r7, #20] - 80044b8: 2200 movs r2, #0 - 80044ba: 2180 movs r1, #128 ; 0x80 - 80044bc: 68f8 ldr r0, [r7, #12] - 80044be: f000 fd8e bl 8004fde - 80044c2: 4603 mov r3, r0 - 80044c4: 2b00 cmp r3, #0 - 80044c6: d001 beq.n 80044cc + 800457a: 683b ldr r3, [r7, #0] + 800457c: 9300 str r3, [sp, #0] + 800457e: 697b ldr r3, [r7, #20] + 8004580: 2200 movs r2, #0 + 8004582: 2180 movs r1, #128 ; 0x80 + 8004584: 68f8 ldr r0, [r7, #12] + 8004586: f000 fd8e bl 80050a6 + 800458a: 4603 mov r3, r0 + 800458c: 2b00 cmp r3, #0 + 800458e: d001 beq.n 8004594 { return HAL_TIMEOUT; - 80044c8: 2303 movs r3, #3 - 80044ca: e03c b.n 8004546 + 8004590: 2303 movs r3, #3 + 8004592: e03c b.n 800460e } if (pdata8bits == NULL) - 80044cc: 69fb ldr r3, [r7, #28] - 80044ce: 2b00 cmp r3, #0 - 80044d0: d10b bne.n 80044ea + 8004594: 69fb ldr r3, [r7, #28] + 8004596: 2b00 cmp r3, #0 + 8004598: d10b bne.n 80045b2 { huart->Instance->TDR = (uint16_t)(*pdata16bits & 0x01FFU); - 80044d2: 69bb ldr r3, [r7, #24] - 80044d4: 881b ldrh r3, [r3, #0] - 80044d6: 461a mov r2, r3 - 80044d8: 68fb ldr r3, [r7, #12] - 80044da: 681b ldr r3, [r3, #0] - 80044dc: f3c2 0208 ubfx r2, r2, #0, #9 - 80044e0: 629a str r2, [r3, #40] ; 0x28 + 800459a: 69bb ldr r3, [r7, #24] + 800459c: 881b ldrh r3, [r3, #0] + 800459e: 461a mov r2, r3 + 80045a0: 68fb ldr r3, [r7, #12] + 80045a2: 681b ldr r3, [r3, #0] + 80045a4: f3c2 0208 ubfx r2, r2, #0, #9 + 80045a8: 629a str r2, [r3, #40] ; 0x28 pdata16bits++; - 80044e2: 69bb ldr r3, [r7, #24] - 80044e4: 3302 adds r3, #2 - 80044e6: 61bb str r3, [r7, #24] - 80044e8: e007 b.n 80044fa + 80045aa: 69bb ldr r3, [r7, #24] + 80045ac: 3302 adds r3, #2 + 80045ae: 61bb str r3, [r7, #24] + 80045b0: e007 b.n 80045c2 } else { huart->Instance->TDR = (uint8_t)(*pdata8bits & 0xFFU); - 80044ea: 69fb ldr r3, [r7, #28] - 80044ec: 781a ldrb r2, [r3, #0] - 80044ee: 68fb ldr r3, [r7, #12] - 80044f0: 681b ldr r3, [r3, #0] - 80044f2: 629a str r2, [r3, #40] ; 0x28 + 80045b2: 69fb ldr r3, [r7, #28] + 80045b4: 781a ldrb r2, [r3, #0] + 80045b6: 68fb ldr r3, [r7, #12] + 80045b8: 681b ldr r3, [r3, #0] + 80045ba: 629a str r2, [r3, #40] ; 0x28 pdata8bits++; - 80044f4: 69fb ldr r3, [r7, #28] - 80044f6: 3301 adds r3, #1 - 80044f8: 61fb str r3, [r7, #28] + 80045bc: 69fb ldr r3, [r7, #28] + 80045be: 3301 adds r3, #1 + 80045c0: 61fb str r3, [r7, #28] } huart->TxXferCount--; - 80044fa: 68fb ldr r3, [r7, #12] - 80044fc: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 - 8004500: b29b uxth r3, r3 - 8004502: 3b01 subs r3, #1 - 8004504: b29a uxth r2, r3 - 8004506: 68fb ldr r3, [r7, #12] - 8004508: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 80045c2: 68fb ldr r3, [r7, #12] + 80045c4: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 + 80045c8: b29b uxth r3, r3 + 80045ca: 3b01 subs r3, #1 + 80045cc: b29a uxth r2, r3 + 80045ce: 68fb ldr r3, [r7, #12] + 80045d0: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 while (huart->TxXferCount > 0U) - 800450c: 68fb ldr r3, [r7, #12] - 800450e: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 - 8004512: b29b uxth r3, r3 - 8004514: 2b00 cmp r3, #0 - 8004516: d1cc bne.n 80044b2 + 80045d4: 68fb ldr r3, [r7, #12] + 80045d6: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 + 80045da: b29b uxth r3, r3 + 80045dc: 2b00 cmp r3, #0 + 80045de: d1cc bne.n 800457a } if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - 8004518: 683b ldr r3, [r7, #0] - 800451a: 9300 str r3, [sp, #0] - 800451c: 697b ldr r3, [r7, #20] - 800451e: 2200 movs r2, #0 - 8004520: 2140 movs r1, #64 ; 0x40 - 8004522: 68f8 ldr r0, [r7, #12] - 8004524: f000 fd5b bl 8004fde - 8004528: 4603 mov r3, r0 - 800452a: 2b00 cmp r3, #0 - 800452c: d001 beq.n 8004532 + 80045e0: 683b ldr r3, [r7, #0] + 80045e2: 9300 str r3, [sp, #0] + 80045e4: 697b ldr r3, [r7, #20] + 80045e6: 2200 movs r2, #0 + 80045e8: 2140 movs r1, #64 ; 0x40 + 80045ea: 68f8 ldr r0, [r7, #12] + 80045ec: f000 fd5b bl 80050a6 + 80045f0: 4603 mov r3, r0 + 80045f2: 2b00 cmp r3, #0 + 80045f4: d001 beq.n 80045fa { return HAL_TIMEOUT; - 800452e: 2303 movs r3, #3 - 8004530: e009 b.n 8004546 + 80045f6: 2303 movs r3, #3 + 80045f8: e009 b.n 800460e } /* At end of Tx process, restore huart->gState to Ready */ huart->gState = HAL_UART_STATE_READY; - 8004532: 68fb ldr r3, [r7, #12] - 8004534: 2220 movs r2, #32 - 8004536: 675a str r2, [r3, #116] ; 0x74 + 80045fa: 68fb ldr r3, [r7, #12] + 80045fc: 2220 movs r2, #32 + 80045fe: 675a str r2, [r3, #116] ; 0x74 /* Process Unlocked */ __HAL_UNLOCK(huart); - 8004538: 68fb ldr r3, [r7, #12] - 800453a: 2200 movs r2, #0 - 800453c: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004600: 68fb ldr r3, [r7, #12] + 8004602: 2200 movs r2, #0 + 8004604: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_OK; - 8004540: 2300 movs r3, #0 - 8004542: e000 b.n 8004546 + 8004608: 2300 movs r3, #0 + 800460a: e000 b.n 800460e } else { return HAL_BUSY; - 8004544: 2302 movs r3, #2 + 800460c: 2302 movs r3, #2 } } - 8004546: 4618 mov r0, r3 - 8004548: 3720 adds r7, #32 - 800454a: 46bd mov sp, r7 - 800454c: bd80 pop {r7, pc} + 800460e: 4618 mov r0, r3 + 8004610: 3720 adds r7, #32 + 8004612: 46bd mov sp, r7 + 8004614: bd80 pop {r7, pc} ... -08004550 : +08004618 : * @param pData Pointer to data buffer. * @param Size Amount of data to be received. * @retval HAL status */ HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) { - 8004550: b480 push {r7} - 8004552: b085 sub sp, #20 - 8004554: af00 add r7, sp, #0 - 8004556: 60f8 str r0, [r7, #12] - 8004558: 60b9 str r1, [r7, #8] - 800455a: 4613 mov r3, r2 - 800455c: 80fb strh r3, [r7, #6] + 8004618: b480 push {r7} + 800461a: b085 sub sp, #20 + 800461c: af00 add r7, sp, #0 + 800461e: 60f8 str r0, [r7, #12] + 8004620: 60b9 str r1, [r7, #8] + 8004622: 4613 mov r3, r2 + 8004624: 80fb strh r3, [r7, #6] /* Check that a Rx process is not already ongoing */ if (huart->RxState == HAL_UART_STATE_READY) - 800455e: 68fb ldr r3, [r7, #12] - 8004560: 6f9b ldr r3, [r3, #120] ; 0x78 - 8004562: 2b20 cmp r3, #32 - 8004564: f040 808a bne.w 800467c + 8004626: 68fb ldr r3, [r7, #12] + 8004628: 6f9b ldr r3, [r3, #120] ; 0x78 + 800462a: 2b20 cmp r3, #32 + 800462c: f040 808a bne.w 8004744 { if ((pData == NULL) || (Size == 0U)) - 8004568: 68bb ldr r3, [r7, #8] - 800456a: 2b00 cmp r3, #0 - 800456c: d002 beq.n 8004574 - 800456e: 88fb ldrh r3, [r7, #6] - 8004570: 2b00 cmp r3, #0 - 8004572: d101 bne.n 8004578 + 8004630: 68bb ldr r3, [r7, #8] + 8004632: 2b00 cmp r3, #0 + 8004634: d002 beq.n 800463c + 8004636: 88fb ldrh r3, [r7, #6] + 8004638: 2b00 cmp r3, #0 + 800463a: d101 bne.n 8004640 { return HAL_ERROR; - 8004574: 2301 movs r3, #1 - 8004576: e082 b.n 800467e + 800463c: 2301 movs r3, #1 + 800463e: e082 b.n 8004746 } /* Process Locked */ __HAL_LOCK(huart); - 8004578: 68fb ldr r3, [r7, #12] - 800457a: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 - 800457e: 2b01 cmp r3, #1 - 8004580: d101 bne.n 8004586 - 8004582: 2302 movs r3, #2 - 8004584: e07b b.n 800467e - 8004586: 68fb ldr r3, [r7, #12] - 8004588: 2201 movs r2, #1 - 800458a: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004640: 68fb ldr r3, [r7, #12] + 8004642: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 + 8004646: 2b01 cmp r3, #1 + 8004648: d101 bne.n 800464e + 800464a: 2302 movs r3, #2 + 800464c: e07b b.n 8004746 + 800464e: 68fb ldr r3, [r7, #12] + 8004650: 2201 movs r2, #1 + 8004652: f883 2070 strb.w r2, [r3, #112] ; 0x70 huart->pRxBuffPtr = pData; - 800458e: 68fb ldr r3, [r7, #12] - 8004590: 68ba ldr r2, [r7, #8] - 8004592: 655a str r2, [r3, #84] ; 0x54 + 8004656: 68fb ldr r3, [r7, #12] + 8004658: 68ba ldr r2, [r7, #8] + 800465a: 655a str r2, [r3, #84] ; 0x54 huart->RxXferSize = Size; - 8004594: 68fb ldr r3, [r7, #12] - 8004596: 88fa ldrh r2, [r7, #6] - 8004598: f8a3 2058 strh.w r2, [r3, #88] ; 0x58 + 800465c: 68fb ldr r3, [r7, #12] + 800465e: 88fa ldrh r2, [r7, #6] + 8004660: f8a3 2058 strh.w r2, [r3, #88] ; 0x58 huart->RxXferCount = Size; - 800459c: 68fb ldr r3, [r7, #12] - 800459e: 88fa ldrh r2, [r7, #6] - 80045a0: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 8004664: 68fb ldr r3, [r7, #12] + 8004666: 88fa ldrh r2, [r7, #6] + 8004668: f8a3 205a strh.w r2, [r3, #90] ; 0x5a huart->RxISR = NULL; - 80045a4: 68fb ldr r3, [r7, #12] - 80045a6: 2200 movs r2, #0 - 80045a8: 661a str r2, [r3, #96] ; 0x60 + 800466c: 68fb ldr r3, [r7, #12] + 800466e: 2200 movs r2, #0 + 8004670: 661a str r2, [r3, #96] ; 0x60 /* Computation of UART mask to apply to RDR register */ UART_MASK_COMPUTATION(huart); - 80045aa: 68fb ldr r3, [r7, #12] - 80045ac: 689b ldr r3, [r3, #8] - 80045ae: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 80045b2: d10e bne.n 80045d2 - 80045b4: 68fb ldr r3, [r7, #12] - 80045b6: 691b ldr r3, [r3, #16] - 80045b8: 2b00 cmp r3, #0 - 80045ba: d105 bne.n 80045c8 - 80045bc: 68fb ldr r3, [r7, #12] - 80045be: f240 12ff movw r2, #511 ; 0x1ff - 80045c2: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80045c6: e02d b.n 8004624 - 80045c8: 68fb ldr r3, [r7, #12] - 80045ca: 22ff movs r2, #255 ; 0xff - 80045cc: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80045d0: e028 b.n 8004624 - 80045d2: 68fb ldr r3, [r7, #12] - 80045d4: 689b ldr r3, [r3, #8] - 80045d6: 2b00 cmp r3, #0 - 80045d8: d10d bne.n 80045f6 - 80045da: 68fb ldr r3, [r7, #12] - 80045dc: 691b ldr r3, [r3, #16] - 80045de: 2b00 cmp r3, #0 - 80045e0: d104 bne.n 80045ec - 80045e2: 68fb ldr r3, [r7, #12] - 80045e4: 22ff movs r2, #255 ; 0xff - 80045e6: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80045ea: e01b b.n 8004624 - 80045ec: 68fb ldr r3, [r7, #12] - 80045ee: 227f movs r2, #127 ; 0x7f - 80045f0: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80045f4: e016 b.n 8004624 - 80045f6: 68fb ldr r3, [r7, #12] - 80045f8: 689b ldr r3, [r3, #8] - 80045fa: f1b3 5f80 cmp.w r3, #268435456 ; 0x10000000 - 80045fe: d10d bne.n 800461c - 8004600: 68fb ldr r3, [r7, #12] - 8004602: 691b ldr r3, [r3, #16] - 8004604: 2b00 cmp r3, #0 - 8004606: d104 bne.n 8004612 - 8004608: 68fb ldr r3, [r7, #12] - 800460a: 227f movs r2, #127 ; 0x7f - 800460c: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 8004610: e008 b.n 8004624 - 8004612: 68fb ldr r3, [r7, #12] - 8004614: 223f movs r2, #63 ; 0x3f - 8004616: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 800461a: e003 b.n 8004624 - 800461c: 68fb ldr r3, [r7, #12] - 800461e: 2200 movs r2, #0 - 8004620: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 8004672: 68fb ldr r3, [r7, #12] + 8004674: 689b ldr r3, [r3, #8] + 8004676: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 800467a: d10e bne.n 800469a + 800467c: 68fb ldr r3, [r7, #12] + 800467e: 691b ldr r3, [r3, #16] + 8004680: 2b00 cmp r3, #0 + 8004682: d105 bne.n 8004690 + 8004684: 68fb ldr r3, [r7, #12] + 8004686: f240 12ff movw r2, #511 ; 0x1ff + 800468a: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 800468e: e02d b.n 80046ec + 8004690: 68fb ldr r3, [r7, #12] + 8004692: 22ff movs r2, #255 ; 0xff + 8004694: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 8004698: e028 b.n 80046ec + 800469a: 68fb ldr r3, [r7, #12] + 800469c: 689b ldr r3, [r3, #8] + 800469e: 2b00 cmp r3, #0 + 80046a0: d10d bne.n 80046be + 80046a2: 68fb ldr r3, [r7, #12] + 80046a4: 691b ldr r3, [r3, #16] + 80046a6: 2b00 cmp r3, #0 + 80046a8: d104 bne.n 80046b4 + 80046aa: 68fb ldr r3, [r7, #12] + 80046ac: 22ff movs r2, #255 ; 0xff + 80046ae: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80046b2: e01b b.n 80046ec + 80046b4: 68fb ldr r3, [r7, #12] + 80046b6: 227f movs r2, #127 ; 0x7f + 80046b8: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80046bc: e016 b.n 80046ec + 80046be: 68fb ldr r3, [r7, #12] + 80046c0: 689b ldr r3, [r3, #8] + 80046c2: f1b3 5f80 cmp.w r3, #268435456 ; 0x10000000 + 80046c6: d10d bne.n 80046e4 + 80046c8: 68fb ldr r3, [r7, #12] + 80046ca: 691b ldr r3, [r3, #16] + 80046cc: 2b00 cmp r3, #0 + 80046ce: d104 bne.n 80046da + 80046d0: 68fb ldr r3, [r7, #12] + 80046d2: 227f movs r2, #127 ; 0x7f + 80046d4: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80046d8: e008 b.n 80046ec + 80046da: 68fb ldr r3, [r7, #12] + 80046dc: 223f movs r2, #63 ; 0x3f + 80046de: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80046e2: e003 b.n 80046ec + 80046e4: 68fb ldr r3, [r7, #12] + 80046e6: 2200 movs r2, #0 + 80046e8: f8a3 205c strh.w r2, [r3, #92] ; 0x5c huart->ErrorCode = HAL_UART_ERROR_NONE; - 8004624: 68fb ldr r3, [r7, #12] - 8004626: 2200 movs r2, #0 - 8004628: 67da str r2, [r3, #124] ; 0x7c + 80046ec: 68fb ldr r3, [r7, #12] + 80046ee: 2200 movs r2, #0 + 80046f0: 67da str r2, [r3, #124] ; 0x7c huart->RxState = HAL_UART_STATE_BUSY_RX; - 800462a: 68fb ldr r3, [r7, #12] - 800462c: 2222 movs r2, #34 ; 0x22 - 800462e: 679a str r2, [r3, #120] ; 0x78 + 80046f2: 68fb ldr r3, [r7, #12] + 80046f4: 2222 movs r2, #34 ; 0x22 + 80046f6: 679a str r2, [r3, #120] ; 0x78 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - 8004630: 68fb ldr r3, [r7, #12] - 8004632: 681b ldr r3, [r3, #0] - 8004634: 689a ldr r2, [r3, #8] - 8004636: 68fb ldr r3, [r7, #12] - 8004638: 681b ldr r3, [r3, #0] - 800463a: f042 0201 orr.w r2, r2, #1 - 800463e: 609a str r2, [r3, #8] + 80046f8: 68fb ldr r3, [r7, #12] + 80046fa: 681b ldr r3, [r3, #0] + 80046fc: 689a ldr r2, [r3, #8] + 80046fe: 68fb ldr r3, [r7, #12] + 8004700: 681b ldr r3, [r3, #0] + 8004702: f042 0201 orr.w r2, r2, #1 + 8004706: 609a str r2, [r3, #8] /* Set the Rx ISR function pointer according to the data word length */ if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - 8004640: 68fb ldr r3, [r7, #12] - 8004642: 689b ldr r3, [r3, #8] - 8004644: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004648: d107 bne.n 800465a - 800464a: 68fb ldr r3, [r7, #12] - 800464c: 691b ldr r3, [r3, #16] - 800464e: 2b00 cmp r3, #0 - 8004650: d103 bne.n 800465a + 8004708: 68fb ldr r3, [r7, #12] + 800470a: 689b ldr r3, [r3, #8] + 800470c: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004710: d107 bne.n 8004722 + 8004712: 68fb ldr r3, [r7, #12] + 8004714: 691b ldr r3, [r3, #16] + 8004716: 2b00 cmp r3, #0 + 8004718: d103 bne.n 8004722 { huart->RxISR = UART_RxISR_16BIT; - 8004652: 68fb ldr r3, [r7, #12] - 8004654: 4a0d ldr r2, [pc, #52] ; (800468c ) - 8004656: 661a str r2, [r3, #96] ; 0x60 - 8004658: e002 b.n 8004660 + 800471a: 68fb ldr r3, [r7, #12] + 800471c: 4a0d ldr r2, [pc, #52] ; (8004754 ) + 800471e: 661a str r2, [r3, #96] ; 0x60 + 8004720: e002 b.n 8004728 } else { huart->RxISR = UART_RxISR_8BIT; - 800465a: 68fb ldr r3, [r7, #12] - 800465c: 4a0c ldr r2, [pc, #48] ; (8004690 ) - 800465e: 661a str r2, [r3, #96] ; 0x60 + 8004722: 68fb ldr r3, [r7, #12] + 8004724: 4a0c ldr r2, [pc, #48] ; (8004758 ) + 8004726: 661a str r2, [r3, #96] ; 0x60 } /* Process Unlocked */ __HAL_UNLOCK(huart); - 8004660: 68fb ldr r3, [r7, #12] - 8004662: 2200 movs r2, #0 - 8004664: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004728: 68fb ldr r3, [r7, #12] + 800472a: 2200 movs r2, #0 + 800472c: f883 2070 strb.w r2, [r3, #112] ; 0x70 /* Enable the UART Parity Error interrupt and Data Register Not Empty interrupt */ SET_BIT(huart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); - 8004668: 68fb ldr r3, [r7, #12] - 800466a: 681b ldr r3, [r3, #0] - 800466c: 681a ldr r2, [r3, #0] - 800466e: 68fb ldr r3, [r7, #12] - 8004670: 681b ldr r3, [r3, #0] - 8004672: f442 7290 orr.w r2, r2, #288 ; 0x120 - 8004676: 601a str r2, [r3, #0] + 8004730: 68fb ldr r3, [r7, #12] + 8004732: 681b ldr r3, [r3, #0] + 8004734: 681a ldr r2, [r3, #0] + 8004736: 68fb ldr r3, [r7, #12] + 8004738: 681b ldr r3, [r3, #0] + 800473a: f442 7290 orr.w r2, r2, #288 ; 0x120 + 800473e: 601a str r2, [r3, #0] return HAL_OK; - 8004678: 2300 movs r3, #0 - 800467a: e000 b.n 800467e + 8004740: 2300 movs r3, #0 + 8004742: e000 b.n 8004746 } else { return HAL_BUSY; - 800467c: 2302 movs r3, #2 + 8004744: 2302 movs r3, #2 } } - 800467e: 4618 mov r0, r3 - 8004680: 3714 adds r7, #20 - 8004682: 46bd mov sp, r7 - 8004684: f85d 7b04 ldr.w r7, [sp], #4 - 8004688: 4770 bx lr - 800468a: bf00 nop - 800468c: 080051b3 .word 0x080051b3 - 8004690: 0800510d .word 0x0800510d - -08004694 : + 8004746: 4618 mov r0, r3 + 8004748: 3714 adds r7, #20 + 800474a: 46bd mov sp, r7 + 800474c: f85d 7b04 ldr.w r7, [sp], #4 + 8004750: 4770 bx lr + 8004752: bf00 nop + 8004754: 0800527b .word 0x0800527b + 8004758: 080051d5 .word 0x080051d5 + +0800475c : * @brief Handle UART interrupt request. * @param huart UART handle. * @retval None */ void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) { - 8004694: b580 push {r7, lr} - 8004696: b088 sub sp, #32 - 8004698: af00 add r7, sp, #0 - 800469a: 6078 str r0, [r7, #4] + 800475c: b580 push {r7, lr} + 800475e: b088 sub sp, #32 + 8004760: af00 add r7, sp, #0 + 8004762: 6078 str r0, [r7, #4] uint32_t isrflags = READ_REG(huart->Instance->ISR); - 800469c: 687b ldr r3, [r7, #4] - 800469e: 681b ldr r3, [r3, #0] - 80046a0: 69db ldr r3, [r3, #28] - 80046a2: 61fb str r3, [r7, #28] + 8004764: 687b ldr r3, [r7, #4] + 8004766: 681b ldr r3, [r3, #0] + 8004768: 69db ldr r3, [r3, #28] + 800476a: 61fb str r3, [r7, #28] uint32_t cr1its = READ_REG(huart->Instance->CR1); - 80046a4: 687b ldr r3, [r7, #4] - 80046a6: 681b ldr r3, [r3, #0] - 80046a8: 681b ldr r3, [r3, #0] - 80046aa: 61bb str r3, [r7, #24] + 800476c: 687b ldr r3, [r7, #4] + 800476e: 681b ldr r3, [r3, #0] + 8004770: 681b ldr r3, [r3, #0] + 8004772: 61bb str r3, [r7, #24] uint32_t cr3its = READ_REG(huart->Instance->CR3); - 80046ac: 687b ldr r3, [r7, #4] - 80046ae: 681b ldr r3, [r3, #0] - 80046b0: 689b ldr r3, [r3, #8] - 80046b2: 617b str r3, [r7, #20] + 8004774: 687b ldr r3, [r7, #4] + 8004776: 681b ldr r3, [r3, #0] + 8004778: 689b ldr r3, [r3, #8] + 800477a: 617b str r3, [r7, #20] uint32_t errorflags; uint32_t errorcode; /* If no error occurs */ errorflags = (isrflags & (uint32_t)(USART_ISR_PE | USART_ISR_FE | USART_ISR_ORE | USART_ISR_NE)); - 80046b4: 69fb ldr r3, [r7, #28] - 80046b6: f003 030f and.w r3, r3, #15 - 80046ba: 613b str r3, [r7, #16] + 800477c: 69fb ldr r3, [r7, #28] + 800477e: f003 030f and.w r3, r3, #15 + 8004782: 613b str r3, [r7, #16] if (errorflags == 0U) - 80046bc: 693b ldr r3, [r7, #16] - 80046be: 2b00 cmp r3, #0 - 80046c0: d113 bne.n 80046ea + 8004784: 693b ldr r3, [r7, #16] + 8004786: 2b00 cmp r3, #0 + 8004788: d113 bne.n 80047b2 { /* UART in mode Receiver ---------------------------------------------------*/ if (((isrflags & USART_ISR_RXNE) != 0U) - 80046c2: 69fb ldr r3, [r7, #28] - 80046c4: f003 0320 and.w r3, r3, #32 - 80046c8: 2b00 cmp r3, #0 - 80046ca: d00e beq.n 80046ea + 800478a: 69fb ldr r3, [r7, #28] + 800478c: f003 0320 and.w r3, r3, #32 + 8004790: 2b00 cmp r3, #0 + 8004792: d00e beq.n 80047b2 && ((cr1its & USART_CR1_RXNEIE) != 0U)) - 80046cc: 69bb ldr r3, [r7, #24] - 80046ce: f003 0320 and.w r3, r3, #32 - 80046d2: 2b00 cmp r3, #0 - 80046d4: d009 beq.n 80046ea + 8004794: 69bb ldr r3, [r7, #24] + 8004796: f003 0320 and.w r3, r3, #32 + 800479a: 2b00 cmp r3, #0 + 800479c: d009 beq.n 80047b2 { if (huart->RxISR != NULL) - 80046d6: 687b ldr r3, [r7, #4] - 80046d8: 6e1b ldr r3, [r3, #96] ; 0x60 - 80046da: 2b00 cmp r3, #0 - 80046dc: f000 80eb beq.w 80048b6 + 800479e: 687b ldr r3, [r7, #4] + 80047a0: 6e1b ldr r3, [r3, #96] ; 0x60 + 80047a2: 2b00 cmp r3, #0 + 80047a4: f000 80eb beq.w 800497e { huart->RxISR(huart); - 80046e0: 687b ldr r3, [r7, #4] - 80046e2: 6e1b ldr r3, [r3, #96] ; 0x60 - 80046e4: 6878 ldr r0, [r7, #4] - 80046e6: 4798 blx r3 + 80047a8: 687b ldr r3, [r7, #4] + 80047aa: 6e1b ldr r3, [r3, #96] ; 0x60 + 80047ac: 6878 ldr r0, [r7, #4] + 80047ae: 4798 blx r3 } return; - 80046e8: e0e5 b.n 80048b6 + 80047b0: e0e5 b.n 800497e } } /* If some errors occur */ if ((errorflags != 0U) - 80046ea: 693b ldr r3, [r7, #16] - 80046ec: 2b00 cmp r3, #0 - 80046ee: f000 80c0 beq.w 8004872 + 80047b2: 693b ldr r3, [r7, #16] + 80047b4: 2b00 cmp r3, #0 + 80047b6: f000 80c0 beq.w 800493a && (((cr3its & USART_CR3_EIE) != 0U) - 80046f2: 697b ldr r3, [r7, #20] - 80046f4: f003 0301 and.w r3, r3, #1 - 80046f8: 2b00 cmp r3, #0 - 80046fa: d105 bne.n 8004708 + 80047ba: 697b ldr r3, [r7, #20] + 80047bc: f003 0301 and.w r3, r3, #1 + 80047c0: 2b00 cmp r3, #0 + 80047c2: d105 bne.n 80047d0 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != 0U))) - 80046fc: 69bb ldr r3, [r7, #24] - 80046fe: f403 7390 and.w r3, r3, #288 ; 0x120 - 8004702: 2b00 cmp r3, #0 - 8004704: f000 80b5 beq.w 8004872 + 80047c4: 69bb ldr r3, [r7, #24] + 80047c6: f403 7390 and.w r3, r3, #288 ; 0x120 + 80047ca: 2b00 cmp r3, #0 + 80047cc: f000 80b5 beq.w 800493a { /* UART parity error interrupt occurred -------------------------------------*/ if (((isrflags & USART_ISR_PE) != 0U) && ((cr1its & USART_CR1_PEIE) != 0U)) - 8004708: 69fb ldr r3, [r7, #28] - 800470a: f003 0301 and.w r3, r3, #1 - 800470e: 2b00 cmp r3, #0 - 8004710: d00e beq.n 8004730 - 8004712: 69bb ldr r3, [r7, #24] - 8004714: f403 7380 and.w r3, r3, #256 ; 0x100 - 8004718: 2b00 cmp r3, #0 - 800471a: d009 beq.n 8004730 + 80047d0: 69fb ldr r3, [r7, #28] + 80047d2: f003 0301 and.w r3, r3, #1 + 80047d6: 2b00 cmp r3, #0 + 80047d8: d00e beq.n 80047f8 + 80047da: 69bb ldr r3, [r7, #24] + 80047dc: f403 7380 and.w r3, r3, #256 ; 0x100 + 80047e0: 2b00 cmp r3, #0 + 80047e2: d009 beq.n 80047f8 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_PEF); - 800471c: 687b ldr r3, [r7, #4] - 800471e: 681b ldr r3, [r3, #0] - 8004720: 2201 movs r2, #1 - 8004722: 621a str r2, [r3, #32] + 80047e4: 687b ldr r3, [r7, #4] + 80047e6: 681b ldr r3, [r3, #0] + 80047e8: 2201 movs r2, #1 + 80047ea: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_PE; - 8004724: 687b ldr r3, [r7, #4] - 8004726: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004728: f043 0201 orr.w r2, r3, #1 - 800472c: 687b ldr r3, [r7, #4] - 800472e: 67da str r2, [r3, #124] ; 0x7c + 80047ec: 687b ldr r3, [r7, #4] + 80047ee: 6fdb ldr r3, [r3, #124] ; 0x7c + 80047f0: f043 0201 orr.w r2, r3, #1 + 80047f4: 687b ldr r3, [r7, #4] + 80047f6: 67da str r2, [r3, #124] ; 0x7c } /* UART frame error interrupt occurred --------------------------------------*/ if (((isrflags & USART_ISR_FE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) - 8004730: 69fb ldr r3, [r7, #28] - 8004732: f003 0302 and.w r3, r3, #2 - 8004736: 2b00 cmp r3, #0 - 8004738: d00e beq.n 8004758 - 800473a: 697b ldr r3, [r7, #20] - 800473c: f003 0301 and.w r3, r3, #1 - 8004740: 2b00 cmp r3, #0 - 8004742: d009 beq.n 8004758 + 80047f8: 69fb ldr r3, [r7, #28] + 80047fa: f003 0302 and.w r3, r3, #2 + 80047fe: 2b00 cmp r3, #0 + 8004800: d00e beq.n 8004820 + 8004802: 697b ldr r3, [r7, #20] + 8004804: f003 0301 and.w r3, r3, #1 + 8004808: 2b00 cmp r3, #0 + 800480a: d009 beq.n 8004820 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_FEF); - 8004744: 687b ldr r3, [r7, #4] - 8004746: 681b ldr r3, [r3, #0] - 8004748: 2202 movs r2, #2 - 800474a: 621a str r2, [r3, #32] + 800480c: 687b ldr r3, [r7, #4] + 800480e: 681b ldr r3, [r3, #0] + 8004810: 2202 movs r2, #2 + 8004812: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_FE; - 800474c: 687b ldr r3, [r7, #4] - 800474e: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004750: f043 0204 orr.w r2, r3, #4 - 8004754: 687b ldr r3, [r7, #4] - 8004756: 67da str r2, [r3, #124] ; 0x7c + 8004814: 687b ldr r3, [r7, #4] + 8004816: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004818: f043 0204 orr.w r2, r3, #4 + 800481c: 687b ldr r3, [r7, #4] + 800481e: 67da str r2, [r3, #124] ; 0x7c } /* UART noise error interrupt occurred --------------------------------------*/ if (((isrflags & USART_ISR_NE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) - 8004758: 69fb ldr r3, [r7, #28] - 800475a: f003 0304 and.w r3, r3, #4 - 800475e: 2b00 cmp r3, #0 - 8004760: d00e beq.n 8004780 - 8004762: 697b ldr r3, [r7, #20] - 8004764: f003 0301 and.w r3, r3, #1 - 8004768: 2b00 cmp r3, #0 - 800476a: d009 beq.n 8004780 + 8004820: 69fb ldr r3, [r7, #28] + 8004822: f003 0304 and.w r3, r3, #4 + 8004826: 2b00 cmp r3, #0 + 8004828: d00e beq.n 8004848 + 800482a: 697b ldr r3, [r7, #20] + 800482c: f003 0301 and.w r3, r3, #1 + 8004830: 2b00 cmp r3, #0 + 8004832: d009 beq.n 8004848 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_NEF); - 800476c: 687b ldr r3, [r7, #4] - 800476e: 681b ldr r3, [r3, #0] - 8004770: 2204 movs r2, #4 - 8004772: 621a str r2, [r3, #32] + 8004834: 687b ldr r3, [r7, #4] + 8004836: 681b ldr r3, [r3, #0] + 8004838: 2204 movs r2, #4 + 800483a: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_NE; - 8004774: 687b ldr r3, [r7, #4] - 8004776: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004778: f043 0202 orr.w r2, r3, #2 - 800477c: 687b ldr r3, [r7, #4] - 800477e: 67da str r2, [r3, #124] ; 0x7c + 800483c: 687b ldr r3, [r7, #4] + 800483e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004840: f043 0202 orr.w r2, r3, #2 + 8004844: 687b ldr r3, [r7, #4] + 8004846: 67da str r2, [r3, #124] ; 0x7c } /* UART Over-Run interrupt occurred -----------------------------------------*/ if (((isrflags & USART_ISR_ORE) != 0U) - 8004780: 69fb ldr r3, [r7, #28] - 8004782: f003 0308 and.w r3, r3, #8 - 8004786: 2b00 cmp r3, #0 - 8004788: d013 beq.n 80047b2 + 8004848: 69fb ldr r3, [r7, #28] + 800484a: f003 0308 and.w r3, r3, #8 + 800484e: 2b00 cmp r3, #0 + 8004850: d013 beq.n 800487a && (((cr1its & USART_CR1_RXNEIE) != 0U) || - 800478a: 69bb ldr r3, [r7, #24] - 800478c: f003 0320 and.w r3, r3, #32 - 8004790: 2b00 cmp r3, #0 - 8004792: d104 bne.n 800479e + 8004852: 69bb ldr r3, [r7, #24] + 8004854: f003 0320 and.w r3, r3, #32 + 8004858: 2b00 cmp r3, #0 + 800485a: d104 bne.n 8004866 ((cr3its & USART_CR3_EIE) != 0U))) - 8004794: 697b ldr r3, [r7, #20] - 8004796: f003 0301 and.w r3, r3, #1 + 800485c: 697b ldr r3, [r7, #20] + 800485e: f003 0301 and.w r3, r3, #1 && (((cr1its & USART_CR1_RXNEIE) != 0U) || - 800479a: 2b00 cmp r3, #0 - 800479c: d009 beq.n 80047b2 + 8004862: 2b00 cmp r3, #0 + 8004864: d009 beq.n 800487a { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_OREF); - 800479e: 687b ldr r3, [r7, #4] - 80047a0: 681b ldr r3, [r3, #0] - 80047a2: 2208 movs r2, #8 - 80047a4: 621a str r2, [r3, #32] + 8004866: 687b ldr r3, [r7, #4] + 8004868: 681b ldr r3, [r3, #0] + 800486a: 2208 movs r2, #8 + 800486c: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_ORE; - 80047a6: 687b ldr r3, [r7, #4] - 80047a8: 6fdb ldr r3, [r3, #124] ; 0x7c - 80047aa: f043 0208 orr.w r2, r3, #8 - 80047ae: 687b ldr r3, [r7, #4] - 80047b0: 67da str r2, [r3, #124] ; 0x7c + 800486e: 687b ldr r3, [r7, #4] + 8004870: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004872: f043 0208 orr.w r2, r3, #8 + 8004876: 687b ldr r3, [r7, #4] + 8004878: 67da str r2, [r3, #124] ; 0x7c } /* Call UART Error Call back function if need be --------------------------*/ if (huart->ErrorCode != HAL_UART_ERROR_NONE) - 80047b2: 687b ldr r3, [r7, #4] - 80047b4: 6fdb ldr r3, [r3, #124] ; 0x7c - 80047b6: 2b00 cmp r3, #0 - 80047b8: d07f beq.n 80048ba + 800487a: 687b ldr r3, [r7, #4] + 800487c: 6fdb ldr r3, [r3, #124] ; 0x7c + 800487e: 2b00 cmp r3, #0 + 8004880: d07f beq.n 8004982 { /* UART in mode Receiver ---------------------------------------------------*/ if (((isrflags & USART_ISR_RXNE) != 0U) - 80047ba: 69fb ldr r3, [r7, #28] - 80047bc: f003 0320 and.w r3, r3, #32 - 80047c0: 2b00 cmp r3, #0 - 80047c2: d00c beq.n 80047de + 8004882: 69fb ldr r3, [r7, #28] + 8004884: f003 0320 and.w r3, r3, #32 + 8004888: 2b00 cmp r3, #0 + 800488a: d00c beq.n 80048a6 && ((cr1its & USART_CR1_RXNEIE) != 0U)) - 80047c4: 69bb ldr r3, [r7, #24] - 80047c6: f003 0320 and.w r3, r3, #32 - 80047ca: 2b00 cmp r3, #0 - 80047cc: d007 beq.n 80047de + 800488c: 69bb ldr r3, [r7, #24] + 800488e: f003 0320 and.w r3, r3, #32 + 8004892: 2b00 cmp r3, #0 + 8004894: d007 beq.n 80048a6 { if (huart->RxISR != NULL) - 80047ce: 687b ldr r3, [r7, #4] - 80047d0: 6e1b ldr r3, [r3, #96] ; 0x60 - 80047d2: 2b00 cmp r3, #0 - 80047d4: d003 beq.n 80047de + 8004896: 687b ldr r3, [r7, #4] + 8004898: 6e1b ldr r3, [r3, #96] ; 0x60 + 800489a: 2b00 cmp r3, #0 + 800489c: d003 beq.n 80048a6 { huart->RxISR(huart); - 80047d6: 687b ldr r3, [r7, #4] - 80047d8: 6e1b ldr r3, [r3, #96] ; 0x60 - 80047da: 6878 ldr r0, [r7, #4] - 80047dc: 4798 blx r3 + 800489e: 687b ldr r3, [r7, #4] + 80048a0: 6e1b ldr r3, [r3, #96] ; 0x60 + 80048a2: 6878 ldr r0, [r7, #4] + 80048a4: 4798 blx r3 } } /* If Overrun error occurs, or if any error occurs in DMA mode reception, consider error as blocking */ errorcode = huart->ErrorCode; - 80047de: 687b ldr r3, [r7, #4] - 80047e0: 6fdb ldr r3, [r3, #124] ; 0x7c - 80047e2: 60fb str r3, [r7, #12] + 80048a6: 687b ldr r3, [r7, #4] + 80048a8: 6fdb ldr r3, [r3, #124] ; 0x7c + 80048aa: 60fb str r3, [r7, #12] if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || - 80047e4: 687b ldr r3, [r7, #4] - 80047e6: 681b ldr r3, [r3, #0] - 80047e8: 689b ldr r3, [r3, #8] - 80047ea: f003 0340 and.w r3, r3, #64 ; 0x40 - 80047ee: 2b40 cmp r3, #64 ; 0x40 - 80047f0: d004 beq.n 80047fc + 80048ac: 687b ldr r3, [r7, #4] + 80048ae: 681b ldr r3, [r3, #0] + 80048b0: 689b ldr r3, [r3, #8] + 80048b2: f003 0340 and.w r3, r3, #64 ; 0x40 + 80048b6: 2b40 cmp r3, #64 ; 0x40 + 80048b8: d004 beq.n 80048c4 ((errorcode & HAL_UART_ERROR_ORE) != 0U)) - 80047f2: 68fb ldr r3, [r7, #12] - 80047f4: f003 0308 and.w r3, r3, #8 + 80048ba: 68fb ldr r3, [r7, #12] + 80048bc: f003 0308 and.w r3, r3, #8 if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || - 80047f8: 2b00 cmp r3, #0 - 80047fa: d031 beq.n 8004860 + 80048c0: 2b00 cmp r3, #0 + 80048c2: d031 beq.n 8004928 { /* Blocking error : transfer is aborted Set the UART state ready to be able to start again the process, Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ UART_EndRxTransfer(huart); - 80047fc: 6878 ldr r0, [r7, #4] - 80047fe: f000 fc36 bl 800506e + 80048c4: 6878 ldr r0, [r7, #4] + 80048c6: f000 fc36 bl 8005136 /* Disable the UART DMA Rx request if enabled */ if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004802: 687b ldr r3, [r7, #4] - 8004804: 681b ldr r3, [r3, #0] - 8004806: 689b ldr r3, [r3, #8] - 8004808: f003 0340 and.w r3, r3, #64 ; 0x40 - 800480c: 2b40 cmp r3, #64 ; 0x40 - 800480e: d123 bne.n 8004858 + 80048ca: 687b ldr r3, [r7, #4] + 80048cc: 681b ldr r3, [r3, #0] + 80048ce: 689b ldr r3, [r3, #8] + 80048d0: f003 0340 and.w r3, r3, #64 ; 0x40 + 80048d4: 2b40 cmp r3, #64 ; 0x40 + 80048d6: d123 bne.n 8004920 { CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - 8004810: 687b ldr r3, [r7, #4] - 8004812: 681b ldr r3, [r3, #0] - 8004814: 689a ldr r2, [r3, #8] - 8004816: 687b ldr r3, [r7, #4] - 8004818: 681b ldr r3, [r3, #0] - 800481a: f022 0240 bic.w r2, r2, #64 ; 0x40 - 800481e: 609a str r2, [r3, #8] + 80048d8: 687b ldr r3, [r7, #4] + 80048da: 681b ldr r3, [r3, #0] + 80048dc: 689a ldr r2, [r3, #8] + 80048de: 687b ldr r3, [r7, #4] + 80048e0: 681b ldr r3, [r3, #0] + 80048e2: f022 0240 bic.w r2, r2, #64 ; 0x40 + 80048e6: 609a str r2, [r3, #8] /* Abort the UART DMA Rx channel */ if (huart->hdmarx != NULL) - 8004820: 687b ldr r3, [r7, #4] - 8004822: 6edb ldr r3, [r3, #108] ; 0x6c - 8004824: 2b00 cmp r3, #0 - 8004826: d013 beq.n 8004850 + 80048e8: 687b ldr r3, [r7, #4] + 80048ea: 6edb ldr r3, [r3, #108] ; 0x6c + 80048ec: 2b00 cmp r3, #0 + 80048ee: d013 beq.n 8004918 { /* Set the UART DMA Abort callback : will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; - 8004828: 687b ldr r3, [r7, #4] - 800482a: 6edb ldr r3, [r3, #108] ; 0x6c - 800482c: 4a26 ldr r2, [pc, #152] ; (80048c8 ) - 800482e: 651a str r2, [r3, #80] ; 0x50 + 80048f0: 687b ldr r3, [r7, #4] + 80048f2: 6edb ldr r3, [r3, #108] ; 0x6c + 80048f4: 4a26 ldr r2, [pc, #152] ; (8004990 ) + 80048f6: 651a str r2, [r3, #80] ; 0x50 /* Abort DMA RX */ if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - 8004830: 687b ldr r3, [r7, #4] - 8004832: 6edb ldr r3, [r3, #108] ; 0x6c - 8004834: 4618 mov r0, r3 - 8004836: f7fd fa5c bl 8001cf2 - 800483a: 4603 mov r3, r0 - 800483c: 2b00 cmp r3, #0 - 800483e: d016 beq.n 800486e + 80048f8: 687b ldr r3, [r7, #4] + 80048fa: 6edb ldr r3, [r3, #108] ; 0x6c + 80048fc: 4618 mov r0, r3 + 80048fe: f7fd fa5c bl 8001dba + 8004902: 4603 mov r3, r0 + 8004904: 2b00 cmp r3, #0 + 8004906: d016 beq.n 8004936 { /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ huart->hdmarx->XferAbortCallback(huart->hdmarx); - 8004840: 687b ldr r3, [r7, #4] - 8004842: 6edb ldr r3, [r3, #108] ; 0x6c - 8004844: 6d1b ldr r3, [r3, #80] ; 0x50 - 8004846: 687a ldr r2, [r7, #4] - 8004848: 6ed2 ldr r2, [r2, #108] ; 0x6c - 800484a: 4610 mov r0, r2 - 800484c: 4798 blx r3 + 8004908: 687b ldr r3, [r7, #4] + 800490a: 6edb ldr r3, [r3, #108] ; 0x6c + 800490c: 6d1b ldr r3, [r3, #80] ; 0x50 + 800490e: 687a ldr r2, [r7, #4] + 8004910: 6ed2 ldr r2, [r2, #108] ; 0x6c + 8004912: 4610 mov r0, r2 + 8004914: 4798 blx r3 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 800484e: e00e b.n 800486e + 8004916: e00e b.n 8004936 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004850: 6878 ldr r0, [r7, #4] - 8004852: f000 f845 bl 80048e0 + 8004918: 6878 ldr r0, [r7, #4] + 800491a: f000 f845 bl 80049a8 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004856: e00a b.n 800486e + 800491e: e00a b.n 8004936 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004858: 6878 ldr r0, [r7, #4] - 800485a: f000 f841 bl 80048e0 + 8004920: 6878 ldr r0, [r7, #4] + 8004922: f000 f841 bl 80049a8 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 800485e: e006 b.n 800486e + 8004926: e006 b.n 8004936 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004860: 6878 ldr r0, [r7, #4] - 8004862: f000 f83d bl 80048e0 + 8004928: 6878 ldr r0, [r7, #4] + 800492a: f000 f83d bl 80049a8 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ huart->ErrorCode = HAL_UART_ERROR_NONE; - 8004866: 687b ldr r3, [r7, #4] - 8004868: 2200 movs r2, #0 - 800486a: 67da str r2, [r3, #124] ; 0x7c + 800492e: 687b ldr r3, [r7, #4] + 8004930: 2200 movs r2, #0 + 8004932: 67da str r2, [r3, #124] ; 0x7c } } return; - 800486c: e025 b.n 80048ba + 8004934: e025 b.n 8004982 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 800486e: bf00 nop + 8004936: bf00 nop return; - 8004870: e023 b.n 80048ba + 8004938: e023 b.n 8004982 } /* End if some error occurs */ /* UART in mode Transmitter ------------------------------------------------*/ if (((isrflags & USART_ISR_TXE) != 0U) - 8004872: 69fb ldr r3, [r7, #28] - 8004874: f003 0380 and.w r3, r3, #128 ; 0x80 - 8004878: 2b00 cmp r3, #0 - 800487a: d00d beq.n 8004898 + 800493a: 69fb ldr r3, [r7, #28] + 800493c: f003 0380 and.w r3, r3, #128 ; 0x80 + 8004940: 2b00 cmp r3, #0 + 8004942: d00d beq.n 8004960 && ((cr1its & USART_CR1_TXEIE) != 0U)) - 800487c: 69bb ldr r3, [r7, #24] - 800487e: f003 0380 and.w r3, r3, #128 ; 0x80 - 8004882: 2b00 cmp r3, #0 - 8004884: d008 beq.n 8004898 + 8004944: 69bb ldr r3, [r7, #24] + 8004946: f003 0380 and.w r3, r3, #128 ; 0x80 + 800494a: 2b00 cmp r3, #0 + 800494c: d008 beq.n 8004960 { if (huart->TxISR != NULL) - 8004886: 687b ldr r3, [r7, #4] - 8004888: 6e5b ldr r3, [r3, #100] ; 0x64 - 800488a: 2b00 cmp r3, #0 - 800488c: d017 beq.n 80048be + 800494e: 687b ldr r3, [r7, #4] + 8004950: 6e5b ldr r3, [r3, #100] ; 0x64 + 8004952: 2b00 cmp r3, #0 + 8004954: d017 beq.n 8004986 { huart->TxISR(huart); - 800488e: 687b ldr r3, [r7, #4] - 8004890: 6e5b ldr r3, [r3, #100] ; 0x64 - 8004892: 6878 ldr r0, [r7, #4] - 8004894: 4798 blx r3 + 8004956: 687b ldr r3, [r7, #4] + 8004958: 6e5b ldr r3, [r3, #100] ; 0x64 + 800495a: 6878 ldr r0, [r7, #4] + 800495c: 4798 blx r3 } return; - 8004896: e012 b.n 80048be + 800495e: e012 b.n 8004986 } /* UART in mode Transmitter (transmission end) -----------------------------*/ if (((isrflags & USART_ISR_TC) != 0U) && ((cr1its & USART_CR1_TCIE) != 0U)) - 8004898: 69fb ldr r3, [r7, #28] - 800489a: f003 0340 and.w r3, r3, #64 ; 0x40 - 800489e: 2b00 cmp r3, #0 - 80048a0: d00e beq.n 80048c0 - 80048a2: 69bb ldr r3, [r7, #24] - 80048a4: f003 0340 and.w r3, r3, #64 ; 0x40 - 80048a8: 2b00 cmp r3, #0 - 80048aa: d009 beq.n 80048c0 + 8004960: 69fb ldr r3, [r7, #28] + 8004962: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004966: 2b00 cmp r3, #0 + 8004968: d00e beq.n 8004988 + 800496a: 69bb ldr r3, [r7, #24] + 800496c: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004970: 2b00 cmp r3, #0 + 8004972: d009 beq.n 8004988 { UART_EndTransmit_IT(huart); - 80048ac: 6878 ldr r0, [r7, #4] - 80048ae: f000 fc14 bl 80050da + 8004974: 6878 ldr r0, [r7, #4] + 8004976: f000 fc14 bl 80051a2 return; - 80048b2: bf00 nop - 80048b4: e004 b.n 80048c0 + 800497a: bf00 nop + 800497c: e004 b.n 8004988 return; - 80048b6: bf00 nop - 80048b8: e002 b.n 80048c0 + 800497e: bf00 nop + 8004980: e002 b.n 8004988 return; - 80048ba: bf00 nop - 80048bc: e000 b.n 80048c0 + 8004982: bf00 nop + 8004984: e000 b.n 8004988 return; - 80048be: bf00 nop + 8004986: bf00 nop } } - 80048c0: 3720 adds r7, #32 - 80048c2: 46bd mov sp, r7 - 80048c4: bd80 pop {r7, pc} - 80048c6: bf00 nop - 80048c8: 080050af .word 0x080050af + 8004988: 3720 adds r7, #32 + 800498a: 46bd mov sp, r7 + 800498c: bd80 pop {r7, pc} + 800498e: bf00 nop + 8004990: 08005177 .word 0x08005177 -080048cc : +08004994 : * @brief Tx Transfer completed callback. * @param huart UART handle. * @retval None */ __weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) { - 80048cc: b480 push {r7} - 80048ce: b083 sub sp, #12 - 80048d0: af00 add r7, sp, #0 - 80048d2: 6078 str r0, [r7, #4] + 8004994: b480 push {r7} + 8004996: b083 sub sp, #12 + 8004998: af00 add r7, sp, #0 + 800499a: 6078 str r0, [r7, #4] UNUSED(huart); /* NOTE : This function should not be modified, when the callback is needed, the HAL_UART_TxCpltCallback can be implemented in the user file. */ } - 80048d4: bf00 nop - 80048d6: 370c adds r7, #12 - 80048d8: 46bd mov sp, r7 - 80048da: f85d 7b04 ldr.w r7, [sp], #4 - 80048de: 4770 bx lr + 800499c: bf00 nop + 800499e: 370c adds r7, #12 + 80049a0: 46bd mov sp, r7 + 80049a2: f85d 7b04 ldr.w r7, [sp], #4 + 80049a6: 4770 bx lr -080048e0 : +080049a8 : * @brief UART error callback. * @param huart UART handle. * @retval None */ __weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) { - 80048e0: b480 push {r7} - 80048e2: b083 sub sp, #12 - 80048e4: af00 add r7, sp, #0 - 80048e6: 6078 str r0, [r7, #4] + 80049a8: b480 push {r7} + 80049aa: b083 sub sp, #12 + 80049ac: af00 add r7, sp, #0 + 80049ae: 6078 str r0, [r7, #4] UNUSED(huart); /* NOTE : This function should not be modified, when the callback is needed, the HAL_UART_ErrorCallback can be implemented in the user file. */ } - 80048e8: bf00 nop - 80048ea: 370c adds r7, #12 - 80048ec: 46bd mov sp, r7 - 80048ee: f85d 7b04 ldr.w r7, [sp], #4 - 80048f2: 4770 bx lr + 80049b0: bf00 nop + 80049b2: 370c adds r7, #12 + 80049b4: 46bd mov sp, r7 + 80049b6: f85d 7b04 ldr.w r7, [sp], #4 + 80049ba: 4770 bx lr -080048f4 : +080049bc : * @brief Configure the UART peripheral. * @param huart UART handle. * @retval HAL status */ HAL_StatusTypeDef UART_SetConfig(UART_HandleTypeDef *huart) { - 80048f4: b580 push {r7, lr} - 80048f6: b088 sub sp, #32 - 80048f8: af00 add r7, sp, #0 - 80048fa: 6078 str r0, [r7, #4] + 80049bc: b580 push {r7, lr} + 80049be: b088 sub sp, #32 + 80049c0: af00 add r7, sp, #0 + 80049c2: 6078 str r0, [r7, #4] uint32_t tmpreg; uint16_t brrtemp; UART_ClockSourceTypeDef clocksource; uint32_t usartdiv = 0x00000000U; - 80048fc: 2300 movs r3, #0 - 80048fe: 61bb str r3, [r7, #24] + 80049c4: 2300 movs r3, #0 + 80049c6: 61bb str r3, [r7, #24] HAL_StatusTypeDef ret = HAL_OK; - 8004900: 2300 movs r3, #0 - 8004902: 75fb strb r3, [r7, #23] + 80049c8: 2300 movs r3, #0 + 80049ca: 75fb strb r3, [r7, #23] * the UART Word Length, Parity, Mode and oversampling: * set the M bits according to huart->Init.WordLength value * set PCE and PS bits according to huart->Init.Parity value * set TE and RE bits according to huart->Init.Mode value * set OVER8 bit according to huart->Init.OverSampling value */ tmpreg = (uint32_t)huart->Init.WordLength | huart->Init.Parity | huart->Init.Mode | huart->Init.OverSampling ; - 8004904: 687b ldr r3, [r7, #4] - 8004906: 689a ldr r2, [r3, #8] - 8004908: 687b ldr r3, [r7, #4] - 800490a: 691b ldr r3, [r3, #16] - 800490c: 431a orrs r2, r3 - 800490e: 687b ldr r3, [r7, #4] - 8004910: 695b ldr r3, [r3, #20] - 8004912: 431a orrs r2, r3 - 8004914: 687b ldr r3, [r7, #4] - 8004916: 69db ldr r3, [r3, #28] - 8004918: 4313 orrs r3, r2 - 800491a: 613b str r3, [r7, #16] + 80049cc: 687b ldr r3, [r7, #4] + 80049ce: 689a ldr r2, [r3, #8] + 80049d0: 687b ldr r3, [r7, #4] + 80049d2: 691b ldr r3, [r3, #16] + 80049d4: 431a orrs r2, r3 + 80049d6: 687b ldr r3, [r7, #4] + 80049d8: 695b ldr r3, [r3, #20] + 80049da: 431a orrs r2, r3 + 80049dc: 687b ldr r3, [r7, #4] + 80049de: 69db ldr r3, [r3, #28] + 80049e0: 4313 orrs r3, r2 + 80049e2: 613b str r3, [r7, #16] MODIFY_REG(huart->Instance->CR1, USART_CR1_FIELDS, tmpreg); - 800491c: 687b ldr r3, [r7, #4] - 800491e: 681b ldr r3, [r3, #0] - 8004920: 681a ldr r2, [r3, #0] - 8004922: 4bb1 ldr r3, [pc, #708] ; (8004be8 ) - 8004924: 4013 ands r3, r2 - 8004926: 687a ldr r2, [r7, #4] - 8004928: 6812 ldr r2, [r2, #0] - 800492a: 6939 ldr r1, [r7, #16] - 800492c: 430b orrs r3, r1 - 800492e: 6013 str r3, [r2, #0] + 80049e4: 687b ldr r3, [r7, #4] + 80049e6: 681b ldr r3, [r3, #0] + 80049e8: 681a ldr r2, [r3, #0] + 80049ea: 4bb1 ldr r3, [pc, #708] ; (8004cb0 ) + 80049ec: 4013 ands r3, r2 + 80049ee: 687a ldr r2, [r7, #4] + 80049f0: 6812 ldr r2, [r2, #0] + 80049f2: 6939 ldr r1, [r7, #16] + 80049f4: 430b orrs r3, r1 + 80049f6: 6013 str r3, [r2, #0] /*-------------------------- USART CR2 Configuration -----------------------*/ /* Configure the UART Stop Bits: Set STOP[13:12] bits according * to huart->Init.StopBits value */ MODIFY_REG(huart->Instance->CR2, USART_CR2_STOP, huart->Init.StopBits); - 8004930: 687b ldr r3, [r7, #4] - 8004932: 681b ldr r3, [r3, #0] - 8004934: 685b ldr r3, [r3, #4] - 8004936: f423 5140 bic.w r1, r3, #12288 ; 0x3000 - 800493a: 687b ldr r3, [r7, #4] - 800493c: 68da ldr r2, [r3, #12] - 800493e: 687b ldr r3, [r7, #4] - 8004940: 681b ldr r3, [r3, #0] - 8004942: 430a orrs r2, r1 - 8004944: 605a str r2, [r3, #4] + 80049f8: 687b ldr r3, [r7, #4] + 80049fa: 681b ldr r3, [r3, #0] + 80049fc: 685b ldr r3, [r3, #4] + 80049fe: f423 5140 bic.w r1, r3, #12288 ; 0x3000 + 8004a02: 687b ldr r3, [r7, #4] + 8004a04: 68da ldr r2, [r3, #12] + 8004a06: 687b ldr r3, [r7, #4] + 8004a08: 681b ldr r3, [r3, #0] + 8004a0a: 430a orrs r2, r1 + 8004a0c: 605a str r2, [r3, #4] /* Configure * - UART HardWare Flow Control: set CTSE and RTSE bits according * to huart->Init.HwFlowCtl value * - one-bit sampling method versus three samples' majority rule according * to huart->Init.OneBitSampling (not applicable to LPUART) */ tmpreg = (uint32_t)huart->Init.HwFlowCtl; - 8004946: 687b ldr r3, [r7, #4] - 8004948: 699b ldr r3, [r3, #24] - 800494a: 613b str r3, [r7, #16] + 8004a0e: 687b ldr r3, [r7, #4] + 8004a10: 699b ldr r3, [r3, #24] + 8004a12: 613b str r3, [r7, #16] tmpreg |= huart->Init.OneBitSampling; - 800494c: 687b ldr r3, [r7, #4] - 800494e: 6a1b ldr r3, [r3, #32] - 8004950: 693a ldr r2, [r7, #16] - 8004952: 4313 orrs r3, r2 - 8004954: 613b str r3, [r7, #16] + 8004a14: 687b ldr r3, [r7, #4] + 8004a16: 6a1b ldr r3, [r3, #32] + 8004a18: 693a ldr r2, [r7, #16] + 8004a1a: 4313 orrs r3, r2 + 8004a1c: 613b str r3, [r7, #16] MODIFY_REG(huart->Instance->CR3, USART_CR3_FIELDS, tmpreg); - 8004956: 687b ldr r3, [r7, #4] - 8004958: 681b ldr r3, [r3, #0] - 800495a: 689b ldr r3, [r3, #8] - 800495c: f423 6130 bic.w r1, r3, #2816 ; 0xb00 - 8004960: 687b ldr r3, [r7, #4] - 8004962: 681b ldr r3, [r3, #0] - 8004964: 693a ldr r2, [r7, #16] - 8004966: 430a orrs r2, r1 - 8004968: 609a str r2, [r3, #8] + 8004a1e: 687b ldr r3, [r7, #4] + 8004a20: 681b ldr r3, [r3, #0] + 8004a22: 689b ldr r3, [r3, #8] + 8004a24: f423 6130 bic.w r1, r3, #2816 ; 0xb00 + 8004a28: 687b ldr r3, [r7, #4] + 8004a2a: 681b ldr r3, [r3, #0] + 8004a2c: 693a ldr r2, [r7, #16] + 8004a2e: 430a orrs r2, r1 + 8004a30: 609a str r2, [r3, #8] /*-------------------------- USART BRR Configuration -----------------------*/ UART_GETCLOCKSOURCE(huart, clocksource); - 800496a: 687b ldr r3, [r7, #4] - 800496c: 681b ldr r3, [r3, #0] - 800496e: 4a9f ldr r2, [pc, #636] ; (8004bec ) - 8004970: 4293 cmp r3, r2 - 8004972: d121 bne.n 80049b8 - 8004974: 4b9e ldr r3, [pc, #632] ; (8004bf0 ) - 8004976: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 800497a: f003 0303 and.w r3, r3, #3 - 800497e: 2b03 cmp r3, #3 - 8004980: d816 bhi.n 80049b0 - 8004982: a201 add r2, pc, #4 ; (adr r2, 8004988 ) - 8004984: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004988: 08004999 .word 0x08004999 - 800498c: 080049a5 .word 0x080049a5 - 8004990: 0800499f .word 0x0800499f - 8004994: 080049ab .word 0x080049ab - 8004998: 2301 movs r3, #1 - 800499a: 77fb strb r3, [r7, #31] - 800499c: e151 b.n 8004c42 - 800499e: 2302 movs r3, #2 - 80049a0: 77fb strb r3, [r7, #31] - 80049a2: e14e b.n 8004c42 - 80049a4: 2304 movs r3, #4 - 80049a6: 77fb strb r3, [r7, #31] - 80049a8: e14b b.n 8004c42 - 80049aa: 2308 movs r3, #8 - 80049ac: 77fb strb r3, [r7, #31] - 80049ae: e148 b.n 8004c42 - 80049b0: 2310 movs r3, #16 - 80049b2: 77fb strb r3, [r7, #31] - 80049b4: bf00 nop - 80049b6: e144 b.n 8004c42 - 80049b8: 687b ldr r3, [r7, #4] - 80049ba: 681b ldr r3, [r3, #0] - 80049bc: 4a8d ldr r2, [pc, #564] ; (8004bf4 ) - 80049be: 4293 cmp r3, r2 - 80049c0: d134 bne.n 8004a2c - 80049c2: 4b8b ldr r3, [pc, #556] ; (8004bf0 ) - 80049c4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 80049c8: f003 030c and.w r3, r3, #12 - 80049cc: 2b0c cmp r3, #12 - 80049ce: d829 bhi.n 8004a24 - 80049d0: a201 add r2, pc, #4 ; (adr r2, 80049d8 ) - 80049d2: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 80049d6: bf00 nop - 80049d8: 08004a0d .word 0x08004a0d - 80049dc: 08004a25 .word 0x08004a25 - 80049e0: 08004a25 .word 0x08004a25 - 80049e4: 08004a25 .word 0x08004a25 - 80049e8: 08004a19 .word 0x08004a19 - 80049ec: 08004a25 .word 0x08004a25 - 80049f0: 08004a25 .word 0x08004a25 - 80049f4: 08004a25 .word 0x08004a25 - 80049f8: 08004a13 .word 0x08004a13 - 80049fc: 08004a25 .word 0x08004a25 - 8004a00: 08004a25 .word 0x08004a25 - 8004a04: 08004a25 .word 0x08004a25 - 8004a08: 08004a1f .word 0x08004a1f - 8004a0c: 2300 movs r3, #0 - 8004a0e: 77fb strb r3, [r7, #31] - 8004a10: e117 b.n 8004c42 - 8004a12: 2302 movs r3, #2 - 8004a14: 77fb strb r3, [r7, #31] - 8004a16: e114 b.n 8004c42 - 8004a18: 2304 movs r3, #4 - 8004a1a: 77fb strb r3, [r7, #31] - 8004a1c: e111 b.n 8004c42 - 8004a1e: 2308 movs r3, #8 - 8004a20: 77fb strb r3, [r7, #31] - 8004a22: e10e b.n 8004c42 - 8004a24: 2310 movs r3, #16 - 8004a26: 77fb strb r3, [r7, #31] - 8004a28: bf00 nop - 8004a2a: e10a b.n 8004c42 - 8004a2c: 687b ldr r3, [r7, #4] - 8004a2e: 681b ldr r3, [r3, #0] - 8004a30: 4a71 ldr r2, [pc, #452] ; (8004bf8 ) - 8004a32: 4293 cmp r3, r2 - 8004a34: d120 bne.n 8004a78 - 8004a36: 4b6e ldr r3, [pc, #440] ; (8004bf0 ) - 8004a38: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004a3c: f003 0330 and.w r3, r3, #48 ; 0x30 - 8004a40: 2b10 cmp r3, #16 - 8004a42: d00f beq.n 8004a64 - 8004a44: 2b10 cmp r3, #16 - 8004a46: d802 bhi.n 8004a4e - 8004a48: 2b00 cmp r3, #0 - 8004a4a: d005 beq.n 8004a58 - 8004a4c: e010 b.n 8004a70 - 8004a4e: 2b20 cmp r3, #32 - 8004a50: d005 beq.n 8004a5e - 8004a52: 2b30 cmp r3, #48 ; 0x30 - 8004a54: d009 beq.n 8004a6a - 8004a56: e00b b.n 8004a70 - 8004a58: 2300 movs r3, #0 - 8004a5a: 77fb strb r3, [r7, #31] - 8004a5c: e0f1 b.n 8004c42 - 8004a5e: 2302 movs r3, #2 - 8004a60: 77fb strb r3, [r7, #31] - 8004a62: e0ee b.n 8004c42 - 8004a64: 2304 movs r3, #4 - 8004a66: 77fb strb r3, [r7, #31] - 8004a68: e0eb b.n 8004c42 - 8004a6a: 2308 movs r3, #8 - 8004a6c: 77fb strb r3, [r7, #31] - 8004a6e: e0e8 b.n 8004c42 - 8004a70: 2310 movs r3, #16 - 8004a72: 77fb strb r3, [r7, #31] - 8004a74: bf00 nop - 8004a76: e0e4 b.n 8004c42 - 8004a78: 687b ldr r3, [r7, #4] - 8004a7a: 681b ldr r3, [r3, #0] - 8004a7c: 4a5f ldr r2, [pc, #380] ; (8004bfc ) - 8004a7e: 4293 cmp r3, r2 - 8004a80: d120 bne.n 8004ac4 - 8004a82: 4b5b ldr r3, [pc, #364] ; (8004bf0 ) - 8004a84: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004a88: f003 03c0 and.w r3, r3, #192 ; 0xc0 - 8004a8c: 2b40 cmp r3, #64 ; 0x40 - 8004a8e: d00f beq.n 8004ab0 - 8004a90: 2b40 cmp r3, #64 ; 0x40 - 8004a92: d802 bhi.n 8004a9a - 8004a94: 2b00 cmp r3, #0 - 8004a96: d005 beq.n 8004aa4 - 8004a98: e010 b.n 8004abc - 8004a9a: 2b80 cmp r3, #128 ; 0x80 - 8004a9c: d005 beq.n 8004aaa - 8004a9e: 2bc0 cmp r3, #192 ; 0xc0 - 8004aa0: d009 beq.n 8004ab6 - 8004aa2: e00b b.n 8004abc - 8004aa4: 2300 movs r3, #0 - 8004aa6: 77fb strb r3, [r7, #31] - 8004aa8: e0cb b.n 8004c42 - 8004aaa: 2302 movs r3, #2 - 8004aac: 77fb strb r3, [r7, #31] - 8004aae: e0c8 b.n 8004c42 - 8004ab0: 2304 movs r3, #4 - 8004ab2: 77fb strb r3, [r7, #31] - 8004ab4: e0c5 b.n 8004c42 - 8004ab6: 2308 movs r3, #8 - 8004ab8: 77fb strb r3, [r7, #31] - 8004aba: e0c2 b.n 8004c42 - 8004abc: 2310 movs r3, #16 - 8004abe: 77fb strb r3, [r7, #31] - 8004ac0: bf00 nop - 8004ac2: e0be b.n 8004c42 - 8004ac4: 687b ldr r3, [r7, #4] - 8004ac6: 681b ldr r3, [r3, #0] - 8004ac8: 4a4d ldr r2, [pc, #308] ; (8004c00 ) - 8004aca: 4293 cmp r3, r2 - 8004acc: d124 bne.n 8004b18 - 8004ace: 4b48 ldr r3, [pc, #288] ; (8004bf0 ) - 8004ad0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004ad4: f403 7340 and.w r3, r3, #768 ; 0x300 - 8004ad8: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 8004adc: d012 beq.n 8004b04 - 8004ade: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 8004ae2: d802 bhi.n 8004aea - 8004ae4: 2b00 cmp r3, #0 - 8004ae6: d007 beq.n 8004af8 - 8004ae8: e012 b.n 8004b10 - 8004aea: f5b3 7f00 cmp.w r3, #512 ; 0x200 - 8004aee: d006 beq.n 8004afe - 8004af0: f5b3 7f40 cmp.w r3, #768 ; 0x300 - 8004af4: d009 beq.n 8004b0a - 8004af6: e00b b.n 8004b10 - 8004af8: 2300 movs r3, #0 - 8004afa: 77fb strb r3, [r7, #31] - 8004afc: e0a1 b.n 8004c42 - 8004afe: 2302 movs r3, #2 - 8004b00: 77fb strb r3, [r7, #31] - 8004b02: e09e b.n 8004c42 - 8004b04: 2304 movs r3, #4 - 8004b06: 77fb strb r3, [r7, #31] - 8004b08: e09b b.n 8004c42 - 8004b0a: 2308 movs r3, #8 - 8004b0c: 77fb strb r3, [r7, #31] - 8004b0e: e098 b.n 8004c42 - 8004b10: 2310 movs r3, #16 - 8004b12: 77fb strb r3, [r7, #31] - 8004b14: bf00 nop - 8004b16: e094 b.n 8004c42 - 8004b18: 687b ldr r3, [r7, #4] - 8004b1a: 681b ldr r3, [r3, #0] - 8004b1c: 4a39 ldr r2, [pc, #228] ; (8004c04 ) - 8004b1e: 4293 cmp r3, r2 - 8004b20: d124 bne.n 8004b6c - 8004b22: 4b33 ldr r3, [pc, #204] ; (8004bf0 ) - 8004b24: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004b28: f403 6340 and.w r3, r3, #3072 ; 0xc00 - 8004b2c: f5b3 6f80 cmp.w r3, #1024 ; 0x400 - 8004b30: d012 beq.n 8004b58 - 8004b32: f5b3 6f80 cmp.w r3, #1024 ; 0x400 - 8004b36: d802 bhi.n 8004b3e - 8004b38: 2b00 cmp r3, #0 - 8004b3a: d007 beq.n 8004b4c - 8004b3c: e012 b.n 8004b64 - 8004b3e: f5b3 6f00 cmp.w r3, #2048 ; 0x800 - 8004b42: d006 beq.n 8004b52 - 8004b44: f5b3 6f40 cmp.w r3, #3072 ; 0xc00 - 8004b48: d009 beq.n 8004b5e - 8004b4a: e00b b.n 8004b64 - 8004b4c: 2301 movs r3, #1 - 8004b4e: 77fb strb r3, [r7, #31] - 8004b50: e077 b.n 8004c42 - 8004b52: 2302 movs r3, #2 - 8004b54: 77fb strb r3, [r7, #31] - 8004b56: e074 b.n 8004c42 - 8004b58: 2304 movs r3, #4 - 8004b5a: 77fb strb r3, [r7, #31] - 8004b5c: e071 b.n 8004c42 - 8004b5e: 2308 movs r3, #8 - 8004b60: 77fb strb r3, [r7, #31] - 8004b62: e06e b.n 8004c42 - 8004b64: 2310 movs r3, #16 - 8004b66: 77fb strb r3, [r7, #31] - 8004b68: bf00 nop - 8004b6a: e06a b.n 8004c42 - 8004b6c: 687b ldr r3, [r7, #4] - 8004b6e: 681b ldr r3, [r3, #0] - 8004b70: 4a25 ldr r2, [pc, #148] ; (8004c08 ) - 8004b72: 4293 cmp r3, r2 - 8004b74: d124 bne.n 8004bc0 - 8004b76: 4b1e ldr r3, [pc, #120] ; (8004bf0 ) - 8004b78: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004b7c: f403 5340 and.w r3, r3, #12288 ; 0x3000 - 8004b80: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004b84: d012 beq.n 8004bac - 8004b86: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004b8a: d802 bhi.n 8004b92 - 8004b8c: 2b00 cmp r3, #0 - 8004b8e: d007 beq.n 8004ba0 - 8004b90: e012 b.n 8004bb8 - 8004b92: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 8004b96: d006 beq.n 8004ba6 - 8004b98: f5b3 5f40 cmp.w r3, #12288 ; 0x3000 - 8004b9c: d009 beq.n 8004bb2 - 8004b9e: e00b b.n 8004bb8 - 8004ba0: 2300 movs r3, #0 - 8004ba2: 77fb strb r3, [r7, #31] - 8004ba4: e04d b.n 8004c42 - 8004ba6: 2302 movs r3, #2 - 8004ba8: 77fb strb r3, [r7, #31] - 8004baa: e04a b.n 8004c42 - 8004bac: 2304 movs r3, #4 - 8004bae: 77fb strb r3, [r7, #31] - 8004bb0: e047 b.n 8004c42 - 8004bb2: 2308 movs r3, #8 - 8004bb4: 77fb strb r3, [r7, #31] - 8004bb6: e044 b.n 8004c42 - 8004bb8: 2310 movs r3, #16 - 8004bba: 77fb strb r3, [r7, #31] - 8004bbc: bf00 nop - 8004bbe: e040 b.n 8004c42 - 8004bc0: 687b ldr r3, [r7, #4] - 8004bc2: 681b ldr r3, [r3, #0] - 8004bc4: 4a11 ldr r2, [pc, #68] ; (8004c0c ) - 8004bc6: 4293 cmp r3, r2 - 8004bc8: d139 bne.n 8004c3e - 8004bca: 4b09 ldr r3, [pc, #36] ; (8004bf0 ) - 8004bcc: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004bd0: f403 4340 and.w r3, r3, #49152 ; 0xc000 - 8004bd4: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 - 8004bd8: d027 beq.n 8004c2a - 8004bda: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 - 8004bde: d817 bhi.n 8004c10 - 8004be0: 2b00 cmp r3, #0 - 8004be2: d01c beq.n 8004c1e - 8004be4: e027 b.n 8004c36 - 8004be6: bf00 nop - 8004be8: efff69f3 .word 0xefff69f3 - 8004bec: 40011000 .word 0x40011000 - 8004bf0: 40023800 .word 0x40023800 - 8004bf4: 40004400 .word 0x40004400 - 8004bf8: 40004800 .word 0x40004800 - 8004bfc: 40004c00 .word 0x40004c00 - 8004c00: 40005000 .word 0x40005000 - 8004c04: 40011400 .word 0x40011400 - 8004c08: 40007800 .word 0x40007800 - 8004c0c: 40007c00 .word 0x40007c00 - 8004c10: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 - 8004c14: d006 beq.n 8004c24 - 8004c16: f5b3 4f40 cmp.w r3, #49152 ; 0xc000 - 8004c1a: d009 beq.n 8004c30 - 8004c1c: e00b b.n 8004c36 - 8004c1e: 2300 movs r3, #0 - 8004c20: 77fb strb r3, [r7, #31] - 8004c22: e00e b.n 8004c42 - 8004c24: 2302 movs r3, #2 - 8004c26: 77fb strb r3, [r7, #31] - 8004c28: e00b b.n 8004c42 - 8004c2a: 2304 movs r3, #4 - 8004c2c: 77fb strb r3, [r7, #31] - 8004c2e: e008 b.n 8004c42 - 8004c30: 2308 movs r3, #8 - 8004c32: 77fb strb r3, [r7, #31] - 8004c34: e005 b.n 8004c42 - 8004c36: 2310 movs r3, #16 - 8004c38: 77fb strb r3, [r7, #31] - 8004c3a: bf00 nop - 8004c3c: e001 b.n 8004c42 - 8004c3e: 2310 movs r3, #16 - 8004c40: 77fb strb r3, [r7, #31] + 8004a32: 687b ldr r3, [r7, #4] + 8004a34: 681b ldr r3, [r3, #0] + 8004a36: 4a9f ldr r2, [pc, #636] ; (8004cb4 ) + 8004a38: 4293 cmp r3, r2 + 8004a3a: d121 bne.n 8004a80 + 8004a3c: 4b9e ldr r3, [pc, #632] ; (8004cb8 ) + 8004a3e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004a42: f003 0303 and.w r3, r3, #3 + 8004a46: 2b03 cmp r3, #3 + 8004a48: d816 bhi.n 8004a78 + 8004a4a: a201 add r2, pc, #4 ; (adr r2, 8004a50 ) + 8004a4c: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004a50: 08004a61 .word 0x08004a61 + 8004a54: 08004a6d .word 0x08004a6d + 8004a58: 08004a67 .word 0x08004a67 + 8004a5c: 08004a73 .word 0x08004a73 + 8004a60: 2301 movs r3, #1 + 8004a62: 77fb strb r3, [r7, #31] + 8004a64: e151 b.n 8004d0a + 8004a66: 2302 movs r3, #2 + 8004a68: 77fb strb r3, [r7, #31] + 8004a6a: e14e b.n 8004d0a + 8004a6c: 2304 movs r3, #4 + 8004a6e: 77fb strb r3, [r7, #31] + 8004a70: e14b b.n 8004d0a + 8004a72: 2308 movs r3, #8 + 8004a74: 77fb strb r3, [r7, #31] + 8004a76: e148 b.n 8004d0a + 8004a78: 2310 movs r3, #16 + 8004a7a: 77fb strb r3, [r7, #31] + 8004a7c: bf00 nop + 8004a7e: e144 b.n 8004d0a + 8004a80: 687b ldr r3, [r7, #4] + 8004a82: 681b ldr r3, [r3, #0] + 8004a84: 4a8d ldr r2, [pc, #564] ; (8004cbc ) + 8004a86: 4293 cmp r3, r2 + 8004a88: d134 bne.n 8004af4 + 8004a8a: 4b8b ldr r3, [pc, #556] ; (8004cb8 ) + 8004a8c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004a90: f003 030c and.w r3, r3, #12 + 8004a94: 2b0c cmp r3, #12 + 8004a96: d829 bhi.n 8004aec + 8004a98: a201 add r2, pc, #4 ; (adr r2, 8004aa0 ) + 8004a9a: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004a9e: bf00 nop + 8004aa0: 08004ad5 .word 0x08004ad5 + 8004aa4: 08004aed .word 0x08004aed + 8004aa8: 08004aed .word 0x08004aed + 8004aac: 08004aed .word 0x08004aed + 8004ab0: 08004ae1 .word 0x08004ae1 + 8004ab4: 08004aed .word 0x08004aed + 8004ab8: 08004aed .word 0x08004aed + 8004abc: 08004aed .word 0x08004aed + 8004ac0: 08004adb .word 0x08004adb + 8004ac4: 08004aed .word 0x08004aed + 8004ac8: 08004aed .word 0x08004aed + 8004acc: 08004aed .word 0x08004aed + 8004ad0: 08004ae7 .word 0x08004ae7 + 8004ad4: 2300 movs r3, #0 + 8004ad6: 77fb strb r3, [r7, #31] + 8004ad8: e117 b.n 8004d0a + 8004ada: 2302 movs r3, #2 + 8004adc: 77fb strb r3, [r7, #31] + 8004ade: e114 b.n 8004d0a + 8004ae0: 2304 movs r3, #4 + 8004ae2: 77fb strb r3, [r7, #31] + 8004ae4: e111 b.n 8004d0a + 8004ae6: 2308 movs r3, #8 + 8004ae8: 77fb strb r3, [r7, #31] + 8004aea: e10e b.n 8004d0a + 8004aec: 2310 movs r3, #16 + 8004aee: 77fb strb r3, [r7, #31] + 8004af0: bf00 nop + 8004af2: e10a b.n 8004d0a + 8004af4: 687b ldr r3, [r7, #4] + 8004af6: 681b ldr r3, [r3, #0] + 8004af8: 4a71 ldr r2, [pc, #452] ; (8004cc0 ) + 8004afa: 4293 cmp r3, r2 + 8004afc: d120 bne.n 8004b40 + 8004afe: 4b6e ldr r3, [pc, #440] ; (8004cb8 ) + 8004b00: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004b04: f003 0330 and.w r3, r3, #48 ; 0x30 + 8004b08: 2b10 cmp r3, #16 + 8004b0a: d00f beq.n 8004b2c + 8004b0c: 2b10 cmp r3, #16 + 8004b0e: d802 bhi.n 8004b16 + 8004b10: 2b00 cmp r3, #0 + 8004b12: d005 beq.n 8004b20 + 8004b14: e010 b.n 8004b38 + 8004b16: 2b20 cmp r3, #32 + 8004b18: d005 beq.n 8004b26 + 8004b1a: 2b30 cmp r3, #48 ; 0x30 + 8004b1c: d009 beq.n 8004b32 + 8004b1e: e00b b.n 8004b38 + 8004b20: 2300 movs r3, #0 + 8004b22: 77fb strb r3, [r7, #31] + 8004b24: e0f1 b.n 8004d0a + 8004b26: 2302 movs r3, #2 + 8004b28: 77fb strb r3, [r7, #31] + 8004b2a: e0ee b.n 8004d0a + 8004b2c: 2304 movs r3, #4 + 8004b2e: 77fb strb r3, [r7, #31] + 8004b30: e0eb b.n 8004d0a + 8004b32: 2308 movs r3, #8 + 8004b34: 77fb strb r3, [r7, #31] + 8004b36: e0e8 b.n 8004d0a + 8004b38: 2310 movs r3, #16 + 8004b3a: 77fb strb r3, [r7, #31] + 8004b3c: bf00 nop + 8004b3e: e0e4 b.n 8004d0a + 8004b40: 687b ldr r3, [r7, #4] + 8004b42: 681b ldr r3, [r3, #0] + 8004b44: 4a5f ldr r2, [pc, #380] ; (8004cc4 ) + 8004b46: 4293 cmp r3, r2 + 8004b48: d120 bne.n 8004b8c + 8004b4a: 4b5b ldr r3, [pc, #364] ; (8004cb8 ) + 8004b4c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004b50: f003 03c0 and.w r3, r3, #192 ; 0xc0 + 8004b54: 2b40 cmp r3, #64 ; 0x40 + 8004b56: d00f beq.n 8004b78 + 8004b58: 2b40 cmp r3, #64 ; 0x40 + 8004b5a: d802 bhi.n 8004b62 + 8004b5c: 2b00 cmp r3, #0 + 8004b5e: d005 beq.n 8004b6c + 8004b60: e010 b.n 8004b84 + 8004b62: 2b80 cmp r3, #128 ; 0x80 + 8004b64: d005 beq.n 8004b72 + 8004b66: 2bc0 cmp r3, #192 ; 0xc0 + 8004b68: d009 beq.n 8004b7e + 8004b6a: e00b b.n 8004b84 + 8004b6c: 2300 movs r3, #0 + 8004b6e: 77fb strb r3, [r7, #31] + 8004b70: e0cb b.n 8004d0a + 8004b72: 2302 movs r3, #2 + 8004b74: 77fb strb r3, [r7, #31] + 8004b76: e0c8 b.n 8004d0a + 8004b78: 2304 movs r3, #4 + 8004b7a: 77fb strb r3, [r7, #31] + 8004b7c: e0c5 b.n 8004d0a + 8004b7e: 2308 movs r3, #8 + 8004b80: 77fb strb r3, [r7, #31] + 8004b82: e0c2 b.n 8004d0a + 8004b84: 2310 movs r3, #16 + 8004b86: 77fb strb r3, [r7, #31] + 8004b88: bf00 nop + 8004b8a: e0be b.n 8004d0a + 8004b8c: 687b ldr r3, [r7, #4] + 8004b8e: 681b ldr r3, [r3, #0] + 8004b90: 4a4d ldr r2, [pc, #308] ; (8004cc8 ) + 8004b92: 4293 cmp r3, r2 + 8004b94: d124 bne.n 8004be0 + 8004b96: 4b48 ldr r3, [pc, #288] ; (8004cb8 ) + 8004b98: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004b9c: f403 7340 and.w r3, r3, #768 ; 0x300 + 8004ba0: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8004ba4: d012 beq.n 8004bcc + 8004ba6: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8004baa: d802 bhi.n 8004bb2 + 8004bac: 2b00 cmp r3, #0 + 8004bae: d007 beq.n 8004bc0 + 8004bb0: e012 b.n 8004bd8 + 8004bb2: f5b3 7f00 cmp.w r3, #512 ; 0x200 + 8004bb6: d006 beq.n 8004bc6 + 8004bb8: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8004bbc: d009 beq.n 8004bd2 + 8004bbe: e00b b.n 8004bd8 + 8004bc0: 2300 movs r3, #0 + 8004bc2: 77fb strb r3, [r7, #31] + 8004bc4: e0a1 b.n 8004d0a + 8004bc6: 2302 movs r3, #2 + 8004bc8: 77fb strb r3, [r7, #31] + 8004bca: e09e b.n 8004d0a + 8004bcc: 2304 movs r3, #4 + 8004bce: 77fb strb r3, [r7, #31] + 8004bd0: e09b b.n 8004d0a + 8004bd2: 2308 movs r3, #8 + 8004bd4: 77fb strb r3, [r7, #31] + 8004bd6: e098 b.n 8004d0a + 8004bd8: 2310 movs r3, #16 + 8004bda: 77fb strb r3, [r7, #31] + 8004bdc: bf00 nop + 8004bde: e094 b.n 8004d0a + 8004be0: 687b ldr r3, [r7, #4] + 8004be2: 681b ldr r3, [r3, #0] + 8004be4: 4a39 ldr r2, [pc, #228] ; (8004ccc ) + 8004be6: 4293 cmp r3, r2 + 8004be8: d124 bne.n 8004c34 + 8004bea: 4b33 ldr r3, [pc, #204] ; (8004cb8 ) + 8004bec: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004bf0: f403 6340 and.w r3, r3, #3072 ; 0xc00 + 8004bf4: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004bf8: d012 beq.n 8004c20 + 8004bfa: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004bfe: d802 bhi.n 8004c06 + 8004c00: 2b00 cmp r3, #0 + 8004c02: d007 beq.n 8004c14 + 8004c04: e012 b.n 8004c2c + 8004c06: f5b3 6f00 cmp.w r3, #2048 ; 0x800 + 8004c0a: d006 beq.n 8004c1a + 8004c0c: f5b3 6f40 cmp.w r3, #3072 ; 0xc00 + 8004c10: d009 beq.n 8004c26 + 8004c12: e00b b.n 8004c2c + 8004c14: 2301 movs r3, #1 + 8004c16: 77fb strb r3, [r7, #31] + 8004c18: e077 b.n 8004d0a + 8004c1a: 2302 movs r3, #2 + 8004c1c: 77fb strb r3, [r7, #31] + 8004c1e: e074 b.n 8004d0a + 8004c20: 2304 movs r3, #4 + 8004c22: 77fb strb r3, [r7, #31] + 8004c24: e071 b.n 8004d0a + 8004c26: 2308 movs r3, #8 + 8004c28: 77fb strb r3, [r7, #31] + 8004c2a: e06e b.n 8004d0a + 8004c2c: 2310 movs r3, #16 + 8004c2e: 77fb strb r3, [r7, #31] + 8004c30: bf00 nop + 8004c32: e06a b.n 8004d0a + 8004c34: 687b ldr r3, [r7, #4] + 8004c36: 681b ldr r3, [r3, #0] + 8004c38: 4a25 ldr r2, [pc, #148] ; (8004cd0 ) + 8004c3a: 4293 cmp r3, r2 + 8004c3c: d124 bne.n 8004c88 + 8004c3e: 4b1e ldr r3, [pc, #120] ; (8004cb8 ) + 8004c40: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004c44: f403 5340 and.w r3, r3, #12288 ; 0x3000 + 8004c48: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004c4c: d012 beq.n 8004c74 + 8004c4e: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004c52: d802 bhi.n 8004c5a + 8004c54: 2b00 cmp r3, #0 + 8004c56: d007 beq.n 8004c68 + 8004c58: e012 b.n 8004c80 + 8004c5a: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8004c5e: d006 beq.n 8004c6e + 8004c60: f5b3 5f40 cmp.w r3, #12288 ; 0x3000 + 8004c64: d009 beq.n 8004c7a + 8004c66: e00b b.n 8004c80 + 8004c68: 2300 movs r3, #0 + 8004c6a: 77fb strb r3, [r7, #31] + 8004c6c: e04d b.n 8004d0a + 8004c6e: 2302 movs r3, #2 + 8004c70: 77fb strb r3, [r7, #31] + 8004c72: e04a b.n 8004d0a + 8004c74: 2304 movs r3, #4 + 8004c76: 77fb strb r3, [r7, #31] + 8004c78: e047 b.n 8004d0a + 8004c7a: 2308 movs r3, #8 + 8004c7c: 77fb strb r3, [r7, #31] + 8004c7e: e044 b.n 8004d0a + 8004c80: 2310 movs r3, #16 + 8004c82: 77fb strb r3, [r7, #31] + 8004c84: bf00 nop + 8004c86: e040 b.n 8004d0a + 8004c88: 687b ldr r3, [r7, #4] + 8004c8a: 681b ldr r3, [r3, #0] + 8004c8c: 4a11 ldr r2, [pc, #68] ; (8004cd4 ) + 8004c8e: 4293 cmp r3, r2 + 8004c90: d139 bne.n 8004d06 + 8004c92: 4b09 ldr r3, [pc, #36] ; (8004cb8 ) + 8004c94: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004c98: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8004c9c: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 8004ca0: d027 beq.n 8004cf2 + 8004ca2: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 8004ca6: d817 bhi.n 8004cd8 + 8004ca8: 2b00 cmp r3, #0 + 8004caa: d01c beq.n 8004ce6 + 8004cac: e027 b.n 8004cfe + 8004cae: bf00 nop + 8004cb0: efff69f3 .word 0xefff69f3 + 8004cb4: 40011000 .word 0x40011000 + 8004cb8: 40023800 .word 0x40023800 + 8004cbc: 40004400 .word 0x40004400 + 8004cc0: 40004800 .word 0x40004800 + 8004cc4: 40004c00 .word 0x40004c00 + 8004cc8: 40005000 .word 0x40005000 + 8004ccc: 40011400 .word 0x40011400 + 8004cd0: 40007800 .word 0x40007800 + 8004cd4: 40007c00 .word 0x40007c00 + 8004cd8: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 8004cdc: d006 beq.n 8004cec + 8004cde: f5b3 4f40 cmp.w r3, #49152 ; 0xc000 + 8004ce2: d009 beq.n 8004cf8 + 8004ce4: e00b b.n 8004cfe + 8004ce6: 2300 movs r3, #0 + 8004ce8: 77fb strb r3, [r7, #31] + 8004cea: e00e b.n 8004d0a + 8004cec: 2302 movs r3, #2 + 8004cee: 77fb strb r3, [r7, #31] + 8004cf0: e00b b.n 8004d0a + 8004cf2: 2304 movs r3, #4 + 8004cf4: 77fb strb r3, [r7, #31] + 8004cf6: e008 b.n 8004d0a + 8004cf8: 2308 movs r3, #8 + 8004cfa: 77fb strb r3, [r7, #31] + 8004cfc: e005 b.n 8004d0a + 8004cfe: 2310 movs r3, #16 + 8004d00: 77fb strb r3, [r7, #31] + 8004d02: bf00 nop + 8004d04: e001 b.n 8004d0a + 8004d06: 2310 movs r3, #16 + 8004d08: 77fb strb r3, [r7, #31] if (huart->Init.OverSampling == UART_OVERSAMPLING_8) - 8004c42: 687b ldr r3, [r7, #4] - 8004c44: 69db ldr r3, [r3, #28] - 8004c46: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 - 8004c4a: d17c bne.n 8004d46 + 8004d0a: 687b ldr r3, [r7, #4] + 8004d0c: 69db ldr r3, [r3, #28] + 8004d0e: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 8004d12: d17c bne.n 8004e0e { switch (clocksource) - 8004c4c: 7ffb ldrb r3, [r7, #31] - 8004c4e: 2b08 cmp r3, #8 - 8004c50: d859 bhi.n 8004d06 - 8004c52: a201 add r2, pc, #4 ; (adr r2, 8004c58 ) - 8004c54: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004c58: 08004c7d .word 0x08004c7d - 8004c5c: 08004c9b .word 0x08004c9b - 8004c60: 08004cb9 .word 0x08004cb9 - 8004c64: 08004d07 .word 0x08004d07 - 8004c68: 08004cd1 .word 0x08004cd1 - 8004c6c: 08004d07 .word 0x08004d07 - 8004c70: 08004d07 .word 0x08004d07 - 8004c74: 08004d07 .word 0x08004d07 - 8004c78: 08004cef .word 0x08004cef + 8004d14: 7ffb ldrb r3, [r7, #31] + 8004d16: 2b08 cmp r3, #8 + 8004d18: d859 bhi.n 8004dce + 8004d1a: a201 add r2, pc, #4 ; (adr r2, 8004d20 ) + 8004d1c: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004d20: 08004d45 .word 0x08004d45 + 8004d24: 08004d63 .word 0x08004d63 + 8004d28: 08004d81 .word 0x08004d81 + 8004d2c: 08004dcf .word 0x08004dcf + 8004d30: 08004d99 .word 0x08004d99 + 8004d34: 08004dcf .word 0x08004dcf + 8004d38: 08004dcf .word 0x08004dcf + 8004d3c: 08004dcf .word 0x08004dcf + 8004d40: 08004db7 .word 0x08004db7 { case UART_CLOCKSOURCE_PCLK1: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); - 8004c7c: f7fd fe50 bl 8002920 - 8004c80: 4603 mov r3, r0 - 8004c82: 005a lsls r2, r3, #1 - 8004c84: 687b ldr r3, [r7, #4] - 8004c86: 685b ldr r3, [r3, #4] - 8004c88: 085b lsrs r3, r3, #1 - 8004c8a: 441a add r2, r3 - 8004c8c: 687b ldr r3, [r7, #4] - 8004c8e: 685b ldr r3, [r3, #4] - 8004c90: fbb2 f3f3 udiv r3, r2, r3 - 8004c94: b29b uxth r3, r3 - 8004c96: 61bb str r3, [r7, #24] + 8004d44: f7fd fe50 bl 80029e8 + 8004d48: 4603 mov r3, r0 + 8004d4a: 005a lsls r2, r3, #1 + 8004d4c: 687b ldr r3, [r7, #4] + 8004d4e: 685b ldr r3, [r3, #4] + 8004d50: 085b lsrs r3, r3, #1 + 8004d52: 441a add r2, r3 + 8004d54: 687b ldr r3, [r7, #4] + 8004d56: 685b ldr r3, [r3, #4] + 8004d58: fbb2 f3f3 udiv r3, r2, r3 + 8004d5c: b29b uxth r3, r3 + 8004d5e: 61bb str r3, [r7, #24] break; - 8004c98: e038 b.n 8004d0c + 8004d60: e038 b.n 8004dd4 case UART_CLOCKSOURCE_PCLK2: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); - 8004c9a: f7fd fe55 bl 8002948 - 8004c9e: 4603 mov r3, r0 - 8004ca0: 005a lsls r2, r3, #1 - 8004ca2: 687b ldr r3, [r7, #4] - 8004ca4: 685b ldr r3, [r3, #4] - 8004ca6: 085b lsrs r3, r3, #1 - 8004ca8: 441a add r2, r3 - 8004caa: 687b ldr r3, [r7, #4] - 8004cac: 685b ldr r3, [r3, #4] - 8004cae: fbb2 f3f3 udiv r3, r2, r3 - 8004cb2: b29b uxth r3, r3 - 8004cb4: 61bb str r3, [r7, #24] + 8004d62: f7fd fe55 bl 8002a10 + 8004d66: 4603 mov r3, r0 + 8004d68: 005a lsls r2, r3, #1 + 8004d6a: 687b ldr r3, [r7, #4] + 8004d6c: 685b ldr r3, [r3, #4] + 8004d6e: 085b lsrs r3, r3, #1 + 8004d70: 441a add r2, r3 + 8004d72: 687b ldr r3, [r7, #4] + 8004d74: 685b ldr r3, [r3, #4] + 8004d76: fbb2 f3f3 udiv r3, r2, r3 + 8004d7a: b29b uxth r3, r3 + 8004d7c: 61bb str r3, [r7, #24] break; - 8004cb6: e029 b.n 8004d0c + 8004d7e: e029 b.n 8004dd4 case UART_CLOCKSOURCE_HSI: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HSI_VALUE, huart->Init.BaudRate)); - 8004cb8: 687b ldr r3, [r7, #4] - 8004cba: 685b ldr r3, [r3, #4] - 8004cbc: 085a lsrs r2, r3, #1 - 8004cbe: 4b5d ldr r3, [pc, #372] ; (8004e34 ) - 8004cc0: 4413 add r3, r2 - 8004cc2: 687a ldr r2, [r7, #4] - 8004cc4: 6852 ldr r2, [r2, #4] - 8004cc6: fbb3 f3f2 udiv r3, r3, r2 - 8004cca: b29b uxth r3, r3 - 8004ccc: 61bb str r3, [r7, #24] + 8004d80: 687b ldr r3, [r7, #4] + 8004d82: 685b ldr r3, [r3, #4] + 8004d84: 085a lsrs r2, r3, #1 + 8004d86: 4b5d ldr r3, [pc, #372] ; (8004efc ) + 8004d88: 4413 add r3, r2 + 8004d8a: 687a ldr r2, [r7, #4] + 8004d8c: 6852 ldr r2, [r2, #4] + 8004d8e: fbb3 f3f2 udiv r3, r3, r2 + 8004d92: b29b uxth r3, r3 + 8004d94: 61bb str r3, [r7, #24] break; - 8004cce: e01d b.n 8004d0c + 8004d96: e01d b.n 8004dd4 case UART_CLOCKSOURCE_SYSCLK: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); - 8004cd0: f7fd fd68 bl 80027a4 - 8004cd4: 4603 mov r3, r0 - 8004cd6: 005a lsls r2, r3, #1 - 8004cd8: 687b ldr r3, [r7, #4] - 8004cda: 685b ldr r3, [r3, #4] - 8004cdc: 085b lsrs r3, r3, #1 - 8004cde: 441a add r2, r3 - 8004ce0: 687b ldr r3, [r7, #4] - 8004ce2: 685b ldr r3, [r3, #4] - 8004ce4: fbb2 f3f3 udiv r3, r2, r3 - 8004ce8: b29b uxth r3, r3 - 8004cea: 61bb str r3, [r7, #24] + 8004d98: f7fd fd68 bl 800286c + 8004d9c: 4603 mov r3, r0 + 8004d9e: 005a lsls r2, r3, #1 + 8004da0: 687b ldr r3, [r7, #4] + 8004da2: 685b ldr r3, [r3, #4] + 8004da4: 085b lsrs r3, r3, #1 + 8004da6: 441a add r2, r3 + 8004da8: 687b ldr r3, [r7, #4] + 8004daa: 685b ldr r3, [r3, #4] + 8004dac: fbb2 f3f3 udiv r3, r2, r3 + 8004db0: b29b uxth r3, r3 + 8004db2: 61bb str r3, [r7, #24] break; - 8004cec: e00e b.n 8004d0c + 8004db4: e00e b.n 8004dd4 case UART_CLOCKSOURCE_LSE: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(LSE_VALUE, huart->Init.BaudRate)); - 8004cee: 687b ldr r3, [r7, #4] - 8004cf0: 685b ldr r3, [r3, #4] - 8004cf2: 085b lsrs r3, r3, #1 - 8004cf4: f503 3280 add.w r2, r3, #65536 ; 0x10000 - 8004cf8: 687b ldr r3, [r7, #4] - 8004cfa: 685b ldr r3, [r3, #4] - 8004cfc: fbb2 f3f3 udiv r3, r2, r3 - 8004d00: b29b uxth r3, r3 - 8004d02: 61bb str r3, [r7, #24] + 8004db6: 687b ldr r3, [r7, #4] + 8004db8: 685b ldr r3, [r3, #4] + 8004dba: 085b lsrs r3, r3, #1 + 8004dbc: f503 3280 add.w r2, r3, #65536 ; 0x10000 + 8004dc0: 687b ldr r3, [r7, #4] + 8004dc2: 685b ldr r3, [r3, #4] + 8004dc4: fbb2 f3f3 udiv r3, r2, r3 + 8004dc8: b29b uxth r3, r3 + 8004dca: 61bb str r3, [r7, #24] break; - 8004d04: e002 b.n 8004d0c + 8004dcc: e002 b.n 8004dd4 case UART_CLOCKSOURCE_UNDEFINED: default: ret = HAL_ERROR; - 8004d06: 2301 movs r3, #1 - 8004d08: 75fb strb r3, [r7, #23] + 8004dce: 2301 movs r3, #1 + 8004dd0: 75fb strb r3, [r7, #23] break; - 8004d0a: bf00 nop + 8004dd2: bf00 nop } /* USARTDIV must be greater than or equal to 0d16 */ if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) - 8004d0c: 69bb ldr r3, [r7, #24] - 8004d0e: 2b0f cmp r3, #15 - 8004d10: d916 bls.n 8004d40 - 8004d12: 69bb ldr r3, [r7, #24] - 8004d14: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 8004d18: d212 bcs.n 8004d40 + 8004dd4: 69bb ldr r3, [r7, #24] + 8004dd6: 2b0f cmp r3, #15 + 8004dd8: d916 bls.n 8004e08 + 8004dda: 69bb ldr r3, [r7, #24] + 8004ddc: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8004de0: d212 bcs.n 8004e08 { brrtemp = (uint16_t)(usartdiv & 0xFFF0U); - 8004d1a: 69bb ldr r3, [r7, #24] - 8004d1c: b29b uxth r3, r3 - 8004d1e: f023 030f bic.w r3, r3, #15 - 8004d22: 81fb strh r3, [r7, #14] + 8004de2: 69bb ldr r3, [r7, #24] + 8004de4: b29b uxth r3, r3 + 8004de6: f023 030f bic.w r3, r3, #15 + 8004dea: 81fb strh r3, [r7, #14] brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U); - 8004d24: 69bb ldr r3, [r7, #24] - 8004d26: 085b lsrs r3, r3, #1 - 8004d28: b29b uxth r3, r3 - 8004d2a: f003 0307 and.w r3, r3, #7 - 8004d2e: b29a uxth r2, r3 - 8004d30: 89fb ldrh r3, [r7, #14] - 8004d32: 4313 orrs r3, r2 - 8004d34: 81fb strh r3, [r7, #14] + 8004dec: 69bb ldr r3, [r7, #24] + 8004dee: 085b lsrs r3, r3, #1 + 8004df0: b29b uxth r3, r3 + 8004df2: f003 0307 and.w r3, r3, #7 + 8004df6: b29a uxth r2, r3 + 8004df8: 89fb ldrh r3, [r7, #14] + 8004dfa: 4313 orrs r3, r2 + 8004dfc: 81fb strh r3, [r7, #14] huart->Instance->BRR = brrtemp; - 8004d36: 687b ldr r3, [r7, #4] - 8004d38: 681b ldr r3, [r3, #0] - 8004d3a: 89fa ldrh r2, [r7, #14] - 8004d3c: 60da str r2, [r3, #12] - 8004d3e: e06e b.n 8004e1e + 8004dfe: 687b ldr r3, [r7, #4] + 8004e00: 681b ldr r3, [r3, #0] + 8004e02: 89fa ldrh r2, [r7, #14] + 8004e04: 60da str r2, [r3, #12] + 8004e06: e06e b.n 8004ee6 } else { ret = HAL_ERROR; - 8004d40: 2301 movs r3, #1 - 8004d42: 75fb strb r3, [r7, #23] - 8004d44: e06b b.n 8004e1e + 8004e08: 2301 movs r3, #1 + 8004e0a: 75fb strb r3, [r7, #23] + 8004e0c: e06b b.n 8004ee6 } } else { switch (clocksource) - 8004d46: 7ffb ldrb r3, [r7, #31] - 8004d48: 2b08 cmp r3, #8 - 8004d4a: d857 bhi.n 8004dfc - 8004d4c: a201 add r2, pc, #4 ; (adr r2, 8004d54 ) - 8004d4e: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004d52: bf00 nop - 8004d54: 08004d79 .word 0x08004d79 - 8004d58: 08004d95 .word 0x08004d95 - 8004d5c: 08004db1 .word 0x08004db1 - 8004d60: 08004dfd .word 0x08004dfd - 8004d64: 08004dc9 .word 0x08004dc9 - 8004d68: 08004dfd .word 0x08004dfd - 8004d6c: 08004dfd .word 0x08004dfd - 8004d70: 08004dfd .word 0x08004dfd - 8004d74: 08004de5 .word 0x08004de5 + 8004e0e: 7ffb ldrb r3, [r7, #31] + 8004e10: 2b08 cmp r3, #8 + 8004e12: d857 bhi.n 8004ec4 + 8004e14: a201 add r2, pc, #4 ; (adr r2, 8004e1c ) + 8004e16: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004e1a: bf00 nop + 8004e1c: 08004e41 .word 0x08004e41 + 8004e20: 08004e5d .word 0x08004e5d + 8004e24: 08004e79 .word 0x08004e79 + 8004e28: 08004ec5 .word 0x08004ec5 + 8004e2c: 08004e91 .word 0x08004e91 + 8004e30: 08004ec5 .word 0x08004ec5 + 8004e34: 08004ec5 .word 0x08004ec5 + 8004e38: 08004ec5 .word 0x08004ec5 + 8004e3c: 08004ead .word 0x08004ead { case UART_CLOCKSOURCE_PCLK1: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); - 8004d78: f7fd fdd2 bl 8002920 - 8004d7c: 4602 mov r2, r0 - 8004d7e: 687b ldr r3, [r7, #4] - 8004d80: 685b ldr r3, [r3, #4] - 8004d82: 085b lsrs r3, r3, #1 - 8004d84: 441a add r2, r3 - 8004d86: 687b ldr r3, [r7, #4] - 8004d88: 685b ldr r3, [r3, #4] - 8004d8a: fbb2 f3f3 udiv r3, r2, r3 - 8004d8e: b29b uxth r3, r3 - 8004d90: 61bb str r3, [r7, #24] + 8004e40: f7fd fdd2 bl 80029e8 + 8004e44: 4602 mov r2, r0 + 8004e46: 687b ldr r3, [r7, #4] + 8004e48: 685b ldr r3, [r3, #4] + 8004e4a: 085b lsrs r3, r3, #1 + 8004e4c: 441a add r2, r3 + 8004e4e: 687b ldr r3, [r7, #4] + 8004e50: 685b ldr r3, [r3, #4] + 8004e52: fbb2 f3f3 udiv r3, r2, r3 + 8004e56: b29b uxth r3, r3 + 8004e58: 61bb str r3, [r7, #24] break; - 8004d92: e036 b.n 8004e02 + 8004e5a: e036 b.n 8004eca case UART_CLOCKSOURCE_PCLK2: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); - 8004d94: f7fd fdd8 bl 8002948 - 8004d98: 4602 mov r2, r0 - 8004d9a: 687b ldr r3, [r7, #4] - 8004d9c: 685b ldr r3, [r3, #4] - 8004d9e: 085b lsrs r3, r3, #1 - 8004da0: 441a add r2, r3 - 8004da2: 687b ldr r3, [r7, #4] - 8004da4: 685b ldr r3, [r3, #4] - 8004da6: fbb2 f3f3 udiv r3, r2, r3 - 8004daa: b29b uxth r3, r3 - 8004dac: 61bb str r3, [r7, #24] + 8004e5c: f7fd fdd8 bl 8002a10 + 8004e60: 4602 mov r2, r0 + 8004e62: 687b ldr r3, [r7, #4] + 8004e64: 685b ldr r3, [r3, #4] + 8004e66: 085b lsrs r3, r3, #1 + 8004e68: 441a add r2, r3 + 8004e6a: 687b ldr r3, [r7, #4] + 8004e6c: 685b ldr r3, [r3, #4] + 8004e6e: fbb2 f3f3 udiv r3, r2, r3 + 8004e72: b29b uxth r3, r3 + 8004e74: 61bb str r3, [r7, #24] break; - 8004dae: e028 b.n 8004e02 + 8004e76: e028 b.n 8004eca case UART_CLOCKSOURCE_HSI: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HSI_VALUE, huart->Init.BaudRate)); - 8004db0: 687b ldr r3, [r7, #4] - 8004db2: 685b ldr r3, [r3, #4] - 8004db4: 085a lsrs r2, r3, #1 - 8004db6: 4b20 ldr r3, [pc, #128] ; (8004e38 ) - 8004db8: 4413 add r3, r2 - 8004dba: 687a ldr r2, [r7, #4] - 8004dbc: 6852 ldr r2, [r2, #4] - 8004dbe: fbb3 f3f2 udiv r3, r3, r2 - 8004dc2: b29b uxth r3, r3 - 8004dc4: 61bb str r3, [r7, #24] + 8004e78: 687b ldr r3, [r7, #4] + 8004e7a: 685b ldr r3, [r3, #4] + 8004e7c: 085a lsrs r2, r3, #1 + 8004e7e: 4b20 ldr r3, [pc, #128] ; (8004f00 ) + 8004e80: 4413 add r3, r2 + 8004e82: 687a ldr r2, [r7, #4] + 8004e84: 6852 ldr r2, [r2, #4] + 8004e86: fbb3 f3f2 udiv r3, r3, r2 + 8004e8a: b29b uxth r3, r3 + 8004e8c: 61bb str r3, [r7, #24] break; - 8004dc6: e01c b.n 8004e02 + 8004e8e: e01c b.n 8004eca case UART_CLOCKSOURCE_SYSCLK: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); - 8004dc8: f7fd fcec bl 80027a4 - 8004dcc: 4602 mov r2, r0 - 8004dce: 687b ldr r3, [r7, #4] - 8004dd0: 685b ldr r3, [r3, #4] - 8004dd2: 085b lsrs r3, r3, #1 - 8004dd4: 441a add r2, r3 - 8004dd6: 687b ldr r3, [r7, #4] - 8004dd8: 685b ldr r3, [r3, #4] - 8004dda: fbb2 f3f3 udiv r3, r2, r3 - 8004dde: b29b uxth r3, r3 - 8004de0: 61bb str r3, [r7, #24] + 8004e90: f7fd fcec bl 800286c + 8004e94: 4602 mov r2, r0 + 8004e96: 687b ldr r3, [r7, #4] + 8004e98: 685b ldr r3, [r3, #4] + 8004e9a: 085b lsrs r3, r3, #1 + 8004e9c: 441a add r2, r3 + 8004e9e: 687b ldr r3, [r7, #4] + 8004ea0: 685b ldr r3, [r3, #4] + 8004ea2: fbb2 f3f3 udiv r3, r2, r3 + 8004ea6: b29b uxth r3, r3 + 8004ea8: 61bb str r3, [r7, #24] break; - 8004de2: e00e b.n 8004e02 + 8004eaa: e00e b.n 8004eca case UART_CLOCKSOURCE_LSE: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(LSE_VALUE, huart->Init.BaudRate)); - 8004de4: 687b ldr r3, [r7, #4] - 8004de6: 685b ldr r3, [r3, #4] - 8004de8: 085b lsrs r3, r3, #1 - 8004dea: f503 4200 add.w r2, r3, #32768 ; 0x8000 - 8004dee: 687b ldr r3, [r7, #4] - 8004df0: 685b ldr r3, [r3, #4] - 8004df2: fbb2 f3f3 udiv r3, r2, r3 - 8004df6: b29b uxth r3, r3 - 8004df8: 61bb str r3, [r7, #24] + 8004eac: 687b ldr r3, [r7, #4] + 8004eae: 685b ldr r3, [r3, #4] + 8004eb0: 085b lsrs r3, r3, #1 + 8004eb2: f503 4200 add.w r2, r3, #32768 ; 0x8000 + 8004eb6: 687b ldr r3, [r7, #4] + 8004eb8: 685b ldr r3, [r3, #4] + 8004eba: fbb2 f3f3 udiv r3, r2, r3 + 8004ebe: b29b uxth r3, r3 + 8004ec0: 61bb str r3, [r7, #24] break; - 8004dfa: e002 b.n 8004e02 + 8004ec2: e002 b.n 8004eca case UART_CLOCKSOURCE_UNDEFINED: default: ret = HAL_ERROR; - 8004dfc: 2301 movs r3, #1 - 8004dfe: 75fb strb r3, [r7, #23] + 8004ec4: 2301 movs r3, #1 + 8004ec6: 75fb strb r3, [r7, #23] break; - 8004e00: bf00 nop + 8004ec8: bf00 nop } /* USARTDIV must be greater than or equal to 0d16 */ if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) - 8004e02: 69bb ldr r3, [r7, #24] - 8004e04: 2b0f cmp r3, #15 - 8004e06: d908 bls.n 8004e1a - 8004e08: 69bb ldr r3, [r7, #24] - 8004e0a: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 8004e0e: d204 bcs.n 8004e1a + 8004eca: 69bb ldr r3, [r7, #24] + 8004ecc: 2b0f cmp r3, #15 + 8004ece: d908 bls.n 8004ee2 + 8004ed0: 69bb ldr r3, [r7, #24] + 8004ed2: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8004ed6: d204 bcs.n 8004ee2 { huart->Instance->BRR = usartdiv; - 8004e10: 687b ldr r3, [r7, #4] - 8004e12: 681b ldr r3, [r3, #0] - 8004e14: 69ba ldr r2, [r7, #24] - 8004e16: 60da str r2, [r3, #12] - 8004e18: e001 b.n 8004e1e + 8004ed8: 687b ldr r3, [r7, #4] + 8004eda: 681b ldr r3, [r3, #0] + 8004edc: 69ba ldr r2, [r7, #24] + 8004ede: 60da str r2, [r3, #12] + 8004ee0: e001 b.n 8004ee6 } else { ret = HAL_ERROR; - 8004e1a: 2301 movs r3, #1 - 8004e1c: 75fb strb r3, [r7, #23] + 8004ee2: 2301 movs r3, #1 + 8004ee4: 75fb strb r3, [r7, #23] } } /* Clear ISR function pointers */ huart->RxISR = NULL; - 8004e1e: 687b ldr r3, [r7, #4] - 8004e20: 2200 movs r2, #0 - 8004e22: 661a str r2, [r3, #96] ; 0x60 + 8004ee6: 687b ldr r3, [r7, #4] + 8004ee8: 2200 movs r2, #0 + 8004eea: 661a str r2, [r3, #96] ; 0x60 huart->TxISR = NULL; - 8004e24: 687b ldr r3, [r7, #4] - 8004e26: 2200 movs r2, #0 - 8004e28: 665a str r2, [r3, #100] ; 0x64 + 8004eec: 687b ldr r3, [r7, #4] + 8004eee: 2200 movs r2, #0 + 8004ef0: 665a str r2, [r3, #100] ; 0x64 return ret; - 8004e2a: 7dfb ldrb r3, [r7, #23] + 8004ef2: 7dfb ldrb r3, [r7, #23] } - 8004e2c: 4618 mov r0, r3 - 8004e2e: 3720 adds r7, #32 - 8004e30: 46bd mov sp, r7 - 8004e32: bd80 pop {r7, pc} - 8004e34: 01e84800 .word 0x01e84800 - 8004e38: 00f42400 .word 0x00f42400 - -08004e3c : + 8004ef4: 4618 mov r0, r3 + 8004ef6: 3720 adds r7, #32 + 8004ef8: 46bd mov sp, r7 + 8004efa: bd80 pop {r7, pc} + 8004efc: 01e84800 .word 0x01e84800 + 8004f00: 00f42400 .word 0x00f42400 + +08004f04 : * @brief Configure the UART peripheral advanced features. * @param huart UART handle. * @retval None */ void UART_AdvFeatureConfig(UART_HandleTypeDef *huart) { - 8004e3c: b480 push {r7} - 8004e3e: b083 sub sp, #12 - 8004e40: af00 add r7, sp, #0 - 8004e42: 6078 str r0, [r7, #4] + 8004f04: b480 push {r7} + 8004f06: b083 sub sp, #12 + 8004f08: af00 add r7, sp, #0 + 8004f0a: 6078 str r0, [r7, #4] /* Check whether the set of advanced features to configure is properly set */ assert_param(IS_UART_ADVFEATURE_INIT(huart->AdvancedInit.AdvFeatureInit)); /* if required, configure TX pin active level inversion */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_TXINVERT_INIT)) - 8004e44: 687b ldr r3, [r7, #4] - 8004e46: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004e48: f003 0301 and.w r3, r3, #1 - 8004e4c: 2b00 cmp r3, #0 - 8004e4e: d00a beq.n 8004e66 + 8004f0c: 687b ldr r3, [r7, #4] + 8004f0e: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004f10: f003 0301 and.w r3, r3, #1 + 8004f14: 2b00 cmp r3, #0 + 8004f16: d00a beq.n 8004f2e { assert_param(IS_UART_ADVFEATURE_TXINV(huart->AdvancedInit.TxPinLevelInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_TXINV, huart->AdvancedInit.TxPinLevelInvert); - 8004e50: 687b ldr r3, [r7, #4] - 8004e52: 681b ldr r3, [r3, #0] - 8004e54: 685b ldr r3, [r3, #4] - 8004e56: f423 3100 bic.w r1, r3, #131072 ; 0x20000 - 8004e5a: 687b ldr r3, [r7, #4] - 8004e5c: 6a9a ldr r2, [r3, #40] ; 0x28 - 8004e5e: 687b ldr r3, [r7, #4] - 8004e60: 681b ldr r3, [r3, #0] - 8004e62: 430a orrs r2, r1 - 8004e64: 605a str r2, [r3, #4] + 8004f18: 687b ldr r3, [r7, #4] + 8004f1a: 681b ldr r3, [r3, #0] + 8004f1c: 685b ldr r3, [r3, #4] + 8004f1e: f423 3100 bic.w r1, r3, #131072 ; 0x20000 + 8004f22: 687b ldr r3, [r7, #4] + 8004f24: 6a9a ldr r2, [r3, #40] ; 0x28 + 8004f26: 687b ldr r3, [r7, #4] + 8004f28: 681b ldr r3, [r3, #0] + 8004f2a: 430a orrs r2, r1 + 8004f2c: 605a str r2, [r3, #4] } /* if required, configure RX pin active level inversion */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXINVERT_INIT)) - 8004e66: 687b ldr r3, [r7, #4] - 8004e68: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004e6a: f003 0302 and.w r3, r3, #2 - 8004e6e: 2b00 cmp r3, #0 - 8004e70: d00a beq.n 8004e88 + 8004f2e: 687b ldr r3, [r7, #4] + 8004f30: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004f32: f003 0302 and.w r3, r3, #2 + 8004f36: 2b00 cmp r3, #0 + 8004f38: d00a beq.n 8004f50 { assert_param(IS_UART_ADVFEATURE_RXINV(huart->AdvancedInit.RxPinLevelInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_RXINV, huart->AdvancedInit.RxPinLevelInvert); - 8004e72: 687b ldr r3, [r7, #4] - 8004e74: 681b ldr r3, [r3, #0] - 8004e76: 685b ldr r3, [r3, #4] - 8004e78: f423 3180 bic.w r1, r3, #65536 ; 0x10000 - 8004e7c: 687b ldr r3, [r7, #4] - 8004e7e: 6ada ldr r2, [r3, #44] ; 0x2c - 8004e80: 687b ldr r3, [r7, #4] - 8004e82: 681b ldr r3, [r3, #0] - 8004e84: 430a orrs r2, r1 - 8004e86: 605a str r2, [r3, #4] + 8004f3a: 687b ldr r3, [r7, #4] + 8004f3c: 681b ldr r3, [r3, #0] + 8004f3e: 685b ldr r3, [r3, #4] + 8004f40: f423 3180 bic.w r1, r3, #65536 ; 0x10000 + 8004f44: 687b ldr r3, [r7, #4] + 8004f46: 6ada ldr r2, [r3, #44] ; 0x2c + 8004f48: 687b ldr r3, [r7, #4] + 8004f4a: 681b ldr r3, [r3, #0] + 8004f4c: 430a orrs r2, r1 + 8004f4e: 605a str r2, [r3, #4] } /* if required, configure data inversion */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_DATAINVERT_INIT)) - 8004e88: 687b ldr r3, [r7, #4] - 8004e8a: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004e8c: f003 0304 and.w r3, r3, #4 - 8004e90: 2b00 cmp r3, #0 - 8004e92: d00a beq.n 8004eaa + 8004f50: 687b ldr r3, [r7, #4] + 8004f52: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004f54: f003 0304 and.w r3, r3, #4 + 8004f58: 2b00 cmp r3, #0 + 8004f5a: d00a beq.n 8004f72 { assert_param(IS_UART_ADVFEATURE_DATAINV(huart->AdvancedInit.DataInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_DATAINV, huart->AdvancedInit.DataInvert); - 8004e94: 687b ldr r3, [r7, #4] - 8004e96: 681b ldr r3, [r3, #0] - 8004e98: 685b ldr r3, [r3, #4] - 8004e9a: f423 2180 bic.w r1, r3, #262144 ; 0x40000 - 8004e9e: 687b ldr r3, [r7, #4] - 8004ea0: 6b1a ldr r2, [r3, #48] ; 0x30 - 8004ea2: 687b ldr r3, [r7, #4] - 8004ea4: 681b ldr r3, [r3, #0] - 8004ea6: 430a orrs r2, r1 - 8004ea8: 605a str r2, [r3, #4] + 8004f5c: 687b ldr r3, [r7, #4] + 8004f5e: 681b ldr r3, [r3, #0] + 8004f60: 685b ldr r3, [r3, #4] + 8004f62: f423 2180 bic.w r1, r3, #262144 ; 0x40000 + 8004f66: 687b ldr r3, [r7, #4] + 8004f68: 6b1a ldr r2, [r3, #48] ; 0x30 + 8004f6a: 687b ldr r3, [r7, #4] + 8004f6c: 681b ldr r3, [r3, #0] + 8004f6e: 430a orrs r2, r1 + 8004f70: 605a str r2, [r3, #4] } /* if required, configure RX/TX pins swap */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_SWAP_INIT)) - 8004eaa: 687b ldr r3, [r7, #4] - 8004eac: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004eae: f003 0308 and.w r3, r3, #8 - 8004eb2: 2b00 cmp r3, #0 - 8004eb4: d00a beq.n 8004ecc + 8004f72: 687b ldr r3, [r7, #4] + 8004f74: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004f76: f003 0308 and.w r3, r3, #8 + 8004f7a: 2b00 cmp r3, #0 + 8004f7c: d00a beq.n 8004f94 { assert_param(IS_UART_ADVFEATURE_SWAP(huart->AdvancedInit.Swap)); MODIFY_REG(huart->Instance->CR2, USART_CR2_SWAP, huart->AdvancedInit.Swap); - 8004eb6: 687b ldr r3, [r7, #4] - 8004eb8: 681b ldr r3, [r3, #0] - 8004eba: 685b ldr r3, [r3, #4] - 8004ebc: f423 4100 bic.w r1, r3, #32768 ; 0x8000 - 8004ec0: 687b ldr r3, [r7, #4] - 8004ec2: 6b5a ldr r2, [r3, #52] ; 0x34 - 8004ec4: 687b ldr r3, [r7, #4] - 8004ec6: 681b ldr r3, [r3, #0] - 8004ec8: 430a orrs r2, r1 - 8004eca: 605a str r2, [r3, #4] + 8004f7e: 687b ldr r3, [r7, #4] + 8004f80: 681b ldr r3, [r3, #0] + 8004f82: 685b ldr r3, [r3, #4] + 8004f84: f423 4100 bic.w r1, r3, #32768 ; 0x8000 + 8004f88: 687b ldr r3, [r7, #4] + 8004f8a: 6b5a ldr r2, [r3, #52] ; 0x34 + 8004f8c: 687b ldr r3, [r7, #4] + 8004f8e: 681b ldr r3, [r3, #0] + 8004f90: 430a orrs r2, r1 + 8004f92: 605a str r2, [r3, #4] } /* if required, configure RX overrun detection disabling */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXOVERRUNDISABLE_INIT)) - 8004ecc: 687b ldr r3, [r7, #4] - 8004ece: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004ed0: f003 0310 and.w r3, r3, #16 - 8004ed4: 2b00 cmp r3, #0 - 8004ed6: d00a beq.n 8004eee + 8004f94: 687b ldr r3, [r7, #4] + 8004f96: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004f98: f003 0310 and.w r3, r3, #16 + 8004f9c: 2b00 cmp r3, #0 + 8004f9e: d00a beq.n 8004fb6 { assert_param(IS_UART_OVERRUN(huart->AdvancedInit.OverrunDisable)); MODIFY_REG(huart->Instance->CR3, USART_CR3_OVRDIS, huart->AdvancedInit.OverrunDisable); - 8004ed8: 687b ldr r3, [r7, #4] - 8004eda: 681b ldr r3, [r3, #0] - 8004edc: 689b ldr r3, [r3, #8] - 8004ede: f423 5180 bic.w r1, r3, #4096 ; 0x1000 - 8004ee2: 687b ldr r3, [r7, #4] - 8004ee4: 6b9a ldr r2, [r3, #56] ; 0x38 - 8004ee6: 687b ldr r3, [r7, #4] - 8004ee8: 681b ldr r3, [r3, #0] - 8004eea: 430a orrs r2, r1 - 8004eec: 609a str r2, [r3, #8] + 8004fa0: 687b ldr r3, [r7, #4] + 8004fa2: 681b ldr r3, [r3, #0] + 8004fa4: 689b ldr r3, [r3, #8] + 8004fa6: f423 5180 bic.w r1, r3, #4096 ; 0x1000 + 8004faa: 687b ldr r3, [r7, #4] + 8004fac: 6b9a ldr r2, [r3, #56] ; 0x38 + 8004fae: 687b ldr r3, [r7, #4] + 8004fb0: 681b ldr r3, [r3, #0] + 8004fb2: 430a orrs r2, r1 + 8004fb4: 609a str r2, [r3, #8] } /* if required, configure DMA disabling on reception error */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_DMADISABLEONERROR_INIT)) - 8004eee: 687b ldr r3, [r7, #4] - 8004ef0: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004ef2: f003 0320 and.w r3, r3, #32 - 8004ef6: 2b00 cmp r3, #0 - 8004ef8: d00a beq.n 8004f10 + 8004fb6: 687b ldr r3, [r7, #4] + 8004fb8: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004fba: f003 0320 and.w r3, r3, #32 + 8004fbe: 2b00 cmp r3, #0 + 8004fc0: d00a beq.n 8004fd8 { assert_param(IS_UART_ADVFEATURE_DMAONRXERROR(huart->AdvancedInit.DMADisableonRxError)); MODIFY_REG(huart->Instance->CR3, USART_CR3_DDRE, huart->AdvancedInit.DMADisableonRxError); - 8004efa: 687b ldr r3, [r7, #4] - 8004efc: 681b ldr r3, [r3, #0] - 8004efe: 689b ldr r3, [r3, #8] - 8004f00: f423 5100 bic.w r1, r3, #8192 ; 0x2000 - 8004f04: 687b ldr r3, [r7, #4] - 8004f06: 6bda ldr r2, [r3, #60] ; 0x3c - 8004f08: 687b ldr r3, [r7, #4] - 8004f0a: 681b ldr r3, [r3, #0] - 8004f0c: 430a orrs r2, r1 - 8004f0e: 609a str r2, [r3, #8] + 8004fc2: 687b ldr r3, [r7, #4] + 8004fc4: 681b ldr r3, [r3, #0] + 8004fc6: 689b ldr r3, [r3, #8] + 8004fc8: f423 5100 bic.w r1, r3, #8192 ; 0x2000 + 8004fcc: 687b ldr r3, [r7, #4] + 8004fce: 6bda ldr r2, [r3, #60] ; 0x3c + 8004fd0: 687b ldr r3, [r7, #4] + 8004fd2: 681b ldr r3, [r3, #0] + 8004fd4: 430a orrs r2, r1 + 8004fd6: 609a str r2, [r3, #8] } /* if required, configure auto Baud rate detection scheme */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_AUTOBAUDRATE_INIT)) - 8004f10: 687b ldr r3, [r7, #4] - 8004f12: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004f14: f003 0340 and.w r3, r3, #64 ; 0x40 - 8004f18: 2b00 cmp r3, #0 - 8004f1a: d01a beq.n 8004f52 + 8004fd8: 687b ldr r3, [r7, #4] + 8004fda: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004fdc: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004fe0: 2b00 cmp r3, #0 + 8004fe2: d01a beq.n 800501a { assert_param(IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(huart->Instance)); assert_param(IS_UART_ADVFEATURE_AUTOBAUDRATE(huart->AdvancedInit.AutoBaudRateEnable)); MODIFY_REG(huart->Instance->CR2, USART_CR2_ABREN, huart->AdvancedInit.AutoBaudRateEnable); - 8004f1c: 687b ldr r3, [r7, #4] - 8004f1e: 681b ldr r3, [r3, #0] - 8004f20: 685b ldr r3, [r3, #4] - 8004f22: f423 1180 bic.w r1, r3, #1048576 ; 0x100000 - 8004f26: 687b ldr r3, [r7, #4] - 8004f28: 6c1a ldr r2, [r3, #64] ; 0x40 - 8004f2a: 687b ldr r3, [r7, #4] - 8004f2c: 681b ldr r3, [r3, #0] - 8004f2e: 430a orrs r2, r1 - 8004f30: 605a str r2, [r3, #4] + 8004fe4: 687b ldr r3, [r7, #4] + 8004fe6: 681b ldr r3, [r3, #0] + 8004fe8: 685b ldr r3, [r3, #4] + 8004fea: f423 1180 bic.w r1, r3, #1048576 ; 0x100000 + 8004fee: 687b ldr r3, [r7, #4] + 8004ff0: 6c1a ldr r2, [r3, #64] ; 0x40 + 8004ff2: 687b ldr r3, [r7, #4] + 8004ff4: 681b ldr r3, [r3, #0] + 8004ff6: 430a orrs r2, r1 + 8004ff8: 605a str r2, [r3, #4] /* set auto Baudrate detection parameters if detection is enabled */ if (huart->AdvancedInit.AutoBaudRateEnable == UART_ADVFEATURE_AUTOBAUDRATE_ENABLE) - 8004f32: 687b ldr r3, [r7, #4] - 8004f34: 6c1b ldr r3, [r3, #64] ; 0x40 - 8004f36: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 8004f3a: d10a bne.n 8004f52 + 8004ffa: 687b ldr r3, [r7, #4] + 8004ffc: 6c1b ldr r3, [r3, #64] ; 0x40 + 8004ffe: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8005002: d10a bne.n 800501a { assert_param(IS_UART_ADVFEATURE_AUTOBAUDRATEMODE(huart->AdvancedInit.AutoBaudRateMode)); MODIFY_REG(huart->Instance->CR2, USART_CR2_ABRMODE, huart->AdvancedInit.AutoBaudRateMode); - 8004f3c: 687b ldr r3, [r7, #4] - 8004f3e: 681b ldr r3, [r3, #0] - 8004f40: 685b ldr r3, [r3, #4] - 8004f42: f423 01c0 bic.w r1, r3, #6291456 ; 0x600000 - 8004f46: 687b ldr r3, [r7, #4] - 8004f48: 6c5a ldr r2, [r3, #68] ; 0x44 - 8004f4a: 687b ldr r3, [r7, #4] - 8004f4c: 681b ldr r3, [r3, #0] - 8004f4e: 430a orrs r2, r1 - 8004f50: 605a str r2, [r3, #4] + 8005004: 687b ldr r3, [r7, #4] + 8005006: 681b ldr r3, [r3, #0] + 8005008: 685b ldr r3, [r3, #4] + 800500a: f423 01c0 bic.w r1, r3, #6291456 ; 0x600000 + 800500e: 687b ldr r3, [r7, #4] + 8005010: 6c5a ldr r2, [r3, #68] ; 0x44 + 8005012: 687b ldr r3, [r7, #4] + 8005014: 681b ldr r3, [r3, #0] + 8005016: 430a orrs r2, r1 + 8005018: 605a str r2, [r3, #4] } } /* if required, configure MSB first on communication line */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_MSBFIRST_INIT)) - 8004f52: 687b ldr r3, [r7, #4] - 8004f54: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004f56: f003 0380 and.w r3, r3, #128 ; 0x80 - 8004f5a: 2b00 cmp r3, #0 - 8004f5c: d00a beq.n 8004f74 + 800501a: 687b ldr r3, [r7, #4] + 800501c: 6a5b ldr r3, [r3, #36] ; 0x24 + 800501e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8005022: 2b00 cmp r3, #0 + 8005024: d00a beq.n 800503c { assert_param(IS_UART_ADVFEATURE_MSBFIRST(huart->AdvancedInit.MSBFirst)); MODIFY_REG(huart->Instance->CR2, USART_CR2_MSBFIRST, huart->AdvancedInit.MSBFirst); - 8004f5e: 687b ldr r3, [r7, #4] - 8004f60: 681b ldr r3, [r3, #0] - 8004f62: 685b ldr r3, [r3, #4] - 8004f64: f423 2100 bic.w r1, r3, #524288 ; 0x80000 - 8004f68: 687b ldr r3, [r7, #4] - 8004f6a: 6c9a ldr r2, [r3, #72] ; 0x48 - 8004f6c: 687b ldr r3, [r7, #4] - 8004f6e: 681b ldr r3, [r3, #0] - 8004f70: 430a orrs r2, r1 - 8004f72: 605a str r2, [r3, #4] + 8005026: 687b ldr r3, [r7, #4] + 8005028: 681b ldr r3, [r3, #0] + 800502a: 685b ldr r3, [r3, #4] + 800502c: f423 2100 bic.w r1, r3, #524288 ; 0x80000 + 8005030: 687b ldr r3, [r7, #4] + 8005032: 6c9a ldr r2, [r3, #72] ; 0x48 + 8005034: 687b ldr r3, [r7, #4] + 8005036: 681b ldr r3, [r3, #0] + 8005038: 430a orrs r2, r1 + 800503a: 605a str r2, [r3, #4] } } - 8004f74: bf00 nop - 8004f76: 370c adds r7, #12 - 8004f78: 46bd mov sp, r7 - 8004f7a: f85d 7b04 ldr.w r7, [sp], #4 - 8004f7e: 4770 bx lr + 800503c: bf00 nop + 800503e: 370c adds r7, #12 + 8005040: 46bd mov sp, r7 + 8005042: f85d 7b04 ldr.w r7, [sp], #4 + 8005046: 4770 bx lr -08004f80 : +08005048 : * @brief Check the UART Idle State. * @param huart UART handle. * @retval HAL status */ HAL_StatusTypeDef UART_CheckIdleState(UART_HandleTypeDef *huart) { - 8004f80: b580 push {r7, lr} - 8004f82: b086 sub sp, #24 - 8004f84: af02 add r7, sp, #8 - 8004f86: 6078 str r0, [r7, #4] + 8005048: b580 push {r7, lr} + 800504a: b086 sub sp, #24 + 800504c: af02 add r7, sp, #8 + 800504e: 6078 str r0, [r7, #4] uint32_t tickstart; /* Initialize the UART ErrorCode */ huart->ErrorCode = HAL_UART_ERROR_NONE; - 8004f88: 687b ldr r3, [r7, #4] - 8004f8a: 2200 movs r2, #0 - 8004f8c: 67da str r2, [r3, #124] ; 0x7c + 8005050: 687b ldr r3, [r7, #4] + 8005052: 2200 movs r2, #0 + 8005054: 67da str r2, [r3, #124] ; 0x7c /* Init tickstart for timeout managment*/ tickstart = HAL_GetTick(); - 8004f8e: f7fc fd93 bl 8001ab8 - 8004f92: 60f8 str r0, [r7, #12] + 8005056: f7fc fd93 bl 8001b80 + 800505a: 60f8 str r0, [r7, #12] /* Check if the Transmitter is enabled */ if ((huart->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE) - 8004f94: 687b ldr r3, [r7, #4] - 8004f96: 681b ldr r3, [r3, #0] - 8004f98: 681b ldr r3, [r3, #0] - 8004f9a: f003 0308 and.w r3, r3, #8 - 8004f9e: 2b08 cmp r3, #8 - 8004fa0: d10e bne.n 8004fc0 + 800505c: 687b ldr r3, [r7, #4] + 800505e: 681b ldr r3, [r3, #0] + 8005060: 681b ldr r3, [r3, #0] + 8005062: f003 0308 and.w r3, r3, #8 + 8005066: 2b08 cmp r3, #8 + 8005068: d10e bne.n 8005088 { /* Wait until TEACK flag is set */ if (UART_WaitOnFlagUntilTimeout(huart, USART_ISR_TEACK, RESET, tickstart, HAL_UART_TIMEOUT_VALUE) != HAL_OK) - 8004fa2: f06f 437e mvn.w r3, #4261412864 ; 0xfe000000 - 8004fa6: 9300 str r3, [sp, #0] - 8004fa8: 68fb ldr r3, [r7, #12] - 8004faa: 2200 movs r2, #0 - 8004fac: f44f 1100 mov.w r1, #2097152 ; 0x200000 - 8004fb0: 6878 ldr r0, [r7, #4] - 8004fb2: f000 f814 bl 8004fde - 8004fb6: 4603 mov r3, r0 - 8004fb8: 2b00 cmp r3, #0 - 8004fba: d001 beq.n 8004fc0 + 800506a: f06f 437e mvn.w r3, #4261412864 ; 0xfe000000 + 800506e: 9300 str r3, [sp, #0] + 8005070: 68fb ldr r3, [r7, #12] + 8005072: 2200 movs r2, #0 + 8005074: f44f 1100 mov.w r1, #2097152 ; 0x200000 + 8005078: 6878 ldr r0, [r7, #4] + 800507a: f000 f814 bl 80050a6 + 800507e: 4603 mov r3, r0 + 8005080: 2b00 cmp r3, #0 + 8005082: d001 beq.n 8005088 { /* Timeout occurred */ return HAL_TIMEOUT; - 8004fbc: 2303 movs r3, #3 - 8004fbe: e00a b.n 8004fd6 + 8005084: 2303 movs r3, #3 + 8005086: e00a b.n 800509e } } /* Initialize the UART State */ huart->gState = HAL_UART_STATE_READY; - 8004fc0: 687b ldr r3, [r7, #4] - 8004fc2: 2220 movs r2, #32 - 8004fc4: 675a str r2, [r3, #116] ; 0x74 + 8005088: 687b ldr r3, [r7, #4] + 800508a: 2220 movs r2, #32 + 800508c: 675a str r2, [r3, #116] ; 0x74 huart->RxState = HAL_UART_STATE_READY; - 8004fc6: 687b ldr r3, [r7, #4] - 8004fc8: 2220 movs r2, #32 - 8004fca: 679a str r2, [r3, #120] ; 0x78 + 800508e: 687b ldr r3, [r7, #4] + 8005090: 2220 movs r2, #32 + 8005092: 679a str r2, [r3, #120] ; 0x78 /* Process Unlocked */ __HAL_UNLOCK(huart); - 8004fcc: 687b ldr r3, [r7, #4] - 8004fce: 2200 movs r2, #0 - 8004fd0: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8005094: 687b ldr r3, [r7, #4] + 8005096: 2200 movs r2, #0 + 8005098: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_OK; - 8004fd4: 2300 movs r3, #0 + 800509c: 2300 movs r3, #0 } - 8004fd6: 4618 mov r0, r3 - 8004fd8: 3710 adds r7, #16 - 8004fda: 46bd mov sp, r7 - 8004fdc: bd80 pop {r7, pc} + 800509e: 4618 mov r0, r3 + 80050a0: 3710 adds r7, #16 + 80050a2: 46bd mov sp, r7 + 80050a4: bd80 pop {r7, pc} -08004fde : +080050a6 : * @param Tickstart Tick start value * @param Timeout Timeout duration * @retval HAL status */ HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout) { - 8004fde: b580 push {r7, lr} - 8004fe0: b084 sub sp, #16 - 8004fe2: af00 add r7, sp, #0 - 8004fe4: 60f8 str r0, [r7, #12] - 8004fe6: 60b9 str r1, [r7, #8] - 8004fe8: 603b str r3, [r7, #0] - 8004fea: 4613 mov r3, r2 - 8004fec: 71fb strb r3, [r7, #7] + 80050a6: b580 push {r7, lr} + 80050a8: b084 sub sp, #16 + 80050aa: af00 add r7, sp, #0 + 80050ac: 60f8 str r0, [r7, #12] + 80050ae: 60b9 str r1, [r7, #8] + 80050b0: 603b str r3, [r7, #0] + 80050b2: 4613 mov r3, r2 + 80050b4: 71fb strb r3, [r7, #7] /* Wait until flag is set */ while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - 8004fee: e02a b.n 8005046 + 80050b6: e02a b.n 800510e { /* Check for the Timeout */ if (Timeout != HAL_MAX_DELAY) - 8004ff0: 69bb ldr r3, [r7, #24] - 8004ff2: f1b3 3fff cmp.w r3, #4294967295 ; 0xffffffff - 8004ff6: d026 beq.n 8005046 + 80050b8: 69bb ldr r3, [r7, #24] + 80050ba: f1b3 3fff cmp.w r3, #4294967295 ; 0xffffffff + 80050be: d026 beq.n 800510e { if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - 8004ff8: f7fc fd5e bl 8001ab8 - 8004ffc: 4602 mov r2, r0 - 8004ffe: 683b ldr r3, [r7, #0] - 8005000: 1ad3 subs r3, r2, r3 - 8005002: 69ba ldr r2, [r7, #24] - 8005004: 429a cmp r2, r3 - 8005006: d302 bcc.n 800500e - 8005008: 69bb ldr r3, [r7, #24] - 800500a: 2b00 cmp r3, #0 - 800500c: d11b bne.n 8005046 + 80050c0: f7fc fd5e bl 8001b80 + 80050c4: 4602 mov r2, r0 + 80050c6: 683b ldr r3, [r7, #0] + 80050c8: 1ad3 subs r3, r2, r3 + 80050ca: 69ba ldr r2, [r7, #24] + 80050cc: 429a cmp r2, r3 + 80050ce: d302 bcc.n 80050d6 + 80050d0: 69bb ldr r3, [r7, #24] + 80050d2: 2b00 cmp r3, #0 + 80050d4: d11b bne.n 800510e { /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); - 800500e: 68fb ldr r3, [r7, #12] - 8005010: 681b ldr r3, [r3, #0] - 8005012: 681a ldr r2, [r3, #0] - 8005014: 68fb ldr r3, [r7, #12] - 8005016: 681b ldr r3, [r3, #0] - 8005018: f422 72d0 bic.w r2, r2, #416 ; 0x1a0 - 800501c: 601a str r2, [r3, #0] + 80050d6: 68fb ldr r3, [r7, #12] + 80050d8: 681b ldr r3, [r3, #0] + 80050da: 681a ldr r2, [r3, #0] + 80050dc: 68fb ldr r3, [r7, #12] + 80050de: 681b ldr r3, [r3, #0] + 80050e0: f422 72d0 bic.w r2, r2, #416 ; 0x1a0 + 80050e4: 601a str r2, [r3, #0] CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 800501e: 68fb ldr r3, [r7, #12] - 8005020: 681b ldr r3, [r3, #0] - 8005022: 689a ldr r2, [r3, #8] - 8005024: 68fb ldr r3, [r7, #12] - 8005026: 681b ldr r3, [r3, #0] - 8005028: f022 0201 bic.w r2, r2, #1 - 800502c: 609a str r2, [r3, #8] + 80050e6: 68fb ldr r3, [r7, #12] + 80050e8: 681b ldr r3, [r3, #0] + 80050ea: 689a ldr r2, [r3, #8] + 80050ec: 68fb ldr r3, [r7, #12] + 80050ee: 681b ldr r3, [r3, #0] + 80050f0: f022 0201 bic.w r2, r2, #1 + 80050f4: 609a str r2, [r3, #8] huart->gState = HAL_UART_STATE_READY; - 800502e: 68fb ldr r3, [r7, #12] - 8005030: 2220 movs r2, #32 - 8005032: 675a str r2, [r3, #116] ; 0x74 + 80050f6: 68fb ldr r3, [r7, #12] + 80050f8: 2220 movs r2, #32 + 80050fa: 675a str r2, [r3, #116] ; 0x74 huart->RxState = HAL_UART_STATE_READY; - 8005034: 68fb ldr r3, [r7, #12] - 8005036: 2220 movs r2, #32 - 8005038: 679a str r2, [r3, #120] ; 0x78 + 80050fc: 68fb ldr r3, [r7, #12] + 80050fe: 2220 movs r2, #32 + 8005100: 679a str r2, [r3, #120] ; 0x78 /* Process Unlocked */ __HAL_UNLOCK(huart); - 800503a: 68fb ldr r3, [r7, #12] - 800503c: 2200 movs r2, #0 - 800503e: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8005102: 68fb ldr r3, [r7, #12] + 8005104: 2200 movs r2, #0 + 8005106: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_TIMEOUT; - 8005042: 2303 movs r3, #3 - 8005044: e00f b.n 8005066 + 800510a: 2303 movs r3, #3 + 800510c: e00f b.n 800512e while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - 8005046: 68fb ldr r3, [r7, #12] - 8005048: 681b ldr r3, [r3, #0] - 800504a: 69da ldr r2, [r3, #28] - 800504c: 68bb ldr r3, [r7, #8] - 800504e: 4013 ands r3, r2 - 8005050: 68ba ldr r2, [r7, #8] - 8005052: 429a cmp r2, r3 - 8005054: bf0c ite eq - 8005056: 2301 moveq r3, #1 - 8005058: 2300 movne r3, #0 - 800505a: b2db uxtb r3, r3 - 800505c: 461a mov r2, r3 - 800505e: 79fb ldrb r3, [r7, #7] - 8005060: 429a cmp r2, r3 - 8005062: d0c5 beq.n 8004ff0 + 800510e: 68fb ldr r3, [r7, #12] + 8005110: 681b ldr r3, [r3, #0] + 8005112: 69da ldr r2, [r3, #28] + 8005114: 68bb ldr r3, [r7, #8] + 8005116: 4013 ands r3, r2 + 8005118: 68ba ldr r2, [r7, #8] + 800511a: 429a cmp r2, r3 + 800511c: bf0c ite eq + 800511e: 2301 moveq r3, #1 + 8005120: 2300 movne r3, #0 + 8005122: b2db uxtb r3, r3 + 8005124: 461a mov r2, r3 + 8005126: 79fb ldrb r3, [r7, #7] + 8005128: 429a cmp r2, r3 + 800512a: d0c5 beq.n 80050b8 } } } return HAL_OK; - 8005064: 2300 movs r3, #0 + 800512c: 2300 movs r3, #0 } - 8005066: 4618 mov r0, r3 - 8005068: 3710 adds r7, #16 - 800506a: 46bd mov sp, r7 - 800506c: bd80 pop {r7, pc} + 800512e: 4618 mov r0, r3 + 8005130: 3710 adds r7, #16 + 8005132: 46bd mov sp, r7 + 8005134: bd80 pop {r7, pc} -0800506e : +08005136 : * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion). * @param huart UART handle. * @retval None */ static void UART_EndRxTransfer(UART_HandleTypeDef *huart) { - 800506e: b480 push {r7} - 8005070: b083 sub sp, #12 - 8005072: af00 add r7, sp, #0 - 8005074: 6078 str r0, [r7, #4] + 8005136: b480 push {r7} + 8005138: b083 sub sp, #12 + 800513a: af00 add r7, sp, #0 + 800513c: 6078 str r0, [r7, #4] /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - 8005076: 687b ldr r3, [r7, #4] - 8005078: 681b ldr r3, [r3, #0] - 800507a: 681a ldr r2, [r3, #0] - 800507c: 687b ldr r3, [r7, #4] - 800507e: 681b ldr r3, [r3, #0] - 8005080: f422 7290 bic.w r2, r2, #288 ; 0x120 - 8005084: 601a str r2, [r3, #0] + 800513e: 687b ldr r3, [r7, #4] + 8005140: 681b ldr r3, [r3, #0] + 8005142: 681a ldr r2, [r3, #0] + 8005144: 687b ldr r3, [r7, #4] + 8005146: 681b ldr r3, [r3, #0] + 8005148: f422 7290 bic.w r2, r2, #288 ; 0x120 + 800514c: 601a str r2, [r3, #0] CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 8005086: 687b ldr r3, [r7, #4] - 8005088: 681b ldr r3, [r3, #0] - 800508a: 689a ldr r2, [r3, #8] - 800508c: 687b ldr r3, [r7, #4] - 800508e: 681b ldr r3, [r3, #0] - 8005090: f022 0201 bic.w r2, r2, #1 - 8005094: 609a str r2, [r3, #8] + 800514e: 687b ldr r3, [r7, #4] + 8005150: 681b ldr r3, [r3, #0] + 8005152: 689a ldr r2, [r3, #8] + 8005154: 687b ldr r3, [r7, #4] + 8005156: 681b ldr r3, [r3, #0] + 8005158: f022 0201 bic.w r2, r2, #1 + 800515c: 609a str r2, [r3, #8] /* At end of Rx process, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 8005096: 687b ldr r3, [r7, #4] - 8005098: 2220 movs r2, #32 - 800509a: 679a str r2, [r3, #120] ; 0x78 + 800515e: 687b ldr r3, [r7, #4] + 8005160: 2220 movs r2, #32 + 8005162: 679a str r2, [r3, #120] ; 0x78 /* Reset RxIsr function pointer */ huart->RxISR = NULL; - 800509c: 687b ldr r3, [r7, #4] - 800509e: 2200 movs r2, #0 - 80050a0: 661a str r2, [r3, #96] ; 0x60 + 8005164: 687b ldr r3, [r7, #4] + 8005166: 2200 movs r2, #0 + 8005168: 661a str r2, [r3, #96] ; 0x60 } - 80050a2: bf00 nop - 80050a4: 370c adds r7, #12 - 80050a6: 46bd mov sp, r7 - 80050a8: f85d 7b04 ldr.w r7, [sp], #4 - 80050ac: 4770 bx lr + 800516a: bf00 nop + 800516c: 370c adds r7, #12 + 800516e: 46bd mov sp, r7 + 8005170: f85d 7b04 ldr.w r7, [sp], #4 + 8005174: 4770 bx lr -080050ae : +08005176 : * (To be called at end of DMA Abort procedure following error occurrence). * @param hdma DMA handle. * @retval None */ static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma) { - 80050ae: b580 push {r7, lr} - 80050b0: b084 sub sp, #16 - 80050b2: af00 add r7, sp, #0 - 80050b4: 6078 str r0, [r7, #4] + 8005176: b580 push {r7, lr} + 8005178: b084 sub sp, #16 + 800517a: af00 add r7, sp, #0 + 800517c: 6078 str r0, [r7, #4] UART_HandleTypeDef *huart = (UART_HandleTypeDef *)(hdma->Parent); - 80050b6: 687b ldr r3, [r7, #4] - 80050b8: 6b9b ldr r3, [r3, #56] ; 0x38 - 80050ba: 60fb str r3, [r7, #12] + 800517e: 687b ldr r3, [r7, #4] + 8005180: 6b9b ldr r3, [r3, #56] ; 0x38 + 8005182: 60fb str r3, [r7, #12] huart->RxXferCount = 0U; - 80050bc: 68fb ldr r3, [r7, #12] - 80050be: 2200 movs r2, #0 - 80050c0: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 8005184: 68fb ldr r3, [r7, #12] + 8005186: 2200 movs r2, #0 + 8005188: f8a3 205a strh.w r2, [r3, #90] ; 0x5a huart->TxXferCount = 0U; - 80050c4: 68fb ldr r3, [r7, #12] - 80050c6: 2200 movs r2, #0 - 80050c8: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 800518c: 68fb ldr r3, [r7, #12] + 800518e: 2200 movs r2, #0 + 8005190: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 80050cc: 68f8 ldr r0, [r7, #12] - 80050ce: f7ff fc07 bl 80048e0 + 8005194: 68f8 ldr r0, [r7, #12] + 8005196: f7ff fc07 bl 80049a8 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ } - 80050d2: bf00 nop - 80050d4: 3710 adds r7, #16 - 80050d6: 46bd mov sp, r7 - 80050d8: bd80 pop {r7, pc} + 800519a: bf00 nop + 800519c: 3710 adds r7, #16 + 800519e: 46bd mov sp, r7 + 80051a0: bd80 pop {r7, pc} -080050da : +080051a2 : * @param huart pointer to a UART_HandleTypeDef structure that contains * the configuration information for the specified UART module. * @retval None */ static void UART_EndTransmit_IT(UART_HandleTypeDef *huart) { - 80050da: b580 push {r7, lr} - 80050dc: b082 sub sp, #8 - 80050de: af00 add r7, sp, #0 - 80050e0: 6078 str r0, [r7, #4] + 80051a2: b580 push {r7, lr} + 80051a4: b082 sub sp, #8 + 80051a6: af00 add r7, sp, #0 + 80051a8: 6078 str r0, [r7, #4] /* Disable the UART Transmit Complete Interrupt */ CLEAR_BIT(huart->Instance->CR1, USART_CR1_TCIE); - 80050e2: 687b ldr r3, [r7, #4] - 80050e4: 681b ldr r3, [r3, #0] - 80050e6: 681a ldr r2, [r3, #0] - 80050e8: 687b ldr r3, [r7, #4] - 80050ea: 681b ldr r3, [r3, #0] - 80050ec: f022 0240 bic.w r2, r2, #64 ; 0x40 - 80050f0: 601a str r2, [r3, #0] + 80051aa: 687b ldr r3, [r7, #4] + 80051ac: 681b ldr r3, [r3, #0] + 80051ae: 681a ldr r2, [r3, #0] + 80051b0: 687b ldr r3, [r7, #4] + 80051b2: 681b ldr r3, [r3, #0] + 80051b4: f022 0240 bic.w r2, r2, #64 ; 0x40 + 80051b8: 601a str r2, [r3, #0] /* Tx process is ended, restore huart->gState to Ready */ huart->gState = HAL_UART_STATE_READY; - 80050f2: 687b ldr r3, [r7, #4] - 80050f4: 2220 movs r2, #32 - 80050f6: 675a str r2, [r3, #116] ; 0x74 + 80051ba: 687b ldr r3, [r7, #4] + 80051bc: 2220 movs r2, #32 + 80051be: 675a str r2, [r3, #116] ; 0x74 /* Cleat TxISR function pointer */ huart->TxISR = NULL; - 80050f8: 687b ldr r3, [r7, #4] - 80050fa: 2200 movs r2, #0 - 80050fc: 665a str r2, [r3, #100] ; 0x64 + 80051c0: 687b ldr r3, [r7, #4] + 80051c2: 2200 movs r2, #0 + 80051c4: 665a str r2, [r3, #100] ; 0x64 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered Tx complete callback*/ huart->TxCpltCallback(huart); #else /*Call legacy weak Tx complete callback*/ HAL_UART_TxCpltCallback(huart); - 80050fe: 6878 ldr r0, [r7, #4] - 8005100: f7ff fbe4 bl 80048cc + 80051c6: 6878 ldr r0, [r7, #4] + 80051c8: f7ff fbe4 bl 8004994 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ } - 8005104: bf00 nop - 8005106: 3708 adds r7, #8 - 8005108: 46bd mov sp, r7 - 800510a: bd80 pop {r7, pc} + 80051cc: bf00 nop + 80051ce: 3708 adds r7, #8 + 80051d0: 46bd mov sp, r7 + 80051d2: bd80 pop {r7, pc} -0800510c : +080051d4 : * @brief RX interrrupt handler for 7 or 8 bits data word length . * @param huart UART handle. * @retval None */ static void UART_RxISR_8BIT(UART_HandleTypeDef *huart) { - 800510c: b580 push {r7, lr} - 800510e: b084 sub sp, #16 - 8005110: af00 add r7, sp, #0 - 8005112: 6078 str r0, [r7, #4] + 80051d4: b580 push {r7, lr} + 80051d6: b084 sub sp, #16 + 80051d8: af00 add r7, sp, #0 + 80051da: 6078 str r0, [r7, #4] uint16_t uhMask = huart->Mask; - 8005114: 687b ldr r3, [r7, #4] - 8005116: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c - 800511a: 81fb strh r3, [r7, #14] + 80051dc: 687b ldr r3, [r7, #4] + 80051de: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c + 80051e2: 81fb strh r3, [r7, #14] uint16_t uhdata; /* Check that a Rx process is ongoing */ if (huart->RxState == HAL_UART_STATE_BUSY_RX) - 800511c: 687b ldr r3, [r7, #4] - 800511e: 6f9b ldr r3, [r3, #120] ; 0x78 - 8005120: 2b22 cmp r3, #34 ; 0x22 - 8005122: d13a bne.n 800519a + 80051e4: 687b ldr r3, [r7, #4] + 80051e6: 6f9b ldr r3, [r3, #120] ; 0x78 + 80051e8: 2b22 cmp r3, #34 ; 0x22 + 80051ea: d13a bne.n 8005262 { uhdata = (uint16_t) READ_REG(huart->Instance->RDR); - 8005124: 687b ldr r3, [r7, #4] - 8005126: 681b ldr r3, [r3, #0] - 8005128: 6a5b ldr r3, [r3, #36] ; 0x24 - 800512a: 81bb strh r3, [r7, #12] + 80051ec: 687b ldr r3, [r7, #4] + 80051ee: 681b ldr r3, [r3, #0] + 80051f0: 6a5b ldr r3, [r3, #36] ; 0x24 + 80051f2: 81bb strh r3, [r7, #12] *huart->pRxBuffPtr = (uint8_t)(uhdata & (uint8_t)uhMask); - 800512c: 89bb ldrh r3, [r7, #12] - 800512e: b2d9 uxtb r1, r3 - 8005130: 89fb ldrh r3, [r7, #14] - 8005132: b2da uxtb r2, r3 - 8005134: 687b ldr r3, [r7, #4] - 8005136: 6d5b ldr r3, [r3, #84] ; 0x54 - 8005138: 400a ands r2, r1 - 800513a: b2d2 uxtb r2, r2 - 800513c: 701a strb r2, [r3, #0] + 80051f4: 89bb ldrh r3, [r7, #12] + 80051f6: b2d9 uxtb r1, r3 + 80051f8: 89fb ldrh r3, [r7, #14] + 80051fa: b2da uxtb r2, r3 + 80051fc: 687b ldr r3, [r7, #4] + 80051fe: 6d5b ldr r3, [r3, #84] ; 0x54 + 8005200: 400a ands r2, r1 + 8005202: b2d2 uxtb r2, r2 + 8005204: 701a strb r2, [r3, #0] huart->pRxBuffPtr++; - 800513e: 687b ldr r3, [r7, #4] - 8005140: 6d5b ldr r3, [r3, #84] ; 0x54 - 8005142: 1c5a adds r2, r3, #1 - 8005144: 687b ldr r3, [r7, #4] - 8005146: 655a str r2, [r3, #84] ; 0x54 + 8005206: 687b ldr r3, [r7, #4] + 8005208: 6d5b ldr r3, [r3, #84] ; 0x54 + 800520a: 1c5a adds r2, r3, #1 + 800520c: 687b ldr r3, [r7, #4] + 800520e: 655a str r2, [r3, #84] ; 0x54 huart->RxXferCount--; - 8005148: 687b ldr r3, [r7, #4] - 800514a: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 800514e: b29b uxth r3, r3 - 8005150: 3b01 subs r3, #1 - 8005152: b29a uxth r2, r3 - 8005154: 687b ldr r3, [r7, #4] - 8005156: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 8005210: 687b ldr r3, [r7, #4] + 8005212: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 8005216: b29b uxth r3, r3 + 8005218: 3b01 subs r3, #1 + 800521a: b29a uxth r2, r3 + 800521c: 687b ldr r3, [r7, #4] + 800521e: f8a3 205a strh.w r2, [r3, #90] ; 0x5a if (huart->RxXferCount == 0U) - 800515a: 687b ldr r3, [r7, #4] - 800515c: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 8005160: b29b uxth r3, r3 - 8005162: 2b00 cmp r3, #0 - 8005164: d121 bne.n 80051aa + 8005222: 687b ldr r3, [r7, #4] + 8005224: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 8005228: b29b uxth r3, r3 + 800522a: 2b00 cmp r3, #0 + 800522c: d121 bne.n 8005272 { /* Disable the UART Parity Error Interrupt and RXNE interrupts */ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - 8005166: 687b ldr r3, [r7, #4] - 8005168: 681b ldr r3, [r3, #0] - 800516a: 681a ldr r2, [r3, #0] - 800516c: 687b ldr r3, [r7, #4] - 800516e: 681b ldr r3, [r3, #0] - 8005170: f422 7290 bic.w r2, r2, #288 ; 0x120 - 8005174: 601a str r2, [r3, #0] + 800522e: 687b ldr r3, [r7, #4] + 8005230: 681b ldr r3, [r3, #0] + 8005232: 681a ldr r2, [r3, #0] + 8005234: 687b ldr r3, [r7, #4] + 8005236: 681b ldr r3, [r3, #0] + 8005238: f422 7290 bic.w r2, r2, #288 ; 0x120 + 800523c: 601a str r2, [r3, #0] /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 8005176: 687b ldr r3, [r7, #4] - 8005178: 681b ldr r3, [r3, #0] - 800517a: 689a ldr r2, [r3, #8] - 800517c: 687b ldr r3, [r7, #4] - 800517e: 681b ldr r3, [r3, #0] - 8005180: f022 0201 bic.w r2, r2, #1 - 8005184: 609a str r2, [r3, #8] + 800523e: 687b ldr r3, [r7, #4] + 8005240: 681b ldr r3, [r3, #0] + 8005242: 689a ldr r2, [r3, #8] + 8005244: 687b ldr r3, [r7, #4] + 8005246: 681b ldr r3, [r3, #0] + 8005248: f022 0201 bic.w r2, r2, #1 + 800524c: 609a str r2, [r3, #8] /* Rx process is completed, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 8005186: 687b ldr r3, [r7, #4] - 8005188: 2220 movs r2, #32 - 800518a: 679a str r2, [r3, #120] ; 0x78 + 800524e: 687b ldr r3, [r7, #4] + 8005250: 2220 movs r2, #32 + 8005252: 679a str r2, [r3, #120] ; 0x78 /* Clear RxISR function pointer */ huart->RxISR = NULL; - 800518c: 687b ldr r3, [r7, #4] - 800518e: 2200 movs r2, #0 - 8005190: 661a str r2, [r3, #96] ; 0x60 + 8005254: 687b ldr r3, [r7, #4] + 8005256: 2200 movs r2, #0 + 8005258: 661a str r2, [r3, #96] ; 0x60 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered Rx complete callback*/ huart->RxCpltCallback(huart); #else /*Call legacy weak Rx complete callback*/ HAL_UART_RxCpltCallback(huart); - 8005192: 6878 ldr r0, [r7, #4] - 8005194: f7fc f942 bl 800141c + 800525a: 6878 ldr r0, [r7, #4] + 800525c: f7fc f932 bl 80014c4 else { /* Clear RXNE interrupt flag */ __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); } } - 8005198: e007 b.n 80051aa + 8005260: e007 b.n 8005272 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); - 800519a: 687b ldr r3, [r7, #4] - 800519c: 681b ldr r3, [r3, #0] - 800519e: 699a ldr r2, [r3, #24] - 80051a0: 687b ldr r3, [r7, #4] - 80051a2: 681b ldr r3, [r3, #0] - 80051a4: f042 0208 orr.w r2, r2, #8 - 80051a8: 619a str r2, [r3, #24] + 8005262: 687b ldr r3, [r7, #4] + 8005264: 681b ldr r3, [r3, #0] + 8005266: 699a ldr r2, [r3, #24] + 8005268: 687b ldr r3, [r7, #4] + 800526a: 681b ldr r3, [r3, #0] + 800526c: f042 0208 orr.w r2, r2, #8 + 8005270: 619a str r2, [r3, #24] } - 80051aa: bf00 nop - 80051ac: 3710 adds r7, #16 - 80051ae: 46bd mov sp, r7 - 80051b0: bd80 pop {r7, pc} + 8005272: bf00 nop + 8005274: 3710 adds r7, #16 + 8005276: 46bd mov sp, r7 + 8005278: bd80 pop {r7, pc} -080051b2 : +0800527a : * interruptions have been enabled by HAL_UART_Receive_IT() * @param huart UART handle. * @retval None */ static void UART_RxISR_16BIT(UART_HandleTypeDef *huart) { - 80051b2: b580 push {r7, lr} - 80051b4: b084 sub sp, #16 - 80051b6: af00 add r7, sp, #0 - 80051b8: 6078 str r0, [r7, #4] + 800527a: b580 push {r7, lr} + 800527c: b084 sub sp, #16 + 800527e: af00 add r7, sp, #0 + 8005280: 6078 str r0, [r7, #4] uint16_t *tmp; uint16_t uhMask = huart->Mask; - 80051ba: 687b ldr r3, [r7, #4] - 80051bc: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c - 80051c0: 81fb strh r3, [r7, #14] + 8005282: 687b ldr r3, [r7, #4] + 8005284: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c + 8005288: 81fb strh r3, [r7, #14] uint16_t uhdata; /* Check that a Rx process is ongoing */ if (huart->RxState == HAL_UART_STATE_BUSY_RX) - 80051c2: 687b ldr r3, [r7, #4] - 80051c4: 6f9b ldr r3, [r3, #120] ; 0x78 - 80051c6: 2b22 cmp r3, #34 ; 0x22 - 80051c8: d13a bne.n 8005240 + 800528a: 687b ldr r3, [r7, #4] + 800528c: 6f9b ldr r3, [r3, #120] ; 0x78 + 800528e: 2b22 cmp r3, #34 ; 0x22 + 8005290: d13a bne.n 8005308 { uhdata = (uint16_t) READ_REG(huart->Instance->RDR); - 80051ca: 687b ldr r3, [r7, #4] - 80051cc: 681b ldr r3, [r3, #0] - 80051ce: 6a5b ldr r3, [r3, #36] ; 0x24 - 80051d0: 81bb strh r3, [r7, #12] + 8005292: 687b ldr r3, [r7, #4] + 8005294: 681b ldr r3, [r3, #0] + 8005296: 6a5b ldr r3, [r3, #36] ; 0x24 + 8005298: 81bb strh r3, [r7, #12] tmp = (uint16_t *) huart->pRxBuffPtr ; - 80051d2: 687b ldr r3, [r7, #4] - 80051d4: 6d5b ldr r3, [r3, #84] ; 0x54 - 80051d6: 60bb str r3, [r7, #8] + 800529a: 687b ldr r3, [r7, #4] + 800529c: 6d5b ldr r3, [r3, #84] ; 0x54 + 800529e: 60bb str r3, [r7, #8] *tmp = (uint16_t)(uhdata & uhMask); - 80051d8: 89ba ldrh r2, [r7, #12] - 80051da: 89fb ldrh r3, [r7, #14] - 80051dc: 4013 ands r3, r2 - 80051de: b29a uxth r2, r3 - 80051e0: 68bb ldr r3, [r7, #8] - 80051e2: 801a strh r2, [r3, #0] + 80052a0: 89ba ldrh r2, [r7, #12] + 80052a2: 89fb ldrh r3, [r7, #14] + 80052a4: 4013 ands r3, r2 + 80052a6: b29a uxth r2, r3 + 80052a8: 68bb ldr r3, [r7, #8] + 80052aa: 801a strh r2, [r3, #0] huart->pRxBuffPtr += 2U; - 80051e4: 687b ldr r3, [r7, #4] - 80051e6: 6d5b ldr r3, [r3, #84] ; 0x54 - 80051e8: 1c9a adds r2, r3, #2 - 80051ea: 687b ldr r3, [r7, #4] - 80051ec: 655a str r2, [r3, #84] ; 0x54 + 80052ac: 687b ldr r3, [r7, #4] + 80052ae: 6d5b ldr r3, [r3, #84] ; 0x54 + 80052b0: 1c9a adds r2, r3, #2 + 80052b2: 687b ldr r3, [r7, #4] + 80052b4: 655a str r2, [r3, #84] ; 0x54 huart->RxXferCount--; - 80051ee: 687b ldr r3, [r7, #4] - 80051f0: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 80051f4: b29b uxth r3, r3 - 80051f6: 3b01 subs r3, #1 - 80051f8: b29a uxth r2, r3 - 80051fa: 687b ldr r3, [r7, #4] - 80051fc: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 80052b6: 687b ldr r3, [r7, #4] + 80052b8: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 80052bc: b29b uxth r3, r3 + 80052be: 3b01 subs r3, #1 + 80052c0: b29a uxth r2, r3 + 80052c2: 687b ldr r3, [r7, #4] + 80052c4: f8a3 205a strh.w r2, [r3, #90] ; 0x5a if (huart->RxXferCount == 0U) - 8005200: 687b ldr r3, [r7, #4] - 8005202: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 8005206: b29b uxth r3, r3 - 8005208: 2b00 cmp r3, #0 - 800520a: d121 bne.n 8005250 + 80052c8: 687b ldr r3, [r7, #4] + 80052ca: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 80052ce: b29b uxth r3, r3 + 80052d0: 2b00 cmp r3, #0 + 80052d2: d121 bne.n 8005318 { /* Disable the UART Parity Error Interrupt and RXNE interrupt*/ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - 800520c: 687b ldr r3, [r7, #4] - 800520e: 681b ldr r3, [r3, #0] - 8005210: 681a ldr r2, [r3, #0] - 8005212: 687b ldr r3, [r7, #4] - 8005214: 681b ldr r3, [r3, #0] - 8005216: f422 7290 bic.w r2, r2, #288 ; 0x120 - 800521a: 601a str r2, [r3, #0] + 80052d4: 687b ldr r3, [r7, #4] + 80052d6: 681b ldr r3, [r3, #0] + 80052d8: 681a ldr r2, [r3, #0] + 80052da: 687b ldr r3, [r7, #4] + 80052dc: 681b ldr r3, [r3, #0] + 80052de: f422 7290 bic.w r2, r2, #288 ; 0x120 + 80052e2: 601a str r2, [r3, #0] /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 800521c: 687b ldr r3, [r7, #4] - 800521e: 681b ldr r3, [r3, #0] - 8005220: 689a ldr r2, [r3, #8] - 8005222: 687b ldr r3, [r7, #4] - 8005224: 681b ldr r3, [r3, #0] - 8005226: f022 0201 bic.w r2, r2, #1 - 800522a: 609a str r2, [r3, #8] + 80052e4: 687b ldr r3, [r7, #4] + 80052e6: 681b ldr r3, [r3, #0] + 80052e8: 689a ldr r2, [r3, #8] + 80052ea: 687b ldr r3, [r7, #4] + 80052ec: 681b ldr r3, [r3, #0] + 80052ee: f022 0201 bic.w r2, r2, #1 + 80052f2: 609a str r2, [r3, #8] /* Rx process is completed, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 800522c: 687b ldr r3, [r7, #4] - 800522e: 2220 movs r2, #32 - 8005230: 679a str r2, [r3, #120] ; 0x78 + 80052f4: 687b ldr r3, [r7, #4] + 80052f6: 2220 movs r2, #32 + 80052f8: 679a str r2, [r3, #120] ; 0x78 /* Clear RxISR function pointer */ huart->RxISR = NULL; - 8005232: 687b ldr r3, [r7, #4] - 8005234: 2200 movs r2, #0 - 8005236: 661a str r2, [r3, #96] ; 0x60 + 80052fa: 687b ldr r3, [r7, #4] + 80052fc: 2200 movs r2, #0 + 80052fe: 661a str r2, [r3, #96] ; 0x60 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered Rx complete callback*/ huart->RxCpltCallback(huart); #else /*Call legacy weak Rx complete callback*/ HAL_UART_RxCpltCallback(huart); - 8005238: 6878 ldr r0, [r7, #4] - 800523a: f7fc f8ef bl 800141c + 8005300: 6878 ldr r0, [r7, #4] + 8005302: f7fc f8df bl 80014c4 else { /* Clear RXNE interrupt flag */ __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); } } - 800523e: e007 b.n 8005250 + 8005306: e007 b.n 8005318 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); - 8005240: 687b ldr r3, [r7, #4] - 8005242: 681b ldr r3, [r3, #0] - 8005244: 699a ldr r2, [r3, #24] - 8005246: 687b ldr r3, [r7, #4] - 8005248: 681b ldr r3, [r3, #0] - 800524a: f042 0208 orr.w r2, r2, #8 - 800524e: 619a str r2, [r3, #24] + 8005308: 687b ldr r3, [r7, #4] + 800530a: 681b ldr r3, [r3, #0] + 800530c: 699a ldr r2, [r3, #24] + 800530e: 687b ldr r3, [r7, #4] + 8005310: 681b ldr r3, [r3, #0] + 8005312: f042 0208 orr.w r2, r2, #8 + 8005316: 619a str r2, [r3, #24] } - 8005250: bf00 nop - 8005252: 3710 adds r7, #16 - 8005254: 46bd mov sp, r7 - 8005256: bd80 pop {r7, pc} - -08005258 <__libc_init_array>: - 8005258: b570 push {r4, r5, r6, lr} - 800525a: 4e0d ldr r6, [pc, #52] ; (8005290 <__libc_init_array+0x38>) - 800525c: 4c0d ldr r4, [pc, #52] ; (8005294 <__libc_init_array+0x3c>) - 800525e: 1ba4 subs r4, r4, r6 - 8005260: 10a4 asrs r4, r4, #2 - 8005262: 2500 movs r5, #0 - 8005264: 42a5 cmp r5, r4 - 8005266: d109 bne.n 800527c <__libc_init_array+0x24> - 8005268: 4e0b ldr r6, [pc, #44] ; (8005298 <__libc_init_array+0x40>) - 800526a: 4c0c ldr r4, [pc, #48] ; (800529c <__libc_init_array+0x44>) - 800526c: f000 f820 bl 80052b0 <_init> - 8005270: 1ba4 subs r4, r4, r6 - 8005272: 10a4 asrs r4, r4, #2 - 8005274: 2500 movs r5, #0 - 8005276: 42a5 cmp r5, r4 - 8005278: d105 bne.n 8005286 <__libc_init_array+0x2e> - 800527a: bd70 pop {r4, r5, r6, pc} - 800527c: f856 3025 ldr.w r3, [r6, r5, lsl #2] - 8005280: 4798 blx r3 - 8005282: 3501 adds r5, #1 - 8005284: e7ee b.n 8005264 <__libc_init_array+0xc> - 8005286: f856 3025 ldr.w r3, [r6, r5, lsl #2] - 800528a: 4798 blx r3 - 800528c: 3501 adds r5, #1 - 800528e: e7f2 b.n 8005276 <__libc_init_array+0x1e> - 8005290: 080052e8 .word 0x080052e8 - 8005294: 080052e8 .word 0x080052e8 - 8005298: 080052e8 .word 0x080052e8 - 800529c: 080052f0 .word 0x080052f0 - -080052a0 : - 80052a0: 4402 add r2, r0 - 80052a2: 4603 mov r3, r0 - 80052a4: 4293 cmp r3, r2 - 80052a6: d100 bne.n 80052aa - 80052a8: 4770 bx lr - 80052aa: f803 1b01 strb.w r1, [r3], #1 - 80052ae: e7f9 b.n 80052a4 - -080052b0 <_init>: - 80052b0: b5f8 push {r3, r4, r5, r6, r7, lr} - 80052b2: bf00 nop - 80052b4: bcf8 pop {r3, r4, r5, r6, r7} - 80052b6: bc08 pop {r3} - 80052b8: 469e mov lr, r3 - 80052ba: 4770 bx lr - -080052bc <_fini>: - 80052bc: b5f8 push {r3, r4, r5, r6, r7, lr} - 80052be: bf00 nop - 80052c0: bcf8 pop {r3, r4, r5, r6, r7} - 80052c2: bc08 pop {r3} - 80052c4: 469e mov lr, r3 - 80052c6: 4770 bx lr + 8005318: bf00 nop + 800531a: 3710 adds r7, #16 + 800531c: 46bd mov sp, r7 + 800531e: bd80 pop {r7, pc} + +08005320 <__libc_init_array>: + 8005320: b570 push {r4, r5, r6, lr} + 8005322: 4e0d ldr r6, [pc, #52] ; (8005358 <__libc_init_array+0x38>) + 8005324: 4c0d ldr r4, [pc, #52] ; (800535c <__libc_init_array+0x3c>) + 8005326: 1ba4 subs r4, r4, r6 + 8005328: 10a4 asrs r4, r4, #2 + 800532a: 2500 movs r5, #0 + 800532c: 42a5 cmp r5, r4 + 800532e: d109 bne.n 8005344 <__libc_init_array+0x24> + 8005330: 4e0b ldr r6, [pc, #44] ; (8005360 <__libc_init_array+0x40>) + 8005332: 4c0c ldr r4, [pc, #48] ; (8005364 <__libc_init_array+0x44>) + 8005334: f000 f820 bl 8005378 <_init> + 8005338: 1ba4 subs r4, r4, r6 + 800533a: 10a4 asrs r4, r4, #2 + 800533c: 2500 movs r5, #0 + 800533e: 42a5 cmp r5, r4 + 8005340: d105 bne.n 800534e <__libc_init_array+0x2e> + 8005342: bd70 pop {r4, r5, r6, pc} + 8005344: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 8005348: 4798 blx r3 + 800534a: 3501 adds r5, #1 + 800534c: e7ee b.n 800532c <__libc_init_array+0xc> + 800534e: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 8005352: 4798 blx r3 + 8005354: 3501 adds r5, #1 + 8005356: e7f2 b.n 800533e <__libc_init_array+0x1e> + 8005358: 080053b0 .word 0x080053b0 + 800535c: 080053b0 .word 0x080053b0 + 8005360: 080053b0 .word 0x080053b0 + 8005364: 080053b8 .word 0x080053b8 + +08005368 : + 8005368: 4402 add r2, r0 + 800536a: 4603 mov r3, r0 + 800536c: 4293 cmp r3, r2 + 800536e: d100 bne.n 8005372 + 8005370: 4770 bx lr + 8005372: f803 1b01 strb.w r1, [r3], #1 + 8005376: e7f9 b.n 800536c + +08005378 <_init>: + 8005378: b5f8 push {r3, r4, r5, r6, r7, lr} + 800537a: bf00 nop + 800537c: bcf8 pop {r3, r4, r5, r6, r7} + 800537e: bc08 pop {r3} + 8005380: 469e mov lr, r3 + 8005382: 4770 bx lr + +08005384 <_fini>: + 8005384: b5f8 push {r3, r4, r5, r6, r7, lr} + 8005386: bf00 nop + 8005388: bcf8 pop {r3, r4, r5, r6, r7} + 800538a: bc08 pop {r3} + 800538c: 469e mov lr, r3 + 800538e: 4770 bx lr diff --git a/otto_controller/otto_controller.ioc b/otto_controller/otto_controller.ioc index 41a3850..a1b71b9 100644 --- a/otto_controller/otto_controller.ioc +++ b/otto_controller/otto_controller.ioc @@ -60,11 +60,11 @@ NVIC.TIM6_DAC_IRQn=true\:2\:2\:true\:true\:true\:2\:true\:true NVIC.USART6_IRQn=true\:2\:0\:true\:true\:true\:3\:true\:true NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false PA0/WKUP.GPIOParameters=GPIO_Label -PA0/WKUP.GPIO_Label=encoder_sx1 +PA0/WKUP.GPIO_Label=encoder_dx1 PA0/WKUP.Locked=true PA0/WKUP.Signal=S_TIM5_CH1 PA1.GPIOParameters=GPIO_Label -PA1.GPIO_Label=encoder_sx2 +PA1.GPIO_Label=encoder_dx2 PA1.Locked=true PA1.Signal=S_TIM5_CH2 PA13.Mode=Serial_Wire @@ -76,7 +76,7 @@ PA3.GPIO_Label=current1 PA3.Locked=true PA3.Signal=GPIO_Analog PA5.GPIOParameters=GPIO_Label -PA5.GPIO_Label=encoder_dx1 +PA5.GPIO_Label=encoder_sx1 PA5.Locked=true PA5.Signal=S_TIM2_CH1_ETR PA6.GPIOParameters=GPIO_Label @@ -84,7 +84,7 @@ PA6.GPIO_Label=fault2 PA6.Locked=true PA6.Signal=GPIO_Input PB3.GPIOParameters=GPIO_Label -PB3.GPIO_Label=encoder_dx2 +PB3.GPIO_Label=encoder_sx2 PB3.Locked=true PB3.Signal=S_TIM2_CH2 PC0.GPIOParameters=GPIO_Label diff --git a/utils/pid_tuning/otto_pid_tuning/.mxproject b/utils/pid_tuning/otto_pid_tuning/.mxproject index 7190dbe..e6dd859 100644 --- a/utils/pid_tuning/otto_pid_tuning/.mxproject +++ b/utils/pid_tuning/otto_pid_tuning/.mxproject @@ -1,17 +1,19 @@ [PreviousGenFiles] AdvancedFolderStructure=true HeaderFileListSize=3 -HeaderFiles#0=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/stm32f7xx_it.h -HeaderFiles#1=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/stm32f7xx_hal_conf.h -HeaderFiles#2=/home/fdila/Projects/otto/otto_controller_source/Core/Inc/main.h +HeaderFiles#0=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Inc/stm32f7xx_it.h +HeaderFiles#1=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Inc/stm32f7xx_hal_conf.h +HeaderFiles#2=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Inc/main.h HeaderFolderListSize=1 -HeaderPath#0=/home/fdila/Projects/otto/otto_controller_source/Core/Inc +HeaderPath#0=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Inc SourceFileListSize=3 -SourceFiles#0=/home/fdila/Projects/otto/otto_controller_source/Core/Src/stm32f7xx_it.c -SourceFiles#1=/home/fdila/Projects/otto/otto_controller_source/Core/Src/stm32f7xx_hal_msp.c -SourceFiles#2=/home/fdila/Projects/otto/otto_controller_source/Core/Src/main.c +SourceFiles#0=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_it.c +SourceFiles#1=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_hal_msp.c +SourceFiles#2=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Src/main.c SourceFolderListSize=1 -SourcePath#0=/home/fdila/Projects/otto/otto_controller_source/Core/Src +SourcePath#0=/home/fdila/Projects/otto/utils/pid_tuning/otto_pid_tuning/Core/Src +HeaderFiles=; +SourceFiles=; [PreviousLibFiles] LibFiles=Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_cortex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_def.h;Drivers/STM32F7xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_exti.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart_ex.h;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c;Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.c;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_cortex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_tim_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_rcc_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_flash_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_gpio_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_dma_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pwr_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_def.h;Drivers/STM32F7xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_i2c_ex.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_exti.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart.h;Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_uart_ex.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f767xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Include/system_stm32f7xx.h;Drivers/CMSIS/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/cmsis_armclang.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm4.h; diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/main.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/main.h index c545cce..6b45ffa 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/main.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/main.h @@ -65,14 +65,14 @@ void Error_Handler(void); #define user_button_EXTI_IRQn EXTI15_10_IRQn #define current2_Pin GPIO_PIN_0 #define current2_GPIO_Port GPIOC -#define encoder_sx1_Pin GPIO_PIN_0 -#define encoder_sx1_GPIO_Port GPIOA -#define encoder_sx2_Pin GPIO_PIN_1 -#define encoder_sx2_GPIO_Port GPIOA +#define encoder_dx1_Pin GPIO_PIN_0 +#define encoder_dx1_GPIO_Port GPIOA +#define encoder_dx2_Pin GPIO_PIN_1 +#define encoder_dx2_GPIO_Port GPIOA #define current1_Pin GPIO_PIN_3 #define current1_GPIO_Port GPIOA -#define encoder_dx1_Pin GPIO_PIN_5 -#define encoder_dx1_GPIO_Port GPIOA +#define encoder_sx1_Pin GPIO_PIN_5 +#define encoder_sx1_GPIO_Port GPIOA #define fault2_Pin GPIO_PIN_6 #define fault2_GPIO_Port GPIOA #define dir2_Pin GPIO_PIN_12 @@ -89,8 +89,8 @@ void Error_Handler(void); #define pwm2_GPIO_Port GPIOD #define pwm1_Pin GPIO_PIN_15 #define pwm1_GPIO_Port GPIOD -#define encoder_dx2_Pin GPIO_PIN_3 -#define encoder_dx2_GPIO_Port GPIOB +#define encoder_sx2_Pin GPIO_PIN_3 +#define encoder_sx2_GPIO_Port GPIOB /* USER CODE BEGIN Private defines */ /* USER CODE END Private defines */ diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp b/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp index 29c710a..1c5d3da 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp +++ b/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp @@ -122,12 +122,14 @@ static void MX_NVIC_Init(void); /* USER CODE END 0 */ /** - * @brief The application entry point. - * @retval int - */ -int main(void) { + * @brief The application entry point. + * @retval int + */ +int main(void) +{ /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ + /* MCU Configuration--------------------------------------------------------*/ @@ -183,51 +185,56 @@ int main(void) { } /** - * @brief System Clock Configuration - * @retval None - */ -void SystemClock_Config(void) { - RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; - RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; /** Configure the main internal regulator output voltage - */ + */ __HAL_RCC_PWR_CLK_ENABLE(); __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); /** Initializes the CPU, AHB and APB busses clocks - */ + */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { Error_Handler(); } /** Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK - | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) + { Error_Handler(); } PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) + { Error_Handler(); } } /** - * @brief NVIC Configuration. - * @retval None - */ -static void MX_NVIC_Init(void) { + * @brief NVIC Configuration. + * @retval None + */ +static void MX_NVIC_Init(void) +{ /* TIM3_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM3_IRQn, 2, 1); HAL_NVIC_EnableIRQ(TIM3_IRQn); @@ -240,18 +247,19 @@ static void MX_NVIC_Init(void) { } /** - * @brief TIM2 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM2_Init(void) { + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) +{ /* USER CODE BEGIN TIM2_Init 0 */ /* USER CODE END TIM2_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_Encoder_InitTypeDef sConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM2_Init 1 */ @@ -271,12 +279,14 @@ static void MX_TIM2_Init(void) { sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM2_Init 2 */ @@ -286,18 +296,19 @@ static void MX_TIM2_Init(void) { } /** - * @brief TIM3 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM3_Init(void) { + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) +{ /* USER CODE BEGIN TIM3_Init 0 */ /* USER CODE END TIM3_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM3_Init 1 */ @@ -308,16 +319,19 @@ static void MX_TIM3_Init(void) { htim3.Init.Period = 159; htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) + { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM3_Init 2 */ @@ -327,19 +341,20 @@ static void MX_TIM3_Init(void) { } /** - * @brief TIM4 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM4_Init(void) { + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) +{ /* USER CODE BEGIN TIM4_Init 0 */ /* USER CODE END TIM4_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; - TIM_OC_InitTypeDef sConfigOC = { 0 }; + TIM_ClockConfigTypeDef sClockSourceConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_OC_InitTypeDef sConfigOC = {0}; /* USER CODE BEGIN TIM4_Init 1 */ @@ -350,29 +365,35 @@ static void MX_TIM4_Init(void) { htim4.Init.Period = 799; htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) + { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) + { Error_Handler(); } - if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) + { Error_Handler(); } sConfigOC.OCMode = TIM_OCMODE_PWM1; sConfigOC.Pulse = 0; sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) + { Error_Handler(); } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM4_Init 2 */ @@ -383,18 +404,19 @@ static void MX_TIM4_Init(void) { } /** - * @brief TIM5 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM5_Init(void) { + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) +{ /* USER CODE BEGIN TIM5_Init 0 */ /* USER CODE END TIM5_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = { 0 }; - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_Encoder_InitTypeDef sConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM5_Init 1 */ @@ -414,12 +436,14 @@ static void MX_TIM5_Init(void) { sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM5_Init 2 */ @@ -429,17 +453,18 @@ static void MX_TIM5_Init(void) { } /** - * @brief TIM6 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM6_Init(void) { + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) +{ /* USER CODE BEGIN TIM6_Init 0 */ /* USER CODE END TIM6_Init 0 */ - TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = {0}; /* USER CODE BEGIN TIM6_Init 1 */ @@ -449,12 +474,14 @@ static void MX_TIM6_Init(void) { htim6.Init.CounterMode = TIM_COUNTERMODE_UP; htim6.Init.Period = 799; htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) + { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN TIM6_Init 2 */ @@ -464,11 +491,12 @@ static void MX_TIM6_Init(void) { } /** - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) { + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) +{ /* USER CODE BEGIN USART6_Init 0 */ @@ -487,7 +515,8 @@ static void MX_USART6_UART_Init(void) { huart6.Init.OverSampling = UART_OVERSAMPLING_16; huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - if (HAL_UART_Init(&huart6) != HAL_OK) { + if (HAL_UART_Init(&huart6) != HAL_OK) + { Error_Handler(); } /* USER CODE BEGIN USART6_Init 2 */ @@ -497,12 +526,13 @@ static void MX_USART6_UART_Init(void) { } /** - * @brief GPIO Initialization Function - * @param None - * @retval None - */ -static void MX_GPIO_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; /* GPIO Ports Clock Enable */ __HAL_RCC_GPIOC_CLK_ENABLE(); @@ -513,10 +543,10 @@ static void MX_GPIO_Init(void) { __HAL_RCC_GPIOB_CLK_ENABLE(); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin, GPIO_PIN_RESET); + HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, sleep2_Pin | sleep1_Pin, GPIO_PIN_SET); + HAL_GPIO_WritePin(GPIOF, sleep2_Pin|sleep1_Pin, GPIO_PIN_SET); /*Configure GPIO pin : user_button_Pin */ GPIO_InitStruct.Pin = user_button_Pin; @@ -543,14 +573,14 @@ static void MX_GPIO_Init(void) { HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); /*Configure GPIO pins : dir2_Pin dir1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin; + GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); /*Configure GPIO pins : sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = sleep2_Pin | sleep1_Pin; + GPIO_InitStruct.Pin = sleep2_Pin|sleep1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; @@ -639,10 +669,11 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { /* USER CODE END 4 */ /** - * @brief This function is executed in case of error occurrence. - * @retval None - */ -void Error_Handler(void) { + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) +{ /* USER CODE BEGIN Error_Handler_Debug */ /* User can add his own implementation to report the HAL error return state */ diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_hal_msp.c b/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_hal_msp.c index 821e58b..2918b9b 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_hal_msp.c +++ b/utils/pid_tuning/otto_pid_tuning/Core/Src/stm32f7xx_hal_msp.c @@ -102,19 +102,19 @@ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ - GPIO_InitStruct.Pin = encoder_dx1_Pin; + GPIO_InitStruct.Pin = encoder_sx1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - HAL_GPIO_Init(encoder_dx1_GPIO_Port, &GPIO_InitStruct); + HAL_GPIO_Init(encoder_sx1_GPIO_Port, &GPIO_InitStruct); - GPIO_InitStruct.Pin = encoder_dx2_Pin; + GPIO_InitStruct.Pin = encoder_sx2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - HAL_GPIO_Init(encoder_dx2_GPIO_Port, &GPIO_InitStruct); + HAL_GPIO_Init(encoder_sx2_GPIO_Port, &GPIO_InitStruct); /* USER CODE BEGIN TIM2_MspInit 1 */ @@ -133,7 +133,7 @@ void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) PA0/WKUP ------> TIM5_CH1 PA1 ------> TIM5_CH2 */ - GPIO_InitStruct.Pin = encoder_sx1_Pin|encoder_sx2_Pin; + GPIO_InitStruct.Pin = encoder_dx1_Pin|encoder_dx2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; @@ -238,9 +238,9 @@ void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ - HAL_GPIO_DeInit(encoder_dx1_GPIO_Port, encoder_dx1_Pin); + HAL_GPIO_DeInit(encoder_sx1_GPIO_Port, encoder_sx1_Pin); - HAL_GPIO_DeInit(encoder_dx2_GPIO_Port, encoder_dx2_Pin); + HAL_GPIO_DeInit(encoder_sx2_GPIO_Port, encoder_sx2_Pin); /* USER CODE BEGIN TIM2_MspDeInit 1 */ @@ -258,7 +258,7 @@ void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) PA0/WKUP ------> TIM5_CH1 PA1 ------> TIM5_CH2 */ - HAL_GPIO_DeInit(GPIOA, encoder_sx1_Pin|encoder_sx2_Pin); + HAL_GPIO_DeInit(GPIOA, encoder_dx1_Pin|encoder_dx2_Pin); /* USER CODE BEGIN TIM5_MspDeInit 1 */ diff --git a/utils/pid_tuning/otto_pid_tuning/otto_pid_tuning.ioc b/utils/pid_tuning/otto_pid_tuning/otto_pid_tuning.ioc index 13617ea..844db89 100644 --- a/utils/pid_tuning/otto_pid_tuning/otto_pid_tuning.ioc +++ b/utils/pid_tuning/otto_pid_tuning/otto_pid_tuning.ioc @@ -60,11 +60,11 @@ NVIC.TIM6_DAC_IRQn=true\:2\:2\:true\:true\:true\:2\:true\:true NVIC.USART6_IRQn=true\:2\:0\:true\:true\:true\:3\:true\:true NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false PA0/WKUP.GPIOParameters=GPIO_Label -PA0/WKUP.GPIO_Label=encoder_sx1 +PA0/WKUP.GPIO_Label=encoder_dx1 PA0/WKUP.Locked=true PA0/WKUP.Signal=S_TIM5_CH1 PA1.GPIOParameters=GPIO_Label -PA1.GPIO_Label=encoder_sx2 +PA1.GPIO_Label=encoder_dx2 PA1.Locked=true PA1.Signal=S_TIM5_CH2 PA13.Mode=Serial_Wire @@ -76,7 +76,7 @@ PA3.GPIO_Label=current1 PA3.Locked=true PA3.Signal=GPIO_Analog PA5.GPIOParameters=GPIO_Label -PA5.GPIO_Label=encoder_dx1 +PA5.GPIO_Label=encoder_sx1 PA5.Locked=true PA5.Signal=S_TIM2_CH1_ETR PA6.GPIOParameters=GPIO_Label @@ -84,7 +84,7 @@ PA6.GPIO_Label=fault2 PA6.Locked=true PA6.Signal=GPIO_Input PB3.GPIOParameters=GPIO_Label -PB3.GPIO_Label=encoder_dx2 +PB3.GPIO_Label=encoder_sx2 PB3.Locked=true PB3.Signal=S_TIM2_CH2 PC0.GPIOParameters=GPIO_Label -- 2.52.0