From c20e09eb44f96bea8e608e5b6f5855df3d5171c7 Mon Sep 17 00:00:00 2001 From: Federica Di Lauro Date: Sat, 14 Dec 2019 17:03:25 +0100 Subject: [PATCH] pid and motor_controller classes implemented --- .../Core/Inc/motor_controller.h | 48 + otto_controller_source/Core/Inc/odometry.h | 45 + .../Core/Inc/odometry_calc.h | 76 - otto_controller_source/Core/Inc/pid.h | 62 + otto_controller_source/Core/Src/main.c | 581 - otto_controller_source/Core/Src/main.cpp | 566 + .../Core/Src/odometry_calc.cpp | 44 - .../Debug/Core/Src/subdir.mk | 53 + .../Debug/Core/Startup/subdir.mk | 16 + .../STM32F7xx_HAL_Driver/Src/subdir.mk | 104 + otto_controller_source/Debug/makefile | 80 + otto_controller_source/Debug/objects.list | 26 + otto_controller_source/Debug/objects.mk | 8 + .../Debug/otto_controller_source.list | 13320 ++++++++++++++++ otto_controller_source/Debug/sources.mk | 32 + 15 files changed, 14360 insertions(+), 701 deletions(-) create mode 100644 otto_controller_source/Core/Inc/motor_controller.h create mode 100644 otto_controller_source/Core/Inc/odometry.h delete mode 100644 otto_controller_source/Core/Inc/odometry_calc.h create mode 100644 otto_controller_source/Core/Inc/pid.h delete mode 100644 otto_controller_source/Core/Src/main.c create mode 100644 otto_controller_source/Core/Src/main.cpp delete mode 100644 otto_controller_source/Core/Src/odometry_calc.cpp create mode 100644 otto_controller_source/Debug/Core/Src/subdir.mk create mode 100644 otto_controller_source/Debug/Core/Startup/subdir.mk create mode 100644 otto_controller_source/Debug/Drivers/STM32F7xx_HAL_Driver/Src/subdir.mk create mode 100644 otto_controller_source/Debug/makefile create mode 100644 otto_controller_source/Debug/objects.list create mode 100644 otto_controller_source/Debug/objects.mk create mode 100644 otto_controller_source/Debug/otto_controller_source.list create mode 100644 otto_controller_source/Debug/sources.mk diff --git a/otto_controller_source/Core/Inc/motor_controller.h b/otto_controller_source/Core/Inc/motor_controller.h new file mode 100644 index 0000000..de78f39 --- /dev/null +++ b/otto_controller_source/Core/Inc/motor_controller.h @@ -0,0 +1,48 @@ +#ifndef MOTOR_CONTROLLER_H +#define MOTOR_CONTROLLER_H + +#include "main.h" + +class MotorController { +public: + GPIO_TypeDef *sleep_gpio_port_; + uint16_t sleep_pin_; + GPIO_TypeDef *dir_gpio_port_; + uint16_t dir_pin_; + TIM_HandleTypeDef* pwm_timer_; + uint32_t pwm_channel_; + + MotorController(GPIO_TypeDef *sleep_gpio_port, uint16_t sleep_pin, + GPIO_TypeDef *dir_gpio_port, uint16_t dir_pin, + TIM_HandleTypeDef* pwm_timer, uint32_t pwm_channel) { + this->sleep_gpio_port_ = sleep_gpio_port; + this->sleep_pin_ = sleep_pin; + this->dir_gpio_port_ = dir_gpio_port; + this->dir_pin_ = dir_pin; + this->pwm_timer_ = pwm_timer; + this->pwm_channel_ = pwm_channel; + } + + void setup(){ + HAL_TIM_PWM_Start(pwm_timer_, pwm_channel_); + } + + void forward(int duty_cycle){ + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); + } + + void backward(int duty_cycle){ + HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); + } + + void brake(){ + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); + } + + void coast(){ + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_RESET); + } +}; +#endif diff --git a/otto_controller_source/Core/Inc/odometry.h b/otto_controller_source/Core/Inc/odometry.h new file mode 100644 index 0000000..67210fc --- /dev/null +++ b/otto_controller_source/Core/Inc/odometry.h @@ -0,0 +1,45 @@ +#ifndef ODOMETRY_CALC_H +#define ODOMETRY_CALC_H + +#include "main.h" +#include "encoder.h" + +class Odometry { +public: + Encoder left_encoder_; + Encoder right_encoder_; + float kBaseline; + + float linear_velocity; + float angular_velocity; + int delta_time; + + Odometry() { + left_encoder_ = NULL; + right_encoder_ = NULL; + kBaseline = 0.35; //in meters + } + + Odometry(Encoder left, Encoder right) { + + left_encoder_ = left; + right_encoder_ = right; + kBaseline = 0.35; //in meters + } + + void UpdateValues() { + float left_velocity = left_encoder_.GetLinearVelocity(); + float right_velocity = right_encoder_.GetLinearVelocity(); + + //verificato che delta_r == delta_l + this->delta_time = left_encoder_.current_millis_ + - left_encoder_.previous_millis_; + + this->linear_velocity = (left_velocity + right_velocity) / 2; + this->angular_velocity = (right_velocity - left_velocity) / kBaseline; + return; + } + +}; + +#endif diff --git a/otto_controller_source/Core/Inc/odometry_calc.h b/otto_controller_source/Core/Inc/odometry_calc.h deleted file mode 100644 index 1a9a0d5..0000000 --- a/otto_controller_source/Core/Inc/odometry_calc.h +++ /dev/null @@ -1,76 +0,0 @@ -#ifndef ODOMETRY_CALC_H -#define ODOMETRY_CALC_H - -#include -#include -#include -#include -#include - -#include "main.h" -#include "encoder.h" - -class OdometryCalc { -public: - Encoder left_encoder_; - Encoder right_encoder_; - float theta_; - nav_msgs::Odometry odometry_; - float kBaseline; - - OdometryCalc() { - left_encoder_ = NULL; - right_encoder_ = NULL; - theta_ = 0; - - // odometry_.pose.covariance = 0.0; - odometry_.pose.pose.position.x = 0.0; - odometry_.pose.pose.position.y = 0.0; - odometry_.pose.pose.position.z = 0.0; - - //orientation è il quaternione - odometry_.pose.pose.orientation.x = 0.0; - odometry_.pose.pose.orientation.y = 0.0; - odometry_.pose.pose.orientation.z = 0.0; - odometry_.pose.pose.orientation.w = 0.0; - - //odometry_.twist.covariance = 0.0; - odometry_.twist.twist.angular.z = 0; - odometry_.twist.twist.linear.x = 0; - - kBaseline = 0.35; //in meters - } - - OdometryCalc(Encoder left, Encoder right){ - - left_encoder_ = left; - right_encoder_ = right; - - theta_ = 0; - - odometry_.header.frame_id = "odom"; - odometry_.child_frame_id = "base_link"; - - // odometry_.pose.covariance = 0.0; - odometry_.pose.pose.position.x = 0.0; - odometry_.pose.pose.position.y = 0.0; - odometry_.pose.pose.position.z = 0.0; - - //orientation è il quaternione - odometry_.pose.pose.orientation.x = 0.0; - odometry_.pose.pose.orientation.y = 0.0; - odometry_.pose.pose.orientation.z = 0.0; - odometry_.pose.pose.orientation.w = 0.0; - - //odometry_.twist.covariance = 0.0; - odometry_.twist.twist.angular.z = 0; - odometry_.twist.twist.linear.x = 0; - - kBaseline = 0.35; //in meters - } - - void OdometryUpdateMessage(); - -}; - -#endif diff --git a/otto_controller_source/Core/Inc/pid.h b/otto_controller_source/Core/Inc/pid.h new file mode 100644 index 0000000..ec9877e --- /dev/null +++ b/otto_controller_source/Core/Inc/pid.h @@ -0,0 +1,62 @@ +#ifndef PID_H +#define PID_H + +class Pid { +public: + float kp_; + float ki_; + float kd_; + float previous_error_; + float error_; + float error_sum_; + float setpoint_; + int min_; + int max_; + + Pid(float kp, float ki, float kd, int min, int max){ + this->kp_ = kp; + this->ki_ = ki; + this->kd_ = kd; + this->previous_error_ = 0; + this->error_ = 0; + this->error_sum_ = 0; + this->setpoint_ = 0; + this->min_ = min; + this->max_ = max; + } + + void set(float setpoint){ + this->setpoint_ = setpoint; + } + + int update(float measure){ + + this->error_ = this->setpoint_ - measure; + + //proportional term + float output = this->error_ * this->kp_; + + //TODO integral term + + //TODO derivative term + + if (output > this->max_){ + + output = this->max_; + + //TODO anti-windup (prima capisco cos'è) + + } else if (output < this->min_){ + + output = this->min_; + + //TODO anti-windup + } + + int integer_output = (int) output; + + return integer_output; + + } +}; +#endif diff --git a/otto_controller_source/Core/Src/main.c b/otto_controller_source/Core/Src/main.c deleted file mode 100644 index fb48918..0000000 --- a/otto_controller_source/Core/Src/main.c +++ /dev/null @@ -1,581 +0,0 @@ -/* USER CODE BEGIN Header */ -/** - ****************************************************************************** - * @file : main.c - * @brief : Main program body - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -/* USER CODE END Header */ - -/* Includes ------------------------------------------------------------------*/ -#include "main.h" - -/* Private includes ----------------------------------------------------------*/ -/* USER CODE BEGIN Includes */ - -#include -#include - -/* USER CODE END Includes */ - -/* Private typedef -----------------------------------------------------------*/ -/* USER CODE BEGIN PTD */ - -/* USER CODE END PTD */ - -/* Private define ------------------------------------------------------------*/ -/* USER CODE BEGIN PD */ -/* USER CODE END PD */ - -/* Private macro -------------------------------------------------------------*/ -/* USER CODE BEGIN PM */ - -/* USER CODE END PM */ - -/* Private variables ---------------------------------------------------------*/ - -TIM_HandleTypeDef htim2; -TIM_HandleTypeDef htim3; -TIM_HandleTypeDef htim4; -TIM_HandleTypeDef htim5; -TIM_HandleTypeDef htim6; - -UART_HandleTypeDef huart6; -DMA_HandleTypeDef hdma_usart6_rx; -DMA_HandleTypeDef hdma_usart6_tx; - -/* USER CODE BEGIN PV */ - -//Odometry -Encoder left_encoder = Encoder(&htim5); -Encoder right_encoder = Encoder(&htim2); -OdometryCalc odom = OdometryCalc(left_encoder, right_encoder); -//test stuff - -float delta_r = 0; -float delta_l = 0; -float velocity_l = 0; -float velocity_r = 0; - -/* USER CODE END PV */ - -/* Private function prototypes -----------------------------------------------*/ -void SystemClock_Config(void); -static void MX_GPIO_Init(void); -static void MX_DMA_Init(void); -static void MX_TIM2_Init(void); -static void MX_TIM3_Init(void); -static void MX_TIM4_Init(void); -static void MX_TIM5_Init(void); -static void MX_USART6_UART_Init(void); -static void MX_TIM6_Init(void); -/* USER CODE BEGIN PFP */ - -/* USER CODE END PFP */ - -/* Private user code ---------------------------------------------------------*/ -/* USER CODE BEGIN 0 */ - -/* USER CODE END 0 */ - -/** - * @brief The application entry point. - * @retval int - */ -int main(void) -{ - /* USER CODE BEGIN 1 */ - - /* USER CODE END 1 */ - - - /* MCU Configuration--------------------------------------------------------*/ - - /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ - HAL_Init(); - - /* USER CODE BEGIN Init */ - - /* USER CODE END Init */ - - /* Configure the system clock */ - SystemClock_Config(); - - /* USER CODE BEGIN SysInit */ - - /* USER CODE END SysInit */ - - /* Initialize all configured peripherals */ - MX_GPIO_Init(); - MX_DMA_Init(); - MX_TIM2_Init(); - MX_TIM3_Init(); - MX_TIM4_Init(); - MX_TIM5_Init(); - MX_USART6_UART_Init(); - MX_TIM6_Init(); - /* USER CODE BEGIN 2 */ - - left_encoder.Setup(); - right_encoder.Setup(); - -// HAL_TIM_Base_Start_IT(&htim3); - - /* USER CODE END 2 */ - - /* Infinite loop */ - /* USER CODE BEGIN WHILE */ - while (1) { - - /* USER CODE END WHILE */ - - /* USER CODE BEGIN 3 */ - } - /* USER CODE END 3 */ -} - -/** - * @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) - { - 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.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) - { - Error_Handler(); - } - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; - PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - { - Error_Handler(); - } -} - -/** - * @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}; - - /* USER CODE BEGIN TIM2_Init 1 */ - - /* USER CODE END TIM2_Init 1 */ - htim2.Instance = TIM2; - htim2.Init.Prescaler = 0; - htim2.Init.CounterMode = TIM_COUNTERMODE_UP; - htim2.Init.Period = 4294967295; - htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - sConfig.IC1Filter = 0; - sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - sConfig.IC2Filter = 0; - 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) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM2_Init 2 */ - - /* USER CODE END TIM2_Init 2 */ - -} - -/** - * @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}; - - /* USER CODE BEGIN TIM3_Init 1 */ - - /* USER CODE END TIM3_Init 1 */ - htim3.Instance = TIM3; - htim3.Init.Prescaler = 9999; - htim3.Init.CounterMode = TIM_COUNTERMODE_UP; - 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) - { - Error_Handler(); - } - sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - 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) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM3_Init 2 */ - - /* USER CODE END TIM3_Init 2 */ - -} - -/** - * @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}; - - /* USER CODE BEGIN TIM4_Init 1 */ - - /* USER CODE END TIM4_Init 1 */ - htim4.Instance = TIM4; - htim4.Init.Prescaler = 0; - htim4.Init.CounterMode = TIM_COUNTERMODE_UP; - 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) - { - Error_Handler(); - } - sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) - { - Error_Handler(); - } - 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) - { - 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) - { - Error_Handler(); - } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM4_Init 2 */ - - /* USER CODE END TIM4_Init 2 */ - HAL_TIM_MspPostInit(&htim4); - -} - -/** - * @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}; - - /* USER CODE BEGIN TIM5_Init 1 */ - - /* USER CODE END TIM5_Init 1 */ - htim5.Instance = TIM5; - htim5.Init.Prescaler = 0; - htim5.Init.CounterMode = TIM_COUNTERMODE_UP; - htim5.Init.Period = 4294967295; - htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - sConfig.IC1Filter = 0; - sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - sConfig.IC2Filter = 0; - 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) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM5_Init 2 */ - - /* USER CODE END TIM5_Init 2 */ - -} - -/** - * @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}; - - /* USER CODE BEGIN TIM6_Init 1 */ - - /* USER CODE END TIM6_Init 1 */ - htim6.Instance = TIM6; - htim6.Init.Prescaler = 9999; - 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) - { - Error_Handler(); - } - sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) - { - Error_Handler(); - } - /* USER CODE BEGIN TIM6_Init 2 */ - - /* USER CODE END TIM6_Init 2 */ - -} - -/** - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) -{ - - /* USER CODE BEGIN USART6_Init 0 */ - - /* USER CODE END USART6_Init 0 */ - - /* USER CODE BEGIN USART6_Init 1 */ - - /* USER CODE END USART6_Init 1 */ - huart6.Instance = USART6; - huart6.Init.BaudRate = 115200; - huart6.Init.WordLength = UART_WORDLENGTH_8B; - huart6.Init.StopBits = UART_STOPBITS_1; - huart6.Init.Parity = UART_PARITY_NONE; - huart6.Init.Mode = UART_MODE_TX_RX; - huart6.Init.HwFlowCtl = UART_HWCONTROL_NONE; - 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) - { - Error_Handler(); - } - /* USER CODE BEGIN USART6_Init 2 */ - - /* USER CODE END USART6_Init 2 */ - -} - -/** - * Enable DMA controller clock - */ -static void MX_DMA_Init(void) -{ - - /* DMA controller clock enable */ - __HAL_RCC_DMA2_CLK_ENABLE(); - - /* DMA interrupt init */ - /* DMA2_Stream1_IRQn interrupt configuration */ - HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 2, 0); - HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn); - /* DMA2_Stream6_IRQn interrupt configuration */ - HAL_NVIC_SetPriority(DMA2_Stream6_IRQn, 2, 0); - HAL_NVIC_EnableIRQ(DMA2_Stream6_IRQn); - -} - -/** - * @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(); - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOF_CLK_ENABLE(); - __HAL_RCC_GPIOE_CLK_ENABLE(); - __HAL_RCC_GPIOD_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - - /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin|sleep2_Pin|sleep1_Pin, GPIO_PIN_RESET); - - /*Configure GPIO pin : current2_Pin */ - GPIO_InitStruct.Pin = current2_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(current2_GPIO_Port, &GPIO_InitStruct); - - /*Configure GPIO pin : current1_Pin */ - GPIO_InitStruct.Pin = current1_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(current1_GPIO_Port, &GPIO_InitStruct); - - /*Configure GPIO pin : fault2_Pin */ - GPIO_InitStruct.Pin = fault2_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); - - /*Configure GPIO pins : dir2_Pin dir1_Pin sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin|sleep2_Pin|sleep1_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 pin : fault1_Pin */ - GPIO_InitStruct.Pin = fault1_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(fault1_GPIO_Port, &GPIO_InitStruct); - -} - -/* USER CODE BEGIN 4 */ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { - if (htim->Instance == TIM3) { - - } -} -/* USER CODE END 4 */ - -/** - * @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 */ - - /* USER CODE END Error_Handler_Debug */ -} - -#ifdef USE_FULL_ASSERT -/** - * @brief Reports the name of the source file and the source line number - * where the assert_param error has occurred. - * @param file: pointer to the source file name - * @param line: assert_param error line source number - * @retval None - */ -void assert_failed(uint8_t *file, uint32_t line) -{ - /* USER CODE BEGIN 6 */ - /* User can add his own implementation to report the file name and line number, - tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ - /* USER CODE END 6 */ -} -#endif /* USE_FULL_ASSERT */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/otto_controller_source/Core/Src/main.cpp b/otto_controller_source/Core/Src/main.cpp new file mode 100644 index 0000000..2db470c --- /dev/null +++ b/otto_controller_source/Core/Src/main.cpp @@ -0,0 +1,566 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file : main.c + * @brief : Main program body + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2019 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ + +#include "encoder.h" +#include "odometry.h" +#include "motor_controller.h" +#include "pid.h" +/* USER CODE END Includes */ + +/* Private typedef -----------------------------------------------------------*/ +/* USER CODE BEGIN PTD */ + +/* USER CODE END PTD */ + +/* Private define ------------------------------------------------------------*/ +/* USER CODE BEGIN PD */ +/* USER CODE END PD */ + +/* Private macro -------------------------------------------------------------*/ +/* USER CODE BEGIN PM */ + +/* USER CODE END PM */ + +/* Private variables ---------------------------------------------------------*/ + +TIM_HandleTypeDef htim2; +TIM_HandleTypeDef htim3; +TIM_HandleTypeDef htim4; +TIM_HandleTypeDef htim5; +TIM_HandleTypeDef htim6; + +UART_HandleTypeDef huart6; +DMA_HandleTypeDef hdma_usart6_rx; +DMA_HandleTypeDef hdma_usart6_tx; + +/* USER CODE BEGIN PV */ + +//Odometry +Encoder left_encoder = Encoder(&htim5); +Encoder right_encoder = Encoder(&htim2); +Odometry odom = Odometry(left_encoder, right_encoder); +//test stuff + +float delta_r = 0; +float delta_l = 0; +float velocity_l = 0; +float velocity_r = 0; + +/* USER CODE END PV */ + +/* Private function prototypes -----------------------------------------------*/ +void SystemClock_Config(void); +static void MX_GPIO_Init(void); +static void MX_DMA_Init(void); +static void MX_TIM2_Init(void); +static void MX_TIM3_Init(void); +static void MX_TIM4_Init(void); +static void MX_TIM5_Init(void); +static void MX_USART6_UART_Init(void); +static void MX_TIM6_Init(void); +/* USER CODE BEGIN PFP */ + +/* USER CODE END PFP */ + +/* Private user code ---------------------------------------------------------*/ +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/** + * @brief The application entry point. + * @retval int + */ +int main(void) { + /* USER CODE BEGIN 1 */ + + /* USER CODE END 1 */ + + /* MCU Configuration--------------------------------------------------------*/ + + /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ + HAL_Init(); + + /* USER CODE BEGIN Init */ + + /* USER CODE END Init */ + + /* Configure the system clock */ + SystemClock_Config(); + + /* USER CODE BEGIN SysInit */ + + /* USER CODE END SysInit */ + + /* Initialize all configured peripherals */ + MX_GPIO_Init(); + MX_DMA_Init(); + MX_TIM2_Init(); + MX_TIM3_Init(); + MX_TIM4_Init(); + MX_TIM5_Init(); + MX_USART6_UART_Init(); + MX_TIM6_Init(); + /* USER CODE BEGIN 2 */ + + left_encoder.Setup(); + right_encoder.Setup(); + + HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_4); + HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_3); + + HAL_GPIO_WritePin(dir1_GPIO_Port, dir1_Pin, GPIO_PIN_SET); + + __HAL_TIM_SET_COMPARE(&htim4, TIM_CHANNEL_4, 790); + __HAL_TIM_SET_COMPARE(&htim4, TIM_CHANNEL_3, 750); + + HAL_TIM_Base_Start_IT(&htim3); + + /* USER CODE END 2 */ + + /* Infinite loop */ + /* USER CODE BEGIN WHILE */ + while (1) { + /* USER CODE END WHILE */ + + /* USER CODE BEGIN 3 */ + } + /* USER CODE END 3 */ +} + +/** + * @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) { + 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.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) { + Error_Handler(); + } + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; + PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + Error_Handler(); + } +} + +/** + * @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 }; + + /* USER CODE BEGIN TIM2_Init 1 */ + + /* USER CODE END TIM2_Init 1 */ + htim2.Instance = TIM2; + htim2.Init.Prescaler = 0; + htim2.Init.CounterMode = TIM_COUNTERMODE_UP; + htim2.Init.Period = 4294967295; + htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + sConfig.IC1Filter = 0; + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + sConfig.IC2Filter = 0; + 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) { + Error_Handler(); + } + /* USER CODE BEGIN TIM2_Init 2 */ + + /* USER CODE END TIM2_Init 2 */ + +} + +/** + * @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 }; + + /* USER CODE BEGIN TIM3_Init 1 */ + + /* USER CODE END TIM3_Init 1 */ + htim3.Instance = TIM3; + htim3.Init.Prescaler = 9999; + htim3.Init.CounterMode = TIM_COUNTERMODE_UP; + 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) { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + 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) { + Error_Handler(); + } + /* USER CODE BEGIN TIM3_Init 2 */ + + /* USER CODE END TIM3_Init 2 */ + +} + +/** + * @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 }; + + /* USER CODE BEGIN TIM4_Init 1 */ + + /* USER CODE END TIM4_Init 1 */ + htim4.Instance = TIM4; + htim4.Init.Prescaler = 0; + htim4.Init.CounterMode = TIM_COUNTERMODE_UP; + 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) { + Error_Handler(); + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { + Error_Handler(); + } + 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) { + 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) { + Error_Handler(); + } + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) + != HAL_OK) { + Error_Handler(); + } + /* USER CODE BEGIN TIM4_Init 2 */ + + /* USER CODE END TIM4_Init 2 */ + HAL_TIM_MspPostInit(&htim4); + +} + +/** + * @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 }; + + /* USER CODE BEGIN TIM5_Init 1 */ + + /* USER CODE END TIM5_Init 1 */ + htim5.Instance = TIM5; + htim5.Init.Prescaler = 0; + htim5.Init.CounterMode = TIM_COUNTERMODE_UP; + htim5.Init.Period = 4294967295; + htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + sConfig.IC1Filter = 0; + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + sConfig.IC2Filter = 0; + 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) { + Error_Handler(); + } + /* USER CODE BEGIN TIM5_Init 2 */ + + /* USER CODE END TIM5_Init 2 */ + +} + +/** + * @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 }; + + /* USER CODE BEGIN TIM6_Init 1 */ + + /* USER CODE END TIM6_Init 1 */ + htim6.Instance = TIM6; + htim6.Init.Prescaler = 9999; + 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) { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) + != HAL_OK) { + Error_Handler(); + } + /* USER CODE BEGIN TIM6_Init 2 */ + + /* USER CODE END TIM6_Init 2 */ + +} + +/** + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) { + + /* USER CODE BEGIN USART6_Init 0 */ + + /* USER CODE END USART6_Init 0 */ + + /* USER CODE BEGIN USART6_Init 1 */ + + /* USER CODE END USART6_Init 1 */ + huart6.Instance = USART6; + huart6.Init.BaudRate = 115200; + huart6.Init.WordLength = UART_WORDLENGTH_8B; + huart6.Init.StopBits = UART_STOPBITS_1; + huart6.Init.Parity = UART_PARITY_NONE; + huart6.Init.Mode = UART_MODE_TX_RX; + huart6.Init.HwFlowCtl = UART_HWCONTROL_NONE; + 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) { + Error_Handler(); + } + /* USER CODE BEGIN USART6_Init 2 */ + + /* USER CODE END USART6_Init 2 */ + +} + +/** + * Enable DMA controller clock + */ +static void MX_DMA_Init(void) { + + /* DMA controller clock enable */ + __HAL_RCC_DMA2_CLK_ENABLE(); + + /* DMA interrupt init */ + /* DMA2_Stream1_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 2, 0); + HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn); + /* DMA2_Stream6_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream6_IRQn, 2, 0); + HAL_NVIC_EnableIRQ(DMA2_Stream6_IRQn); + +} + +/** + * @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(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOF_CLK_ENABLE(); + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin | sleep2_Pin | sleep1_Pin, + GPIO_PIN_RESET); + + /*Configure GPIO pin : current2_Pin */ + GPIO_InitStruct.Pin = current2_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(current2_GPIO_Port, &GPIO_InitStruct); + + /*Configure GPIO pin : current1_Pin */ + GPIO_InitStruct.Pin = current1_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(current1_GPIO_Port, &GPIO_InitStruct); + + /*Configure GPIO pin : fault2_Pin */ + GPIO_InitStruct.Pin = fault2_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); + + /*Configure GPIO pins : dir2_Pin dir1_Pin sleep2_Pin sleep1_Pin */ + GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin | sleep2_Pin | sleep1_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 pin : fault1_Pin */ + GPIO_InitStruct.Pin = fault1_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(fault1_GPIO_Port, &GPIO_InitStruct); + +} + +/* USER CODE BEGIN 4 */ +void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { + if (htim->Instance == TIM3) { + + } +} +/* USER CODE END 4 */ + +/** + * @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 */ + + /* USER CODE END Error_Handler_Debug */ +} + +#ifdef USE_FULL_ASSERT +/** + * @brief Reports the name of the source file and the source line number + * where the assert_param error has occurred. + * @param file: pointer to the source file name + * @param line: assert_param error line source number + * @retval None + */ +void assert_failed(uint8_t *file, uint32_t line) +{ + /* USER CODE BEGIN 6 */ + /* User can add his own implementation to report the file name and line number, + tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ + /* USER CODE END 6 */ +} +#endif /* USE_FULL_ASSERT */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/otto_controller_source/Core/Src/odometry_calc.cpp b/otto_controller_source/Core/Src/odometry_calc.cpp deleted file mode 100644 index d0c6851..0000000 --- a/otto_controller_source/Core/Src/odometry_calc.cpp +++ /dev/null @@ -1,44 +0,0 @@ -#include "odometry_calc.h" - -void OdometryCalc::OdometryUpdateMessage(){ - float left_velocity = left_encoder_.GetLinearVelocity(); - float right_velocity = right_encoder_.GetLinearVelocity(); - - float x = odometry_.pose.pose.position.x; - float y = odometry_.pose.pose.position.y; - - //verificato che delta_r == delta_l - float delta_time = left_encoder_.current_millis_ - - left_encoder_.previous_millis_; - - // calcoli vari - float linear_velocity = (left_velocity + right_velocity) / 2; - float angular_velocity; - if (right_velocity - left_velocity == 0) - angular_velocity = 0; - else - angular_velocity = (right_velocity - left_velocity) / kBaseline; - float diff = angular_velocity / delta_time; - float r = (kBaseline / 2) * ((right_velocity + left_velocity) / - (right_velocity - left_velocity)); - float icc_x = x - r * std::sin(theta_); - float icc_y = y + r * std::cos(theta_); - float new_x = std::cos(diff) * (x - icc_x) - - std::sin(diff) * (y - icc_y) + icc_x; - float new_y = std::sin(diff) * (y - icc_y) + - std::cos(diff) * (y - icc_y) + icc_y; - theta_ = theta_ + diff; - geometry_msgs::Quaternion q = tf::createQuaternionFromYaw(theta_); - - //update msg - odometry_.pose.pose.position.x = new_x; - odometry_.pose.pose.position.y = new_y; - odometry_.pose.pose.orientation.x = q.x; - odometry_.pose.pose.orientation.y = q.y; - odometry_.pose.pose.orientation.z = q.z; - odometry_.pose.pose.orientation.w = q.w; - odometry_.twist.twist.linear.x = linear_velocity; - odometry_.twist.twist.angular.z = angular_velocity; - - return; -} diff --git a/otto_controller_source/Debug/Core/Src/subdir.mk b/otto_controller_source/Debug/Core/Src/subdir.mk new file mode 100644 index 0000000..4fcd8af --- /dev/null +++ b/otto_controller_source/Debug/Core/Src/subdir.mk @@ -0,0 +1,53 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +# Add inputs and outputs from these tool invocations to the build variables +C_SRCS += \ +../Core/Src/stm32f7xx_hal_msp.c \ +../Core/Src/stm32f7xx_it.c \ +../Core/Src/syscalls.c \ +../Core/Src/sysmem.c \ +../Core/Src/system_stm32f7xx.c + +CPP_SRCS += \ +../Core/Src/encoder.cpp \ +../Core/Src/main.cpp + +OBJS += \ +./Core/Src/encoder.o \ +./Core/Src/main.o \ +./Core/Src/stm32f7xx_hal_msp.o \ +./Core/Src/stm32f7xx_it.o \ +./Core/Src/syscalls.o \ +./Core/Src/sysmem.o \ +./Core/Src/system_stm32f7xx.o + +C_DEPS += \ +./Core/Src/stm32f7xx_hal_msp.d \ +./Core/Src/stm32f7xx_it.d \ +./Core/Src/syscalls.d \ +./Core/Src/sysmem.d \ +./Core/Src/system_stm32f7xx.d + +CPP_DEPS += \ +./Core/Src/encoder.d \ +./Core/Src/main.d + + +# Each subdirectory must supply rules for building sources it contributes +Core/Src/encoder.o: ../Core/Src/encoder.cpp + arm-none-eabi-g++ "$<" -mcpu=cortex-m7 -std=gnu++14 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -fno-exceptions -fno-rtti -fno-threadsafe-statics -fno-use-cxa-atexit -Wall -fstack-usage -MMD -MP -MF"Core/Src/encoder.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/main.o: ../Core/Src/main.cpp + arm-none-eabi-g++ "$<" -mcpu=cortex-m7 -std=gnu++14 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -fno-exceptions -fno-rtti -fno-threadsafe-statics -fno-use-cxa-atexit -Wall -fstack-usage -MMD -MP -MF"Core/Src/main.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/stm32f7xx_hal_msp.o: ../Core/Src/stm32f7xx_hal_msp.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Core/Src/stm32f7xx_hal_msp.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/stm32f7xx_it.o: ../Core/Src/stm32f7xx_it.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Core/Src/stm32f7xx_it.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/syscalls.o: ../Core/Src/syscalls.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Core/Src/syscalls.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/sysmem.o: ../Core/Src/sysmem.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Core/Src/sysmem.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Core/Src/system_stm32f7xx.o: ../Core/Src/system_stm32f7xx.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Core/Src/system_stm32f7xx.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" + diff --git a/otto_controller_source/Debug/Core/Startup/subdir.mk b/otto_controller_source/Debug/Core/Startup/subdir.mk new file mode 100644 index 0000000..481e2a5 --- /dev/null +++ b/otto_controller_source/Debug/Core/Startup/subdir.mk @@ -0,0 +1,16 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +# Add inputs and outputs from these tool invocations to the build variables +S_SRCS += \ +../Core/Startup/startup_stm32f767zitx.s + +OBJS += \ +./Core/Startup/startup_stm32f767zitx.o + + +# Each subdirectory must supply rules for building sources it contributes +Core/Startup/%.o: ../Core/Startup/%.s + arm-none-eabi-gcc -mcpu=cortex-m7 -g3 -c -x assembler-with-cpp --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" "$<" + diff --git a/otto_controller_source/Debug/Drivers/STM32F7xx_HAL_Driver/Src/subdir.mk b/otto_controller_source/Debug/Drivers/STM32F7xx_HAL_Driver/Src/subdir.mk new file mode 100644 index 0000000..2a0a6ce --- /dev/null +++ b/otto_controller_source/Debug/Drivers/STM32F7xx_HAL_Driver/Src/subdir.mk @@ -0,0 +1,104 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +# Add inputs and outputs from these tool invocations to the build variables +C_SRCS += \ +../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.c \ +../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.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_exti.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_i2c.c \ +../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_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_rcc.c \ +../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.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_uart.c \ +../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.c + +OBJS += \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.o \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.o + +C_DEPS += \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.d \ +./Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.d + + +# Each subdirectory must supply rules for building sources it contributes +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" +Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.o: ../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.c + arm-none-eabi-gcc "$<" -mcpu=cortex-m7 -std=gnu11 -g3 -DUSE_HAL_DRIVER -DSTM32F767xx -DDEBUG -c -I../Drivers/CMSIS/Include -I../Drivers/CMSIS/Device/ST/STM32F7xx/Include -I../Core/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc -I../Drivers/STM32F7xx_HAL_Driver/Inc/Legacy -O0 -ffunction-sections -fdata-sections -Wall -fstack-usage -MMD -MP -MF"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.d" -MT"$@" --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -o "$@" + diff --git a/otto_controller_source/Debug/makefile b/otto_controller_source/Debug/makefile new file mode 100644 index 0000000..be3ddb4 --- /dev/null +++ b/otto_controller_source/Debug/makefile @@ -0,0 +1,80 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +-include ../makefile.init + +RM := rm -rf + +# All of the sources participating in the build are defined here +-include sources.mk +-include Drivers/STM32F7xx_HAL_Driver/Src/subdir.mk +-include Core/Startup/subdir.mk +-include Core/Src/subdir.mk +-include subdir.mk +-include objects.mk + +ifneq ($(MAKECMDGOALS),clean) +ifneq ($(strip $(CC_DEPS)),) +-include $(CC_DEPS) +endif +ifneq ($(strip $(C++_DEPS)),) +-include $(C++_DEPS) +endif +ifneq ($(strip $(C_UPPER_DEPS)),) +-include $(C_UPPER_DEPS) +endif +ifneq ($(strip $(CXX_DEPS)),) +-include $(CXX_DEPS) +endif +ifneq ($(strip $(C_DEPS)),) +-include $(C_DEPS) +endif +ifneq ($(strip $(CPP_DEPS)),) +-include $(CPP_DEPS) +endif +endif + +-include ../makefile.defs + +# Add inputs and outputs from these tool invocations to the build variables +EXECUTABLES += \ +otto_controller_source.elf \ + +SIZE_OUTPUT += \ +default.size.stdout \ + +OBJDUMP_LIST += \ +otto_controller_source.list \ + + +# All Target +all: otto_controller_source.elf secondary-outputs + +# Tool invocations +otto_controller_source.elf: $(OBJS) $(USER_OBJS) /home/fdila/Projects/otto/otto_controller_source/STM32F767ZITX_FLASH.ld + arm-none-eabi-g++ -o "otto_controller_source.elf" @"objects.list" $(USER_OBJS) $(LIBS) -mcpu=cortex-m7 -T"/home/fdila/Projects/otto/otto_controller_source/STM32F767ZITX_FLASH.ld" -Wl,-Map="otto_controller_source.map" -Wl,--gc-sections -static --specs=nano.specs -mfpu=fpv5-d16 -mfloat-abi=hard -mthumb -Wl,--start-group -lc -lm -lstdc++ -lsupc++ -Wl,--end-group + @echo 'Finished building target: $@' + @echo ' ' + +default.size.stdout: $(EXECUTABLES) + arm-none-eabi-size $(EXECUTABLES) + @echo 'Finished building: $@' + @echo ' ' + +otto_controller_source.list: $(EXECUTABLES) + arm-none-eabi-objdump -h -S $(EXECUTABLES) > "otto_controller_source.list" + @echo 'Finished building: $@' + @echo ' ' + +# Other Targets +clean: + -$(RM) * + -@echo ' ' + +secondary-outputs: $(SIZE_OUTPUT) $(OBJDUMP_LIST) + +.PHONY: all clean dependents +.SECONDARY: + +-include ../makefile.targets diff --git a/otto_controller_source/Debug/objects.list b/otto_controller_source/Debug/objects.list new file mode 100644 index 0000000..c7c9831 --- /dev/null +++ b/otto_controller_source/Debug/objects.list @@ -0,0 +1,26 @@ +"Core/Src/encoder.o" +"Core/Src/main.o" +"Core/Src/stm32f7xx_hal_msp.o" +"Core/Src/stm32f7xx_it.o" +"Core/Src/syscalls.o" +"Core/Src/sysmem.o" +"Core/Src/system_stm32f7xx.o" +"Core/Startup/startup_stm32f767zitx.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_exti.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.o" +"Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart_ex.o" diff --git a/otto_controller_source/Debug/objects.mk b/otto_controller_source/Debug/objects.mk new file mode 100644 index 0000000..742c2da --- /dev/null +++ b/otto_controller_source/Debug/objects.mk @@ -0,0 +1,8 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +USER_OBJS := + +LIBS := + diff --git a/otto_controller_source/Debug/otto_controller_source.list b/otto_controller_source/Debug/otto_controller_source.list new file mode 100644 index 0000000..d43aa98 --- /dev/null +++ b/otto_controller_source/Debug/otto_controller_source.list @@ -0,0 +1,13320 @@ + +otto_controller_source.elf: file format elf32-littlearm + +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 00004cb4 080001f8 080001f8 000101f8 2**2 + CONTENTS, ALLOC, LOAD, READONLY, CODE + 2 .rodata 00000020 08004eac 08004eac 00014eac 2**2 + CONTENTS, ALLOC, LOAD, READONLY, DATA + 3 .ARM.extab 00000000 08004ecc 08004ecc 0002000c 2**0 + CONTENTS + 4 .ARM 00000008 08004ecc 08004ecc 00014ecc 2**2 + CONTENTS, ALLOC, LOAD, READONLY, DATA + 5 .preinit_array 00000000 08004ed4 08004ed4 0002000c 2**0 + CONTENTS, ALLOC, LOAD, DATA + 6 .init_array 00000008 08004ed4 08004ed4 00014ed4 2**2 + CONTENTS, ALLOC, LOAD, DATA + 7 .fini_array 00000004 08004edc 08004edc 00014edc 2**2 + CONTENTS, ALLOC, LOAD, DATA + 8 .data 0000000c 20000000 08004ee0 00020000 2**2 + CONTENTS, ALLOC, LOAD, DATA + 9 .bss 00000320 2000000c 08004eec 0002000c 2**2 + ALLOC + 10 ._user_heap_stack 00000604 2000032c 08004eec 0002032c 2**0 + ALLOC + 11 .ARM.attributes 0000002e 00000000 00000000 0002000c 2**0 + CONTENTS, READONLY + 12 .debug_info 0000d5c4 00000000 00000000 0002003a 2**0 + CONTENTS, READONLY, DEBUGGING + 13 .debug_abbrev 00001d88 00000000 00000000 0002d5fe 2**0 + CONTENTS, READONLY, DEBUGGING + 14 .debug_aranges 00000d18 00000000 00000000 0002f388 2**3 + CONTENTS, READONLY, DEBUGGING + 15 .debug_ranges 00000c30 00000000 00000000 000300a0 2**3 + CONTENTS, READONLY, DEBUGGING + 16 .debug_macro 000281e7 00000000 00000000 00030cd0 2**0 + CONTENTS, READONLY, DEBUGGING + 17 .debug_line 00009871 00000000 00000000 00058eb7 2**0 + CONTENTS, READONLY, DEBUGGING + 18 .debug_str 000f1986 00000000 00000000 00062728 2**0 + CONTENTS, READONLY, DEBUGGING + 19 .comment 0000007b 00000000 00000000 001540ae 2**0 + CONTENTS, READONLY + 20 .debug_frame 000036e4 00000000 00000000 0015412c 2**2 + CONTENTS, READONLY, DEBUGGING + +Disassembly of section .text: + +080001f8 <__do_global_dtors_aux>: + 80001f8: b510 push {r4, lr} + 80001fa: 4c05 ldr r4, [pc, #20] ; (8000210 <__do_global_dtors_aux+0x18>) + 80001fc: 7823 ldrb r3, [r4, #0] + 80001fe: b933 cbnz r3, 800020e <__do_global_dtors_aux+0x16> + 8000200: 4b04 ldr r3, [pc, #16] ; (8000214 <__do_global_dtors_aux+0x1c>) + 8000202: b113 cbz r3, 800020a <__do_global_dtors_aux+0x12> + 8000204: 4804 ldr r0, [pc, #16] ; (8000218 <__do_global_dtors_aux+0x20>) + 8000206: f3af 8000 nop.w + 800020a: 2301 movs r3, #1 + 800020c: 7023 strb r3, [r4, #0] + 800020e: bd10 pop {r4, pc} + 8000210: 2000000c .word 0x2000000c + 8000214: 00000000 .word 0x00000000 + 8000218: 08004e94 .word 0x08004e94 + +0800021c : + 800021c: b508 push {r3, lr} + 800021e: 4b03 ldr r3, [pc, #12] ; (800022c ) + 8000220: b11b cbz r3, 800022a + 8000222: 4903 ldr r1, [pc, #12] ; (8000230 ) + 8000224: 4803 ldr r0, [pc, #12] ; (8000234 ) + 8000226: f3af 8000 nop.w + 800022a: bd08 pop {r3, pc} + 800022c: 00000000 .word 0x00000000 + 8000230: 20000010 .word 0x20000010 + 8000234: 08004e94 .word 0x08004e94 + +08000238 <__aeabi_uldivmod>: + 8000238: b953 cbnz r3, 8000250 <__aeabi_uldivmod+0x18> + 800023a: b94a cbnz r2, 8000250 <__aeabi_uldivmod+0x18> + 800023c: 2900 cmp r1, #0 + 800023e: bf08 it eq + 8000240: 2800 cmpeq r0, #0 + 8000242: bf1c itt ne + 8000244: f04f 31ff movne.w r1, #4294967295 ; 0xffffffff + 8000248: f04f 30ff movne.w r0, #4294967295 ; 0xffffffff + 800024c: f000 b972 b.w 8000534 <__aeabi_idiv0> + 8000250: f1ad 0c08 sub.w ip, sp, #8 + 8000254: e96d ce04 strd ip, lr, [sp, #-16]! + 8000258: f000 f806 bl 8000268 <__udivmoddi4> + 800025c: f8dd e004 ldr.w lr, [sp, #4] + 8000260: e9dd 2302 ldrd r2, r3, [sp, #8] + 8000264: b004 add sp, #16 + 8000266: 4770 bx lr + +08000268 <__udivmoddi4>: + 8000268: e92d 47f0 stmdb sp!, {r4, r5, r6, r7, r8, r9, sl, lr} + 800026c: 9e08 ldr r6, [sp, #32] + 800026e: 4604 mov r4, r0 + 8000270: 4688 mov r8, r1 + 8000272: 2b00 cmp r3, #0 + 8000274: d14b bne.n 800030e <__udivmoddi4+0xa6> + 8000276: 428a cmp r2, r1 + 8000278: 4615 mov r5, r2 + 800027a: d967 bls.n 800034c <__udivmoddi4+0xe4> + 800027c: fab2 f282 clz r2, r2 + 8000280: b14a cbz r2, 8000296 <__udivmoddi4+0x2e> + 8000282: f1c2 0720 rsb r7, r2, #32 + 8000286: fa01 f302 lsl.w r3, r1, r2 + 800028a: fa20 f707 lsr.w r7, r0, r7 + 800028e: 4095 lsls r5, r2 + 8000290: ea47 0803 orr.w r8, r7, r3 + 8000294: 4094 lsls r4, r2 + 8000296: ea4f 4e15 mov.w lr, r5, lsr #16 + 800029a: 0c23 lsrs r3, r4, #16 + 800029c: fbb8 f7fe udiv r7, r8, lr + 80002a0: fa1f fc85 uxth.w ip, r5 + 80002a4: fb0e 8817 mls r8, lr, r7, r8 + 80002a8: ea43 4308 orr.w r3, r3, r8, lsl #16 + 80002ac: fb07 f10c mul.w r1, r7, ip + 80002b0: 4299 cmp r1, r3 + 80002b2: d909 bls.n 80002c8 <__udivmoddi4+0x60> + 80002b4: 18eb adds r3, r5, r3 + 80002b6: f107 30ff add.w r0, r7, #4294967295 ; 0xffffffff + 80002ba: f080 811b bcs.w 80004f4 <__udivmoddi4+0x28c> + 80002be: 4299 cmp r1, r3 + 80002c0: f240 8118 bls.w 80004f4 <__udivmoddi4+0x28c> + 80002c4: 3f02 subs r7, #2 + 80002c6: 442b add r3, r5 + 80002c8: 1a5b subs r3, r3, r1 + 80002ca: b2a4 uxth r4, r4 + 80002cc: fbb3 f0fe udiv r0, r3, lr + 80002d0: fb0e 3310 mls r3, lr, r0, r3 + 80002d4: ea44 4403 orr.w r4, r4, r3, lsl #16 + 80002d8: fb00 fc0c mul.w ip, r0, ip + 80002dc: 45a4 cmp ip, r4 + 80002de: d909 bls.n 80002f4 <__udivmoddi4+0x8c> + 80002e0: 192c adds r4, r5, r4 + 80002e2: f100 33ff add.w r3, r0, #4294967295 ; 0xffffffff + 80002e6: f080 8107 bcs.w 80004f8 <__udivmoddi4+0x290> + 80002ea: 45a4 cmp ip, r4 + 80002ec: f240 8104 bls.w 80004f8 <__udivmoddi4+0x290> + 80002f0: 3802 subs r0, #2 + 80002f2: 442c add r4, r5 + 80002f4: ea40 4007 orr.w r0, r0, r7, lsl #16 + 80002f8: eba4 040c sub.w r4, r4, ip + 80002fc: 2700 movs r7, #0 + 80002fe: b11e cbz r6, 8000308 <__udivmoddi4+0xa0> + 8000300: 40d4 lsrs r4, r2 + 8000302: 2300 movs r3, #0 + 8000304: e9c6 4300 strd r4, r3, [r6] + 8000308: 4639 mov r1, r7 + 800030a: e8bd 87f0 ldmia.w sp!, {r4, r5, r6, r7, r8, r9, sl, pc} + 800030e: 428b cmp r3, r1 + 8000310: d909 bls.n 8000326 <__udivmoddi4+0xbe> + 8000312: 2e00 cmp r6, #0 + 8000314: f000 80eb beq.w 80004ee <__udivmoddi4+0x286> + 8000318: 2700 movs r7, #0 + 800031a: e9c6 0100 strd r0, r1, [r6] + 800031e: 4638 mov r0, r7 + 8000320: 4639 mov r1, r7 + 8000322: e8bd 87f0 ldmia.w sp!, {r4, r5, r6, r7, r8, r9, sl, pc} + 8000326: fab3 f783 clz r7, r3 + 800032a: 2f00 cmp r7, #0 + 800032c: d147 bne.n 80003be <__udivmoddi4+0x156> + 800032e: 428b cmp r3, r1 + 8000330: d302 bcc.n 8000338 <__udivmoddi4+0xd0> + 8000332: 4282 cmp r2, r0 + 8000334: f200 80fa bhi.w 800052c <__udivmoddi4+0x2c4> + 8000338: 1a84 subs r4, r0, r2 + 800033a: eb61 0303 sbc.w r3, r1, r3 + 800033e: 2001 movs r0, #1 + 8000340: 4698 mov r8, r3 + 8000342: 2e00 cmp r6, #0 + 8000344: d0e0 beq.n 8000308 <__udivmoddi4+0xa0> + 8000346: e9c6 4800 strd r4, r8, [r6] + 800034a: e7dd b.n 8000308 <__udivmoddi4+0xa0> + 800034c: b902 cbnz r2, 8000350 <__udivmoddi4+0xe8> + 800034e: deff udf #255 ; 0xff + 8000350: fab2 f282 clz r2, r2 + 8000354: 2a00 cmp r2, #0 + 8000356: f040 808f bne.w 8000478 <__udivmoddi4+0x210> + 800035a: 1b49 subs r1, r1, r5 + 800035c: ea4f 4e15 mov.w lr, r5, lsr #16 + 8000360: fa1f f885 uxth.w r8, r5 + 8000364: 2701 movs r7, #1 + 8000366: fbb1 fcfe udiv ip, r1, lr + 800036a: 0c23 lsrs r3, r4, #16 + 800036c: fb0e 111c mls r1, lr, ip, r1 + 8000370: ea43 4301 orr.w r3, r3, r1, lsl #16 + 8000374: fb08 f10c mul.w r1, r8, ip + 8000378: 4299 cmp r1, r3 + 800037a: d907 bls.n 800038c <__udivmoddi4+0x124> + 800037c: 18eb adds r3, r5, r3 + 800037e: f10c 30ff add.w r0, ip, #4294967295 ; 0xffffffff + 8000382: d202 bcs.n 800038a <__udivmoddi4+0x122> + 8000384: 4299 cmp r1, r3 + 8000386: f200 80cd bhi.w 8000524 <__udivmoddi4+0x2bc> + 800038a: 4684 mov ip, r0 + 800038c: 1a59 subs r1, r3, r1 + 800038e: b2a3 uxth r3, r4 + 8000390: fbb1 f0fe udiv r0, r1, lr + 8000394: fb0e 1410 mls r4, lr, r0, r1 + 8000398: ea43 4404 orr.w r4, r3, r4, lsl #16 + 800039c: fb08 f800 mul.w r8, r8, r0 + 80003a0: 45a0 cmp r8, r4 + 80003a2: d907 bls.n 80003b4 <__udivmoddi4+0x14c> + 80003a4: 192c adds r4, r5, r4 + 80003a6: f100 33ff add.w r3, r0, #4294967295 ; 0xffffffff + 80003aa: d202 bcs.n 80003b2 <__udivmoddi4+0x14a> + 80003ac: 45a0 cmp r8, r4 + 80003ae: f200 80b6 bhi.w 800051e <__udivmoddi4+0x2b6> + 80003b2: 4618 mov r0, r3 + 80003b4: eba4 0408 sub.w r4, r4, r8 + 80003b8: ea40 400c orr.w r0, r0, ip, lsl #16 + 80003bc: e79f b.n 80002fe <__udivmoddi4+0x96> + 80003be: f1c7 0c20 rsb ip, r7, #32 + 80003c2: 40bb lsls r3, r7 + 80003c4: fa22 fe0c lsr.w lr, r2, ip + 80003c8: ea4e 0e03 orr.w lr, lr, r3 + 80003cc: fa01 f407 lsl.w r4, r1, r7 + 80003d0: fa20 f50c lsr.w r5, r0, ip + 80003d4: fa21 f30c lsr.w r3, r1, ip + 80003d8: ea4f 481e mov.w r8, lr, lsr #16 + 80003dc: 4325 orrs r5, r4 + 80003de: fbb3 f9f8 udiv r9, r3, r8 + 80003e2: 0c2c lsrs r4, r5, #16 + 80003e4: fb08 3319 mls r3, r8, r9, r3 + 80003e8: fa1f fa8e uxth.w sl, lr + 80003ec: ea44 4303 orr.w r3, r4, r3, lsl #16 + 80003f0: fb09 f40a mul.w r4, r9, sl + 80003f4: 429c cmp r4, r3 + 80003f6: fa02 f207 lsl.w r2, r2, r7 + 80003fa: fa00 f107 lsl.w r1, r0, r7 + 80003fe: d90b bls.n 8000418 <__udivmoddi4+0x1b0> + 8000400: eb1e 0303 adds.w r3, lr, r3 + 8000404: f109 30ff add.w r0, r9, #4294967295 ; 0xffffffff + 8000408: f080 8087 bcs.w 800051a <__udivmoddi4+0x2b2> + 800040c: 429c cmp r4, r3 + 800040e: f240 8084 bls.w 800051a <__udivmoddi4+0x2b2> + 8000412: f1a9 0902 sub.w r9, r9, #2 + 8000416: 4473 add r3, lr + 8000418: 1b1b subs r3, r3, r4 + 800041a: b2ad uxth r5, r5 + 800041c: fbb3 f0f8 udiv r0, r3, r8 + 8000420: fb08 3310 mls r3, r8, r0, r3 + 8000424: ea45 4403 orr.w r4, r5, r3, lsl #16 + 8000428: fb00 fa0a mul.w sl, r0, sl + 800042c: 45a2 cmp sl, r4 + 800042e: d908 bls.n 8000442 <__udivmoddi4+0x1da> + 8000430: eb1e 0404 adds.w r4, lr, r4 + 8000434: f100 33ff add.w r3, r0, #4294967295 ; 0xffffffff + 8000438: d26b bcs.n 8000512 <__udivmoddi4+0x2aa> + 800043a: 45a2 cmp sl, r4 + 800043c: d969 bls.n 8000512 <__udivmoddi4+0x2aa> + 800043e: 3802 subs r0, #2 + 8000440: 4474 add r4, lr + 8000442: ea40 4009 orr.w r0, r0, r9, lsl #16 + 8000446: fba0 8902 umull r8, r9, r0, r2 + 800044a: eba4 040a sub.w r4, r4, sl + 800044e: 454c cmp r4, r9 + 8000450: 46c2 mov sl, r8 + 8000452: 464b mov r3, r9 + 8000454: d354 bcc.n 8000500 <__udivmoddi4+0x298> + 8000456: d051 beq.n 80004fc <__udivmoddi4+0x294> + 8000458: 2e00 cmp r6, #0 + 800045a: d069 beq.n 8000530 <__udivmoddi4+0x2c8> + 800045c: ebb1 050a subs.w r5, r1, sl + 8000460: eb64 0403 sbc.w r4, r4, r3 + 8000464: fa04 fc0c lsl.w ip, r4, ip + 8000468: 40fd lsrs r5, r7 + 800046a: 40fc lsrs r4, r7 + 800046c: ea4c 0505 orr.w r5, ip, r5 + 8000470: e9c6 5400 strd r5, r4, [r6] + 8000474: 2700 movs r7, #0 + 8000476: e747 b.n 8000308 <__udivmoddi4+0xa0> + 8000478: f1c2 0320 rsb r3, r2, #32 + 800047c: fa20 f703 lsr.w r7, r0, r3 + 8000480: 4095 lsls r5, r2 + 8000482: fa01 f002 lsl.w r0, r1, r2 + 8000486: fa21 f303 lsr.w r3, r1, r3 + 800048a: ea4f 4e15 mov.w lr, r5, lsr #16 + 800048e: 4338 orrs r0, r7 + 8000490: 0c01 lsrs r1, r0, #16 + 8000492: fbb3 f7fe udiv r7, r3, lr + 8000496: fa1f f885 uxth.w r8, r5 + 800049a: fb0e 3317 mls r3, lr, r7, r3 + 800049e: ea41 4103 orr.w r1, r1, r3, lsl #16 + 80004a2: fb07 f308 mul.w r3, r7, r8 + 80004a6: 428b cmp r3, r1 + 80004a8: fa04 f402 lsl.w r4, r4, r2 + 80004ac: d907 bls.n 80004be <__udivmoddi4+0x256> + 80004ae: 1869 adds r1, r5, r1 + 80004b0: f107 3cff add.w ip, r7, #4294967295 ; 0xffffffff + 80004b4: d22f bcs.n 8000516 <__udivmoddi4+0x2ae> + 80004b6: 428b cmp r3, r1 + 80004b8: d92d bls.n 8000516 <__udivmoddi4+0x2ae> + 80004ba: 3f02 subs r7, #2 + 80004bc: 4429 add r1, r5 + 80004be: 1acb subs r3, r1, r3 + 80004c0: b281 uxth r1, r0 + 80004c2: fbb3 f0fe udiv r0, r3, lr + 80004c6: fb0e 3310 mls r3, lr, r0, r3 + 80004ca: ea41 4103 orr.w r1, r1, r3, lsl #16 + 80004ce: fb00 f308 mul.w r3, r0, r8 + 80004d2: 428b cmp r3, r1 + 80004d4: d907 bls.n 80004e6 <__udivmoddi4+0x27e> + 80004d6: 1869 adds r1, r5, r1 + 80004d8: f100 3cff add.w ip, r0, #4294967295 ; 0xffffffff + 80004dc: d217 bcs.n 800050e <__udivmoddi4+0x2a6> + 80004de: 428b cmp r3, r1 + 80004e0: d915 bls.n 800050e <__udivmoddi4+0x2a6> + 80004e2: 3802 subs r0, #2 + 80004e4: 4429 add r1, r5 + 80004e6: 1ac9 subs r1, r1, r3 + 80004e8: ea40 4707 orr.w r7, r0, r7, lsl #16 + 80004ec: e73b b.n 8000366 <__udivmoddi4+0xfe> + 80004ee: 4637 mov r7, r6 + 80004f0: 4630 mov r0, r6 + 80004f2: e709 b.n 8000308 <__udivmoddi4+0xa0> + 80004f4: 4607 mov r7, r0 + 80004f6: e6e7 b.n 80002c8 <__udivmoddi4+0x60> + 80004f8: 4618 mov r0, r3 + 80004fa: e6fb b.n 80002f4 <__udivmoddi4+0x8c> + 80004fc: 4541 cmp r1, r8 + 80004fe: d2ab bcs.n 8000458 <__udivmoddi4+0x1f0> + 8000500: ebb8 0a02 subs.w sl, r8, r2 + 8000504: eb69 020e sbc.w r2, r9, lr + 8000508: 3801 subs r0, #1 + 800050a: 4613 mov r3, r2 + 800050c: e7a4 b.n 8000458 <__udivmoddi4+0x1f0> + 800050e: 4660 mov r0, ip + 8000510: e7e9 b.n 80004e6 <__udivmoddi4+0x27e> + 8000512: 4618 mov r0, r3 + 8000514: e795 b.n 8000442 <__udivmoddi4+0x1da> + 8000516: 4667 mov r7, ip + 8000518: e7d1 b.n 80004be <__udivmoddi4+0x256> + 800051a: 4681 mov r9, r0 + 800051c: e77c b.n 8000418 <__udivmoddi4+0x1b0> + 800051e: 3802 subs r0, #2 + 8000520: 442c add r4, r5 + 8000522: e747 b.n 80003b4 <__udivmoddi4+0x14c> + 8000524: f1ac 0c02 sub.w ip, ip, #2 + 8000528: 442b add r3, r5 + 800052a: e72f b.n 800038c <__udivmoddi4+0x124> + 800052c: 4638 mov r0, r7 + 800052e: e708 b.n 8000342 <__udivmoddi4+0xda> + 8000530: 4637 mov r7, r6 + 8000532: e6e9 b.n 8000308 <__udivmoddi4+0xa0> + +08000534 <__aeabi_idiv0>: + 8000534: 4770 bx lr + 8000536: bf00 nop + +08000538 <_ZN7Encoder10ResetCountEv>: + int count = ((int)__HAL_TIM_GET_COUNTER(this->timer_) - + ((this->timer_->Init.Period)/2)); + return count; + } + + void ResetCount() { + 8000538: b480 push {r7} + 800053a: b083 sub sp, #12 + 800053c: af00 add r7, sp, #0 + 800053e: 6078 str r0, [r7, #4] + //set counter to half its maximum value + __HAL_TIM_SET_COUNTER(timer_, (timer_->Init.Period)/2); + 8000540: 687b ldr r3, [r7, #4] + 8000542: 681b ldr r3, [r3, #0] + 8000544: 68da ldr r2, [r3, #12] + 8000546: 687b ldr r3, [r7, #4] + 8000548: 681b ldr r3, [r3, #0] + 800054a: 681b ldr r3, [r3, #0] + 800054c: 0852 lsrs r2, r2, #1 + 800054e: 625a str r2, [r3, #36] ; 0x24 + } + 8000550: bf00 nop + 8000552: 370c adds r7, #12 + 8000554: 46bd mov sp, r7 + 8000556: f85d 7b04 ldr.w r7, [sp], #4 + 800055a: 4770 bx lr + +0800055c <_ZN7EncoderC1EP17TIM_HandleTypeDef>: +#include "encoder.h" + +Encoder::Encoder(TIM_HandleTypeDef* timer) { + 800055c: b480 push {r7} + 800055e: b083 sub sp, #12 + 8000560: af00 add r7, sp, #0 + 8000562: 6078 str r0, [r7, #4] + 8000564: 6039 str r1, [r7, #0] + 8000566: 687b ldr r3, [r7, #4] + 8000568: 4a08 ldr r2, [pc, #32] ; (800058c <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x30>) + 800056a: 611a str r2, [r3, #16] + 800056c: 687b ldr r3, [r7, #4] + 800056e: 4a08 ldr r2, [pc, #32] ; (8000590 <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x34>) + 8000570: 615a str r2, [r3, #20] + 8000572: 687b ldr r3, [r7, #4] + 8000574: 4a07 ldr r2, [pc, #28] ; (8000594 <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x38>) + 8000576: 619a str r2, [r3, #24] + timer_ = timer; + 8000578: 687b ldr r3, [r7, #4] + 800057a: 683a ldr r2, [r7, #0] + 800057c: 601a str r2, [r3, #0] +} + 800057e: 687b ldr r3, [r7, #4] + 8000580: 4618 mov r0, r3 + 8000582: 370c adds r7, #12 + 8000584: 46bd mov sp, r7 + 8000586: f85d 7b04 ldr.w r7, [sp], #4 + 800058a: 4770 bx lr + 800058c: 00012110 .word 0x00012110 + 8000590: 40490fd0 .word 0x40490fd0 + 8000594: 3f40ff97 .word 0x3f40ff97 + +08000598 <_ZN7Encoder5SetupEv>: + +void Encoder::Setup() { + 8000598: b580 push {r7, lr} + 800059a: b082 sub sp, #8 + 800059c: af00 add r7, sp, #0 + 800059e: 6078 str r0, [r7, #4] + HAL_TIM_Encoder_Start(timer_, TIM_CHANNEL_ALL); + 80005a0: 687b ldr r3, [r7, #4] + 80005a2: 681b ldr r3, [r3, #0] + 80005a4: 213c movs r1, #60 ; 0x3c + 80005a6: 4618 mov r0, r3 + 80005a8: f002 ff36 bl 8003418 + this->ResetCount(); + 80005ac: 6878 ldr r0, [r7, #4] + 80005ae: f7ff ffc3 bl 8000538 <_ZN7Encoder10ResetCountEv> + this->previous_millis_ = 0; + 80005b2: 687b ldr r3, [r7, #4] + 80005b4: 2200 movs r2, #0 + 80005b6: 605a str r2, [r3, #4] + this->current_millis_ = HAL_GetTick(); + 80005b8: f000 ff7a bl 80014b0 + 80005bc: 4602 mov r2, r0 + 80005be: 687b ldr r3, [r7, #4] + 80005c0: 609a str r2, [r3, #8] +} + 80005c2: bf00 nop + 80005c4: 3708 adds r7, #8 + 80005c6: 46bd mov sp, r7 + 80005c8: bd80 pop {r7, pc} + ... + +080005cc <_ZN7EncoderC1Ev>: + Encoder(){ + 80005cc: b480 push {r7} + 80005ce: b083 sub sp, #12 + 80005d0: af00 add r7, sp, #0 + 80005d2: 6078 str r0, [r7, #4] + 80005d4: 687b ldr r3, [r7, #4] + 80005d6: 4a09 ldr r2, [pc, #36] ; (80005fc <_ZN7EncoderC1Ev+0x30>) + 80005d8: 611a str r2, [r3, #16] + 80005da: 687b ldr r3, [r7, #4] + 80005dc: 4a08 ldr r2, [pc, #32] ; (8000600 <_ZN7EncoderC1Ev+0x34>) + 80005de: 615a str r2, [r3, #20] + 80005e0: 687b ldr r3, [r7, #4] + 80005e2: 4a08 ldr r2, [pc, #32] ; (8000604 <_ZN7EncoderC1Ev+0x38>) + 80005e4: 619a str r2, [r3, #24] + timer_ = NULL; + 80005e6: 687b ldr r3, [r7, #4] + 80005e8: 2200 movs r2, #0 + 80005ea: 601a str r2, [r3, #0] + } + 80005ec: 687b ldr r3, [r7, #4] + 80005ee: 4618 mov r0, r3 + 80005f0: 370c adds r7, #12 + 80005f2: 46bd mov sp, r7 + 80005f4: f85d 7b04 ldr.w r7, [sp], #4 + 80005f8: 4770 bx lr + 80005fa: bf00 nop + 80005fc: 00012110 .word 0x00012110 + 8000600: 40490fd0 .word 0x40490fd0 + 8000604: 3f40ff97 .word 0x3f40ff97 + +08000608 <_ZN8OdometryC1E7EncoderS0_>: + left_encoder_ = NULL; + right_encoder_ = NULL; + kBaseline = 0.35; //in meters + } + + Odometry(Encoder left, Encoder right) { + 8000608: b084 sub sp, #16 + 800060a: b5b0 push {r4, r5, r7, lr} + 800060c: b082 sub sp, #8 + 800060e: af00 add r7, sp, #0 + 8000610: 6078 str r0, [r7, #4] + 8000612: f107 001c add.w r0, r7, #28 + 8000616: e880 000e stmia.w r0, {r1, r2, r3} + 800061a: 687b ldr r3, [r7, #4] + 800061c: 4618 mov r0, r3 + 800061e: f7ff ffd5 bl 80005cc <_ZN7EncoderC1Ev> + 8000622: 687b ldr r3, [r7, #4] + 8000624: 331c adds r3, #28 + 8000626: 4618 mov r0, r3 + 8000628: f7ff ffd0 bl 80005cc <_ZN7EncoderC1Ev> + + left_encoder_ = left; + 800062c: 687b ldr r3, [r7, #4] + 800062e: 461d mov r5, r3 + 8000630: f107 041c add.w r4, r7, #28 + 8000634: cc0f ldmia r4!, {r0, r1, r2, r3} + 8000636: c50f stmia r5!, {r0, r1, r2, r3} + 8000638: e894 0007 ldmia.w r4, {r0, r1, r2} + 800063c: e885 0007 stmia.w r5, {r0, r1, r2} + right_encoder_ = right; + 8000640: 687b ldr r3, [r7, #4] + 8000642: f103 041c add.w r4, r3, #28 + 8000646: f107 0538 add.w r5, r7, #56 ; 0x38 + 800064a: cd0f ldmia r5!, {r0, r1, r2, r3} + 800064c: c40f stmia r4!, {r0, r1, r2, r3} + 800064e: e895 0007 ldmia.w r5, {r0, r1, r2} + 8000652: e884 0007 stmia.w r4, {r0, r1, r2} + kBaseline = 0.35; //in meters + 8000656: 687b ldr r3, [r7, #4] + 8000658: 4a04 ldr r2, [pc, #16] ; (800066c <_ZN8OdometryC1E7EncoderS0_+0x64>) + 800065a: 639a str r2, [r3, #56] ; 0x38 + } + 800065c: 687b ldr r3, [r7, #4] + 800065e: 4618 mov r0, r3 + 8000660: 3708 adds r7, #8 + 8000662: 46bd mov sp, r7 + 8000664: e8bd 40b0 ldmia.w sp!, {r4, r5, r7, lr} + 8000668: b004 add sp, #16 + 800066a: 4770 bx lr + 800066c: 3eb33333 .word 0x3eb33333 + +08000670
: + +/** + * @brief The application entry point. + * @retval int + */ +int main(void) { + 8000670: b580 push {r7, lr} + 8000672: af00 add r7, sp, #0 + /* USER CODE END 1 */ + + /* MCU Configuration--------------------------------------------------------*/ + + /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ + HAL_Init(); + 8000674: f000 fecb bl 800140e + /* USER CODE BEGIN Init */ + + /* USER CODE END Init */ + + /* Configure the system clock */ + SystemClock_Config(); + 8000678: f000 f83c bl 80006f4 <_Z18SystemClock_Configv> + /* USER CODE BEGIN SysInit */ + + /* USER CODE END SysInit */ + + /* Initialize all configured peripherals */ + MX_GPIO_Init(); + 800067c: f000 fb1c bl 8000cb8 <_ZL12MX_GPIO_Initv> + MX_DMA_Init(); + 8000680: f000 faf4 bl 8000c6c <_ZL11MX_DMA_Initv> + MX_TIM2_Init(); + 8000684: f000 f8c0 bl 8000808 <_ZL12MX_TIM2_Initv> + MX_TIM3_Init(); + 8000688: f000 f91c bl 80008c4 <_ZL12MX_TIM3_Initv> + MX_TIM4_Init(); + 800068c: f000 f978 bl 8000980 <_ZL12MX_TIM4_Initv> + MX_TIM5_Init(); + 8000690: f000 fa16 bl 8000ac0 <_ZL12MX_TIM5_Initv> + MX_USART6_UART_Init(); + 8000694: f000 fab6 bl 8000c04 <_ZL19MX_USART6_UART_Initv> + MX_TIM6_Init(); + 8000698: f000 fa72 bl 8000b80 <_ZL12MX_TIM6_Initv> + /* USER CODE BEGIN 2 */ + + left_encoder.Setup(); + 800069c: 4810 ldr r0, [pc, #64] ; (80006e0 ) + 800069e: f7ff ff7b bl 8000598 <_ZN7Encoder5SetupEv> + right_encoder.Setup(); + 80006a2: 4810 ldr r0, [pc, #64] ; (80006e4 ) + 80006a4: f7ff ff78 bl 8000598 <_ZN7Encoder5SetupEv> + + HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_4); + 80006a8: 210c movs r1, #12 + 80006aa: 480f ldr r0, [pc, #60] ; (80006e8 ) + 80006ac: f002 fdde bl 800326c + HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_3); + 80006b0: 2108 movs r1, #8 + 80006b2: 480d ldr r0, [pc, #52] ; (80006e8 ) + 80006b4: f002 fdda bl 800326c + + HAL_GPIO_WritePin(dir1_GPIO_Port, dir1_Pin, GPIO_PIN_SET); + 80006b8: 2201 movs r2, #1 + 80006ba: f44f 5100 mov.w r1, #8192 ; 0x2000 + 80006be: 480b ldr r0, [pc, #44] ; (80006ec ) + 80006c0: f001 fcc8 bl 8002054 + + __HAL_TIM_SET_COMPARE(&htim4, TIM_CHANNEL_4, 790); + 80006c4: 4b08 ldr r3, [pc, #32] ; (80006e8 ) + 80006c6: 681b ldr r3, [r3, #0] + 80006c8: f240 3216 movw r2, #790 ; 0x316 + 80006cc: 641a str r2, [r3, #64] ; 0x40 + __HAL_TIM_SET_COMPARE(&htim4, TIM_CHANNEL_3, 750); + 80006ce: 4b06 ldr r3, [pc, #24] ; (80006e8 ) + 80006d0: 681b ldr r3, [r3, #0] + 80006d2: f240 22ee movw r2, #750 ; 0x2ee + 80006d6: 63da str r2, [r3, #60] ; 0x3c + + HAL_TIM_Base_Start_IT(&htim3); + 80006d8: 4805 ldr r0, [pc, #20] ; (80006f0 ) + 80006da: f002 fd67 bl 80031ac + + /* USER CODE END 2 */ + + /* Infinite loop */ + /* USER CODE BEGIN WHILE */ + while (1) { + 80006de: e7fe b.n 80006de + 80006e0: 200002a8 .word 0x200002a8 + 80006e4: 200002c4 .word 0x200002c4 + 80006e8: 200000a8 .word 0x200000a8 + 80006ec: 40021400 .word 0x40021400 + 80006f0: 20000068 .word 0x20000068 + +080006f4 <_Z18SystemClock_Configv>: + +/** + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) { + 80006f4: b580 push {r7, lr} + 80006f6: b0b8 sub sp, #224 ; 0xe0 + 80006f8: af00 add r7, sp, #0 + RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; + 80006fa: f107 03ac add.w r3, r7, #172 ; 0xac + 80006fe: 2234 movs r2, #52 ; 0x34 + 8000700: 2100 movs r1, #0 + 8000702: 4618 mov r0, r3 + 8000704: f004 fbbe bl 8004e84 + RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; + 8000708: f107 0398 add.w r3, r7, #152 ; 0x98 + 800070c: 2200 movs r2, #0 + 800070e: 601a str r2, [r3, #0] + 8000710: 605a str r2, [r3, #4] + 8000712: 609a str r2, [r3, #8] + 8000714: 60da str r2, [r3, #12] + 8000716: 611a str r2, [r3, #16] + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; + 8000718: f107 0308 add.w r3, r7, #8 + 800071c: 2290 movs r2, #144 ; 0x90 + 800071e: 2100 movs r1, #0 + 8000720: 4618 mov r0, r3 + 8000722: f004 fbaf bl 8004e84 + + /** Configure the main internal regulator output voltage + */ + __HAL_RCC_PWR_CLK_ENABLE(); + 8000726: 4b36 ldr r3, [pc, #216] ; (8000800 <_Z18SystemClock_Configv+0x10c>) + 8000728: 6c1b ldr r3, [r3, #64] ; 0x40 + 800072a: 4a35 ldr r2, [pc, #212] ; (8000800 <_Z18SystemClock_Configv+0x10c>) + 800072c: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8000730: 6413 str r3, [r2, #64] ; 0x40 + 8000732: 4b33 ldr r3, [pc, #204] ; (8000800 <_Z18SystemClock_Configv+0x10c>) + 8000734: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000736: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 800073a: 607b str r3, [r7, #4] + 800073c: 687b ldr r3, [r7, #4] + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); + 800073e: 4b31 ldr r3, [pc, #196] ; (8000804 <_Z18SystemClock_Configv+0x110>) + 8000740: 681b ldr r3, [r3, #0] + 8000742: f423 4340 bic.w r3, r3, #49152 ; 0xc000 + 8000746: 4a2f ldr r2, [pc, #188] ; (8000804 <_Z18SystemClock_Configv+0x110>) + 8000748: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 800074c: 6013 str r3, [r2, #0] + 800074e: 4b2d ldr r3, [pc, #180] ; (8000804 <_Z18SystemClock_Configv+0x110>) + 8000750: 681b ldr r3, [r3, #0] + 8000752: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8000756: 603b str r3, [r7, #0] + 8000758: 683b ldr r3, [r7, #0] + /** Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; + 800075a: 2302 movs r3, #2 + 800075c: f8c7 30ac str.w r3, [r7, #172] ; 0xac + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + 8000760: 2301 movs r3, #1 + 8000762: f8c7 30b8 str.w r3, [r7, #184] ; 0xb8 + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + 8000766: 2310 movs r3, #16 + 8000768: f8c7 30bc str.w r3, [r7, #188] ; 0xbc + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + 800076c: 2300 movs r3, #0 + 800076e: f8c7 30c4 str.w r3, [r7, #196] ; 0xc4 + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + 8000772: f107 03ac add.w r3, r7, #172 ; 0xac + 8000776: 4618 mov r0, r3 + 8000778: f001 fc86 bl 8002088 + 800077c: 4603 mov r3, r0 + 800077e: 2b00 cmp r3, #0 + 8000780: bf14 ite ne + 8000782: 2301 movne r3, #1 + 8000784: 2300 moveq r3, #0 + 8000786: b2db uxtb r3, r3 + 8000788: 2b00 cmp r3, #0 + 800078a: d001 beq.n 8000790 <_Z18SystemClock_Configv+0x9c> + Error_Handler(); + 800078c: f000 fb46 bl 8000e1c + } + /** Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + 8000790: 230f movs r3, #15 + 8000792: f8c7 3098 str.w r3, [r7, #152] ; 0x98 + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; + 8000796: 2300 movs r3, #0 + 8000798: f8c7 309c str.w r3, [r7, #156] ; 0x9c + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + 800079c: 2300 movs r3, #0 + 800079e: f8c7 30a0 str.w r3, [r7, #160] ; 0xa0 + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + 80007a2: 2300 movs r3, #0 + 80007a4: f8c7 30a4 str.w r3, [r7, #164] ; 0xa4 + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + 80007a8: 2300 movs r3, #0 + 80007aa: f8c7 30a8 str.w r3, [r7, #168] ; 0xa8 + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { + 80007ae: f107 0398 add.w r3, r7, #152 ; 0x98 + 80007b2: 2100 movs r1, #0 + 80007b4: 4618 mov r0, r3 + 80007b6: f001 fed9 bl 800256c + 80007ba: 4603 mov r3, r0 + 80007bc: 2b00 cmp r3, #0 + 80007be: bf14 ite ne + 80007c0: 2301 movne r3, #1 + 80007c2: 2300 moveq r3, #0 + 80007c4: b2db uxtb r3, r3 + 80007c6: 2b00 cmp r3, #0 + 80007c8: d001 beq.n 80007ce <_Z18SystemClock_Configv+0xda> + Error_Handler(); + 80007ca: f000 fb27 bl 8000e1c + } + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; + 80007ce: f44f 6300 mov.w r3, #2048 ; 0x800 + 80007d2: 60bb str r3, [r7, #8] + PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; + 80007d4: 2300 movs r3, #0 + 80007d6: 663b str r3, [r7, #96] ; 0x60 + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + 80007d8: f107 0308 add.w r3, r7, #8 + 80007dc: 4618 mov r0, r3 + 80007de: f002 f893 bl 8002908 + 80007e2: 4603 mov r3, r0 + 80007e4: 2b00 cmp r3, #0 + 80007e6: bf14 ite ne + 80007e8: 2301 movne r3, #1 + 80007ea: 2300 moveq r3, #0 + 80007ec: b2db uxtb r3, r3 + 80007ee: 2b00 cmp r3, #0 + 80007f0: d001 beq.n 80007f6 <_Z18SystemClock_Configv+0x102> + Error_Handler(); + 80007f2: f000 fb13 bl 8000e1c + } +} + 80007f6: bf00 nop + 80007f8: 37e0 adds r7, #224 ; 0xe0 + 80007fa: 46bd mov sp, r7 + 80007fc: bd80 pop {r7, pc} + 80007fe: bf00 nop + 8000800: 40023800 .word 0x40023800 + 8000804: 40007000 .word 0x40007000 + +08000808 <_ZL12MX_TIM2_Initv>: +/** + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) { + 8000808: b580 push {r7, lr} + 800080a: b08c sub sp, #48 ; 0x30 + 800080c: af00 add r7, sp, #0 + + /* USER CODE BEGIN TIM2_Init 0 */ + + /* USER CODE END TIM2_Init 0 */ + + TIM_Encoder_InitTypeDef sConfig = { 0 }; + 800080e: f107 030c add.w r3, r7, #12 + 8000812: 2224 movs r2, #36 ; 0x24 + 8000814: 2100 movs r1, #0 + 8000816: 4618 mov r0, r3 + 8000818: f004 fb34 bl 8004e84 + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 800081c: 463b mov r3, r7 + 800081e: 2200 movs r2, #0 + 8000820: 601a str r2, [r3, #0] + 8000822: 605a str r2, [r3, #4] + 8000824: 609a str r2, [r3, #8] + + /* USER CODE BEGIN TIM2_Init 1 */ + + /* USER CODE END TIM2_Init 1 */ + htim2.Instance = TIM2; + 8000826: 4b26 ldr r3, [pc, #152] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 8000828: f04f 4280 mov.w r2, #1073741824 ; 0x40000000 + 800082c: 601a str r2, [r3, #0] + htim2.Init.Prescaler = 0; + 800082e: 4b24 ldr r3, [pc, #144] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 8000830: 2200 movs r2, #0 + 8000832: 605a str r2, [r3, #4] + htim2.Init.CounterMode = TIM_COUNTERMODE_UP; + 8000834: 4b22 ldr r3, [pc, #136] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 8000836: 2200 movs r2, #0 + 8000838: 609a str r2, [r3, #8] + htim2.Init.Period = 4294967295; + 800083a: 4b21 ldr r3, [pc, #132] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 800083c: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8000840: 60da str r2, [r3, #12] + htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + 8000842: 4b1f ldr r3, [pc, #124] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 8000844: 2200 movs r2, #0 + 8000846: 611a str r2, [r3, #16] + htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + 8000848: 4b1d ldr r3, [pc, #116] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 800084a: 2200 movs r2, #0 + 800084c: 619a str r2, [r3, #24] + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + 800084e: 2303 movs r3, #3 + 8000850: 60fb str r3, [r7, #12] + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + 8000852: 2300 movs r3, #0 + 8000854: 613b str r3, [r7, #16] + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + 8000856: 2301 movs r3, #1 + 8000858: 617b str r3, [r7, #20] + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + 800085a: 2300 movs r3, #0 + 800085c: 61bb str r3, [r7, #24] + sConfig.IC1Filter = 0; + 800085e: 2300 movs r3, #0 + 8000860: 61fb str r3, [r7, #28] + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + 8000862: 2300 movs r3, #0 + 8000864: 623b str r3, [r7, #32] + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + 8000866: 2301 movs r3, #1 + 8000868: 627b str r3, [r7, #36] ; 0x24 + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + 800086a: 2300 movs r3, #0 + 800086c: 62bb str r3, [r7, #40] ; 0x28 + sConfig.IC2Filter = 0; + 800086e: 2300 movs r3, #0 + 8000870: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { + 8000872: f107 030c add.w r3, r7, #12 + 8000876: 4619 mov r1, r3 + 8000878: 4811 ldr r0, [pc, #68] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 800087a: f002 fd3b bl 80032f4 + 800087e: 4603 mov r3, r0 + 8000880: 2b00 cmp r3, #0 + 8000882: bf14 ite ne + 8000884: 2301 movne r3, #1 + 8000886: 2300 moveq r3, #0 + 8000888: b2db uxtb r3, r3 + 800088a: 2b00 cmp r3, #0 + 800088c: d001 beq.n 8000892 <_ZL12MX_TIM2_Initv+0x8a> + Error_Handler(); + 800088e: f000 fac5 bl 8000e1c + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + 8000892: 2300 movs r3, #0 + 8000894: 603b str r3, [r7, #0] + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + 8000896: 2300 movs r3, #0 + 8000898: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) + 800089a: 463b mov r3, r7 + 800089c: 4619 mov r1, r3 + 800089e: 4808 ldr r0, [pc, #32] ; (80008c0 <_ZL12MX_TIM2_Initv+0xb8>) + 80008a0: f003 fcc8 bl 8004234 + 80008a4: 4603 mov r3, r0 + != HAL_OK) { + 80008a6: 2b00 cmp r3, #0 + 80008a8: bf14 ite ne + 80008aa: 2301 movne r3, #1 + 80008ac: 2300 moveq r3, #0 + 80008ae: b2db uxtb r3, r3 + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) + 80008b0: 2b00 cmp r3, #0 + 80008b2: d001 beq.n 80008b8 <_ZL12MX_TIM2_Initv+0xb0> + Error_Handler(); + 80008b4: f000 fab2 bl 8000e1c + } + /* USER CODE BEGIN TIM2_Init 2 */ + + /* USER CODE END TIM2_Init 2 */ + +} + 80008b8: bf00 nop + 80008ba: 3730 adds r7, #48 ; 0x30 + 80008bc: 46bd mov sp, r7 + 80008be: bd80 pop {r7, pc} + 80008c0: 20000028 .word 0x20000028 + +080008c4 <_ZL12MX_TIM3_Initv>: +/** + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) { + 80008c4: b580 push {r7, lr} + 80008c6: b088 sub sp, #32 + 80008c8: af00 add r7, sp, #0 + + /* USER CODE BEGIN TIM3_Init 0 */ + + /* USER CODE END TIM3_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + 80008ca: f107 0310 add.w r3, r7, #16 + 80008ce: 2200 movs r2, #0 + 80008d0: 601a str r2, [r3, #0] + 80008d2: 605a str r2, [r3, #4] + 80008d4: 609a str r2, [r3, #8] + 80008d6: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 80008d8: 1d3b adds r3, r7, #4 + 80008da: 2200 movs r2, #0 + 80008dc: 601a str r2, [r3, #0] + 80008de: 605a str r2, [r3, #4] + 80008e0: 609a str r2, [r3, #8] + + /* USER CODE BEGIN TIM3_Init 1 */ + + /* USER CODE END TIM3_Init 1 */ + htim3.Instance = TIM3; + 80008e2: 4b25 ldr r3, [pc, #148] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 80008e4: 4a25 ldr r2, [pc, #148] ; (800097c <_ZL12MX_TIM3_Initv+0xb8>) + 80008e6: 601a str r2, [r3, #0] + htim3.Init.Prescaler = 9999; + 80008e8: 4b23 ldr r3, [pc, #140] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 80008ea: f242 720f movw r2, #9999 ; 0x270f + 80008ee: 605a str r2, [r3, #4] + htim3.Init.CounterMode = TIM_COUNTERMODE_UP; + 80008f0: 4b21 ldr r3, [pc, #132] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 80008f2: 2200 movs r2, #0 + 80008f4: 609a str r2, [r3, #8] + htim3.Init.Period = 159; + 80008f6: 4b20 ldr r3, [pc, #128] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 80008f8: 229f movs r2, #159 ; 0x9f + 80008fa: 60da str r2, [r3, #12] + htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + 80008fc: 4b1e ldr r3, [pc, #120] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 80008fe: 2200 movs r2, #0 + 8000900: 611a str r2, [r3, #16] + htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + 8000902: 4b1d ldr r3, [pc, #116] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 8000904: 2200 movs r2, #0 + 8000906: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { + 8000908: 481b ldr r0, [pc, #108] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 800090a: f002 fc23 bl 8003154 + 800090e: 4603 mov r3, r0 + 8000910: 2b00 cmp r3, #0 + 8000912: bf14 ite ne + 8000914: 2301 movne r3, #1 + 8000916: 2300 moveq r3, #0 + 8000918: b2db uxtb r3, r3 + 800091a: 2b00 cmp r3, #0 + 800091c: d001 beq.n 8000922 <_ZL12MX_TIM3_Initv+0x5e> + Error_Handler(); + 800091e: f000 fa7d bl 8000e1c + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + 8000922: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8000926: 613b str r3, [r7, #16] + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { + 8000928: f107 0310 add.w r3, r7, #16 + 800092c: 4619 mov r1, r3 + 800092e: 4812 ldr r0, [pc, #72] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 8000930: f002 ffe0 bl 80038f4 + 8000934: 4603 mov r3, r0 + 8000936: 2b00 cmp r3, #0 + 8000938: bf14 ite ne + 800093a: 2301 movne r3, #1 + 800093c: 2300 moveq r3, #0 + 800093e: b2db uxtb r3, r3 + 8000940: 2b00 cmp r3, #0 + 8000942: d001 beq.n 8000948 <_ZL12MX_TIM3_Initv+0x84> + Error_Handler(); + 8000944: f000 fa6a bl 8000e1c + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + 8000948: 2300 movs r3, #0 + 800094a: 607b str r3, [r7, #4] + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + 800094c: 2300 movs r3, #0 + 800094e: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) + 8000950: 1d3b adds r3, r7, #4 + 8000952: 4619 mov r1, r3 + 8000954: 4808 ldr r0, [pc, #32] ; (8000978 <_ZL12MX_TIM3_Initv+0xb4>) + 8000956: f003 fc6d bl 8004234 + 800095a: 4603 mov r3, r0 + != HAL_OK) { + 800095c: 2b00 cmp r3, #0 + 800095e: bf14 ite ne + 8000960: 2301 movne r3, #1 + 8000962: 2300 moveq r3, #0 + 8000964: b2db uxtb r3, r3 + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) + 8000966: 2b00 cmp r3, #0 + 8000968: d001 beq.n 800096e <_ZL12MX_TIM3_Initv+0xaa> + Error_Handler(); + 800096a: f000 fa57 bl 8000e1c + } + /* USER CODE BEGIN TIM3_Init 2 */ + + /* USER CODE END TIM3_Init 2 */ + +} + 800096e: bf00 nop + 8000970: 3720 adds r7, #32 + 8000972: 46bd mov sp, r7 + 8000974: bd80 pop {r7, pc} + 8000976: bf00 nop + 8000978: 20000068 .word 0x20000068 + 800097c: 40000400 .word 0x40000400 + +08000980 <_ZL12MX_TIM4_Initv>: +/** + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) { + 8000980: b580 push {r7, lr} + 8000982: b08e sub sp, #56 ; 0x38 + 8000984: af00 add r7, sp, #0 + + /* USER CODE BEGIN TIM4_Init 0 */ + + /* USER CODE END TIM4_Init 0 */ + + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + 8000986: f107 0328 add.w r3, r7, #40 ; 0x28 + 800098a: 2200 movs r2, #0 + 800098c: 601a str r2, [r3, #0] + 800098e: 605a str r2, [r3, #4] + 8000990: 609a str r2, [r3, #8] + 8000992: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000994: f107 031c add.w r3, r7, #28 + 8000998: 2200 movs r2, #0 + 800099a: 601a str r2, [r3, #0] + 800099c: 605a str r2, [r3, #4] + 800099e: 609a str r2, [r3, #8] + TIM_OC_InitTypeDef sConfigOC = { 0 }; + 80009a0: 463b mov r3, r7 + 80009a2: 2200 movs r2, #0 + 80009a4: 601a str r2, [r3, #0] + 80009a6: 605a str r2, [r3, #4] + 80009a8: 609a str r2, [r3, #8] + 80009aa: 60da str r2, [r3, #12] + 80009ac: 611a str r2, [r3, #16] + 80009ae: 615a str r2, [r3, #20] + 80009b0: 619a str r2, [r3, #24] + + /* USER CODE BEGIN TIM4_Init 1 */ + + /* USER CODE END TIM4_Init 1 */ + htim4.Instance = TIM4; + 80009b2: 4b41 ldr r3, [pc, #260] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009b4: 4a41 ldr r2, [pc, #260] ; (8000abc <_ZL12MX_TIM4_Initv+0x13c>) + 80009b6: 601a str r2, [r3, #0] + htim4.Init.Prescaler = 0; + 80009b8: 4b3f ldr r3, [pc, #252] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009ba: 2200 movs r2, #0 + 80009bc: 605a str r2, [r3, #4] + htim4.Init.CounterMode = TIM_COUNTERMODE_UP; + 80009be: 4b3e ldr r3, [pc, #248] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009c0: 2200 movs r2, #0 + 80009c2: 609a str r2, [r3, #8] + htim4.Init.Period = 799; + 80009c4: 4b3c ldr r3, [pc, #240] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009c6: f240 321f movw r2, #799 ; 0x31f + 80009ca: 60da str r2, [r3, #12] + htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + 80009cc: 4b3a ldr r3, [pc, #232] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009ce: 2200 movs r2, #0 + 80009d0: 611a str r2, [r3, #16] + htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + 80009d2: 4b39 ldr r3, [pc, #228] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009d4: 2200 movs r2, #0 + 80009d6: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { + 80009d8: 4837 ldr r0, [pc, #220] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 80009da: f002 fbbb bl 8003154 + 80009de: 4603 mov r3, r0 + 80009e0: 2b00 cmp r3, #0 + 80009e2: bf14 ite ne + 80009e4: 2301 movne r3, #1 + 80009e6: 2300 moveq r3, #0 + 80009e8: b2db uxtb r3, r3 + 80009ea: 2b00 cmp r3, #0 + 80009ec: d001 beq.n 80009f2 <_ZL12MX_TIM4_Initv+0x72> + Error_Handler(); + 80009ee: f000 fa15 bl 8000e1c + } + sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; + 80009f2: f44f 5380 mov.w r3, #4096 ; 0x1000 + 80009f6: 62bb str r3, [r7, #40] ; 0x28 + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { + 80009f8: f107 0328 add.w r3, r7, #40 ; 0x28 + 80009fc: 4619 mov r1, r3 + 80009fe: 482e ldr r0, [pc, #184] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000a00: f002 ff78 bl 80038f4 + 8000a04: 4603 mov r3, r0 + 8000a06: 2b00 cmp r3, #0 + 8000a08: bf14 ite ne + 8000a0a: 2301 movne r3, #1 + 8000a0c: 2300 moveq r3, #0 + 8000a0e: b2db uxtb r3, r3 + 8000a10: 2b00 cmp r3, #0 + 8000a12: d001 beq.n 8000a18 <_ZL12MX_TIM4_Initv+0x98> + Error_Handler(); + 8000a14: f000 fa02 bl 8000e1c + } + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { + 8000a18: 4827 ldr r0, [pc, #156] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000a1a: f002 fbf1 bl 8003200 + 8000a1e: 4603 mov r3, r0 + 8000a20: 2b00 cmp r3, #0 + 8000a22: bf14 ite ne + 8000a24: 2301 movne r3, #1 + 8000a26: 2300 moveq r3, #0 + 8000a28: b2db uxtb r3, r3 + 8000a2a: 2b00 cmp r3, #0 + 8000a2c: d001 beq.n 8000a32 <_ZL12MX_TIM4_Initv+0xb2> + Error_Handler(); + 8000a2e: f000 f9f5 bl 8000e1c + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + 8000a32: 2300 movs r3, #0 + 8000a34: 61fb str r3, [r7, #28] + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + 8000a36: 2300 movs r3, #0 + 8000a38: 627b str r3, [r7, #36] ; 0x24 + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) + 8000a3a: f107 031c add.w r3, r7, #28 + 8000a3e: 4619 mov r1, r3 + 8000a40: 481d ldr r0, [pc, #116] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000a42: f003 fbf7 bl 8004234 + 8000a46: 4603 mov r3, r0 + != HAL_OK) { + 8000a48: 2b00 cmp r3, #0 + 8000a4a: bf14 ite ne + 8000a4c: 2301 movne r3, #1 + 8000a4e: 2300 moveq r3, #0 + 8000a50: b2db uxtb r3, r3 + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) + 8000a52: 2b00 cmp r3, #0 + 8000a54: d001 beq.n 8000a5a <_ZL12MX_TIM4_Initv+0xda> + Error_Handler(); + 8000a56: f000 f9e1 bl 8000e1c + } + sConfigOC.OCMode = TIM_OCMODE_PWM1; + 8000a5a: 2360 movs r3, #96 ; 0x60 + 8000a5c: 603b str r3, [r7, #0] + sConfigOC.Pulse = 0; + 8000a5e: 2300 movs r3, #0 + 8000a60: 607b str r3, [r7, #4] + sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; + 8000a62: 2300 movs r3, #0 + 8000a64: 60bb str r3, [r7, #8] + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + 8000a66: 2300 movs r3, #0 + 8000a68: 613b str r3, [r7, #16] + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) + 8000a6a: 463b mov r3, r7 + 8000a6c: 2208 movs r2, #8 + 8000a6e: 4619 mov r1, r3 + 8000a70: 4811 ldr r0, [pc, #68] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000a72: f002 fe27 bl 80036c4 + 8000a76: 4603 mov r3, r0 + != HAL_OK) { + 8000a78: 2b00 cmp r3, #0 + 8000a7a: bf14 ite ne + 8000a7c: 2301 movne r3, #1 + 8000a7e: 2300 moveq r3, #0 + 8000a80: b2db uxtb r3, r3 + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) + 8000a82: 2b00 cmp r3, #0 + 8000a84: d001 beq.n 8000a8a <_ZL12MX_TIM4_Initv+0x10a> + Error_Handler(); + 8000a86: f000 f9c9 bl 8000e1c + } + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) + 8000a8a: 463b mov r3, r7 + 8000a8c: 220c movs r2, #12 + 8000a8e: 4619 mov r1, r3 + 8000a90: 4809 ldr r0, [pc, #36] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000a92: f002 fe17 bl 80036c4 + 8000a96: 4603 mov r3, r0 + != HAL_OK) { + 8000a98: 2b00 cmp r3, #0 + 8000a9a: bf14 ite ne + 8000a9c: 2301 movne r3, #1 + 8000a9e: 2300 moveq r3, #0 + 8000aa0: b2db uxtb r3, r3 + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) + 8000aa2: 2b00 cmp r3, #0 + 8000aa4: d001 beq.n 8000aaa <_ZL12MX_TIM4_Initv+0x12a> + Error_Handler(); + 8000aa6: f000 f9b9 bl 8000e1c + } + /* USER CODE BEGIN TIM4_Init 2 */ + + /* USER CODE END TIM4_Init 2 */ + HAL_TIM_MspPostInit(&htim4); + 8000aaa: 4803 ldr r0, [pc, #12] ; (8000ab8 <_ZL12MX_TIM4_Initv+0x138>) + 8000aac: f000 fb08 bl 80010c0 + +} + 8000ab0: bf00 nop + 8000ab2: 3738 adds r7, #56 ; 0x38 + 8000ab4: 46bd mov sp, r7 + 8000ab6: bd80 pop {r7, pc} + 8000ab8: 200000a8 .word 0x200000a8 + 8000abc: 40000800 .word 0x40000800 + +08000ac0 <_ZL12MX_TIM5_Initv>: +/** + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) { + 8000ac0: b580 push {r7, lr} + 8000ac2: b08c sub sp, #48 ; 0x30 + 8000ac4: af00 add r7, sp, #0 + + /* USER CODE BEGIN TIM5_Init 0 */ + + /* USER CODE END TIM5_Init 0 */ + + TIM_Encoder_InitTypeDef sConfig = { 0 }; + 8000ac6: f107 030c add.w r3, r7, #12 + 8000aca: 2224 movs r2, #36 ; 0x24 + 8000acc: 2100 movs r1, #0 + 8000ace: 4618 mov r0, r3 + 8000ad0: f004 f9d8 bl 8004e84 + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000ad4: 463b mov r3, r7 + 8000ad6: 2200 movs r2, #0 + 8000ad8: 601a str r2, [r3, #0] + 8000ada: 605a str r2, [r3, #4] + 8000adc: 609a str r2, [r3, #8] + + /* USER CODE BEGIN TIM5_Init 1 */ + + /* USER CODE END TIM5_Init 1 */ + htim5.Instance = TIM5; + 8000ade: 4b26 ldr r3, [pc, #152] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000ae0: 4a26 ldr r2, [pc, #152] ; (8000b7c <_ZL12MX_TIM5_Initv+0xbc>) + 8000ae2: 601a str r2, [r3, #0] + htim5.Init.Prescaler = 0; + 8000ae4: 4b24 ldr r3, [pc, #144] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000ae6: 2200 movs r2, #0 + 8000ae8: 605a str r2, [r3, #4] + htim5.Init.CounterMode = TIM_COUNTERMODE_UP; + 8000aea: 4b23 ldr r3, [pc, #140] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000aec: 2200 movs r2, #0 + 8000aee: 609a str r2, [r3, #8] + htim5.Init.Period = 4294967295; + 8000af0: 4b21 ldr r3, [pc, #132] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000af2: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8000af6: 60da str r2, [r3, #12] + htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + 8000af8: 4b1f ldr r3, [pc, #124] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000afa: 2200 movs r2, #0 + 8000afc: 611a str r2, [r3, #16] + htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + 8000afe: 4b1e ldr r3, [pc, #120] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000b00: 2200 movs r2, #0 + 8000b02: 619a str r2, [r3, #24] + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + 8000b04: 2303 movs r3, #3 + 8000b06: 60fb str r3, [r7, #12] + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + 8000b08: 2300 movs r3, #0 + 8000b0a: 613b str r3, [r7, #16] + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + 8000b0c: 2301 movs r3, #1 + 8000b0e: 617b str r3, [r7, #20] + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + 8000b10: 2300 movs r3, #0 + 8000b12: 61bb str r3, [r7, #24] + sConfig.IC1Filter = 0; + 8000b14: 2300 movs r3, #0 + 8000b16: 61fb str r3, [r7, #28] + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + 8000b18: 2300 movs r3, #0 + 8000b1a: 623b str r3, [r7, #32] + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + 8000b1c: 2301 movs r3, #1 + 8000b1e: 627b str r3, [r7, #36] ; 0x24 + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + 8000b20: 2300 movs r3, #0 + 8000b22: 62bb str r3, [r7, #40] ; 0x28 + sConfig.IC2Filter = 0; + 8000b24: 2300 movs r3, #0 + 8000b26: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { + 8000b28: f107 030c add.w r3, r7, #12 + 8000b2c: 4619 mov r1, r3 + 8000b2e: 4812 ldr r0, [pc, #72] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000b30: f002 fbe0 bl 80032f4 + 8000b34: 4603 mov r3, r0 + 8000b36: 2b00 cmp r3, #0 + 8000b38: bf14 ite ne + 8000b3a: 2301 movne r3, #1 + 8000b3c: 2300 moveq r3, #0 + 8000b3e: b2db uxtb r3, r3 + 8000b40: 2b00 cmp r3, #0 + 8000b42: d001 beq.n 8000b48 <_ZL12MX_TIM5_Initv+0x88> + Error_Handler(); + 8000b44: f000 f96a bl 8000e1c + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + 8000b48: 2300 movs r3, #0 + 8000b4a: 603b str r3, [r7, #0] + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + 8000b4c: 2300 movs r3, #0 + 8000b4e: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) + 8000b50: 463b mov r3, r7 + 8000b52: 4619 mov r1, r3 + 8000b54: 4808 ldr r0, [pc, #32] ; (8000b78 <_ZL12MX_TIM5_Initv+0xb8>) + 8000b56: f003 fb6d bl 8004234 + 8000b5a: 4603 mov r3, r0 + != HAL_OK) { + 8000b5c: 2b00 cmp r3, #0 + 8000b5e: bf14 ite ne + 8000b60: 2301 movne r3, #1 + 8000b62: 2300 moveq r3, #0 + 8000b64: b2db uxtb r3, r3 + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) + 8000b66: 2b00 cmp r3, #0 + 8000b68: d001 beq.n 8000b6e <_ZL12MX_TIM5_Initv+0xae> + Error_Handler(); + 8000b6a: f000 f957 bl 8000e1c + } + /* USER CODE BEGIN TIM5_Init 2 */ + + /* USER CODE END TIM5_Init 2 */ + +} + 8000b6e: bf00 nop + 8000b70: 3730 adds r7, #48 ; 0x30 + 8000b72: 46bd mov sp, r7 + 8000b74: bd80 pop {r7, pc} + 8000b76: bf00 nop + 8000b78: 200000e8 .word 0x200000e8 + 8000b7c: 40000c00 .word 0x40000c00 + +08000b80 <_ZL12MX_TIM6_Initv>: +/** + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) { + 8000b80: b580 push {r7, lr} + 8000b82: b084 sub sp, #16 + 8000b84: af00 add r7, sp, #0 + + /* USER CODE BEGIN TIM6_Init 0 */ + + /* USER CODE END TIM6_Init 0 */ + + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000b86: 1d3b adds r3, r7, #4 + 8000b88: 2200 movs r2, #0 + 8000b8a: 601a str r2, [r3, #0] + 8000b8c: 605a str r2, [r3, #4] + 8000b8e: 609a str r2, [r3, #8] + + /* USER CODE BEGIN TIM6_Init 1 */ + + /* USER CODE END TIM6_Init 1 */ + htim6.Instance = TIM6; + 8000b90: 4b1a ldr r3, [pc, #104] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000b92: 4a1b ldr r2, [pc, #108] ; (8000c00 <_ZL12MX_TIM6_Initv+0x80>) + 8000b94: 601a str r2, [r3, #0] + htim6.Init.Prescaler = 9999; + 8000b96: 4b19 ldr r3, [pc, #100] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000b98: f242 720f movw r2, #9999 ; 0x270f + 8000b9c: 605a str r2, [r3, #4] + htim6.Init.CounterMode = TIM_COUNTERMODE_UP; + 8000b9e: 4b17 ldr r3, [pc, #92] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000ba0: 2200 movs r2, #0 + 8000ba2: 609a str r2, [r3, #8] + htim6.Init.Period = 799; + 8000ba4: 4b15 ldr r3, [pc, #84] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000ba6: f240 321f movw r2, #799 ; 0x31f + 8000baa: 60da str r2, [r3, #12] + htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + 8000bac: 4b13 ldr r3, [pc, #76] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000bae: 2200 movs r2, #0 + 8000bb0: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { + 8000bb2: 4812 ldr r0, [pc, #72] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000bb4: f002 face bl 8003154 + 8000bb8: 4603 mov r3, r0 + 8000bba: 2b00 cmp r3, #0 + 8000bbc: bf14 ite ne + 8000bbe: 2301 movne r3, #1 + 8000bc0: 2300 moveq r3, #0 + 8000bc2: b2db uxtb r3, r3 + 8000bc4: 2b00 cmp r3, #0 + 8000bc6: d001 beq.n 8000bcc <_ZL12MX_TIM6_Initv+0x4c> + Error_Handler(); + 8000bc8: f000 f928 bl 8000e1c + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + 8000bcc: 2300 movs r3, #0 + 8000bce: 607b str r3, [r7, #4] + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + 8000bd0: 2300 movs r3, #0 + 8000bd2: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) + 8000bd4: 1d3b adds r3, r7, #4 + 8000bd6: 4619 mov r1, r3 + 8000bd8: 4808 ldr r0, [pc, #32] ; (8000bfc <_ZL12MX_TIM6_Initv+0x7c>) + 8000bda: f003 fb2b bl 8004234 + 8000bde: 4603 mov r3, r0 + != HAL_OK) { + 8000be0: 2b00 cmp r3, #0 + 8000be2: bf14 ite ne + 8000be4: 2301 movne r3, #1 + 8000be6: 2300 moveq r3, #0 + 8000be8: b2db uxtb r3, r3 + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) + 8000bea: 2b00 cmp r3, #0 + 8000bec: d001 beq.n 8000bf2 <_ZL12MX_TIM6_Initv+0x72> + Error_Handler(); + 8000bee: f000 f915 bl 8000e1c + } + /* USER CODE BEGIN TIM6_Init 2 */ + + /* USER CODE END TIM6_Init 2 */ + +} + 8000bf2: bf00 nop + 8000bf4: 3710 adds r7, #16 + 8000bf6: 46bd mov sp, r7 + 8000bf8: bd80 pop {r7, pc} + 8000bfa: bf00 nop + 8000bfc: 20000128 .word 0x20000128 + 8000c00: 40001000 .word 0x40001000 + +08000c04 <_ZL19MX_USART6_UART_Initv>: +/** + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) { + 8000c04: b580 push {r7, lr} + 8000c06: 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; + 8000c08: 4b16 ldr r3, [pc, #88] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c0a: 4a17 ldr r2, [pc, #92] ; (8000c68 <_ZL19MX_USART6_UART_Initv+0x64>) + 8000c0c: 601a str r2, [r3, #0] + huart6.Init.BaudRate = 115200; + 8000c0e: 4b15 ldr r3, [pc, #84] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c10: f44f 32e1 mov.w r2, #115200 ; 0x1c200 + 8000c14: 605a str r2, [r3, #4] + huart6.Init.WordLength = UART_WORDLENGTH_8B; + 8000c16: 4b13 ldr r3, [pc, #76] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c18: 2200 movs r2, #0 + 8000c1a: 609a str r2, [r3, #8] + huart6.Init.StopBits = UART_STOPBITS_1; + 8000c1c: 4b11 ldr r3, [pc, #68] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c1e: 2200 movs r2, #0 + 8000c20: 60da str r2, [r3, #12] + huart6.Init.Parity = UART_PARITY_NONE; + 8000c22: 4b10 ldr r3, [pc, #64] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c24: 2200 movs r2, #0 + 8000c26: 611a str r2, [r3, #16] + huart6.Init.Mode = UART_MODE_TX_RX; + 8000c28: 4b0e ldr r3, [pc, #56] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c2a: 220c movs r2, #12 + 8000c2c: 615a str r2, [r3, #20] + huart6.Init.HwFlowCtl = UART_HWCONTROL_NONE; + 8000c2e: 4b0d ldr r3, [pc, #52] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c30: 2200 movs r2, #0 + 8000c32: 619a str r2, [r3, #24] + huart6.Init.OverSampling = UART_OVERSAMPLING_16; + 8000c34: 4b0b ldr r3, [pc, #44] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c36: 2200 movs r2, #0 + 8000c38: 61da str r2, [r3, #28] + huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; + 8000c3a: 4b0a ldr r3, [pc, #40] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c3c: 2200 movs r2, #0 + 8000c3e: 621a str r2, [r3, #32] + huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; + 8000c40: 4b08 ldr r3, [pc, #32] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c42: 2200 movs r2, #0 + 8000c44: 625a str r2, [r3, #36] ; 0x24 + if (HAL_UART_Init(&huart6) != HAL_OK) { + 8000c46: 4807 ldr r0, [pc, #28] ; (8000c64 <_ZL19MX_USART6_UART_Initv+0x60>) + 8000c48: f003 fb6e bl 8004328 + 8000c4c: 4603 mov r3, r0 + 8000c4e: 2b00 cmp r3, #0 + 8000c50: bf14 ite ne + 8000c52: 2301 movne r3, #1 + 8000c54: 2300 moveq r3, #0 + 8000c56: b2db uxtb r3, r3 + 8000c58: 2b00 cmp r3, #0 + 8000c5a: d001 beq.n 8000c60 <_ZL19MX_USART6_UART_Initv+0x5c> + Error_Handler(); + 8000c5c: f000 f8de bl 8000e1c + } + /* USER CODE BEGIN USART6_Init 2 */ + + /* USER CODE END USART6_Init 2 */ + +} + 8000c60: bf00 nop + 8000c62: bd80 pop {r7, pc} + 8000c64: 20000168 .word 0x20000168 + 8000c68: 40011400 .word 0x40011400 + +08000c6c <_ZL11MX_DMA_Initv>: + +/** + * Enable DMA controller clock + */ +static void MX_DMA_Init(void) { + 8000c6c: b580 push {r7, lr} + 8000c6e: b082 sub sp, #8 + 8000c70: af00 add r7, sp, #0 + + /* DMA controller clock enable */ + __HAL_RCC_DMA2_CLK_ENABLE(); + 8000c72: 4b10 ldr r3, [pc, #64] ; (8000cb4 <_ZL11MX_DMA_Initv+0x48>) + 8000c74: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000c76: 4a0f ldr r2, [pc, #60] ; (8000cb4 <_ZL11MX_DMA_Initv+0x48>) + 8000c78: f443 0380 orr.w r3, r3, #4194304 ; 0x400000 + 8000c7c: 6313 str r3, [r2, #48] ; 0x30 + 8000c7e: 4b0d ldr r3, [pc, #52] ; (8000cb4 <_ZL11MX_DMA_Initv+0x48>) + 8000c80: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000c82: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8000c86: 607b str r3, [r7, #4] + 8000c88: 687b ldr r3, [r7, #4] + + /* DMA interrupt init */ + /* DMA2_Stream1_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 2, 0); + 8000c8a: 2200 movs r2, #0 + 8000c8c: 2102 movs r1, #2 + 8000c8e: 2039 movs r0, #57 ; 0x39 + 8000c90: f000 fcf5 bl 800167e + HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn); + 8000c94: 2039 movs r0, #57 ; 0x39 + 8000c96: f000 fd0e bl 80016b6 + /* DMA2_Stream6_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream6_IRQn, 2, 0); + 8000c9a: 2200 movs r2, #0 + 8000c9c: 2102 movs r1, #2 + 8000c9e: 2045 movs r0, #69 ; 0x45 + 8000ca0: f000 fced bl 800167e + HAL_NVIC_EnableIRQ(DMA2_Stream6_IRQn); + 8000ca4: 2045 movs r0, #69 ; 0x45 + 8000ca6: f000 fd06 bl 80016b6 + +} + 8000caa: bf00 nop + 8000cac: 3708 adds r7, #8 + 8000cae: 46bd mov sp, r7 + 8000cb0: bd80 pop {r7, pc} + 8000cb2: bf00 nop + 8000cb4: 40023800 .word 0x40023800 + +08000cb8 <_ZL12MX_GPIO_Initv>: +/** + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) { + 8000cb8: b580 push {r7, lr} + 8000cba: b08c sub sp, #48 ; 0x30 + 8000cbc: af00 add r7, sp, #0 + GPIO_InitTypeDef GPIO_InitStruct = { 0 }; + 8000cbe: f107 031c add.w r3, r7, #28 + 8000cc2: 2200 movs r2, #0 + 8000cc4: 601a str r2, [r3, #0] + 8000cc6: 605a str r2, [r3, #4] + 8000cc8: 609a str r2, [r3, #8] + 8000cca: 60da str r2, [r3, #12] + 8000ccc: 611a str r2, [r3, #16] + + /* GPIO Ports Clock Enable */ + __HAL_RCC_GPIOC_CLK_ENABLE(); + 8000cce: 4b49 ldr r3, [pc, #292] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000cd0: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000cd2: 4a48 ldr r2, [pc, #288] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000cd4: f043 0304 orr.w r3, r3, #4 + 8000cd8: 6313 str r3, [r2, #48] ; 0x30 + 8000cda: 4b46 ldr r3, [pc, #280] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000cdc: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000cde: f003 0304 and.w r3, r3, #4 + 8000ce2: 61bb str r3, [r7, #24] + 8000ce4: 69bb ldr r3, [r7, #24] + __HAL_RCC_GPIOA_CLK_ENABLE(); + 8000ce6: 4b43 ldr r3, [pc, #268] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000ce8: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000cea: 4a42 ldr r2, [pc, #264] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000cec: f043 0301 orr.w r3, r3, #1 + 8000cf0: 6313 str r3, [r2, #48] ; 0x30 + 8000cf2: 4b40 ldr r3, [pc, #256] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000cf4: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000cf6: f003 0301 and.w r3, r3, #1 + 8000cfa: 617b str r3, [r7, #20] + 8000cfc: 697b ldr r3, [r7, #20] + __HAL_RCC_GPIOF_CLK_ENABLE(); + 8000cfe: 4b3d ldr r3, [pc, #244] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d00: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d02: 4a3c ldr r2, [pc, #240] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d04: f043 0320 orr.w r3, r3, #32 + 8000d08: 6313 str r3, [r2, #48] ; 0x30 + 8000d0a: 4b3a ldr r3, [pc, #232] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d0c: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d0e: f003 0320 and.w r3, r3, #32 + 8000d12: 613b str r3, [r7, #16] + 8000d14: 693b ldr r3, [r7, #16] + __HAL_RCC_GPIOE_CLK_ENABLE(); + 8000d16: 4b37 ldr r3, [pc, #220] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d18: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d1a: 4a36 ldr r2, [pc, #216] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d1c: f043 0310 orr.w r3, r3, #16 + 8000d20: 6313 str r3, [r2, #48] ; 0x30 + 8000d22: 4b34 ldr r3, [pc, #208] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d24: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d26: f003 0310 and.w r3, r3, #16 + 8000d2a: 60fb str r3, [r7, #12] + 8000d2c: 68fb ldr r3, [r7, #12] + __HAL_RCC_GPIOD_CLK_ENABLE(); + 8000d2e: 4b31 ldr r3, [pc, #196] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d30: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d32: 4a30 ldr r2, [pc, #192] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d34: f043 0308 orr.w r3, r3, #8 + 8000d38: 6313 str r3, [r2, #48] ; 0x30 + 8000d3a: 4b2e ldr r3, [pc, #184] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d3c: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d3e: f003 0308 and.w r3, r3, #8 + 8000d42: 60bb str r3, [r7, #8] + 8000d44: 68bb ldr r3, [r7, #8] + __HAL_RCC_GPIOB_CLK_ENABLE(); + 8000d46: 4b2b ldr r3, [pc, #172] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d48: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d4a: 4a2a ldr r2, [pc, #168] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d4c: f043 0302 orr.w r3, r3, #2 + 8000d50: 6313 str r3, [r2, #48] ; 0x30 + 8000d52: 4b28 ldr r3, [pc, #160] ; (8000df4 <_ZL12MX_GPIO_Initv+0x13c>) + 8000d54: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000d56: f003 0302 and.w r3, r3, #2 + 8000d5a: 607b str r3, [r7, #4] + 8000d5c: 687b ldr r3, [r7, #4] + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin | sleep2_Pin | sleep1_Pin, + 8000d5e: 2200 movs r2, #0 + 8000d60: f44f 4170 mov.w r1, #61440 ; 0xf000 + 8000d64: 4824 ldr r0, [pc, #144] ; (8000df8 <_ZL12MX_GPIO_Initv+0x140>) + 8000d66: f001 f975 bl 8002054 + GPIO_PIN_RESET); + + /*Configure GPIO pin : current2_Pin */ + GPIO_InitStruct.Pin = current2_Pin; + 8000d6a: 2301 movs r3, #1 + 8000d6c: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + 8000d6e: 2303 movs r3, #3 + 8000d70: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000d72: 2300 movs r3, #0 + 8000d74: 627b str r3, [r7, #36] ; 0x24 + HAL_GPIO_Init(current2_GPIO_Port, &GPIO_InitStruct); + 8000d76: f107 031c add.w r3, r7, #28 + 8000d7a: 4619 mov r1, r3 + 8000d7c: 481f ldr r0, [pc, #124] ; (8000dfc <_ZL12MX_GPIO_Initv+0x144>) + 8000d7e: f000 ffbf bl 8001d00 + + /*Configure GPIO pin : current1_Pin */ + GPIO_InitStruct.Pin = current1_Pin; + 8000d82: 2308 movs r3, #8 + 8000d84: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + 8000d86: 2303 movs r3, #3 + 8000d88: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000d8a: 2300 movs r3, #0 + 8000d8c: 627b str r3, [r7, #36] ; 0x24 + HAL_GPIO_Init(current1_GPIO_Port, &GPIO_InitStruct); + 8000d8e: f107 031c add.w r3, r7, #28 + 8000d92: 4619 mov r1, r3 + 8000d94: 481a ldr r0, [pc, #104] ; (8000e00 <_ZL12MX_GPIO_Initv+0x148>) + 8000d96: f000 ffb3 bl 8001d00 + + /*Configure GPIO pin : fault2_Pin */ + GPIO_InitStruct.Pin = fault2_Pin; + 8000d9a: 2340 movs r3, #64 ; 0x40 + 8000d9c: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + 8000d9e: 2300 movs r3, #0 + 8000da0: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000da2: 2300 movs r3, #0 + 8000da4: 627b str r3, [r7, #36] ; 0x24 + HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); + 8000da6: f107 031c add.w r3, r7, #28 + 8000daa: 4619 mov r1, r3 + 8000dac: 4814 ldr r0, [pc, #80] ; (8000e00 <_ZL12MX_GPIO_Initv+0x148>) + 8000dae: f000 ffa7 bl 8001d00 + + /*Configure GPIO pins : dir2_Pin dir1_Pin sleep2_Pin sleep1_Pin */ + GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin | sleep2_Pin | sleep1_Pin; + 8000db2: f44f 4370 mov.w r3, #61440 ; 0xf000 + 8000db6: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + 8000db8: 2301 movs r3, #1 + 8000dba: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000dbc: 2300 movs r3, #0 + 8000dbe: 627b str r3, [r7, #36] ; 0x24 + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + 8000dc0: 2300 movs r3, #0 + 8000dc2: 62bb str r3, [r7, #40] ; 0x28 + HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); + 8000dc4: f107 031c add.w r3, r7, #28 + 8000dc8: 4619 mov r1, r3 + 8000dca: 480b ldr r0, [pc, #44] ; (8000df8 <_ZL12MX_GPIO_Initv+0x140>) + 8000dcc: f000 ff98 bl 8001d00 + + /*Configure GPIO pin : fault1_Pin */ + GPIO_InitStruct.Pin = fault1_Pin; + 8000dd0: f44f 7300 mov.w r3, #512 ; 0x200 + 8000dd4: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + 8000dd6: 2300 movs r3, #0 + 8000dd8: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000dda: 2300 movs r3, #0 + 8000ddc: 627b str r3, [r7, #36] ; 0x24 + HAL_GPIO_Init(fault1_GPIO_Port, &GPIO_InitStruct); + 8000dde: f107 031c add.w r3, r7, #28 + 8000de2: 4619 mov r1, r3 + 8000de4: 4807 ldr r0, [pc, #28] ; (8000e04 <_ZL12MX_GPIO_Initv+0x14c>) + 8000de6: f000 ff8b bl 8001d00 + +} + 8000dea: bf00 nop + 8000dec: 3730 adds r7, #48 ; 0x30 + 8000dee: 46bd mov sp, r7 + 8000df0: bd80 pop {r7, pc} + 8000df2: bf00 nop + 8000df4: 40023800 .word 0x40023800 + 8000df8: 40021400 .word 0x40021400 + 8000dfc: 40020800 .word 0x40020800 + 8000e00: 40020000 .word 0x40020000 + 8000e04: 40021000 .word 0x40021000 + +08000e08 : + +/* USER CODE BEGIN 4 */ +void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { + 8000e08: b480 push {r7} + 8000e0a: b083 sub sp, #12 + 8000e0c: af00 add r7, sp, #0 + 8000e0e: 6078 str r0, [r7, #4] + if (htim->Instance == TIM3) { + + } +} + 8000e10: bf00 nop + 8000e12: 370c adds r7, #12 + 8000e14: 46bd mov sp, r7 + 8000e16: f85d 7b04 ldr.w r7, [sp], #4 + 8000e1a: 4770 bx lr + +08000e1c : + +/** + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) { + 8000e1c: b480 push {r7} + 8000e1e: 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 */ +} + 8000e20: bf00 nop + 8000e22: 46bd mov sp, r7 + 8000e24: f85d 7b04 ldr.w r7, [sp], #4 + 8000e28: 4770 bx lr + ... + +08000e2c <_Z41__static_initialization_and_destruction_0ii>: + 8000e2c: b5f0 push {r4, r5, r6, r7, lr} + 8000e2e: b08f sub sp, #60 ; 0x3c + 8000e30: af0c add r7, sp, #48 ; 0x30 + 8000e32: 6078 str r0, [r7, #4] + 8000e34: 6039 str r1, [r7, #0] + 8000e36: 687b ldr r3, [r7, #4] + 8000e38: 2b01 cmp r3, #1 + 8000e3a: d121 bne.n 8000e80 <_Z41__static_initialization_and_destruction_0ii+0x54> + 8000e3c: 683b ldr r3, [r7, #0] + 8000e3e: f64f 72ff movw r2, #65535 ; 0xffff + 8000e42: 4293 cmp r3, r2 + 8000e44: d11c bne.n 8000e80 <_Z41__static_initialization_and_destruction_0ii+0x54> +Encoder left_encoder = Encoder(&htim5); + 8000e46: 4910 ldr r1, [pc, #64] ; (8000e88 <_Z41__static_initialization_and_destruction_0ii+0x5c>) + 8000e48: 4810 ldr r0, [pc, #64] ; (8000e8c <_Z41__static_initialization_and_destruction_0ii+0x60>) + 8000e4a: f7ff fb87 bl 800055c <_ZN7EncoderC1EP17TIM_HandleTypeDef> +Encoder right_encoder = Encoder(&htim2); + 8000e4e: 4910 ldr r1, [pc, #64] ; (8000e90 <_Z41__static_initialization_and_destruction_0ii+0x64>) + 8000e50: 4810 ldr r0, [pc, #64] ; (8000e94 <_Z41__static_initialization_and_destruction_0ii+0x68>) + 8000e52: f7ff fb83 bl 800055c <_ZN7EncoderC1EP17TIM_HandleTypeDef> +Odometry odom = Odometry(left_encoder, right_encoder); + 8000e56: 4e0d ldr r6, [pc, #52] ; (8000e8c <_Z41__static_initialization_and_destruction_0ii+0x60>) + 8000e58: 4b0e ldr r3, [pc, #56] ; (8000e94 <_Z41__static_initialization_and_destruction_0ii+0x68>) + 8000e5a: ac04 add r4, sp, #16 + 8000e5c: 461d mov r5, r3 + 8000e5e: cd0f ldmia r5!, {r0, r1, r2, r3} + 8000e60: c40f stmia r4!, {r0, r1, r2, r3} + 8000e62: e895 0007 ldmia.w r5, {r0, r1, r2} + 8000e66: e884 0007 stmia.w r4, {r0, r1, r2} + 8000e6a: 466c mov r4, sp + 8000e6c: f106 030c add.w r3, r6, #12 + 8000e70: cb0f ldmia r3, {r0, r1, r2, r3} + 8000e72: e884 000f stmia.w r4, {r0, r1, r2, r3} + 8000e76: e896 000e ldmia.w r6, {r1, r2, r3} + 8000e7a: 4807 ldr r0, [pc, #28] ; (8000e98 <_Z41__static_initialization_and_destruction_0ii+0x6c>) + 8000e7c: f7ff fbc4 bl 8000608 <_ZN8OdometryC1E7EncoderS0_> +} + 8000e80: bf00 nop + 8000e82: 370c adds r7, #12 + 8000e84: 46bd mov sp, r7 + 8000e86: bdf0 pop {r4, r5, r6, r7, pc} + 8000e88: 200000e8 .word 0x200000e8 + 8000e8c: 200002a8 .word 0x200002a8 + 8000e90: 20000028 .word 0x20000028 + 8000e94: 200002c4 .word 0x200002c4 + 8000e98: 200002e0 .word 0x200002e0 + +08000e9c <_GLOBAL__sub_I_htim2>: + 8000e9c: b580 push {r7, lr} + 8000e9e: af00 add r7, sp, #0 + 8000ea0: f64f 71ff movw r1, #65535 ; 0xffff + 8000ea4: 2001 movs r0, #1 + 8000ea6: f7ff ffc1 bl 8000e2c <_Z41__static_initialization_and_destruction_0ii> + 8000eaa: bd80 pop {r7, pc} + +08000eac : +void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); + /** + * Initializes the Global MSP. + */ +void HAL_MspInit(void) +{ + 8000eac: b480 push {r7} + 8000eae: b083 sub sp, #12 + 8000eb0: af00 add r7, sp, #0 + /* USER CODE BEGIN MspInit 0 */ + + /* USER CODE END MspInit 0 */ + + __HAL_RCC_PWR_CLK_ENABLE(); + 8000eb2: 4b0f ldr r3, [pc, #60] ; (8000ef0 ) + 8000eb4: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000eb6: 4a0e ldr r2, [pc, #56] ; (8000ef0 ) + 8000eb8: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8000ebc: 6413 str r3, [r2, #64] ; 0x40 + 8000ebe: 4b0c ldr r3, [pc, #48] ; (8000ef0 ) + 8000ec0: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000ec2: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8000ec6: 607b str r3, [r7, #4] + 8000ec8: 687b ldr r3, [r7, #4] + __HAL_RCC_SYSCFG_CLK_ENABLE(); + 8000eca: 4b09 ldr r3, [pc, #36] ; (8000ef0 ) + 8000ecc: 6c5b ldr r3, [r3, #68] ; 0x44 + 8000ece: 4a08 ldr r2, [pc, #32] ; (8000ef0 ) + 8000ed0: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8000ed4: 6453 str r3, [r2, #68] ; 0x44 + 8000ed6: 4b06 ldr r3, [pc, #24] ; (8000ef0 ) + 8000ed8: 6c5b ldr r3, [r3, #68] ; 0x44 + 8000eda: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8000ede: 603b str r3, [r7, #0] + 8000ee0: 683b ldr r3, [r7, #0] + /* System interrupt init*/ + + /* USER CODE BEGIN MspInit 1 */ + + /* USER CODE END MspInit 1 */ +} + 8000ee2: bf00 nop + 8000ee4: 370c adds r7, #12 + 8000ee6: 46bd mov sp, r7 + 8000ee8: f85d 7b04 ldr.w r7, [sp], #4 + 8000eec: 4770 bx lr + 8000eee: bf00 nop + 8000ef0: 40023800 .word 0x40023800 + +08000ef4 : +* 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) +{ + 8000ef4: b580 push {r7, lr} + 8000ef6: b08c sub sp, #48 ; 0x30 + 8000ef8: af00 add r7, sp, #0 + 8000efa: 6078 str r0, [r7, #4] + GPIO_InitTypeDef GPIO_InitStruct = {0}; + 8000efc: f107 031c add.w r3, r7, #28 + 8000f00: 2200 movs r2, #0 + 8000f02: 601a str r2, [r3, #0] + 8000f04: 605a str r2, [r3, #4] + 8000f06: 609a str r2, [r3, #8] + 8000f08: 60da str r2, [r3, #12] + 8000f0a: 611a str r2, [r3, #16] + if(htim_encoder->Instance==TIM2) + 8000f0c: 687b ldr r3, [r7, #4] + 8000f0e: 681b ldr r3, [r3, #0] + 8000f10: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8000f14: d144 bne.n 8000fa0 + { + /* USER CODE BEGIN TIM2_MspInit 0 */ + + /* USER CODE END TIM2_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM2_CLK_ENABLE(); + 8000f16: 4b3b ldr r3, [pc, #236] ; (8001004 ) + 8000f18: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000f1a: 4a3a ldr r2, [pc, #232] ; (8001004 ) + 8000f1c: f043 0301 orr.w r3, r3, #1 + 8000f20: 6413 str r3, [r2, #64] ; 0x40 + 8000f22: 4b38 ldr r3, [pc, #224] ; (8001004 ) + 8000f24: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000f26: f003 0301 and.w r3, r3, #1 + 8000f2a: 61bb str r3, [r7, #24] + 8000f2c: 69bb ldr r3, [r7, #24] + + __HAL_RCC_GPIOA_CLK_ENABLE(); + 8000f2e: 4b35 ldr r3, [pc, #212] ; (8001004 ) + 8000f30: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000f32: 4a34 ldr r2, [pc, #208] ; (8001004 ) + 8000f34: f043 0301 orr.w r3, r3, #1 + 8000f38: 6313 str r3, [r2, #48] ; 0x30 + 8000f3a: 4b32 ldr r3, [pc, #200] ; (8001004 ) + 8000f3c: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000f3e: f003 0301 and.w r3, r3, #1 + 8000f42: 617b str r3, [r7, #20] + 8000f44: 697b ldr r3, [r7, #20] + __HAL_RCC_GPIOB_CLK_ENABLE(); + 8000f46: 4b2f ldr r3, [pc, #188] ; (8001004 ) + 8000f48: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000f4a: 4a2e ldr r2, [pc, #184] ; (8001004 ) + 8000f4c: f043 0302 orr.w r3, r3, #2 + 8000f50: 6313 str r3, [r2, #48] ; 0x30 + 8000f52: 4b2c ldr r3, [pc, #176] ; (8001004 ) + 8000f54: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000f56: f003 0302 and.w r3, r3, #2 + 8000f5a: 613b str r3, [r7, #16] + 8000f5c: 693b ldr r3, [r7, #16] + /**TIM2 GPIO Configuration + PA5 ------> TIM2_CH1 + PB3 ------> TIM2_CH2 + */ + GPIO_InitStruct.Pin = encoder_dx1_Pin; + 8000f5e: 2320 movs r3, #32 + 8000f60: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + 8000f62: 2302 movs r3, #2 + 8000f64: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000f66: 2300 movs r3, #0 + 8000f68: 627b str r3, [r7, #36] ; 0x24 + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + 8000f6a: 2300 movs r3, #0 + 8000f6c: 62bb str r3, [r7, #40] ; 0x28 + GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; + 8000f6e: 2301 movs r3, #1 + 8000f70: 62fb str r3, [r7, #44] ; 0x2c + HAL_GPIO_Init(encoder_dx1_GPIO_Port, &GPIO_InitStruct); + 8000f72: f107 031c add.w r3, r7, #28 + 8000f76: 4619 mov r1, r3 + 8000f78: 4823 ldr r0, [pc, #140] ; (8001008 ) + 8000f7a: f000 fec1 bl 8001d00 + + GPIO_InitStruct.Pin = encoder_dx2_Pin; + 8000f7e: 2308 movs r3, #8 + 8000f80: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + 8000f82: 2302 movs r3, #2 + 8000f84: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000f86: 2300 movs r3, #0 + 8000f88: 627b str r3, [r7, #36] ; 0x24 + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + 8000f8a: 2300 movs r3, #0 + 8000f8c: 62bb str r3, [r7, #40] ; 0x28 + GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; + 8000f8e: 2301 movs r3, #1 + 8000f90: 62fb str r3, [r7, #44] ; 0x2c + HAL_GPIO_Init(encoder_dx2_GPIO_Port, &GPIO_InitStruct); + 8000f92: f107 031c add.w r3, r7, #28 + 8000f96: 4619 mov r1, r3 + 8000f98: 481c ldr r0, [pc, #112] ; (800100c ) + 8000f9a: f000 feb1 bl 8001d00 + /* USER CODE BEGIN TIM5_MspInit 1 */ + + /* USER CODE END TIM5_MspInit 1 */ + } + +} + 8000f9e: e02c b.n 8000ffa + else if(htim_encoder->Instance==TIM5) + 8000fa0: 687b ldr r3, [r7, #4] + 8000fa2: 681b ldr r3, [r3, #0] + 8000fa4: 4a1a ldr r2, [pc, #104] ; (8001010 ) + 8000fa6: 4293 cmp r3, r2 + 8000fa8: d127 bne.n 8000ffa + __HAL_RCC_TIM5_CLK_ENABLE(); + 8000faa: 4b16 ldr r3, [pc, #88] ; (8001004 ) + 8000fac: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000fae: 4a15 ldr r2, [pc, #84] ; (8001004 ) + 8000fb0: f043 0308 orr.w r3, r3, #8 + 8000fb4: 6413 str r3, [r2, #64] ; 0x40 + 8000fb6: 4b13 ldr r3, [pc, #76] ; (8001004 ) + 8000fb8: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000fba: f003 0308 and.w r3, r3, #8 + 8000fbe: 60fb str r3, [r7, #12] + 8000fc0: 68fb ldr r3, [r7, #12] + __HAL_RCC_GPIOA_CLK_ENABLE(); + 8000fc2: 4b10 ldr r3, [pc, #64] ; (8001004 ) + 8000fc4: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000fc6: 4a0f ldr r2, [pc, #60] ; (8001004 ) + 8000fc8: f043 0301 orr.w r3, r3, #1 + 8000fcc: 6313 str r3, [r2, #48] ; 0x30 + 8000fce: 4b0d ldr r3, [pc, #52] ; (8001004 ) + 8000fd0: 6b1b ldr r3, [r3, #48] ; 0x30 + 8000fd2: f003 0301 and.w r3, r3, #1 + 8000fd6: 60bb str r3, [r7, #8] + 8000fd8: 68bb ldr r3, [r7, #8] + GPIO_InitStruct.Pin = encoder_sx1_Pin|encoder_sx2_Pin; + 8000fda: 2303 movs r3, #3 + 8000fdc: 61fb str r3, [r7, #28] + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + 8000fde: 2302 movs r3, #2 + 8000fe0: 623b str r3, [r7, #32] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8000fe2: 2300 movs r3, #0 + 8000fe4: 627b str r3, [r7, #36] ; 0x24 + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + 8000fe6: 2300 movs r3, #0 + 8000fe8: 62bb str r3, [r7, #40] ; 0x28 + GPIO_InitStruct.Alternate = GPIO_AF2_TIM5; + 8000fea: 2302 movs r3, #2 + 8000fec: 62fb str r3, [r7, #44] ; 0x2c + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + 8000fee: f107 031c add.w r3, r7, #28 + 8000ff2: 4619 mov r1, r3 + 8000ff4: 4804 ldr r0, [pc, #16] ; (8001008 ) + 8000ff6: f000 fe83 bl 8001d00 +} + 8000ffa: bf00 nop + 8000ffc: 3730 adds r7, #48 ; 0x30 + 8000ffe: 46bd mov sp, r7 + 8001000: bd80 pop {r7, pc} + 8001002: bf00 nop + 8001004: 40023800 .word 0x40023800 + 8001008: 40020000 .word 0x40020000 + 800100c: 40020400 .word 0x40020400 + 8001010: 40000c00 .word 0x40000c00 + +08001014 : +* 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) +{ + 8001014: b580 push {r7, lr} + 8001016: b086 sub sp, #24 + 8001018: af00 add r7, sp, #0 + 800101a: 6078 str r0, [r7, #4] + if(htim_base->Instance==TIM3) + 800101c: 687b ldr r3, [r7, #4] + 800101e: 681b ldr r3, [r3, #0] + 8001020: 4a23 ldr r2, [pc, #140] ; (80010b0 ) + 8001022: 4293 cmp r3, r2 + 8001024: d114 bne.n 8001050 + { + /* USER CODE BEGIN TIM3_MspInit 0 */ + + /* USER CODE END TIM3_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM3_CLK_ENABLE(); + 8001026: 4b23 ldr r3, [pc, #140] ; (80010b4 ) + 8001028: 6c1b ldr r3, [r3, #64] ; 0x40 + 800102a: 4a22 ldr r2, [pc, #136] ; (80010b4 ) + 800102c: f043 0302 orr.w r3, r3, #2 + 8001030: 6413 str r3, [r2, #64] ; 0x40 + 8001032: 4b20 ldr r3, [pc, #128] ; (80010b4 ) + 8001034: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001036: f003 0302 and.w r3, r3, #2 + 800103a: 617b str r3, [r7, #20] + 800103c: 697b ldr r3, [r7, #20] + /* TIM3 interrupt Init */ + HAL_NVIC_SetPriority(TIM3_IRQn, 2, 0); + 800103e: 2200 movs r2, #0 + 8001040: 2102 movs r1, #2 + 8001042: 201d movs r0, #29 + 8001044: f000 fb1b bl 800167e + HAL_NVIC_EnableIRQ(TIM3_IRQn); + 8001048: 201d movs r0, #29 + 800104a: f000 fb34 bl 80016b6 + /* USER CODE BEGIN TIM6_MspInit 1 */ + + /* USER CODE END TIM6_MspInit 1 */ + } + +} + 800104e: e02a b.n 80010a6 + else if(htim_base->Instance==TIM4) + 8001050: 687b ldr r3, [r7, #4] + 8001052: 681b ldr r3, [r3, #0] + 8001054: 4a18 ldr r2, [pc, #96] ; (80010b8 ) + 8001056: 4293 cmp r3, r2 + 8001058: d10c bne.n 8001074 + __HAL_RCC_TIM4_CLK_ENABLE(); + 800105a: 4b16 ldr r3, [pc, #88] ; (80010b4 ) + 800105c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800105e: 4a15 ldr r2, [pc, #84] ; (80010b4 ) + 8001060: f043 0304 orr.w r3, r3, #4 + 8001064: 6413 str r3, [r2, #64] ; 0x40 + 8001066: 4b13 ldr r3, [pc, #76] ; (80010b4 ) + 8001068: 6c1b ldr r3, [r3, #64] ; 0x40 + 800106a: f003 0304 and.w r3, r3, #4 + 800106e: 613b str r3, [r7, #16] + 8001070: 693b ldr r3, [r7, #16] +} + 8001072: e018 b.n 80010a6 + else if(htim_base->Instance==TIM6) + 8001074: 687b ldr r3, [r7, #4] + 8001076: 681b ldr r3, [r3, #0] + 8001078: 4a10 ldr r2, [pc, #64] ; (80010bc ) + 800107a: 4293 cmp r3, r2 + 800107c: d113 bne.n 80010a6 + __HAL_RCC_TIM6_CLK_ENABLE(); + 800107e: 4b0d ldr r3, [pc, #52] ; (80010b4 ) + 8001080: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001082: 4a0c ldr r2, [pc, #48] ; (80010b4 ) + 8001084: f043 0310 orr.w r3, r3, #16 + 8001088: 6413 str r3, [r2, #64] ; 0x40 + 800108a: 4b0a ldr r3, [pc, #40] ; (80010b4 ) + 800108c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800108e: f003 0310 and.w r3, r3, #16 + 8001092: 60fb str r3, [r7, #12] + 8001094: 68fb ldr r3, [r7, #12] + HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0); + 8001096: 2200 movs r2, #0 + 8001098: 2100 movs r1, #0 + 800109a: 2036 movs r0, #54 ; 0x36 + 800109c: f000 faef bl 800167e + HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); + 80010a0: 2036 movs r0, #54 ; 0x36 + 80010a2: f000 fb08 bl 80016b6 +} + 80010a6: bf00 nop + 80010a8: 3718 adds r7, #24 + 80010aa: 46bd mov sp, r7 + 80010ac: bd80 pop {r7, pc} + 80010ae: bf00 nop + 80010b0: 40000400 .word 0x40000400 + 80010b4: 40023800 .word 0x40023800 + 80010b8: 40000800 .word 0x40000800 + 80010bc: 40001000 .word 0x40001000 + +080010c0 : + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) +{ + 80010c0: b580 push {r7, lr} + 80010c2: b088 sub sp, #32 + 80010c4: af00 add r7, sp, #0 + 80010c6: 6078 str r0, [r7, #4] + GPIO_InitTypeDef GPIO_InitStruct = {0}; + 80010c8: f107 030c add.w r3, r7, #12 + 80010cc: 2200 movs r2, #0 + 80010ce: 601a str r2, [r3, #0] + 80010d0: 605a str r2, [r3, #4] + 80010d2: 609a str r2, [r3, #8] + 80010d4: 60da str r2, [r3, #12] + 80010d6: 611a str r2, [r3, #16] + if(htim->Instance==TIM4) + 80010d8: 687b ldr r3, [r7, #4] + 80010da: 681b ldr r3, [r3, #0] + 80010dc: 4a11 ldr r2, [pc, #68] ; (8001124 ) + 80010de: 4293 cmp r3, r2 + 80010e0: d11c bne.n 800111c + { + /* USER CODE BEGIN TIM4_MspPostInit 0 */ + + /* USER CODE END TIM4_MspPostInit 0 */ + + __HAL_RCC_GPIOD_CLK_ENABLE(); + 80010e2: 4b11 ldr r3, [pc, #68] ; (8001128 ) + 80010e4: 6b1b ldr r3, [r3, #48] ; 0x30 + 80010e6: 4a10 ldr r2, [pc, #64] ; (8001128 ) + 80010e8: f043 0308 orr.w r3, r3, #8 + 80010ec: 6313 str r3, [r2, #48] ; 0x30 + 80010ee: 4b0e ldr r3, [pc, #56] ; (8001128 ) + 80010f0: 6b1b ldr r3, [r3, #48] ; 0x30 + 80010f2: f003 0308 and.w r3, r3, #8 + 80010f6: 60bb str r3, [r7, #8] + 80010f8: 68bb ldr r3, [r7, #8] + /**TIM4 GPIO Configuration + PD14 ------> TIM4_CH3 + PD15 ------> TIM4_CH4 + */ + GPIO_InitStruct.Pin = pwm2_Pin|pwm1_Pin; + 80010fa: f44f 4340 mov.w r3, #49152 ; 0xc000 + 80010fe: 60fb str r3, [r7, #12] + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + 8001100: 2302 movs r3, #2 + 8001102: 613b str r3, [r7, #16] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 8001104: 2300 movs r3, #0 + 8001106: 617b str r3, [r7, #20] + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + 8001108: 2300 movs r3, #0 + 800110a: 61bb str r3, [r7, #24] + GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; + 800110c: 2302 movs r3, #2 + 800110e: 61fb str r3, [r7, #28] + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + 8001110: f107 030c add.w r3, r7, #12 + 8001114: 4619 mov r1, r3 + 8001116: 4805 ldr r0, [pc, #20] ; (800112c ) + 8001118: f000 fdf2 bl 8001d00 + /* USER CODE BEGIN TIM4_MspPostInit 1 */ + + /* USER CODE END TIM4_MspPostInit 1 */ + } + +} + 800111c: bf00 nop + 800111e: 3720 adds r7, #32 + 8001120: 46bd mov sp, r7 + 8001122: bd80 pop {r7, pc} + 8001124: 40000800 .word 0x40000800 + 8001128: 40023800 .word 0x40023800 + 800112c: 40020c00 .word 0x40020c00 + +08001130 : +* This function configures the hardware resources used in this example +* @param huart: UART handle pointer +* @retval None +*/ +void HAL_UART_MspInit(UART_HandleTypeDef* huart) +{ + 8001130: b580 push {r7, lr} + 8001132: b08a sub sp, #40 ; 0x28 + 8001134: af00 add r7, sp, #0 + 8001136: 6078 str r0, [r7, #4] + GPIO_InitTypeDef GPIO_InitStruct = {0}; + 8001138: f107 0314 add.w r3, r7, #20 + 800113c: 2200 movs r2, #0 + 800113e: 601a str r2, [r3, #0] + 8001140: 605a str r2, [r3, #4] + 8001142: 609a str r2, [r3, #8] + 8001144: 60da str r2, [r3, #12] + 8001146: 611a str r2, [r3, #16] + if(huart->Instance==USART6) + 8001148: 687b ldr r3, [r7, #4] + 800114a: 681b ldr r3, [r3, #0] + 800114c: 4a49 ldr r2, [pc, #292] ; (8001274 ) + 800114e: 4293 cmp r3, r2 + 8001150: f040 808c bne.w 800126c + { + /* USER CODE BEGIN USART6_MspInit 0 */ + + /* USER CODE END USART6_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_USART6_CLK_ENABLE(); + 8001154: 4b48 ldr r3, [pc, #288] ; (8001278 ) + 8001156: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001158: 4a47 ldr r2, [pc, #284] ; (8001278 ) + 800115a: f043 0320 orr.w r3, r3, #32 + 800115e: 6453 str r3, [r2, #68] ; 0x44 + 8001160: 4b45 ldr r3, [pc, #276] ; (8001278 ) + 8001162: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001164: f003 0320 and.w r3, r3, #32 + 8001168: 613b str r3, [r7, #16] + 800116a: 693b ldr r3, [r7, #16] + + __HAL_RCC_GPIOC_CLK_ENABLE(); + 800116c: 4b42 ldr r3, [pc, #264] ; (8001278 ) + 800116e: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001170: 4a41 ldr r2, [pc, #260] ; (8001278 ) + 8001172: f043 0304 orr.w r3, r3, #4 + 8001176: 6313 str r3, [r2, #48] ; 0x30 + 8001178: 4b3f ldr r3, [pc, #252] ; (8001278 ) + 800117a: 6b1b ldr r3, [r3, #48] ; 0x30 + 800117c: f003 0304 and.w r3, r3, #4 + 8001180: 60fb str r3, [r7, #12] + 8001182: 68fb ldr r3, [r7, #12] + /**USART6 GPIO Configuration + PC6 ------> USART6_TX + PC7 ------> USART6_RX + */ + GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; + 8001184: 23c0 movs r3, #192 ; 0xc0 + 8001186: 617b str r3, [r7, #20] + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + 8001188: 2302 movs r3, #2 + 800118a: 61bb str r3, [r7, #24] + GPIO_InitStruct.Pull = GPIO_NOPULL; + 800118c: 2300 movs r3, #0 + 800118e: 61fb str r3, [r7, #28] + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + 8001190: 2303 movs r3, #3 + 8001192: 623b str r3, [r7, #32] + GPIO_InitStruct.Alternate = GPIO_AF8_USART6; + 8001194: 2308 movs r3, #8 + 8001196: 627b str r3, [r7, #36] ; 0x24 + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + 8001198: f107 0314 add.w r3, r7, #20 + 800119c: 4619 mov r1, r3 + 800119e: 4837 ldr r0, [pc, #220] ; (800127c ) + 80011a0: f000 fdae bl 8001d00 + + /* USART6 DMA Init */ + /* USART6_RX Init */ + hdma_usart6_rx.Instance = DMA2_Stream1; + 80011a4: 4b36 ldr r3, [pc, #216] ; (8001280 ) + 80011a6: 4a37 ldr r2, [pc, #220] ; (8001284 ) + 80011a8: 601a str r2, [r3, #0] + hdma_usart6_rx.Init.Channel = DMA_CHANNEL_5; + 80011aa: 4b35 ldr r3, [pc, #212] ; (8001280 ) + 80011ac: f04f 6220 mov.w r2, #167772160 ; 0xa000000 + 80011b0: 605a str r2, [r3, #4] + hdma_usart6_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + 80011b2: 4b33 ldr r3, [pc, #204] ; (8001280 ) + 80011b4: 2200 movs r2, #0 + 80011b6: 609a str r2, [r3, #8] + hdma_usart6_rx.Init.PeriphInc = DMA_PINC_DISABLE; + 80011b8: 4b31 ldr r3, [pc, #196] ; (8001280 ) + 80011ba: 2200 movs r2, #0 + 80011bc: 60da str r2, [r3, #12] + hdma_usart6_rx.Init.MemInc = DMA_MINC_ENABLE; + 80011be: 4b30 ldr r3, [pc, #192] ; (8001280 ) + 80011c0: f44f 6280 mov.w r2, #1024 ; 0x400 + 80011c4: 611a str r2, [r3, #16] + hdma_usart6_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + 80011c6: 4b2e ldr r3, [pc, #184] ; (8001280 ) + 80011c8: 2200 movs r2, #0 + 80011ca: 615a str r2, [r3, #20] + hdma_usart6_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + 80011cc: 4b2c ldr r3, [pc, #176] ; (8001280 ) + 80011ce: 2200 movs r2, #0 + 80011d0: 619a str r2, [r3, #24] + hdma_usart6_rx.Init.Mode = DMA_NORMAL; + 80011d2: 4b2b ldr r3, [pc, #172] ; (8001280 ) + 80011d4: 2200 movs r2, #0 + 80011d6: 61da str r2, [r3, #28] + hdma_usart6_rx.Init.Priority = DMA_PRIORITY_LOW; + 80011d8: 4b29 ldr r3, [pc, #164] ; (8001280 ) + 80011da: 2200 movs r2, #0 + 80011dc: 621a str r2, [r3, #32] + hdma_usart6_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + 80011de: 4b28 ldr r3, [pc, #160] ; (8001280 ) + 80011e0: 2200 movs r2, #0 + 80011e2: 625a str r2, [r3, #36] ; 0x24 + if (HAL_DMA_Init(&hdma_usart6_rx) != HAL_OK) + 80011e4: 4826 ldr r0, [pc, #152] ; (8001280 ) + 80011e6: f000 fa81 bl 80016ec + 80011ea: 4603 mov r3, r0 + 80011ec: 2b00 cmp r3, #0 + 80011ee: d001 beq.n 80011f4 + { + Error_Handler(); + 80011f0: f7ff fe14 bl 8000e1c + } + + __HAL_LINKDMA(huart,hdmarx,hdma_usart6_rx); + 80011f4: 687b ldr r3, [r7, #4] + 80011f6: 4a22 ldr r2, [pc, #136] ; (8001280 ) + 80011f8: 66da str r2, [r3, #108] ; 0x6c + 80011fa: 4a21 ldr r2, [pc, #132] ; (8001280 ) + 80011fc: 687b ldr r3, [r7, #4] + 80011fe: 6393 str r3, [r2, #56] ; 0x38 + + /* USART6_TX Init */ + hdma_usart6_tx.Instance = DMA2_Stream6; + 8001200: 4b21 ldr r3, [pc, #132] ; (8001288 ) + 8001202: 4a22 ldr r2, [pc, #136] ; (800128c ) + 8001204: 601a str r2, [r3, #0] + hdma_usart6_tx.Init.Channel = DMA_CHANNEL_5; + 8001206: 4b20 ldr r3, [pc, #128] ; (8001288 ) + 8001208: f04f 6220 mov.w r2, #167772160 ; 0xa000000 + 800120c: 605a str r2, [r3, #4] + hdma_usart6_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; + 800120e: 4b1e ldr r3, [pc, #120] ; (8001288 ) + 8001210: 2240 movs r2, #64 ; 0x40 + 8001212: 609a str r2, [r3, #8] + hdma_usart6_tx.Init.PeriphInc = DMA_PINC_DISABLE; + 8001214: 4b1c ldr r3, [pc, #112] ; (8001288 ) + 8001216: 2200 movs r2, #0 + 8001218: 60da str r2, [r3, #12] + hdma_usart6_tx.Init.MemInc = DMA_MINC_ENABLE; + 800121a: 4b1b ldr r3, [pc, #108] ; (8001288 ) + 800121c: f44f 6280 mov.w r2, #1024 ; 0x400 + 8001220: 611a str r2, [r3, #16] + hdma_usart6_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + 8001222: 4b19 ldr r3, [pc, #100] ; (8001288 ) + 8001224: 2200 movs r2, #0 + 8001226: 615a str r2, [r3, #20] + hdma_usart6_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + 8001228: 4b17 ldr r3, [pc, #92] ; (8001288 ) + 800122a: 2200 movs r2, #0 + 800122c: 619a str r2, [r3, #24] + hdma_usart6_tx.Init.Mode = DMA_NORMAL; + 800122e: 4b16 ldr r3, [pc, #88] ; (8001288 ) + 8001230: 2200 movs r2, #0 + 8001232: 61da str r2, [r3, #28] + hdma_usart6_tx.Init.Priority = DMA_PRIORITY_LOW; + 8001234: 4b14 ldr r3, [pc, #80] ; (8001288 ) + 8001236: 2200 movs r2, #0 + 8001238: 621a str r2, [r3, #32] + hdma_usart6_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + 800123a: 4b13 ldr r3, [pc, #76] ; (8001288 ) + 800123c: 2200 movs r2, #0 + 800123e: 625a str r2, [r3, #36] ; 0x24 + if (HAL_DMA_Init(&hdma_usart6_tx) != HAL_OK) + 8001240: 4811 ldr r0, [pc, #68] ; (8001288 ) + 8001242: f000 fa53 bl 80016ec + 8001246: 4603 mov r3, r0 + 8001248: 2b00 cmp r3, #0 + 800124a: d001 beq.n 8001250 + { + Error_Handler(); + 800124c: f7ff fde6 bl 8000e1c + } + + __HAL_LINKDMA(huart,hdmatx,hdma_usart6_tx); + 8001250: 687b ldr r3, [r7, #4] + 8001252: 4a0d ldr r2, [pc, #52] ; (8001288 ) + 8001254: 669a str r2, [r3, #104] ; 0x68 + 8001256: 4a0c ldr r2, [pc, #48] ; (8001288 ) + 8001258: 687b ldr r3, [r7, #4] + 800125a: 6393 str r3, [r2, #56] ; 0x38 + + /* USART6 interrupt Init */ + HAL_NVIC_SetPriority(USART6_IRQn, 0, 0); + 800125c: 2200 movs r2, #0 + 800125e: 2100 movs r1, #0 + 8001260: 2047 movs r0, #71 ; 0x47 + 8001262: f000 fa0c bl 800167e + HAL_NVIC_EnableIRQ(USART6_IRQn); + 8001266: 2047 movs r0, #71 ; 0x47 + 8001268: f000 fa25 bl 80016b6 + /* USER CODE BEGIN USART6_MspInit 1 */ + + /* USER CODE END USART6_MspInit 1 */ + } + +} + 800126c: bf00 nop + 800126e: 3728 adds r7, #40 ; 0x28 + 8001270: 46bd mov sp, r7 + 8001272: bd80 pop {r7, pc} + 8001274: 40011400 .word 0x40011400 + 8001278: 40023800 .word 0x40023800 + 800127c: 40020800 .word 0x40020800 + 8001280: 200001e8 .word 0x200001e8 + 8001284: 40026428 .word 0x40026428 + 8001288: 20000248 .word 0x20000248 + 800128c: 400264a0 .word 0x400264a0 + +08001290 : +/******************************************************************************/ +/** + * @brief This function handles Non maskable interrupt. + */ +void NMI_Handler(void) +{ + 8001290: b480 push {r7} + 8001292: af00 add r7, sp, #0 + + /* USER CODE END NonMaskableInt_IRQn 0 */ + /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ + + /* USER CODE END NonMaskableInt_IRQn 1 */ +} + 8001294: bf00 nop + 8001296: 46bd mov sp, r7 + 8001298: f85d 7b04 ldr.w r7, [sp], #4 + 800129c: 4770 bx lr + +0800129e : + +/** + * @brief This function handles Hard fault interrupt. + */ +void HardFault_Handler(void) +{ + 800129e: b480 push {r7} + 80012a0: af00 add r7, sp, #0 + /* USER CODE BEGIN HardFault_IRQn 0 */ + + /* USER CODE END HardFault_IRQn 0 */ + while (1) + 80012a2: e7fe b.n 80012a2 + +080012a4 : + +/** + * @brief This function handles Memory management fault. + */ +void MemManage_Handler(void) +{ + 80012a4: b480 push {r7} + 80012a6: af00 add r7, sp, #0 + /* USER CODE BEGIN MemoryManagement_IRQn 0 */ + + /* USER CODE END MemoryManagement_IRQn 0 */ + while (1) + 80012a8: e7fe b.n 80012a8 + +080012aa : + +/** + * @brief This function handles Pre-fetch fault, memory access fault. + */ +void BusFault_Handler(void) +{ + 80012aa: b480 push {r7} + 80012ac: af00 add r7, sp, #0 + /* USER CODE BEGIN BusFault_IRQn 0 */ + + /* USER CODE END BusFault_IRQn 0 */ + while (1) + 80012ae: e7fe b.n 80012ae + +080012b0 : + +/** + * @brief This function handles Undefined instruction or illegal state. + */ +void UsageFault_Handler(void) +{ + 80012b0: b480 push {r7} + 80012b2: af00 add r7, sp, #0 + /* USER CODE BEGIN UsageFault_IRQn 0 */ + + /* USER CODE END UsageFault_IRQn 0 */ + while (1) + 80012b4: e7fe b.n 80012b4 + +080012b6 : + +/** + * @brief This function handles System service call via SWI instruction. + */ +void SVC_Handler(void) +{ + 80012b6: b480 push {r7} + 80012b8: af00 add r7, sp, #0 + + /* USER CODE END SVCall_IRQn 0 */ + /* USER CODE BEGIN SVCall_IRQn 1 */ + + /* USER CODE END SVCall_IRQn 1 */ +} + 80012ba: bf00 nop + 80012bc: 46bd mov sp, r7 + 80012be: f85d 7b04 ldr.w r7, [sp], #4 + 80012c2: 4770 bx lr + +080012c4 : + +/** + * @brief This function handles Debug monitor. + */ +void DebugMon_Handler(void) +{ + 80012c4: b480 push {r7} + 80012c6: af00 add r7, sp, #0 + + /* USER CODE END DebugMonitor_IRQn 0 */ + /* USER CODE BEGIN DebugMonitor_IRQn 1 */ + + /* USER CODE END DebugMonitor_IRQn 1 */ +} + 80012c8: bf00 nop + 80012ca: 46bd mov sp, r7 + 80012cc: f85d 7b04 ldr.w r7, [sp], #4 + 80012d0: 4770 bx lr + +080012d2 : + +/** + * @brief This function handles Pendable request for system service. + */ +void PendSV_Handler(void) +{ + 80012d2: b480 push {r7} + 80012d4: af00 add r7, sp, #0 + + /* USER CODE END PendSV_IRQn 0 */ + /* USER CODE BEGIN PendSV_IRQn 1 */ + + /* USER CODE END PendSV_IRQn 1 */ +} + 80012d6: bf00 nop + 80012d8: 46bd mov sp, r7 + 80012da: f85d 7b04 ldr.w r7, [sp], #4 + 80012de: 4770 bx lr + +080012e0 : + +/** + * @brief This function handles System tick timer. + */ +void SysTick_Handler(void) +{ + 80012e0: b580 push {r7, lr} + 80012e2: af00 add r7, sp, #0 + /* USER CODE BEGIN SysTick_IRQn 0 */ + + /* USER CODE END SysTick_IRQn 0 */ + HAL_IncTick(); + 80012e4: f000 f8d0 bl 8001488 + /* USER CODE BEGIN SysTick_IRQn 1 */ + + /* USER CODE END SysTick_IRQn 1 */ +} + 80012e8: bf00 nop + 80012ea: bd80 pop {r7, pc} + +080012ec : + +/** + * @brief This function handles TIM3 global interrupt. + */ +void TIM3_IRQHandler(void) +{ + 80012ec: b580 push {r7, lr} + 80012ee: af00 add r7, sp, #0 + /* USER CODE BEGIN TIM3_IRQn 0 */ + + /* USER CODE END TIM3_IRQn 0 */ + HAL_TIM_IRQHandler(&htim3); + 80012f0: 4802 ldr r0, [pc, #8] ; (80012fc ) + 80012f2: f002 f8c8 bl 8003486 + /* USER CODE BEGIN TIM3_IRQn 1 */ + + /* USER CODE END TIM3_IRQn 1 */ +} + 80012f6: bf00 nop + 80012f8: bd80 pop {r7, pc} + 80012fa: bf00 nop + 80012fc: 20000068 .word 0x20000068 + +08001300 : + +/** + * @brief This function handles TIM6 global interrupt, DAC1 and DAC2 underrun error interrupts. + */ +void TIM6_DAC_IRQHandler(void) +{ + 8001300: b580 push {r7, lr} + 8001302: af00 add r7, sp, #0 + /* USER CODE BEGIN TIM6_DAC_IRQn 0 */ + + /* USER CODE END TIM6_DAC_IRQn 0 */ + HAL_TIM_IRQHandler(&htim6); + 8001304: 4802 ldr r0, [pc, #8] ; (8001310 ) + 8001306: f002 f8be bl 8003486 + /* USER CODE BEGIN TIM6_DAC_IRQn 1 */ + + /* USER CODE END TIM6_DAC_IRQn 1 */ +} + 800130a: bf00 nop + 800130c: bd80 pop {r7, pc} + 800130e: bf00 nop + 8001310: 20000128 .word 0x20000128 + +08001314 : + +/** + * @brief This function handles DMA2 stream1 global interrupt. + */ +void DMA2_Stream1_IRQHandler(void) +{ + 8001314: b580 push {r7, lr} + 8001316: af00 add r7, sp, #0 + /* USER CODE BEGIN DMA2_Stream1_IRQn 0 */ + + /* USER CODE END DMA2_Stream1_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_usart6_rx); + 8001318: 4802 ldr r0, [pc, #8] ; (8001324 ) + 800131a: f000 fab7 bl 800188c + /* USER CODE BEGIN DMA2_Stream1_IRQn 1 */ + + /* USER CODE END DMA2_Stream1_IRQn 1 */ +} + 800131e: bf00 nop + 8001320: bd80 pop {r7, pc} + 8001322: bf00 nop + 8001324: 200001e8 .word 0x200001e8 + +08001328 : + +/** + * @brief This function handles DMA2 stream6 global interrupt. + */ +void DMA2_Stream6_IRQHandler(void) +{ + 8001328: b580 push {r7, lr} + 800132a: af00 add r7, sp, #0 + /* USER CODE BEGIN DMA2_Stream6_IRQn 0 */ + + /* USER CODE END DMA2_Stream6_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_usart6_tx); + 800132c: 4802 ldr r0, [pc, #8] ; (8001338 ) + 800132e: f000 faad bl 800188c + /* USER CODE BEGIN DMA2_Stream6_IRQn 1 */ + + /* USER CODE END DMA2_Stream6_IRQn 1 */ +} + 8001332: bf00 nop + 8001334: bd80 pop {r7, pc} + 8001336: bf00 nop + 8001338: 20000248 .word 0x20000248 + +0800133c : + +/** + * @brief This function handles USART6 global interrupt. + */ +void USART6_IRQHandler(void) +{ + 800133c: b580 push {r7, lr} + 800133e: af00 add r7, sp, #0 + /* USER CODE BEGIN USART6_IRQn 0 */ + + /* USER CODE END USART6_IRQn 0 */ + HAL_UART_IRQHandler(&huart6); + 8001340: 4802 ldr r0, [pc, #8] ; (800134c ) + 8001342: f003 f83f bl 80043c4 + /* USER CODE BEGIN USART6_IRQn 1 */ + + /* USER CODE END USART6_IRQn 1 */ +} + 8001346: bf00 nop + 8001348: bd80 pop {r7, pc} + 800134a: bf00 nop + 800134c: 20000168 .word 0x20000168 + +08001350 : + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + 8001350: b480 push {r7} + 8001352: 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 */ + 8001354: 4b15 ldr r3, [pc, #84] ; (80013ac ) + 8001356: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800135a: 4a14 ldr r2, [pc, #80] ; (80013ac ) + 800135c: f443 0370 orr.w r3, r3, #15728640 ; 0xf00000 + 8001360: 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; + 8001364: 4b12 ldr r3, [pc, #72] ; (80013b0 ) + 8001366: 681b ldr r3, [r3, #0] + 8001368: 4a11 ldr r2, [pc, #68] ; (80013b0 ) + 800136a: f043 0301 orr.w r3, r3, #1 + 800136e: 6013 str r3, [r2, #0] + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + 8001370: 4b0f ldr r3, [pc, #60] ; (80013b0 ) + 8001372: 2200 movs r2, #0 + 8001374: 609a str r2, [r3, #8] + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + 8001376: 4b0e ldr r3, [pc, #56] ; (80013b0 ) + 8001378: 681a ldr r2, [r3, #0] + 800137a: 490d ldr r1, [pc, #52] ; (80013b0 ) + 800137c: 4b0d ldr r3, [pc, #52] ; (80013b4 ) + 800137e: 4013 ands r3, r2 + 8001380: 600b str r3, [r1, #0] + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x24003010; + 8001382: 4b0b ldr r3, [pc, #44] ; (80013b0 ) + 8001384: 4a0c ldr r2, [pc, #48] ; (80013b8 ) + 8001386: 605a str r2, [r3, #4] + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + 8001388: 4b09 ldr r3, [pc, #36] ; (80013b0 ) + 800138a: 681b ldr r3, [r3, #0] + 800138c: 4a08 ldr r2, [pc, #32] ; (80013b0 ) + 800138e: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8001392: 6013 str r3, [r2, #0] + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + 8001394: 4b06 ldr r3, [pc, #24] ; (80013b0 ) + 8001396: 2200 movs r2, #0 + 8001398: 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 */ + 800139a: 4b04 ldr r3, [pc, #16] ; (80013ac ) + 800139c: f04f 6200 mov.w r2, #134217728 ; 0x8000000 + 80013a0: 609a str r2, [r3, #8] +#endif +} + 80013a2: bf00 nop + 80013a4: 46bd mov sp, r7 + 80013a6: f85d 7b04 ldr.w r7, [sp], #4 + 80013aa: 4770 bx lr + 80013ac: e000ed00 .word 0xe000ed00 + 80013b0: 40023800 .word 0x40023800 + 80013b4: fef6ffff .word 0xfef6ffff + 80013b8: 24003010 .word 0x24003010 + +080013bc : + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + 80013bc: f8df d034 ldr.w sp, [pc, #52] ; 80013f4 + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + 80013c0: 2100 movs r1, #0 + b LoopCopyDataInit + 80013c2: e003 b.n 80013cc + +080013c4 : + +CopyDataInit: + ldr r3, =_sidata + 80013c4: 4b0c ldr r3, [pc, #48] ; (80013f8 ) + ldr r3, [r3, r1] + 80013c6: 585b ldr r3, [r3, r1] + str r3, [r0, r1] + 80013c8: 5043 str r3, [r0, r1] + adds r1, r1, #4 + 80013ca: 3104 adds r1, #4 + +080013cc : + +LoopCopyDataInit: + ldr r0, =_sdata + 80013cc: 480b ldr r0, [pc, #44] ; (80013fc ) + ldr r3, =_edata + 80013ce: 4b0c ldr r3, [pc, #48] ; (8001400 ) + adds r2, r0, r1 + 80013d0: 1842 adds r2, r0, r1 + cmp r2, r3 + 80013d2: 429a cmp r2, r3 + bcc CopyDataInit + 80013d4: d3f6 bcc.n 80013c4 + ldr r2, =_sbss + 80013d6: 4a0b ldr r2, [pc, #44] ; (8001404 ) + b LoopFillZerobss + 80013d8: e002 b.n 80013e0 + +080013da : +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + 80013da: 2300 movs r3, #0 + str r3, [r2], #4 + 80013dc: f842 3b04 str.w r3, [r2], #4 + +080013e0 : + +LoopFillZerobss: + ldr r3, = _ebss + 80013e0: 4b09 ldr r3, [pc, #36] ; (8001408 ) + cmp r2, r3 + 80013e2: 429a cmp r2, r3 + bcc FillZerobss + 80013e4: d3f9 bcc.n 80013da + +/* Call the clock system initialization function.*/ + bl SystemInit + 80013e6: f7ff ffb3 bl 8001350 +/* Call static constructors */ + bl __libc_init_array + 80013ea: f003 fd27 bl 8004e3c <__libc_init_array> +/* Call the application's entry point.*/ + bl main + 80013ee: f7ff f93f bl 8000670
+ bx lr + 80013f2: 4770 bx lr + ldr sp, =_estack /* set stack pointer */ + 80013f4: 20080000 .word 0x20080000 + ldr r3, =_sidata + 80013f8: 08004ee0 .word 0x08004ee0 + ldr r0, =_sdata + 80013fc: 20000000 .word 0x20000000 + ldr r3, =_edata + 8001400: 2000000c .word 0x2000000c + ldr r2, =_sbss + 8001404: 2000000c .word 0x2000000c + ldr r3, = _ebss + 8001408: 2000032c .word 0x2000032c + +0800140c : + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + 800140c: e7fe b.n 800140c + +0800140e : + * 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) +{ + 800140e: b580 push {r7, lr} + 8001410: 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); + 8001412: 2003 movs r0, #3 + 8001414: f000 f928 bl 8001668 + + /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ + HAL_InitTick(TICK_INT_PRIORITY); + 8001418: 2000 movs r0, #0 + 800141a: f000 f805 bl 8001428 + + /* Init the low level hardware */ + HAL_MspInit(); + 800141e: f7ff fd45 bl 8000eac + + /* Return function status */ + return HAL_OK; + 8001422: 2300 movs r3, #0 +} + 8001424: 4618 mov r0, r3 + 8001426: bd80 pop {r7, pc} + +08001428 : + * implementation in user file. + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) +{ + 8001428: b580 push {r7, lr} + 800142a: b082 sub sp, #8 + 800142c: af00 add r7, sp, #0 + 800142e: 6078 str r0, [r7, #4] + /* Configure the SysTick to have interrupt in 1ms time basis*/ + if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) + 8001430: 4b12 ldr r3, [pc, #72] ; (800147c ) + 8001432: 681a ldr r2, [r3, #0] + 8001434: 4b12 ldr r3, [pc, #72] ; (8001480 ) + 8001436: 781b ldrb r3, [r3, #0] + 8001438: 4619 mov r1, r3 + 800143a: f44f 737a mov.w r3, #1000 ; 0x3e8 + 800143e: fbb3 f3f1 udiv r3, r3, r1 + 8001442: fbb2 f3f3 udiv r3, r2, r3 + 8001446: 4618 mov r0, r3 + 8001448: f000 f943 bl 80016d2 + 800144c: 4603 mov r3, r0 + 800144e: 2b00 cmp r3, #0 + 8001450: d001 beq.n 8001456 + { + return HAL_ERROR; + 8001452: 2301 movs r3, #1 + 8001454: e00e b.n 8001474 + } + + /* Configure the SysTick IRQ priority */ + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + 8001456: 687b ldr r3, [r7, #4] + 8001458: 2b0f cmp r3, #15 + 800145a: d80a bhi.n 8001472 + { + HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); + 800145c: 2200 movs r2, #0 + 800145e: 6879 ldr r1, [r7, #4] + 8001460: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001464: f000 f90b bl 800167e + uwTickPrio = TickPriority; + 8001468: 4a06 ldr r2, [pc, #24] ; (8001484 ) + 800146a: 687b ldr r3, [r7, #4] + 800146c: 6013 str r3, [r2, #0] + { + return HAL_ERROR; + } + + /* Return function status */ + return HAL_OK; + 800146e: 2300 movs r3, #0 + 8001470: e000 b.n 8001474 + return HAL_ERROR; + 8001472: 2301 movs r3, #1 +} + 8001474: 4618 mov r0, r3 + 8001476: 3708 adds r7, #8 + 8001478: 46bd mov sp, r7 + 800147a: bd80 pop {r7, pc} + 800147c: 20000000 .word 0x20000000 + 8001480: 20000008 .word 0x20000008 + 8001484: 20000004 .word 0x20000004 + +08001488 : + * @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) +{ + 8001488: b480 push {r7} + 800148a: af00 add r7, sp, #0 + uwTick += uwTickFreq; + 800148c: 4b06 ldr r3, [pc, #24] ; (80014a8 ) + 800148e: 781b ldrb r3, [r3, #0] + 8001490: 461a mov r2, r3 + 8001492: 4b06 ldr r3, [pc, #24] ; (80014ac ) + 8001494: 681b ldr r3, [r3, #0] + 8001496: 4413 add r3, r2 + 8001498: 4a04 ldr r2, [pc, #16] ; (80014ac ) + 800149a: 6013 str r3, [r2, #0] +} + 800149c: bf00 nop + 800149e: 46bd mov sp, r7 + 80014a0: f85d 7b04 ldr.w r7, [sp], #4 + 80014a4: 4770 bx lr + 80014a6: bf00 nop + 80014a8: 20000008 .word 0x20000008 + 80014ac: 20000328 .word 0x20000328 + +080014b0 : + * @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) +{ + 80014b0: b480 push {r7} + 80014b2: af00 add r7, sp, #0 + return uwTick; + 80014b4: 4b03 ldr r3, [pc, #12] ; (80014c4 ) + 80014b6: 681b ldr r3, [r3, #0] +} + 80014b8: 4618 mov r0, r3 + 80014ba: 46bd mov sp, r7 + 80014bc: f85d 7b04 ldr.w r7, [sp], #4 + 80014c0: 4770 bx lr + 80014c2: bf00 nop + 80014c4: 20000328 .word 0x20000328 + +080014c8 <__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) +{ + 80014c8: b480 push {r7} + 80014ca: b085 sub sp, #20 + 80014cc: af00 add r7, sp, #0 + 80014ce: 6078 str r0, [r7, #4] + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + 80014d0: 687b ldr r3, [r7, #4] + 80014d2: f003 0307 and.w r3, r3, #7 + 80014d6: 60fb str r3, [r7, #12] + + reg_value = SCB->AIRCR; /* read old register configuration */ + 80014d8: 4b0b ldr r3, [pc, #44] ; (8001508 <__NVIC_SetPriorityGrouping+0x40>) + 80014da: 68db ldr r3, [r3, #12] + 80014dc: 60bb str r3, [r7, #8] + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + 80014de: 68ba ldr r2, [r7, #8] + 80014e0: f64f 03ff movw r3, #63743 ; 0xf8ff + 80014e4: 4013 ands r3, r2 + 80014e6: 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 */ + 80014e8: 68fb ldr r3, [r7, #12] + 80014ea: 021a lsls r2, r3, #8 + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + 80014ec: 68bb ldr r3, [r7, #8] + 80014ee: 431a orrs r2, r3 + reg_value = (reg_value | + 80014f0: 4b06 ldr r3, [pc, #24] ; (800150c <__NVIC_SetPriorityGrouping+0x44>) + 80014f2: 4313 orrs r3, r2 + 80014f4: 60bb str r3, [r7, #8] + SCB->AIRCR = reg_value; + 80014f6: 4a04 ldr r2, [pc, #16] ; (8001508 <__NVIC_SetPriorityGrouping+0x40>) + 80014f8: 68bb ldr r3, [r7, #8] + 80014fa: 60d3 str r3, [r2, #12] +} + 80014fc: bf00 nop + 80014fe: 3714 adds r7, #20 + 8001500: 46bd mov sp, r7 + 8001502: f85d 7b04 ldr.w r7, [sp], #4 + 8001506: 4770 bx lr + 8001508: e000ed00 .word 0xe000ed00 + 800150c: 05fa0000 .word 0x05fa0000 + +08001510 <__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) +{ + 8001510: b480 push {r7} + 8001512: af00 add r7, sp, #0 + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); + 8001514: 4b04 ldr r3, [pc, #16] ; (8001528 <__NVIC_GetPriorityGrouping+0x18>) + 8001516: 68db ldr r3, [r3, #12] + 8001518: 0a1b lsrs r3, r3, #8 + 800151a: f003 0307 and.w r3, r3, #7 +} + 800151e: 4618 mov r0, r3 + 8001520: 46bd mov sp, r7 + 8001522: f85d 7b04 ldr.w r7, [sp], #4 + 8001526: 4770 bx lr + 8001528: e000ed00 .word 0xe000ed00 + +0800152c <__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) +{ + 800152c: b480 push {r7} + 800152e: b083 sub sp, #12 + 8001530: af00 add r7, sp, #0 + 8001532: 4603 mov r3, r0 + 8001534: 71fb strb r3, [r7, #7] + if ((int32_t)(IRQn) >= 0) + 8001536: f997 3007 ldrsb.w r3, [r7, #7] + 800153a: 2b00 cmp r3, #0 + 800153c: db0b blt.n 8001556 <__NVIC_EnableIRQ+0x2a> + { + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + 800153e: 79fb ldrb r3, [r7, #7] + 8001540: f003 021f and.w r2, r3, #31 + 8001544: 4907 ldr r1, [pc, #28] ; (8001564 <__NVIC_EnableIRQ+0x38>) + 8001546: f997 3007 ldrsb.w r3, [r7, #7] + 800154a: 095b lsrs r3, r3, #5 + 800154c: 2001 movs r0, #1 + 800154e: fa00 f202 lsl.w r2, r0, r2 + 8001552: f841 2023 str.w r2, [r1, r3, lsl #2] + } +} + 8001556: bf00 nop + 8001558: 370c adds r7, #12 + 800155a: 46bd mov sp, r7 + 800155c: f85d 7b04 ldr.w r7, [sp], #4 + 8001560: 4770 bx lr + 8001562: bf00 nop + 8001564: e000e100 .word 0xe000e100 + +08001568 <__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) +{ + 8001568: b480 push {r7} + 800156a: b083 sub sp, #12 + 800156c: af00 add r7, sp, #0 + 800156e: 4603 mov r3, r0 + 8001570: 6039 str r1, [r7, #0] + 8001572: 71fb strb r3, [r7, #7] + if ((int32_t)(IRQn) >= 0) + 8001574: f997 3007 ldrsb.w r3, [r7, #7] + 8001578: 2b00 cmp r3, #0 + 800157a: db0a blt.n 8001592 <__NVIC_SetPriority+0x2a> + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + 800157c: 683b ldr r3, [r7, #0] + 800157e: b2da uxtb r2, r3 + 8001580: 490c ldr r1, [pc, #48] ; (80015b4 <__NVIC_SetPriority+0x4c>) + 8001582: f997 3007 ldrsb.w r3, [r7, #7] + 8001586: 0112 lsls r2, r2, #4 + 8001588: b2d2 uxtb r2, r2 + 800158a: 440b add r3, r1 + 800158c: 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); + } +} + 8001590: e00a b.n 80015a8 <__NVIC_SetPriority+0x40> + SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + 8001592: 683b ldr r3, [r7, #0] + 8001594: b2da uxtb r2, r3 + 8001596: 4908 ldr r1, [pc, #32] ; (80015b8 <__NVIC_SetPriority+0x50>) + 8001598: 79fb ldrb r3, [r7, #7] + 800159a: f003 030f and.w r3, r3, #15 + 800159e: 3b04 subs r3, #4 + 80015a0: 0112 lsls r2, r2, #4 + 80015a2: b2d2 uxtb r2, r2 + 80015a4: 440b add r3, r1 + 80015a6: 761a strb r2, [r3, #24] +} + 80015a8: bf00 nop + 80015aa: 370c adds r7, #12 + 80015ac: 46bd mov sp, r7 + 80015ae: f85d 7b04 ldr.w r7, [sp], #4 + 80015b2: 4770 bx lr + 80015b4: e000e100 .word 0xe000e100 + 80015b8: e000ed00 .word 0xe000ed00 + +080015bc : + \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) +{ + 80015bc: b480 push {r7} + 80015be: b089 sub sp, #36 ; 0x24 + 80015c0: af00 add r7, sp, #0 + 80015c2: 60f8 str r0, [r7, #12] + 80015c4: 60b9 str r1, [r7, #8] + 80015c6: 607a str r2, [r7, #4] + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + 80015c8: 68fb ldr r3, [r7, #12] + 80015ca: f003 0307 and.w r3, r3, #7 + 80015ce: 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); + 80015d0: 69fb ldr r3, [r7, #28] + 80015d2: f1c3 0307 rsb r3, r3, #7 + 80015d6: 2b04 cmp r3, #4 + 80015d8: bf28 it cs + 80015da: 2304 movcs r3, #4 + 80015dc: 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)); + 80015de: 69fb ldr r3, [r7, #28] + 80015e0: 3304 adds r3, #4 + 80015e2: 2b06 cmp r3, #6 + 80015e4: d902 bls.n 80015ec + 80015e6: 69fb ldr r3, [r7, #28] + 80015e8: 3b03 subs r3, #3 + 80015ea: e000 b.n 80015ee + 80015ec: 2300 movs r3, #0 + 80015ee: 617b str r3, [r7, #20] + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + 80015f0: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 80015f4: 69bb ldr r3, [r7, #24] + 80015f6: fa02 f303 lsl.w r3, r2, r3 + 80015fa: 43da mvns r2, r3 + 80015fc: 68bb ldr r3, [r7, #8] + 80015fe: 401a ands r2, r3 + 8001600: 697b ldr r3, [r7, #20] + 8001602: 409a lsls r2, r3 + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + 8001604: f04f 31ff mov.w r1, #4294967295 ; 0xffffffff + 8001608: 697b ldr r3, [r7, #20] + 800160a: fa01 f303 lsl.w r3, r1, r3 + 800160e: 43d9 mvns r1, r3 + 8001610: 687b ldr r3, [r7, #4] + 8001612: 400b ands r3, r1 + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + 8001614: 4313 orrs r3, r2 + ); +} + 8001616: 4618 mov r0, r3 + 8001618: 3724 adds r7, #36 ; 0x24 + 800161a: 46bd mov sp, r7 + 800161c: f85d 7b04 ldr.w r7, [sp], #4 + 8001620: 4770 bx lr + ... + +08001624 : + \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) +{ + 8001624: b580 push {r7, lr} + 8001626: b082 sub sp, #8 + 8001628: af00 add r7, sp, #0 + 800162a: 6078 str r0, [r7, #4] + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + 800162c: 687b ldr r3, [r7, #4] + 800162e: 3b01 subs r3, #1 + 8001630: f1b3 7f80 cmp.w r3, #16777216 ; 0x1000000 + 8001634: d301 bcc.n 800163a + { + return (1UL); /* Reload value impossible */ + 8001636: 2301 movs r3, #1 + 8001638: e00f b.n 800165a + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + 800163a: 4a0a ldr r2, [pc, #40] ; (8001664 ) + 800163c: 687b ldr r3, [r7, #4] + 800163e: 3b01 subs r3, #1 + 8001640: 6053 str r3, [r2, #4] + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + 8001642: 210f movs r1, #15 + 8001644: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001648: f7ff ff8e bl 8001568 <__NVIC_SetPriority> + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + 800164c: 4b05 ldr r3, [pc, #20] ; (8001664 ) + 800164e: 2200 movs r2, #0 + 8001650: 609a str r2, [r3, #8] + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + 8001652: 4b04 ldr r3, [pc, #16] ; (8001664 ) + 8001654: 2207 movs r2, #7 + 8001656: 601a str r2, [r3, #0] + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ + 8001658: 2300 movs r3, #0 +} + 800165a: 4618 mov r0, r3 + 800165c: 3708 adds r7, #8 + 800165e: 46bd mov sp, r7 + 8001660: bd80 pop {r7, pc} + 8001662: bf00 nop + 8001664: e000e010 .word 0xe000e010 + +08001668 : + * @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) +{ + 8001668: b580 push {r7, lr} + 800166a: b082 sub sp, #8 + 800166c: af00 add r7, sp, #0 + 800166e: 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); + 8001670: 6878 ldr r0, [r7, #4] + 8001672: f7ff ff29 bl 80014c8 <__NVIC_SetPriorityGrouping> +} + 8001676: bf00 nop + 8001678: 3708 adds r7, #8 + 800167a: 46bd mov sp, r7 + 800167c: bd80 pop {r7, pc} + +0800167e : + * 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) +{ + 800167e: b580 push {r7, lr} + 8001680: b086 sub sp, #24 + 8001682: af00 add r7, sp, #0 + 8001684: 4603 mov r3, r0 + 8001686: 60b9 str r1, [r7, #8] + 8001688: 607a str r2, [r7, #4] + 800168a: 73fb strb r3, [r7, #15] + uint32_t prioritygroup = 0x00; + 800168c: 2300 movs r3, #0 + 800168e: 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(); + 8001690: f7ff ff3e bl 8001510 <__NVIC_GetPriorityGrouping> + 8001694: 6178 str r0, [r7, #20] + + NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); + 8001696: 687a ldr r2, [r7, #4] + 8001698: 68b9 ldr r1, [r7, #8] + 800169a: 6978 ldr r0, [r7, #20] + 800169c: f7ff ff8e bl 80015bc + 80016a0: 4602 mov r2, r0 + 80016a2: f997 300f ldrsb.w r3, [r7, #15] + 80016a6: 4611 mov r1, r2 + 80016a8: 4618 mov r0, r3 + 80016aa: f7ff ff5d bl 8001568 <__NVIC_SetPriority> +} + 80016ae: bf00 nop + 80016b0: 3718 adds r7, #24 + 80016b2: 46bd mov sp, r7 + 80016b4: bd80 pop {r7, pc} + +080016b6 : + * 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) +{ + 80016b6: b580 push {r7, lr} + 80016b8: b082 sub sp, #8 + 80016ba: af00 add r7, sp, #0 + 80016bc: 4603 mov r3, r0 + 80016be: 71fb strb r3, [r7, #7] + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Enable interrupt */ + NVIC_EnableIRQ(IRQn); + 80016c0: f997 3007 ldrsb.w r3, [r7, #7] + 80016c4: 4618 mov r0, r3 + 80016c6: f7ff ff31 bl 800152c <__NVIC_EnableIRQ> +} + 80016ca: bf00 nop + 80016cc: 3708 adds r7, #8 + 80016ce: 46bd mov sp, r7 + 80016d0: bd80 pop {r7, pc} + +080016d2 : + * @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) +{ + 80016d2: b580 push {r7, lr} + 80016d4: b082 sub sp, #8 + 80016d6: af00 add r7, sp, #0 + 80016d8: 6078 str r0, [r7, #4] + return SysTick_Config(TicksNumb); + 80016da: 6878 ldr r0, [r7, #4] + 80016dc: f7ff ffa2 bl 8001624 + 80016e0: 4603 mov r3, r0 +} + 80016e2: 4618 mov r0, r3 + 80016e4: 3708 adds r7, #8 + 80016e6: 46bd mov sp, r7 + 80016e8: bd80 pop {r7, pc} + ... + +080016ec : + * @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_Init(DMA_HandleTypeDef *hdma) +{ + 80016ec: b580 push {r7, lr} + 80016ee: b086 sub sp, #24 + 80016f0: af00 add r7, sp, #0 + 80016f2: 6078 str r0, [r7, #4] + uint32_t tmp = 0U; + 80016f4: 2300 movs r3, #0 + 80016f6: 617b str r3, [r7, #20] + uint32_t tickstart = HAL_GetTick(); + 80016f8: f7ff feda bl 80014b0 + 80016fc: 6138 str r0, [r7, #16] + DMA_Base_Registers *regs; + + /* Check the DMA peripheral state */ + if(hdma == NULL) + 80016fe: 687b ldr r3, [r7, #4] + 8001700: 2b00 cmp r3, #0 + 8001702: d101 bne.n 8001708 + { + return HAL_ERROR; + 8001704: 2301 movs r3, #1 + 8001706: e099 b.n 800183c + assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst)); + assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst)); + } + + /* Allocate lock resource */ + __HAL_UNLOCK(hdma); + 8001708: 687b ldr r3, [r7, #4] + 800170a: 2200 movs r2, #0 + 800170c: f883 2034 strb.w r2, [r3, #52] ; 0x34 + + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + 8001710: 687b ldr r3, [r7, #4] + 8001712: 2202 movs r2, #2 + 8001714: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + /* Disable the peripheral */ + __HAL_DMA_DISABLE(hdma); + 8001718: 687b ldr r3, [r7, #4] + 800171a: 681b ldr r3, [r3, #0] + 800171c: 681a ldr r2, [r3, #0] + 800171e: 687b ldr r3, [r7, #4] + 8001720: 681b ldr r3, [r3, #0] + 8001722: f022 0201 bic.w r2, r2, #1 + 8001726: 601a str r2, [r3, #0] + + /* Check if the DMA Stream is effectively disabled */ + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + 8001728: e00f b.n 800174a + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) + 800172a: f7ff fec1 bl 80014b0 + 800172e: 4602 mov r2, r0 + 8001730: 693b ldr r3, [r7, #16] + 8001732: 1ad3 subs r3, r2, r3 + 8001734: 2b05 cmp r3, #5 + 8001736: d908 bls.n 800174a + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + 8001738: 687b ldr r3, [r7, #4] + 800173a: 2220 movs r2, #32 + 800173c: 655a str r2, [r3, #84] ; 0x54 + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_TIMEOUT; + 800173e: 687b ldr r3, [r7, #4] + 8001740: 2203 movs r2, #3 + 8001742: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + return HAL_TIMEOUT; + 8001746: 2303 movs r3, #3 + 8001748: e078 b.n 800183c + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + 800174a: 687b ldr r3, [r7, #4] + 800174c: 681b ldr r3, [r3, #0] + 800174e: 681b ldr r3, [r3, #0] + 8001750: f003 0301 and.w r3, r3, #1 + 8001754: 2b00 cmp r3, #0 + 8001756: d1e8 bne.n 800172a + } + } + + /* Get the CR register value */ + tmp = hdma->Instance->CR; + 8001758: 687b ldr r3, [r7, #4] + 800175a: 681b ldr r3, [r3, #0] + 800175c: 681b ldr r3, [r3, #0] + 800175e: 617b str r3, [r7, #20] + + /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */ + tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ + 8001760: 697a ldr r2, [r7, #20] + 8001762: 4b38 ldr r3, [pc, #224] ; (8001844 ) + 8001764: 4013 ands r3, r2 + 8001766: 617b str r3, [r7, #20] + DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ + DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ + DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM)); + + /* Prepare the DMA Stream configuration */ + tmp |= hdma->Init.Channel | hdma->Init.Direction | + 8001768: 687b ldr r3, [r7, #4] + 800176a: 685a ldr r2, [r3, #4] + 800176c: 687b ldr r3, [r7, #4] + 800176e: 689b ldr r3, [r3, #8] + 8001770: 431a orrs r2, r3 + hdma->Init.PeriphInc | hdma->Init.MemInc | + 8001772: 687b ldr r3, [r7, #4] + 8001774: 68db ldr r3, [r3, #12] + tmp |= hdma->Init.Channel | hdma->Init.Direction | + 8001776: 431a orrs r2, r3 + hdma->Init.PeriphInc | hdma->Init.MemInc | + 8001778: 687b ldr r3, [r7, #4] + 800177a: 691b ldr r3, [r3, #16] + 800177c: 431a orrs r2, r3 + hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | + 800177e: 687b ldr r3, [r7, #4] + 8001780: 695b ldr r3, [r3, #20] + hdma->Init.PeriphInc | hdma->Init.MemInc | + 8001782: 431a orrs r2, r3 + hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | + 8001784: 687b ldr r3, [r7, #4] + 8001786: 699b ldr r3, [r3, #24] + 8001788: 431a orrs r2, r3 + hdma->Init.Mode | hdma->Init.Priority; + 800178a: 687b ldr r3, [r7, #4] + 800178c: 69db ldr r3, [r3, #28] + hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | + 800178e: 431a orrs r2, r3 + hdma->Init.Mode | hdma->Init.Priority; + 8001790: 687b ldr r3, [r7, #4] + 8001792: 6a1b ldr r3, [r3, #32] + 8001794: 4313 orrs r3, r2 + tmp |= hdma->Init.Channel | hdma->Init.Direction | + 8001796: 697a ldr r2, [r7, #20] + 8001798: 4313 orrs r3, r2 + 800179a: 617b str r3, [r7, #20] + + /* the Memory burst and peripheral burst are not used when the FIFO is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + 800179c: 687b ldr r3, [r7, #4] + 800179e: 6a5b ldr r3, [r3, #36] ; 0x24 + 80017a0: 2b04 cmp r3, #4 + 80017a2: d107 bne.n 80017b4 + { + /* Get memory burst and peripheral burst */ + tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst; + 80017a4: 687b ldr r3, [r7, #4] + 80017a6: 6ada ldr r2, [r3, #44] ; 0x2c + 80017a8: 687b ldr r3, [r7, #4] + 80017aa: 6b1b ldr r3, [r3, #48] ; 0x30 + 80017ac: 4313 orrs r3, r2 + 80017ae: 697a ldr r2, [r7, #20] + 80017b0: 4313 orrs r3, r2 + 80017b2: 617b str r3, [r7, #20] + } + + /* Write to DMA Stream CR register */ + hdma->Instance->CR = tmp; + 80017b4: 687b ldr r3, [r7, #4] + 80017b6: 681b ldr r3, [r3, #0] + 80017b8: 697a ldr r2, [r7, #20] + 80017ba: 601a str r2, [r3, #0] + + /* Get the FCR register value */ + tmp = hdma->Instance->FCR; + 80017bc: 687b ldr r3, [r7, #4] + 80017be: 681b ldr r3, [r3, #0] + 80017c0: 695b ldr r3, [r3, #20] + 80017c2: 617b str r3, [r7, #20] + + /* Clear Direct mode and FIFO threshold bits */ + tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); + 80017c4: 697b ldr r3, [r7, #20] + 80017c6: f023 0307 bic.w r3, r3, #7 + 80017ca: 617b str r3, [r7, #20] + + /* Prepare the DMA Stream FIFO configuration */ + tmp |= hdma->Init.FIFOMode; + 80017cc: 687b ldr r3, [r7, #4] + 80017ce: 6a5b ldr r3, [r3, #36] ; 0x24 + 80017d0: 697a ldr r2, [r7, #20] + 80017d2: 4313 orrs r3, r2 + 80017d4: 617b str r3, [r7, #20] + + /* The FIFO threshold is not used when the FIFO mode is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + 80017d6: 687b ldr r3, [r7, #4] + 80017d8: 6a5b ldr r3, [r3, #36] ; 0x24 + 80017da: 2b04 cmp r3, #4 + 80017dc: d117 bne.n 800180e + { + /* Get the FIFO threshold */ + tmp |= hdma->Init.FIFOThreshold; + 80017de: 687b ldr r3, [r7, #4] + 80017e0: 6a9b ldr r3, [r3, #40] ; 0x28 + 80017e2: 697a ldr r2, [r7, #20] + 80017e4: 4313 orrs r3, r2 + 80017e6: 617b str r3, [r7, #20] + + /* Check compatibility between FIFO threshold level and size of the memory burst */ + /* for INCR4, INCR8, INCR16 bursts */ + if (hdma->Init.MemBurst != DMA_MBURST_SINGLE) + 80017e8: 687b ldr r3, [r7, #4] + 80017ea: 6adb ldr r3, [r3, #44] ; 0x2c + 80017ec: 2b00 cmp r3, #0 + 80017ee: d00e beq.n 800180e + { + if (DMA_CheckFifoParam(hdma) != HAL_OK) + 80017f0: 6878 ldr r0, [r7, #4] + 80017f2: f000 fa0b bl 8001c0c + 80017f6: 4603 mov r3, r0 + 80017f8: 2b00 cmp r3, #0 + 80017fa: d008 beq.n 800180e + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_PARAM; + 80017fc: 687b ldr r3, [r7, #4] + 80017fe: 2240 movs r2, #64 ; 0x40 + 8001800: 655a str r2, [r3, #84] ; 0x54 + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + 8001802: 687b ldr r3, [r7, #4] + 8001804: 2201 movs r2, #1 + 8001806: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + return HAL_ERROR; + 800180a: 2301 movs r3, #1 + 800180c: e016 b.n 800183c + } + } + } + + /* Write to DMA Stream FCR */ + hdma->Instance->FCR = tmp; + 800180e: 687b ldr r3, [r7, #4] + 8001810: 681b ldr r3, [r3, #0] + 8001812: 697a ldr r2, [r7, #20] + 8001814: 615a str r2, [r3, #20] + + /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate + DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */ + regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); + 8001816: 6878 ldr r0, [r7, #4] + 8001818: f000 f9c2 bl 8001ba0 + 800181c: 4603 mov r3, r0 + 800181e: 60fb str r3, [r7, #12] + + /* Clear all interrupt flags */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + 8001820: 687b ldr r3, [r7, #4] + 8001822: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001824: 223f movs r2, #63 ; 0x3f + 8001826: 409a lsls r2, r3 + 8001828: 68fb ldr r3, [r7, #12] + 800182a: 609a str r2, [r3, #8] + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + 800182c: 687b ldr r3, [r7, #4] + 800182e: 2200 movs r2, #0 + 8001830: 655a str r2, [r3, #84] ; 0x54 + + /* Initialize the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + 8001832: 687b ldr r3, [r7, #4] + 8001834: 2201 movs r2, #1 + 8001836: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + return HAL_OK; + 800183a: 2300 movs r3, #0 +} + 800183c: 4618 mov r0, r3 + 800183e: 3718 adds r7, #24 + 8001840: 46bd mov sp, r7 + 8001842: bd80 pop {r7, pc} + 8001844: e010803f .word 0xe010803f + +08001848 : + * @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) +{ + 8001848: b480 push {r7} + 800184a: b083 sub sp, #12 + 800184c: af00 add r7, sp, #0 + 800184e: 6078 str r0, [r7, #4] + if(hdma->State != HAL_DMA_STATE_BUSY) + 8001850: 687b ldr r3, [r7, #4] + 8001852: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 + 8001856: b2db uxtb r3, r3 + 8001858: 2b02 cmp r3, #2 + 800185a: d004 beq.n 8001866 + { + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + 800185c: 687b ldr r3, [r7, #4] + 800185e: 2280 movs r2, #128 ; 0x80 + 8001860: 655a str r2, [r3, #84] ; 0x54 + return HAL_ERROR; + 8001862: 2301 movs r3, #1 + 8001864: e00c b.n 8001880 + } + else + { + /* Set Abort State */ + hdma->State = HAL_DMA_STATE_ABORT; + 8001866: 687b ldr r3, [r7, #4] + 8001868: 2205 movs r2, #5 + 800186a: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + 800186e: 687b ldr r3, [r7, #4] + 8001870: 681b ldr r3, [r3, #0] + 8001872: 681a ldr r2, [r3, #0] + 8001874: 687b ldr r3, [r7, #4] + 8001876: 681b ldr r3, [r3, #0] + 8001878: f022 0201 bic.w r2, r2, #1 + 800187c: 601a str r2, [r3, #0] + } + + return HAL_OK; + 800187e: 2300 movs r3, #0 +} + 8001880: 4618 mov r0, r3 + 8001882: 370c adds r7, #12 + 8001884: 46bd mov sp, r7 + 8001886: f85d 7b04 ldr.w r7, [sp], #4 + 800188a: 4770 bx lr + +0800188c : + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval None + */ +void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma) +{ + 800188c: b580 push {r7, lr} + 800188e: b086 sub sp, #24 + 8001890: af00 add r7, sp, #0 + 8001892: 6078 str r0, [r7, #4] + uint32_t tmpisr; + __IO uint32_t count = 0; + 8001894: 2300 movs r3, #0 + 8001896: 60bb str r3, [r7, #8] + uint32_t timeout = SystemCoreClock / 9600; + 8001898: 4b92 ldr r3, [pc, #584] ; (8001ae4 ) + 800189a: 681b ldr r3, [r3, #0] + 800189c: 4a92 ldr r2, [pc, #584] ; (8001ae8 ) + 800189e: fba2 2303 umull r2, r3, r2, r3 + 80018a2: 0a9b lsrs r3, r3, #10 + 80018a4: 617b str r3, [r7, #20] + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + 80018a6: 687b ldr r3, [r7, #4] + 80018a8: 6d9b ldr r3, [r3, #88] ; 0x58 + 80018aa: 613b str r3, [r7, #16] + + tmpisr = regs->ISR; + 80018ac: 693b ldr r3, [r7, #16] + 80018ae: 681b ldr r3, [r3, #0] + 80018b0: 60fb str r3, [r7, #12] + + /* Transfer Error Interrupt management ***************************************/ + if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) + 80018b2: 687b ldr r3, [r7, #4] + 80018b4: 6ddb ldr r3, [r3, #92] ; 0x5c + 80018b6: 2208 movs r2, #8 + 80018b8: 409a lsls r2, r3 + 80018ba: 68fb ldr r3, [r7, #12] + 80018bc: 4013 ands r3, r2 + 80018be: 2b00 cmp r3, #0 + 80018c0: d01a beq.n 80018f8 + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET) + 80018c2: 687b ldr r3, [r7, #4] + 80018c4: 681b ldr r3, [r3, #0] + 80018c6: 681b ldr r3, [r3, #0] + 80018c8: f003 0304 and.w r3, r3, #4 + 80018cc: 2b00 cmp r3, #0 + 80018ce: d013 beq.n 80018f8 + { + /* Disable the transfer error interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TE); + 80018d0: 687b ldr r3, [r7, #4] + 80018d2: 681b ldr r3, [r3, #0] + 80018d4: 681a ldr r2, [r3, #0] + 80018d6: 687b ldr r3, [r7, #4] + 80018d8: 681b ldr r3, [r3, #0] + 80018da: f022 0204 bic.w r2, r2, #4 + 80018de: 601a str r2, [r3, #0] + + /* Clear the transfer error flag */ + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; + 80018e0: 687b ldr r3, [r7, #4] + 80018e2: 6ddb ldr r3, [r3, #92] ; 0x5c + 80018e4: 2208 movs r2, #8 + 80018e6: 409a lsls r2, r3 + 80018e8: 693b ldr r3, [r7, #16] + 80018ea: 609a str r2, [r3, #8] + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_TE; + 80018ec: 687b ldr r3, [r7, #4] + 80018ee: 6d5b ldr r3, [r3, #84] ; 0x54 + 80018f0: f043 0201 orr.w r2, r3, #1 + 80018f4: 687b ldr r3, [r7, #4] + 80018f6: 655a str r2, [r3, #84] ; 0x54 + } + } + /* FIFO Error Interrupt management ******************************************/ + if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) + 80018f8: 687b ldr r3, [r7, #4] + 80018fa: 6ddb ldr r3, [r3, #92] ; 0x5c + 80018fc: 2201 movs r2, #1 + 80018fe: 409a lsls r2, r3 + 8001900: 68fb ldr r3, [r7, #12] + 8001902: 4013 ands r3, r2 + 8001904: 2b00 cmp r3, #0 + 8001906: d012 beq.n 800192e + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET) + 8001908: 687b ldr r3, [r7, #4] + 800190a: 681b ldr r3, [r3, #0] + 800190c: 695b ldr r3, [r3, #20] + 800190e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8001912: 2b00 cmp r3, #0 + 8001914: d00b beq.n 800192e + { + /* Clear the FIFO error flag */ + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; + 8001916: 687b ldr r3, [r7, #4] + 8001918: 6ddb ldr r3, [r3, #92] ; 0x5c + 800191a: 2201 movs r2, #1 + 800191c: 409a lsls r2, r3 + 800191e: 693b ldr r3, [r7, #16] + 8001920: 609a str r2, [r3, #8] + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_FE; + 8001922: 687b ldr r3, [r7, #4] + 8001924: 6d5b ldr r3, [r3, #84] ; 0x54 + 8001926: f043 0202 orr.w r2, r3, #2 + 800192a: 687b ldr r3, [r7, #4] + 800192c: 655a str r2, [r3, #84] ; 0x54 + } + } + /* Direct Mode Error Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) + 800192e: 687b ldr r3, [r7, #4] + 8001930: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001932: 2204 movs r2, #4 + 8001934: 409a lsls r2, r3 + 8001936: 68fb ldr r3, [r7, #12] + 8001938: 4013 ands r3, r2 + 800193a: 2b00 cmp r3, #0 + 800193c: d012 beq.n 8001964 + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET) + 800193e: 687b ldr r3, [r7, #4] + 8001940: 681b ldr r3, [r3, #0] + 8001942: 681b ldr r3, [r3, #0] + 8001944: f003 0302 and.w r3, r3, #2 + 8001948: 2b00 cmp r3, #0 + 800194a: d00b beq.n 8001964 + { + /* Clear the direct mode error flag */ + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; + 800194c: 687b ldr r3, [r7, #4] + 800194e: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001950: 2204 movs r2, #4 + 8001952: 409a lsls r2, r3 + 8001954: 693b ldr r3, [r7, #16] + 8001956: 609a str r2, [r3, #8] + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_DME; + 8001958: 687b ldr r3, [r7, #4] + 800195a: 6d5b ldr r3, [r3, #84] ; 0x54 + 800195c: f043 0204 orr.w r2, r3, #4 + 8001960: 687b ldr r3, [r7, #4] + 8001962: 655a str r2, [r3, #84] ; 0x54 + } + } + /* Half Transfer Complete Interrupt management ******************************/ + if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) + 8001964: 687b ldr r3, [r7, #4] + 8001966: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001968: 2210 movs r2, #16 + 800196a: 409a lsls r2, r3 + 800196c: 68fb ldr r3, [r7, #12] + 800196e: 4013 ands r3, r2 + 8001970: 2b00 cmp r3, #0 + 8001972: d043 beq.n 80019fc + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET) + 8001974: 687b ldr r3, [r7, #4] + 8001976: 681b ldr r3, [r3, #0] + 8001978: 681b ldr r3, [r3, #0] + 800197a: f003 0308 and.w r3, r3, #8 + 800197e: 2b00 cmp r3, #0 + 8001980: d03c beq.n 80019fc + { + /* Clear the half transfer complete flag */ + regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; + 8001982: 687b ldr r3, [r7, #4] + 8001984: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001986: 2210 movs r2, #16 + 8001988: 409a lsls r2, r3 + 800198a: 693b ldr r3, [r7, #16] + 800198c: 609a str r2, [r3, #8] + + /* Multi_Buffering mode enabled */ + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + 800198e: 687b ldr r3, [r7, #4] + 8001990: 681b ldr r3, [r3, #0] + 8001992: 681b ldr r3, [r3, #0] + 8001994: f403 2380 and.w r3, r3, #262144 ; 0x40000 + 8001998: 2b00 cmp r3, #0 + 800199a: d018 beq.n 80019ce + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + 800199c: 687b ldr r3, [r7, #4] + 800199e: 681b ldr r3, [r3, #0] + 80019a0: 681b ldr r3, [r3, #0] + 80019a2: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 80019a6: 2b00 cmp r3, #0 + 80019a8: d108 bne.n 80019bc + { + if(hdma->XferHalfCpltCallback != NULL) + 80019aa: 687b ldr r3, [r7, #4] + 80019ac: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019ae: 2b00 cmp r3, #0 + 80019b0: d024 beq.n 80019fc + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + 80019b2: 687b ldr r3, [r7, #4] + 80019b4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019b6: 6878 ldr r0, [r7, #4] + 80019b8: 4798 blx r3 + 80019ba: e01f b.n 80019fc + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferM1HalfCpltCallback != NULL) + 80019bc: 687b ldr r3, [r7, #4] + 80019be: 6c9b ldr r3, [r3, #72] ; 0x48 + 80019c0: 2b00 cmp r3, #0 + 80019c2: d01b beq.n 80019fc + { + /* Half transfer callback */ + hdma->XferM1HalfCpltCallback(hdma); + 80019c4: 687b ldr r3, [r7, #4] + 80019c6: 6c9b ldr r3, [r3, #72] ; 0x48 + 80019c8: 6878 ldr r0, [r7, #4] + 80019ca: 4798 blx r3 + 80019cc: e016 b.n 80019fc + } + } + else + { + /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + 80019ce: 687b ldr r3, [r7, #4] + 80019d0: 681b ldr r3, [r3, #0] + 80019d2: 681b ldr r3, [r3, #0] + 80019d4: f403 7380 and.w r3, r3, #256 ; 0x100 + 80019d8: 2b00 cmp r3, #0 + 80019da: d107 bne.n 80019ec + { + /* Disable the half transfer interrupt */ + hdma->Instance->CR &= ~(DMA_IT_HT); + 80019dc: 687b ldr r3, [r7, #4] + 80019de: 681b ldr r3, [r3, #0] + 80019e0: 681a ldr r2, [r3, #0] + 80019e2: 687b ldr r3, [r7, #4] + 80019e4: 681b ldr r3, [r3, #0] + 80019e6: f022 0208 bic.w r2, r2, #8 + 80019ea: 601a str r2, [r3, #0] + } + + if(hdma->XferHalfCpltCallback != NULL) + 80019ec: 687b ldr r3, [r7, #4] + 80019ee: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019f0: 2b00 cmp r3, #0 + 80019f2: d003 beq.n 80019fc + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + 80019f4: 687b ldr r3, [r7, #4] + 80019f6: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019f8: 6878 ldr r0, [r7, #4] + 80019fa: 4798 blx r3 + } + } + } + } + /* Transfer Complete Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET) + 80019fc: 687b ldr r3, [r7, #4] + 80019fe: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001a00: 2220 movs r2, #32 + 8001a02: 409a lsls r2, r3 + 8001a04: 68fb ldr r3, [r7, #12] + 8001a06: 4013 ands r3, r2 + 8001a08: 2b00 cmp r3, #0 + 8001a0a: f000 808e beq.w 8001b2a + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET) + 8001a0e: 687b ldr r3, [r7, #4] + 8001a10: 681b ldr r3, [r3, #0] + 8001a12: 681b ldr r3, [r3, #0] + 8001a14: f003 0310 and.w r3, r3, #16 + 8001a18: 2b00 cmp r3, #0 + 8001a1a: f000 8086 beq.w 8001b2a + { + /* Clear the transfer complete flag */ + regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; + 8001a1e: 687b ldr r3, [r7, #4] + 8001a20: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001a22: 2220 movs r2, #32 + 8001a24: 409a lsls r2, r3 + 8001a26: 693b ldr r3, [r7, #16] + 8001a28: 609a str r2, [r3, #8] + + if(HAL_DMA_STATE_ABORT == hdma->State) + 8001a2a: 687b ldr r3, [r7, #4] + 8001a2c: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 + 8001a30: b2db uxtb r3, r3 + 8001a32: 2b05 cmp r3, #5 + 8001a34: d136 bne.n 8001aa4 + { + /* Disable all the transfer interrupts */ + hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); + 8001a36: 687b ldr r3, [r7, #4] + 8001a38: 681b ldr r3, [r3, #0] + 8001a3a: 681a ldr r2, [r3, #0] + 8001a3c: 687b ldr r3, [r7, #4] + 8001a3e: 681b ldr r3, [r3, #0] + 8001a40: f022 0216 bic.w r2, r2, #22 + 8001a44: 601a str r2, [r3, #0] + hdma->Instance->FCR &= ~(DMA_IT_FE); + 8001a46: 687b ldr r3, [r7, #4] + 8001a48: 681b ldr r3, [r3, #0] + 8001a4a: 695a ldr r2, [r3, #20] + 8001a4c: 687b ldr r3, [r7, #4] + 8001a4e: 681b ldr r3, [r3, #0] + 8001a50: f022 0280 bic.w r2, r2, #128 ; 0x80 + 8001a54: 615a str r2, [r3, #20] + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + 8001a56: 687b ldr r3, [r7, #4] + 8001a58: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a5a: 2b00 cmp r3, #0 + 8001a5c: d103 bne.n 8001a66 + 8001a5e: 687b ldr r3, [r7, #4] + 8001a60: 6c9b ldr r3, [r3, #72] ; 0x48 + 8001a62: 2b00 cmp r3, #0 + 8001a64: d007 beq.n 8001a76 + { + hdma->Instance->CR &= ~(DMA_IT_HT); + 8001a66: 687b ldr r3, [r7, #4] + 8001a68: 681b ldr r3, [r3, #0] + 8001a6a: 681a ldr r2, [r3, #0] + 8001a6c: 687b ldr r3, [r7, #4] + 8001a6e: 681b ldr r3, [r3, #0] + 8001a70: f022 0208 bic.w r2, r2, #8 + 8001a74: 601a str r2, [r3, #0] + } + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + 8001a76: 687b ldr r3, [r7, #4] + 8001a78: 6ddb ldr r3, [r3, #92] ; 0x5c + 8001a7a: 223f movs r2, #63 ; 0x3f + 8001a7c: 409a lsls r2, r3 + 8001a7e: 693b ldr r3, [r7, #16] + 8001a80: 609a str r2, [r3, #8] + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + 8001a82: 687b ldr r3, [r7, #4] + 8001a84: 2200 movs r2, #0 + 8001a86: f883 2034 strb.w r2, [r3, #52] ; 0x34 + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + 8001a8a: 687b ldr r3, [r7, #4] + 8001a8c: 2201 movs r2, #1 + 8001a8e: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + if(hdma->XferAbortCallback != NULL) + 8001a92: 687b ldr r3, [r7, #4] + 8001a94: 6d1b ldr r3, [r3, #80] ; 0x50 + 8001a96: 2b00 cmp r3, #0 + 8001a98: d07d beq.n 8001b96 + { + hdma->XferAbortCallback(hdma); + 8001a9a: 687b ldr r3, [r7, #4] + 8001a9c: 6d1b ldr r3, [r3, #80] ; 0x50 + 8001a9e: 6878 ldr r0, [r7, #4] + 8001aa0: 4798 blx r3 + } + return; + 8001aa2: e078 b.n 8001b96 + } + + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + 8001aa4: 687b ldr r3, [r7, #4] + 8001aa6: 681b ldr r3, [r3, #0] + 8001aa8: 681b ldr r3, [r3, #0] + 8001aaa: f403 2380 and.w r3, r3, #262144 ; 0x40000 + 8001aae: 2b00 cmp r3, #0 + 8001ab0: d01c beq.n 8001aec + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + 8001ab2: 687b ldr r3, [r7, #4] + 8001ab4: 681b ldr r3, [r3, #0] + 8001ab6: 681b ldr r3, [r3, #0] + 8001ab8: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8001abc: 2b00 cmp r3, #0 + 8001abe: d108 bne.n 8001ad2 + { + if(hdma->XferM1CpltCallback != NULL) + 8001ac0: 687b ldr r3, [r7, #4] + 8001ac2: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001ac4: 2b00 cmp r3, #0 + 8001ac6: d030 beq.n 8001b2a + { + /* Transfer complete Callback for memory1 */ + hdma->XferM1CpltCallback(hdma); + 8001ac8: 687b ldr r3, [r7, #4] + 8001aca: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001acc: 6878 ldr r0, [r7, #4] + 8001ace: 4798 blx r3 + 8001ad0: e02b b.n 8001b2a + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferCpltCallback != NULL) + 8001ad2: 687b ldr r3, [r7, #4] + 8001ad4: 6bdb ldr r3, [r3, #60] ; 0x3c + 8001ad6: 2b00 cmp r3, #0 + 8001ad8: d027 beq.n 8001b2a + { + /* Transfer complete Callback for memory0 */ + hdma->XferCpltCallback(hdma); + 8001ada: 687b ldr r3, [r7, #4] + 8001adc: 6bdb ldr r3, [r3, #60] ; 0x3c + 8001ade: 6878 ldr r0, [r7, #4] + 8001ae0: 4798 blx r3 + 8001ae2: e022 b.n 8001b2a + 8001ae4: 20000000 .word 0x20000000 + 8001ae8: 1b4e81b5 .word 0x1b4e81b5 + } + } + /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ + else + { + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + 8001aec: 687b ldr r3, [r7, #4] + 8001aee: 681b ldr r3, [r3, #0] + 8001af0: 681b ldr r3, [r3, #0] + 8001af2: f403 7380 and.w r3, r3, #256 ; 0x100 + 8001af6: 2b00 cmp r3, #0 + 8001af8: d10f bne.n 8001b1a + { + /* Disable the transfer complete interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TC); + 8001afa: 687b ldr r3, [r7, #4] + 8001afc: 681b ldr r3, [r3, #0] + 8001afe: 681a ldr r2, [r3, #0] + 8001b00: 687b ldr r3, [r7, #4] + 8001b02: 681b ldr r3, [r3, #0] + 8001b04: f022 0210 bic.w r2, r2, #16 + 8001b08: 601a str r2, [r3, #0] + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + 8001b0a: 687b ldr r3, [r7, #4] + 8001b0c: 2200 movs r2, #0 + 8001b0e: f883 2034 strb.w r2, [r3, #52] ; 0x34 + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + 8001b12: 687b ldr r3, [r7, #4] + 8001b14: 2201 movs r2, #1 + 8001b16: f883 2035 strb.w r2, [r3, #53] ; 0x35 + } + + if(hdma->XferCpltCallback != NULL) + 8001b1a: 687b ldr r3, [r7, #4] + 8001b1c: 6bdb ldr r3, [r3, #60] ; 0x3c + 8001b1e: 2b00 cmp r3, #0 + 8001b20: d003 beq.n 8001b2a + { + /* Transfer complete callback */ + hdma->XferCpltCallback(hdma); + 8001b22: 687b ldr r3, [r7, #4] + 8001b24: 6bdb ldr r3, [r3, #60] ; 0x3c + 8001b26: 6878 ldr r0, [r7, #4] + 8001b28: 4798 blx r3 + } + } + } + + /* manage error case */ + if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) + 8001b2a: 687b ldr r3, [r7, #4] + 8001b2c: 6d5b ldr r3, [r3, #84] ; 0x54 + 8001b2e: 2b00 cmp r3, #0 + 8001b30: d032 beq.n 8001b98 + { + if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) + 8001b32: 687b ldr r3, [r7, #4] + 8001b34: 6d5b ldr r3, [r3, #84] ; 0x54 + 8001b36: f003 0301 and.w r3, r3, #1 + 8001b3a: 2b00 cmp r3, #0 + 8001b3c: d022 beq.n 8001b84 + { + hdma->State = HAL_DMA_STATE_ABORT; + 8001b3e: 687b ldr r3, [r7, #4] + 8001b40: 2205 movs r2, #5 + 8001b42: f883 2035 strb.w r2, [r3, #53] ; 0x35 + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + 8001b46: 687b ldr r3, [r7, #4] + 8001b48: 681b ldr r3, [r3, #0] + 8001b4a: 681a ldr r2, [r3, #0] + 8001b4c: 687b ldr r3, [r7, #4] + 8001b4e: 681b ldr r3, [r3, #0] + 8001b50: f022 0201 bic.w r2, r2, #1 + 8001b54: 601a str r2, [r3, #0] + + do + { + if (++count > timeout) + 8001b56: 68bb ldr r3, [r7, #8] + 8001b58: 3301 adds r3, #1 + 8001b5a: 60bb str r3, [r7, #8] + 8001b5c: 697a ldr r2, [r7, #20] + 8001b5e: 429a cmp r2, r3 + 8001b60: d307 bcc.n 8001b72 + { + break; + } + } + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET); + 8001b62: 687b ldr r3, [r7, #4] + 8001b64: 681b ldr r3, [r3, #0] + 8001b66: 681b ldr r3, [r3, #0] + 8001b68: f003 0301 and.w r3, r3, #1 + 8001b6c: 2b00 cmp r3, #0 + 8001b6e: d1f2 bne.n 8001b56 + 8001b70: e000 b.n 8001b74 + break; + 8001b72: bf00 nop + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + 8001b74: 687b ldr r3, [r7, #4] + 8001b76: 2200 movs r2, #0 + 8001b78: f883 2034 strb.w r2, [r3, #52] ; 0x34 + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + 8001b7c: 687b ldr r3, [r7, #4] + 8001b7e: 2201 movs r2, #1 + 8001b80: f883 2035 strb.w r2, [r3, #53] ; 0x35 + } + + if(hdma->XferErrorCallback != NULL) + 8001b84: 687b ldr r3, [r7, #4] + 8001b86: 6cdb ldr r3, [r3, #76] ; 0x4c + 8001b88: 2b00 cmp r3, #0 + 8001b8a: d005 beq.n 8001b98 + { + /* Transfer error callback */ + hdma->XferErrorCallback(hdma); + 8001b8c: 687b ldr r3, [r7, #4] + 8001b8e: 6cdb ldr r3, [r3, #76] ; 0x4c + 8001b90: 6878 ldr r0, [r7, #4] + 8001b92: 4798 blx r3 + 8001b94: e000 b.n 8001b98 + return; + 8001b96: bf00 nop + } + } +} + 8001b98: 3718 adds r7, #24 + 8001b9a: 46bd mov sp, r7 + 8001b9c: bd80 pop {r7, pc} + 8001b9e: bf00 nop + +08001ba0 : + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval Stream base address + */ +static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma) +{ + 8001ba0: b480 push {r7} + 8001ba2: b085 sub sp, #20 + 8001ba4: af00 add r7, sp, #0 + 8001ba6: 6078 str r0, [r7, #4] + uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U; + 8001ba8: 687b ldr r3, [r7, #4] + 8001baa: 681b ldr r3, [r3, #0] + 8001bac: b2db uxtb r3, r3 + 8001bae: 3b10 subs r3, #16 + 8001bb0: 4a13 ldr r2, [pc, #76] ; (8001c00 ) + 8001bb2: fba2 2303 umull r2, r3, r2, r3 + 8001bb6: 091b lsrs r3, r3, #4 + 8001bb8: 60fb str r3, [r7, #12] + + /* lookup table for necessary bitshift of flags within status registers */ + static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U}; + hdma->StreamIndex = flagBitshiftOffset[stream_number]; + 8001bba: 4a12 ldr r2, [pc, #72] ; (8001c04 ) + 8001bbc: 68fb ldr r3, [r7, #12] + 8001bbe: 4413 add r3, r2 + 8001bc0: 781b ldrb r3, [r3, #0] + 8001bc2: 461a mov r2, r3 + 8001bc4: 687b ldr r3, [r7, #4] + 8001bc6: 65da str r2, [r3, #92] ; 0x5c + + if (stream_number > 3U) + 8001bc8: 68fb ldr r3, [r7, #12] + 8001bca: 2b03 cmp r3, #3 + 8001bcc: d908 bls.n 8001be0 + { + /* return pointer to HISR and HIFCR */ + hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U); + 8001bce: 687b ldr r3, [r7, #4] + 8001bd0: 681b ldr r3, [r3, #0] + 8001bd2: 461a mov r2, r3 + 8001bd4: 4b0c ldr r3, [pc, #48] ; (8001c08 ) + 8001bd6: 4013 ands r3, r2 + 8001bd8: 1d1a adds r2, r3, #4 + 8001bda: 687b ldr r3, [r7, #4] + 8001bdc: 659a str r2, [r3, #88] ; 0x58 + 8001bde: e006 b.n 8001bee + } + else + { + /* return pointer to LISR and LIFCR */ + hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)); + 8001be0: 687b ldr r3, [r7, #4] + 8001be2: 681b ldr r3, [r3, #0] + 8001be4: 461a mov r2, r3 + 8001be6: 4b08 ldr r3, [pc, #32] ; (8001c08 ) + 8001be8: 4013 ands r3, r2 + 8001bea: 687a ldr r2, [r7, #4] + 8001bec: 6593 str r3, [r2, #88] ; 0x58 + } + + return hdma->StreamBaseAddress; + 8001bee: 687b ldr r3, [r7, #4] + 8001bf0: 6d9b ldr r3, [r3, #88] ; 0x58 +} + 8001bf2: 4618 mov r0, r3 + 8001bf4: 3714 adds r7, #20 + 8001bf6: 46bd mov sp, r7 + 8001bf8: f85d 7b04 ldr.w r7, [sp], #4 + 8001bfc: 4770 bx lr + 8001bfe: bf00 nop + 8001c00: aaaaaaab .word 0xaaaaaaab + 8001c04: 08004ec4 .word 0x08004ec4 + 8001c08: fffffc00 .word 0xfffffc00 + +08001c0c : + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma) +{ + 8001c0c: b480 push {r7} + 8001c0e: b085 sub sp, #20 + 8001c10: af00 add r7, sp, #0 + 8001c12: 6078 str r0, [r7, #4] + HAL_StatusTypeDef status = HAL_OK; + 8001c14: 2300 movs r3, #0 + 8001c16: 73fb strb r3, [r7, #15] + uint32_t tmp = hdma->Init.FIFOThreshold; + 8001c18: 687b ldr r3, [r7, #4] + 8001c1a: 6a9b ldr r3, [r3, #40] ; 0x28 + 8001c1c: 60bb str r3, [r7, #8] + + /* Memory Data size equal to Byte */ + if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE) + 8001c1e: 687b ldr r3, [r7, #4] + 8001c20: 699b ldr r3, [r3, #24] + 8001c22: 2b00 cmp r3, #0 + 8001c24: d11f bne.n 8001c66 + { + switch (tmp) + 8001c26: 68bb ldr r3, [r7, #8] + 8001c28: 2b03 cmp r3, #3 + 8001c2a: d855 bhi.n 8001cd8 + 8001c2c: a201 add r2, pc, #4 ; (adr r2, 8001c34 ) + 8001c2e: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8001c32: bf00 nop + 8001c34: 08001c45 .word 0x08001c45 + 8001c38: 08001c57 .word 0x08001c57 + 8001c3c: 08001c45 .word 0x08001c45 + 8001c40: 08001cd9 .word 0x08001cd9 + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + 8001c44: 687b ldr r3, [r7, #4] + 8001c46: 6adb ldr r3, [r3, #44] ; 0x2c + 8001c48: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8001c4c: 2b00 cmp r3, #0 + 8001c4e: d045 beq.n 8001cdc + { + status = HAL_ERROR; + 8001c50: 2301 movs r3, #1 + 8001c52: 73fb strb r3, [r7, #15] + } + break; + 8001c54: e042 b.n 8001cdc + case DMA_FIFO_THRESHOLD_HALFFULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + 8001c56: 687b ldr r3, [r7, #4] + 8001c58: 6adb ldr r3, [r3, #44] ; 0x2c + 8001c5a: f1b3 7fc0 cmp.w r3, #25165824 ; 0x1800000 + 8001c5e: d13f bne.n 8001ce0 + { + status = HAL_ERROR; + 8001c60: 2301 movs r3, #1 + 8001c62: 73fb strb r3, [r7, #15] + } + break; + 8001c64: e03c b.n 8001ce0 + break; + } + } + + /* Memory Data size equal to Half-Word */ + else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD) + 8001c66: 687b ldr r3, [r7, #4] + 8001c68: 699b ldr r3, [r3, #24] + 8001c6a: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8001c6e: d121 bne.n 8001cb4 + { + switch (tmp) + 8001c70: 68bb ldr r3, [r7, #8] + 8001c72: 2b03 cmp r3, #3 + 8001c74: d836 bhi.n 8001ce4 + 8001c76: a201 add r2, pc, #4 ; (adr r2, 8001c7c ) + 8001c78: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8001c7c: 08001c8d .word 0x08001c8d + 8001c80: 08001c93 .word 0x08001c93 + 8001c84: 08001c8d .word 0x08001c8d + 8001c88: 08001ca5 .word 0x08001ca5 + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + status = HAL_ERROR; + 8001c8c: 2301 movs r3, #1 + 8001c8e: 73fb strb r3, [r7, #15] + break; + 8001c90: e02f b.n 8001cf2 + case DMA_FIFO_THRESHOLD_HALFFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + 8001c92: 687b ldr r3, [r7, #4] + 8001c94: 6adb ldr r3, [r3, #44] ; 0x2c + 8001c96: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8001c9a: 2b00 cmp r3, #0 + 8001c9c: d024 beq.n 8001ce8 + { + status = HAL_ERROR; + 8001c9e: 2301 movs r3, #1 + 8001ca0: 73fb strb r3, [r7, #15] + } + break; + 8001ca2: e021 b.n 8001ce8 + case DMA_FIFO_THRESHOLD_FULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + 8001ca4: 687b ldr r3, [r7, #4] + 8001ca6: 6adb ldr r3, [r3, #44] ; 0x2c + 8001ca8: f1b3 7fc0 cmp.w r3, #25165824 ; 0x1800000 + 8001cac: d11e bne.n 8001cec + { + status = HAL_ERROR; + 8001cae: 2301 movs r3, #1 + 8001cb0: 73fb strb r3, [r7, #15] + } + break; + 8001cb2: e01b b.n 8001cec + } + + /* Memory Data size equal to Word */ + else + { + switch (tmp) + 8001cb4: 68bb ldr r3, [r7, #8] + 8001cb6: 2b02 cmp r3, #2 + 8001cb8: d902 bls.n 8001cc0 + 8001cba: 2b03 cmp r3, #3 + 8001cbc: d003 beq.n 8001cc6 + { + status = HAL_ERROR; + } + break; + default: + break; + 8001cbe: e018 b.n 8001cf2 + status = HAL_ERROR; + 8001cc0: 2301 movs r3, #1 + 8001cc2: 73fb strb r3, [r7, #15] + break; + 8001cc4: e015 b.n 8001cf2 + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + 8001cc6: 687b ldr r3, [r7, #4] + 8001cc8: 6adb ldr r3, [r3, #44] ; 0x2c + 8001cca: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8001cce: 2b00 cmp r3, #0 + 8001cd0: d00e beq.n 8001cf0 + status = HAL_ERROR; + 8001cd2: 2301 movs r3, #1 + 8001cd4: 73fb strb r3, [r7, #15] + break; + 8001cd6: e00b b.n 8001cf0 + break; + 8001cd8: bf00 nop + 8001cda: e00a b.n 8001cf2 + break; + 8001cdc: bf00 nop + 8001cde: e008 b.n 8001cf2 + break; + 8001ce0: bf00 nop + 8001ce2: e006 b.n 8001cf2 + break; + 8001ce4: bf00 nop + 8001ce6: e004 b.n 8001cf2 + break; + 8001ce8: bf00 nop + 8001cea: e002 b.n 8001cf2 + break; + 8001cec: bf00 nop + 8001cee: e000 b.n 8001cf2 + break; + 8001cf0: bf00 nop + } + } + + return status; + 8001cf2: 7bfb ldrb r3, [r7, #15] +} + 8001cf4: 4618 mov r0, r3 + 8001cf6: 3714 adds r7, #20 + 8001cf8: 46bd mov sp, r7 + 8001cfa: f85d 7b04 ldr.w r7, [sp], #4 + 8001cfe: 4770 bx lr + +08001d00 : + * @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) +{ + 8001d00: b480 push {r7} + 8001d02: b089 sub sp, #36 ; 0x24 + 8001d04: af00 add r7, sp, #0 + 8001d06: 6078 str r0, [r7, #4] + 8001d08: 6039 str r1, [r7, #0] + uint32_t position = 0x00; + 8001d0a: 2300 movs r3, #0 + 8001d0c: 61fb str r3, [r7, #28] + uint32_t ioposition = 0x00; + 8001d0e: 2300 movs r3, #0 + 8001d10: 617b str r3, [r7, #20] + uint32_t iocurrent = 0x00; + 8001d12: 2300 movs r3, #0 + 8001d14: 613b str r3, [r7, #16] + uint32_t temp = 0x00; + 8001d16: 2300 movs r3, #0 + 8001d18: 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++) + 8001d1a: 2300 movs r3, #0 + 8001d1c: 61fb str r3, [r7, #28] + 8001d1e: e175 b.n 800200c + { + /* Get the IO position */ + ioposition = ((uint32_t)0x01) << position; + 8001d20: 2201 movs r2, #1 + 8001d22: 69fb ldr r3, [r7, #28] + 8001d24: fa02 f303 lsl.w r3, r2, r3 + 8001d28: 617b str r3, [r7, #20] + /* Get the current IO position */ + iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; + 8001d2a: 683b ldr r3, [r7, #0] + 8001d2c: 681b ldr r3, [r3, #0] + 8001d2e: 697a ldr r2, [r7, #20] + 8001d30: 4013 ands r3, r2 + 8001d32: 613b str r3, [r7, #16] + + if(iocurrent == ioposition) + 8001d34: 693a ldr r2, [r7, #16] + 8001d36: 697b ldr r3, [r7, #20] + 8001d38: 429a cmp r2, r3 + 8001d3a: f040 8164 bne.w 8002006 + { + /*--------------------- 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)) + 8001d3e: 683b ldr r3, [r7, #0] + 8001d40: 685b ldr r3, [r3, #4] + 8001d42: 2b02 cmp r3, #2 + 8001d44: d003 beq.n 8001d4e + 8001d46: 683b ldr r3, [r7, #0] + 8001d48: 685b ldr r3, [r3, #4] + 8001d4a: 2b12 cmp r3, #18 + 8001d4c: d123 bne.n 8001d96 + { + /* 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]; + 8001d4e: 69fb ldr r3, [r7, #28] + 8001d50: 08da lsrs r2, r3, #3 + 8001d52: 687b ldr r3, [r7, #4] + 8001d54: 3208 adds r2, #8 + 8001d56: f853 3022 ldr.w r3, [r3, r2, lsl #2] + 8001d5a: 61bb str r3, [r7, #24] + temp &= ~((uint32_t)0xF << ((uint32_t)(position & (uint32_t)0x07) * 4)) ; + 8001d5c: 69fb ldr r3, [r7, #28] + 8001d5e: f003 0307 and.w r3, r3, #7 + 8001d62: 009b lsls r3, r3, #2 + 8001d64: 220f movs r2, #15 + 8001d66: fa02 f303 lsl.w r3, r2, r3 + 8001d6a: 43db mvns r3, r3 + 8001d6c: 69ba ldr r2, [r7, #24] + 8001d6e: 4013 ands r3, r2 + 8001d70: 61bb str r3, [r7, #24] + temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & (uint32_t)0x07) * 4)); + 8001d72: 683b ldr r3, [r7, #0] + 8001d74: 691a ldr r2, [r3, #16] + 8001d76: 69fb ldr r3, [r7, #28] + 8001d78: f003 0307 and.w r3, r3, #7 + 8001d7c: 009b lsls r3, r3, #2 + 8001d7e: fa02 f303 lsl.w r3, r2, r3 + 8001d82: 69ba ldr r2, [r7, #24] + 8001d84: 4313 orrs r3, r2 + 8001d86: 61bb str r3, [r7, #24] + GPIOx->AFR[position >> 3] = temp; + 8001d88: 69fb ldr r3, [r7, #28] + 8001d8a: 08da lsrs r2, r3, #3 + 8001d8c: 687b ldr r3, [r7, #4] + 8001d8e: 3208 adds r2, #8 + 8001d90: 69b9 ldr r1, [r7, #24] + 8001d92: f843 1022 str.w r1, [r3, r2, lsl #2] + } + + /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ + temp = GPIOx->MODER; + 8001d96: 687b ldr r3, [r7, #4] + 8001d98: 681b ldr r3, [r3, #0] + 8001d9a: 61bb str r3, [r7, #24] + temp &= ~(GPIO_MODER_MODER0 << (position * 2)); + 8001d9c: 69fb ldr r3, [r7, #28] + 8001d9e: 005b lsls r3, r3, #1 + 8001da0: 2203 movs r2, #3 + 8001da2: fa02 f303 lsl.w r3, r2, r3 + 8001da6: 43db mvns r3, r3 + 8001da8: 69ba ldr r2, [r7, #24] + 8001daa: 4013 ands r3, r2 + 8001dac: 61bb str r3, [r7, #24] + temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2)); + 8001dae: 683b ldr r3, [r7, #0] + 8001db0: 685b ldr r3, [r3, #4] + 8001db2: f003 0203 and.w r2, r3, #3 + 8001db6: 69fb ldr r3, [r7, #28] + 8001db8: 005b lsls r3, r3, #1 + 8001dba: fa02 f303 lsl.w r3, r2, r3 + 8001dbe: 69ba ldr r2, [r7, #24] + 8001dc0: 4313 orrs r3, r2 + 8001dc2: 61bb str r3, [r7, #24] + GPIOx->MODER = temp; + 8001dc4: 687b ldr r3, [r7, #4] + 8001dc6: 69ba ldr r2, [r7, #24] + 8001dc8: 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) || + 8001dca: 683b ldr r3, [r7, #0] + 8001dcc: 685b ldr r3, [r3, #4] + 8001dce: 2b01 cmp r3, #1 + 8001dd0: d00b beq.n 8001dea + 8001dd2: 683b ldr r3, [r7, #0] + 8001dd4: 685b ldr r3, [r3, #4] + 8001dd6: 2b02 cmp r3, #2 + 8001dd8: d007 beq.n 8001dea + (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) + 8001dda: 683b ldr r3, [r7, #0] + 8001ddc: 685b ldr r3, [r3, #4] + if((GPIO_Init->Mode == GPIO_MODE_OUTPUT_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_PP) || + 8001dde: 2b11 cmp r3, #17 + 8001de0: d003 beq.n 8001dea + (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) + 8001de2: 683b ldr r3, [r7, #0] + 8001de4: 685b ldr r3, [r3, #4] + 8001de6: 2b12 cmp r3, #18 + 8001de8: d130 bne.n 8001e4c + { + /* Check the Speed parameter */ + assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); + /* Configure the IO Speed */ + temp = GPIOx->OSPEEDR; + 8001dea: 687b ldr r3, [r7, #4] + 8001dec: 689b ldr r3, [r3, #8] + 8001dee: 61bb str r3, [r7, #24] + temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2)); + 8001df0: 69fb ldr r3, [r7, #28] + 8001df2: 005b lsls r3, r3, #1 + 8001df4: 2203 movs r2, #3 + 8001df6: fa02 f303 lsl.w r3, r2, r3 + 8001dfa: 43db mvns r3, r3 + 8001dfc: 69ba ldr r2, [r7, #24] + 8001dfe: 4013 ands r3, r2 + 8001e00: 61bb str r3, [r7, #24] + temp |= (GPIO_Init->Speed << (position * 2)); + 8001e02: 683b ldr r3, [r7, #0] + 8001e04: 68da ldr r2, [r3, #12] + 8001e06: 69fb ldr r3, [r7, #28] + 8001e08: 005b lsls r3, r3, #1 + 8001e0a: fa02 f303 lsl.w r3, r2, r3 + 8001e0e: 69ba ldr r2, [r7, #24] + 8001e10: 4313 orrs r3, r2 + 8001e12: 61bb str r3, [r7, #24] + GPIOx->OSPEEDR = temp; + 8001e14: 687b ldr r3, [r7, #4] + 8001e16: 69ba ldr r2, [r7, #24] + 8001e18: 609a str r2, [r3, #8] + + /* Configure the IO Output Type */ + temp = GPIOx->OTYPER; + 8001e1a: 687b ldr r3, [r7, #4] + 8001e1c: 685b ldr r3, [r3, #4] + 8001e1e: 61bb str r3, [r7, #24] + temp &= ~(GPIO_OTYPER_OT_0 << position) ; + 8001e20: 2201 movs r2, #1 + 8001e22: 69fb ldr r3, [r7, #28] + 8001e24: fa02 f303 lsl.w r3, r2, r3 + 8001e28: 43db mvns r3, r3 + 8001e2a: 69ba ldr r2, [r7, #24] + 8001e2c: 4013 ands r3, r2 + 8001e2e: 61bb str r3, [r7, #24] + temp |= (((GPIO_Init->Mode & GPIO_OUTPUT_TYPE) >> 4) << position); + 8001e30: 683b ldr r3, [r7, #0] + 8001e32: 685b ldr r3, [r3, #4] + 8001e34: 091b lsrs r3, r3, #4 + 8001e36: f003 0201 and.w r2, r3, #1 + 8001e3a: 69fb ldr r3, [r7, #28] + 8001e3c: fa02 f303 lsl.w r3, r2, r3 + 8001e40: 69ba ldr r2, [r7, #24] + 8001e42: 4313 orrs r3, r2 + 8001e44: 61bb str r3, [r7, #24] + GPIOx->OTYPER = temp; + 8001e46: 687b ldr r3, [r7, #4] + 8001e48: 69ba ldr r2, [r7, #24] + 8001e4a: 605a str r2, [r3, #4] + } + + /* Activate the Pull-up or Pull down resistor for the current IO */ + temp = GPIOx->PUPDR; + 8001e4c: 687b ldr r3, [r7, #4] + 8001e4e: 68db ldr r3, [r3, #12] + 8001e50: 61bb str r3, [r7, #24] + temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2)); + 8001e52: 69fb ldr r3, [r7, #28] + 8001e54: 005b lsls r3, r3, #1 + 8001e56: 2203 movs r2, #3 + 8001e58: fa02 f303 lsl.w r3, r2, r3 + 8001e5c: 43db mvns r3, r3 + 8001e5e: 69ba ldr r2, [r7, #24] + 8001e60: 4013 ands r3, r2 + 8001e62: 61bb str r3, [r7, #24] + temp |= ((GPIO_Init->Pull) << (position * 2)); + 8001e64: 683b ldr r3, [r7, #0] + 8001e66: 689a ldr r2, [r3, #8] + 8001e68: 69fb ldr r3, [r7, #28] + 8001e6a: 005b lsls r3, r3, #1 + 8001e6c: fa02 f303 lsl.w r3, r2, r3 + 8001e70: 69ba ldr r2, [r7, #24] + 8001e72: 4313 orrs r3, r2 + 8001e74: 61bb str r3, [r7, #24] + GPIOx->PUPDR = temp; + 8001e76: 687b ldr r3, [r7, #4] + 8001e78: 69ba ldr r2, [r7, #24] + 8001e7a: 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) + 8001e7c: 683b ldr r3, [r7, #0] + 8001e7e: 685b ldr r3, [r3, #4] + 8001e80: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8001e84: 2b00 cmp r3, #0 + 8001e86: f000 80be beq.w 8002006 + { + /* Enable SYSCFG Clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + 8001e8a: 4b65 ldr r3, [pc, #404] ; (8002020 ) + 8001e8c: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001e8e: 4a64 ldr r2, [pc, #400] ; (8002020 ) + 8001e90: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8001e94: 6453 str r3, [r2, #68] ; 0x44 + 8001e96: 4b62 ldr r3, [pc, #392] ; (8002020 ) + 8001e98: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001e9a: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8001e9e: 60fb str r3, [r7, #12] + 8001ea0: 68fb ldr r3, [r7, #12] + + temp = SYSCFG->EXTICR[position >> 2]; + 8001ea2: 4a60 ldr r2, [pc, #384] ; (8002024 ) + 8001ea4: 69fb ldr r3, [r7, #28] + 8001ea6: 089b lsrs r3, r3, #2 + 8001ea8: 3302 adds r3, #2 + 8001eaa: f852 3023 ldr.w r3, [r2, r3, lsl #2] + 8001eae: 61bb str r3, [r7, #24] + temp &= ~(((uint32_t)0x0F) << (4 * (position & 0x03))); + 8001eb0: 69fb ldr r3, [r7, #28] + 8001eb2: f003 0303 and.w r3, r3, #3 + 8001eb6: 009b lsls r3, r3, #2 + 8001eb8: 220f movs r2, #15 + 8001eba: fa02 f303 lsl.w r3, r2, r3 + 8001ebe: 43db mvns r3, r3 + 8001ec0: 69ba ldr r2, [r7, #24] + 8001ec2: 4013 ands r3, r2 + 8001ec4: 61bb str r3, [r7, #24] + temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4 * (position & 0x03))); + 8001ec6: 687b ldr r3, [r7, #4] + 8001ec8: 4a57 ldr r2, [pc, #348] ; (8002028 ) + 8001eca: 4293 cmp r3, r2 + 8001ecc: d037 beq.n 8001f3e + 8001ece: 687b ldr r3, [r7, #4] + 8001ed0: 4a56 ldr r2, [pc, #344] ; (800202c ) + 8001ed2: 4293 cmp r3, r2 + 8001ed4: d031 beq.n 8001f3a + 8001ed6: 687b ldr r3, [r7, #4] + 8001ed8: 4a55 ldr r2, [pc, #340] ; (8002030 ) + 8001eda: 4293 cmp r3, r2 + 8001edc: d02b beq.n 8001f36 + 8001ede: 687b ldr r3, [r7, #4] + 8001ee0: 4a54 ldr r2, [pc, #336] ; (8002034 ) + 8001ee2: 4293 cmp r3, r2 + 8001ee4: d025 beq.n 8001f32 + 8001ee6: 687b ldr r3, [r7, #4] + 8001ee8: 4a53 ldr r2, [pc, #332] ; (8002038 ) + 8001eea: 4293 cmp r3, r2 + 8001eec: d01f beq.n 8001f2e + 8001eee: 687b ldr r3, [r7, #4] + 8001ef0: 4a52 ldr r2, [pc, #328] ; (800203c ) + 8001ef2: 4293 cmp r3, r2 + 8001ef4: d019 beq.n 8001f2a + 8001ef6: 687b ldr r3, [r7, #4] + 8001ef8: 4a51 ldr r2, [pc, #324] ; (8002040 ) + 8001efa: 4293 cmp r3, r2 + 8001efc: d013 beq.n 8001f26 + 8001efe: 687b ldr r3, [r7, #4] + 8001f00: 4a50 ldr r2, [pc, #320] ; (8002044 ) + 8001f02: 4293 cmp r3, r2 + 8001f04: d00d beq.n 8001f22 + 8001f06: 687b ldr r3, [r7, #4] + 8001f08: 4a4f ldr r2, [pc, #316] ; (8002048 ) + 8001f0a: 4293 cmp r3, r2 + 8001f0c: d007 beq.n 8001f1e + 8001f0e: 687b ldr r3, [r7, #4] + 8001f10: 4a4e ldr r2, [pc, #312] ; (800204c ) + 8001f12: 4293 cmp r3, r2 + 8001f14: d101 bne.n 8001f1a + 8001f16: 2309 movs r3, #9 + 8001f18: e012 b.n 8001f40 + 8001f1a: 230a movs r3, #10 + 8001f1c: e010 b.n 8001f40 + 8001f1e: 2308 movs r3, #8 + 8001f20: e00e b.n 8001f40 + 8001f22: 2307 movs r3, #7 + 8001f24: e00c b.n 8001f40 + 8001f26: 2306 movs r3, #6 + 8001f28: e00a b.n 8001f40 + 8001f2a: 2305 movs r3, #5 + 8001f2c: e008 b.n 8001f40 + 8001f2e: 2304 movs r3, #4 + 8001f30: e006 b.n 8001f40 + 8001f32: 2303 movs r3, #3 + 8001f34: e004 b.n 8001f40 + 8001f36: 2302 movs r3, #2 + 8001f38: e002 b.n 8001f40 + 8001f3a: 2301 movs r3, #1 + 8001f3c: e000 b.n 8001f40 + 8001f3e: 2300 movs r3, #0 + 8001f40: 69fa ldr r2, [r7, #28] + 8001f42: f002 0203 and.w r2, r2, #3 + 8001f46: 0092 lsls r2, r2, #2 + 8001f48: 4093 lsls r3, r2 + 8001f4a: 69ba ldr r2, [r7, #24] + 8001f4c: 4313 orrs r3, r2 + 8001f4e: 61bb str r3, [r7, #24] + SYSCFG->EXTICR[position >> 2] = temp; + 8001f50: 4934 ldr r1, [pc, #208] ; (8002024 ) + 8001f52: 69fb ldr r3, [r7, #28] + 8001f54: 089b lsrs r3, r3, #2 + 8001f56: 3302 adds r3, #2 + 8001f58: 69ba ldr r2, [r7, #24] + 8001f5a: f841 2023 str.w r2, [r1, r3, lsl #2] + + /* Clear EXTI line configuration */ + temp = EXTI->IMR; + 8001f5e: 4b3c ldr r3, [pc, #240] ; (8002050 ) + 8001f60: 681b ldr r3, [r3, #0] + 8001f62: 61bb str r3, [r7, #24] + temp &= ~((uint32_t)iocurrent); + 8001f64: 693b ldr r3, [r7, #16] + 8001f66: 43db mvns r3, r3 + 8001f68: 69ba ldr r2, [r7, #24] + 8001f6a: 4013 ands r3, r2 + 8001f6c: 61bb str r3, [r7, #24] + if((GPIO_Init->Mode & GPIO_MODE_IT) == GPIO_MODE_IT) + 8001f6e: 683b ldr r3, [r7, #0] + 8001f70: 685b ldr r3, [r3, #4] + 8001f72: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 8001f76: 2b00 cmp r3, #0 + 8001f78: d003 beq.n 8001f82 + { + temp |= iocurrent; + 8001f7a: 69ba ldr r2, [r7, #24] + 8001f7c: 693b ldr r3, [r7, #16] + 8001f7e: 4313 orrs r3, r2 + 8001f80: 61bb str r3, [r7, #24] + } + EXTI->IMR = temp; + 8001f82: 4a33 ldr r2, [pc, #204] ; (8002050 ) + 8001f84: 69bb ldr r3, [r7, #24] + 8001f86: 6013 str r3, [r2, #0] + + temp = EXTI->EMR; + 8001f88: 4b31 ldr r3, [pc, #196] ; (8002050 ) + 8001f8a: 685b ldr r3, [r3, #4] + 8001f8c: 61bb str r3, [r7, #24] + temp &= ~((uint32_t)iocurrent); + 8001f8e: 693b ldr r3, [r7, #16] + 8001f90: 43db mvns r3, r3 + 8001f92: 69ba ldr r2, [r7, #24] + 8001f94: 4013 ands r3, r2 + 8001f96: 61bb str r3, [r7, #24] + if((GPIO_Init->Mode & GPIO_MODE_EVT) == GPIO_MODE_EVT) + 8001f98: 683b ldr r3, [r7, #0] + 8001f9a: 685b ldr r3, [r3, #4] + 8001f9c: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 8001fa0: 2b00 cmp r3, #0 + 8001fa2: d003 beq.n 8001fac + { + temp |= iocurrent; + 8001fa4: 69ba ldr r2, [r7, #24] + 8001fa6: 693b ldr r3, [r7, #16] + 8001fa8: 4313 orrs r3, r2 + 8001faa: 61bb str r3, [r7, #24] + } + EXTI->EMR = temp; + 8001fac: 4a28 ldr r2, [pc, #160] ; (8002050 ) + 8001fae: 69bb ldr r3, [r7, #24] + 8001fb0: 6053 str r3, [r2, #4] + + /* Clear Rising Falling edge configuration */ + temp = EXTI->RTSR; + 8001fb2: 4b27 ldr r3, [pc, #156] ; (8002050 ) + 8001fb4: 689b ldr r3, [r3, #8] + 8001fb6: 61bb str r3, [r7, #24] + temp &= ~((uint32_t)iocurrent); + 8001fb8: 693b ldr r3, [r7, #16] + 8001fba: 43db mvns r3, r3 + 8001fbc: 69ba ldr r2, [r7, #24] + 8001fbe: 4013 ands r3, r2 + 8001fc0: 61bb str r3, [r7, #24] + if((GPIO_Init->Mode & RISING_EDGE) == RISING_EDGE) + 8001fc2: 683b ldr r3, [r7, #0] + 8001fc4: 685b ldr r3, [r3, #4] + 8001fc6: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8001fca: 2b00 cmp r3, #0 + 8001fcc: d003 beq.n 8001fd6 + { + temp |= iocurrent; + 8001fce: 69ba ldr r2, [r7, #24] + 8001fd0: 693b ldr r3, [r7, #16] + 8001fd2: 4313 orrs r3, r2 + 8001fd4: 61bb str r3, [r7, #24] + } + EXTI->RTSR = temp; + 8001fd6: 4a1e ldr r2, [pc, #120] ; (8002050 ) + 8001fd8: 69bb ldr r3, [r7, #24] + 8001fda: 6093 str r3, [r2, #8] + + temp = EXTI->FTSR; + 8001fdc: 4b1c ldr r3, [pc, #112] ; (8002050 ) + 8001fde: 68db ldr r3, [r3, #12] + 8001fe0: 61bb str r3, [r7, #24] + temp &= ~((uint32_t)iocurrent); + 8001fe2: 693b ldr r3, [r7, #16] + 8001fe4: 43db mvns r3, r3 + 8001fe6: 69ba ldr r2, [r7, #24] + 8001fe8: 4013 ands r3, r2 + 8001fea: 61bb str r3, [r7, #24] + if((GPIO_Init->Mode & FALLING_EDGE) == FALLING_EDGE) + 8001fec: 683b ldr r3, [r7, #0] + 8001fee: 685b ldr r3, [r3, #4] + 8001ff0: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8001ff4: 2b00 cmp r3, #0 + 8001ff6: d003 beq.n 8002000 + { + temp |= iocurrent; + 8001ff8: 69ba ldr r2, [r7, #24] + 8001ffa: 693b ldr r3, [r7, #16] + 8001ffc: 4313 orrs r3, r2 + 8001ffe: 61bb str r3, [r7, #24] + } + EXTI->FTSR = temp; + 8002000: 4a13 ldr r2, [pc, #76] ; (8002050 ) + 8002002: 69bb ldr r3, [r7, #24] + 8002004: 60d3 str r3, [r2, #12] + for(position = 0; position < GPIO_NUMBER; position++) + 8002006: 69fb ldr r3, [r7, #28] + 8002008: 3301 adds r3, #1 + 800200a: 61fb str r3, [r7, #28] + 800200c: 69fb ldr r3, [r7, #28] + 800200e: 2b0f cmp r3, #15 + 8002010: f67f ae86 bls.w 8001d20 + } + } + } +} + 8002014: bf00 nop + 8002016: 3724 adds r7, #36 ; 0x24 + 8002018: 46bd mov sp, r7 + 800201a: f85d 7b04 ldr.w r7, [sp], #4 + 800201e: 4770 bx lr + 8002020: 40023800 .word 0x40023800 + 8002024: 40013800 .word 0x40013800 + 8002028: 40020000 .word 0x40020000 + 800202c: 40020400 .word 0x40020400 + 8002030: 40020800 .word 0x40020800 + 8002034: 40020c00 .word 0x40020c00 + 8002038: 40021000 .word 0x40021000 + 800203c: 40021400 .word 0x40021400 + 8002040: 40021800 .word 0x40021800 + 8002044: 40021c00 .word 0x40021c00 + 8002048: 40022000 .word 0x40022000 + 800204c: 40022400 .word 0x40022400 + 8002050: 40013c00 .word 0x40013c00 + +08002054 : + * @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) +{ + 8002054: b480 push {r7} + 8002056: b083 sub sp, #12 + 8002058: af00 add r7, sp, #0 + 800205a: 6078 str r0, [r7, #4] + 800205c: 460b mov r3, r1 + 800205e: 807b strh r3, [r7, #2] + 8002060: 4613 mov r3, r2 + 8002062: 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) + 8002064: 787b ldrb r3, [r7, #1] + 8002066: 2b00 cmp r3, #0 + 8002068: d003 beq.n 8002072 + { + GPIOx->BSRR = GPIO_Pin; + 800206a: 887a ldrh r2, [r7, #2] + 800206c: 687b ldr r3, [r7, #4] + 800206e: 619a str r2, [r3, #24] + } + else + { + GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; + } +} + 8002070: e003 b.n 800207a + GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; + 8002072: 887b ldrh r3, [r7, #2] + 8002074: 041a lsls r2, r3, #16 + 8002076: 687b ldr r3, [r7, #4] + 8002078: 619a str r2, [r3, #24] +} + 800207a: bf00 nop + 800207c: 370c adds r7, #12 + 800207e: 46bd mov sp, r7 + 8002080: f85d 7b04 ldr.w r7, [sp], #4 + 8002084: 4770 bx lr + ... + +08002088 : + * 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) +{ + 8002088: b580 push {r7, lr} + 800208a: b086 sub sp, #24 + 800208c: af00 add r7, sp, #0 + 800208e: 6078 str r0, [r7, #4] + uint32_t tickstart; + FlagStatus pwrclkchanged = RESET; + 8002090: 2300 movs r3, #0 + 8002092: 75fb strb r3, [r7, #23] + + /* Check Null pointer */ + if(RCC_OscInitStruct == NULL) + 8002094: 687b ldr r3, [r7, #4] + 8002096: 2b00 cmp r3, #0 + 8002098: d101 bne.n 800209e + { + return HAL_ERROR; + 800209a: 2301 movs r3, #1 + 800209c: e25e b.n 800255c + + /* Check the parameters */ + assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); + + /*------------------------------- HSE Configuration ------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) + 800209e: 687b ldr r3, [r7, #4] + 80020a0: 681b ldr r3, [r3, #0] + 80020a2: f003 0301 and.w r3, r3, #1 + 80020a6: 2b00 cmp r3, #0 + 80020a8: f000 8087 beq.w 80021ba + { + /* 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) + 80020ac: 4b96 ldr r3, [pc, #600] ; (8002308 ) + 80020ae: 689b ldr r3, [r3, #8] + 80020b0: f003 030c and.w r3, r3, #12 + 80020b4: 2b04 cmp r3, #4 + 80020b6: d00c beq.n 80020d2 + || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) + 80020b8: 4b93 ldr r3, [pc, #588] ; (8002308 ) + 80020ba: 689b ldr r3, [r3, #8] + 80020bc: f003 030c and.w r3, r3, #12 + 80020c0: 2b08 cmp r3, #8 + 80020c2: d112 bne.n 80020ea + 80020c4: 4b90 ldr r3, [pc, #576] ; (8002308 ) + 80020c6: 685b ldr r3, [r3, #4] + 80020c8: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 80020cc: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 80020d0: d10b bne.n 80020ea + { + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + 80020d2: 4b8d ldr r3, [pc, #564] ; (8002308 ) + 80020d4: 681b ldr r3, [r3, #0] + 80020d6: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80020da: 2b00 cmp r3, #0 + 80020dc: d06c beq.n 80021b8 + 80020de: 687b ldr r3, [r7, #4] + 80020e0: 685b ldr r3, [r3, #4] + 80020e2: 2b00 cmp r3, #0 + 80020e4: d168 bne.n 80021b8 + { + return HAL_ERROR; + 80020e6: 2301 movs r3, #1 + 80020e8: e238 b.n 800255c + } + } + else + { + /* Set the new HSE configuration ---------------------------------------*/ + __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); + 80020ea: 687b ldr r3, [r7, #4] + 80020ec: 685b ldr r3, [r3, #4] + 80020ee: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 80020f2: d106 bne.n 8002102 + 80020f4: 4b84 ldr r3, [pc, #528] ; (8002308 ) + 80020f6: 681b ldr r3, [r3, #0] + 80020f8: 4a83 ldr r2, [pc, #524] ; (8002308 ) + 80020fa: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 80020fe: 6013 str r3, [r2, #0] + 8002100: e02e b.n 8002160 + 8002102: 687b ldr r3, [r7, #4] + 8002104: 685b ldr r3, [r3, #4] + 8002106: 2b00 cmp r3, #0 + 8002108: d10c bne.n 8002124 + 800210a: 4b7f ldr r3, [pc, #508] ; (8002308 ) + 800210c: 681b ldr r3, [r3, #0] + 800210e: 4a7e ldr r2, [pc, #504] ; (8002308 ) + 8002110: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002114: 6013 str r3, [r2, #0] + 8002116: 4b7c ldr r3, [pc, #496] ; (8002308 ) + 8002118: 681b ldr r3, [r3, #0] + 800211a: 4a7b ldr r2, [pc, #492] ; (8002308 ) + 800211c: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8002120: 6013 str r3, [r2, #0] + 8002122: e01d b.n 8002160 + 8002124: 687b ldr r3, [r7, #4] + 8002126: 685b ldr r3, [r3, #4] + 8002128: f5b3 2fa0 cmp.w r3, #327680 ; 0x50000 + 800212c: d10c bne.n 8002148 + 800212e: 4b76 ldr r3, [pc, #472] ; (8002308 ) + 8002130: 681b ldr r3, [r3, #0] + 8002132: 4a75 ldr r2, [pc, #468] ; (8002308 ) + 8002134: f443 2380 orr.w r3, r3, #262144 ; 0x40000 + 8002138: 6013 str r3, [r2, #0] + 800213a: 4b73 ldr r3, [pc, #460] ; (8002308 ) + 800213c: 681b ldr r3, [r3, #0] + 800213e: 4a72 ldr r2, [pc, #456] ; (8002308 ) + 8002140: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 8002144: 6013 str r3, [r2, #0] + 8002146: e00b b.n 8002160 + 8002148: 4b6f ldr r3, [pc, #444] ; (8002308 ) + 800214a: 681b ldr r3, [r3, #0] + 800214c: 4a6e ldr r2, [pc, #440] ; (8002308 ) + 800214e: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002152: 6013 str r3, [r2, #0] + 8002154: 4b6c ldr r3, [pc, #432] ; (8002308 ) + 8002156: 681b ldr r3, [r3, #0] + 8002158: 4a6b ldr r2, [pc, #428] ; (8002308 ) + 800215a: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 800215e: 6013 str r3, [r2, #0] + + /* Check the HSE State */ + if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF) + 8002160: 687b ldr r3, [r7, #4] + 8002162: 685b ldr r3, [r3, #4] + 8002164: 2b00 cmp r3, #0 + 8002166: d013 beq.n 8002190 + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002168: f7ff f9a2 bl 80014b0 + 800216c: 6138 str r0, [r7, #16] + + /* Wait till HSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + 800216e: e008 b.n 8002182 + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + 8002170: f7ff f99e bl 80014b0 + 8002174: 4602 mov r2, r0 + 8002176: 693b ldr r3, [r7, #16] + 8002178: 1ad3 subs r3, r2, r3 + 800217a: 2b64 cmp r3, #100 ; 0x64 + 800217c: d901 bls.n 8002182 + { + return HAL_TIMEOUT; + 800217e: 2303 movs r3, #3 + 8002180: e1ec b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + 8002182: 4b61 ldr r3, [pc, #388] ; (8002308 ) + 8002184: 681b ldr r3, [r3, #0] + 8002186: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800218a: 2b00 cmp r3, #0 + 800218c: d0f0 beq.n 8002170 + 800218e: e014 b.n 80021ba + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002190: f7ff f98e bl 80014b0 + 8002194: 6138 str r0, [r7, #16] + + /* Wait till HSE is bypassed or disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + 8002196: e008 b.n 80021aa + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + 8002198: f7ff f98a bl 80014b0 + 800219c: 4602 mov r2, r0 + 800219e: 693b ldr r3, [r7, #16] + 80021a0: 1ad3 subs r3, r2, r3 + 80021a2: 2b64 cmp r3, #100 ; 0x64 + 80021a4: d901 bls.n 80021aa + { + return HAL_TIMEOUT; + 80021a6: 2303 movs r3, #3 + 80021a8: e1d8 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + 80021aa: 4b57 ldr r3, [pc, #348] ; (8002308 ) + 80021ac: 681b ldr r3, [r3, #0] + 80021ae: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80021b2: 2b00 cmp r3, #0 + 80021b4: d1f0 bne.n 8002198 + 80021b6: e000 b.n 80021ba + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + 80021b8: bf00 nop + } + } + } + } + /*----------------------------- HSI Configuration --------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) + 80021ba: 687b ldr r3, [r7, #4] + 80021bc: 681b ldr r3, [r3, #0] + 80021be: f003 0302 and.w r3, r3, #2 + 80021c2: 2b00 cmp r3, #0 + 80021c4: d069 beq.n 800229a + /* 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) + 80021c6: 4b50 ldr r3, [pc, #320] ; (8002308 ) + 80021c8: 689b ldr r3, [r3, #8] + 80021ca: f003 030c and.w r3, r3, #12 + 80021ce: 2b00 cmp r3, #0 + 80021d0: d00b beq.n 80021ea + || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) + 80021d2: 4b4d ldr r3, [pc, #308] ; (8002308 ) + 80021d4: 689b ldr r3, [r3, #8] + 80021d6: f003 030c and.w r3, r3, #12 + 80021da: 2b08 cmp r3, #8 + 80021dc: d11c bne.n 8002218 + 80021de: 4b4a ldr r3, [pc, #296] ; (8002308 ) + 80021e0: 685b ldr r3, [r3, #4] + 80021e2: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 80021e6: 2b00 cmp r3, #0 + 80021e8: d116 bne.n 8002218 + { + /* 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)) + 80021ea: 4b47 ldr r3, [pc, #284] ; (8002308 ) + 80021ec: 681b ldr r3, [r3, #0] + 80021ee: f003 0302 and.w r3, r3, #2 + 80021f2: 2b00 cmp r3, #0 + 80021f4: d005 beq.n 8002202 + 80021f6: 687b ldr r3, [r7, #4] + 80021f8: 68db ldr r3, [r3, #12] + 80021fa: 2b01 cmp r3, #1 + 80021fc: d001 beq.n 8002202 + { + return HAL_ERROR; + 80021fe: 2301 movs r3, #1 + 8002200: e1ac b.n 800255c + } + /* Otherwise, just the calibration is allowed */ + else + { + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + 8002202: 4b41 ldr r3, [pc, #260] ; (8002308 ) + 8002204: 681b ldr r3, [r3, #0] + 8002206: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 800220a: 687b ldr r3, [r7, #4] + 800220c: 691b ldr r3, [r3, #16] + 800220e: 00db lsls r3, r3, #3 + 8002210: 493d ldr r1, [pc, #244] ; (8002308 ) + 8002212: 4313 orrs r3, r2 + 8002214: 600b str r3, [r1, #0] + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) + 8002216: e040 b.n 800229a + } + } + else + { + /* Check the HSI State */ + if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) + 8002218: 687b ldr r3, [r7, #4] + 800221a: 68db ldr r3, [r3, #12] + 800221c: 2b00 cmp r3, #0 + 800221e: d023 beq.n 8002268 + { + /* Enable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_ENABLE(); + 8002220: 4b39 ldr r3, [pc, #228] ; (8002308 ) + 8002222: 681b ldr r3, [r3, #0] + 8002224: 4a38 ldr r2, [pc, #224] ; (8002308 ) + 8002226: f043 0301 orr.w r3, r3, #1 + 800222a: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 800222c: f7ff f940 bl 80014b0 + 8002230: 6138 str r0, [r7, #16] + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + 8002232: e008 b.n 8002246 + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + 8002234: f7ff f93c bl 80014b0 + 8002238: 4602 mov r2, r0 + 800223a: 693b ldr r3, [r7, #16] + 800223c: 1ad3 subs r3, r2, r3 + 800223e: 2b02 cmp r3, #2 + 8002240: d901 bls.n 8002246 + { + return HAL_TIMEOUT; + 8002242: 2303 movs r3, #3 + 8002244: e18a b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + 8002246: 4b30 ldr r3, [pc, #192] ; (8002308 ) + 8002248: 681b ldr r3, [r3, #0] + 800224a: f003 0302 and.w r3, r3, #2 + 800224e: 2b00 cmp r3, #0 + 8002250: d0f0 beq.n 8002234 + } + } + + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + 8002252: 4b2d ldr r3, [pc, #180] ; (8002308 ) + 8002254: 681b ldr r3, [r3, #0] + 8002256: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 800225a: 687b ldr r3, [r7, #4] + 800225c: 691b ldr r3, [r3, #16] + 800225e: 00db lsls r3, r3, #3 + 8002260: 4929 ldr r1, [pc, #164] ; (8002308 ) + 8002262: 4313 orrs r3, r2 + 8002264: 600b str r3, [r1, #0] + 8002266: e018 b.n 800229a + } + else + { + /* Disable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_DISABLE(); + 8002268: 4b27 ldr r3, [pc, #156] ; (8002308 ) + 800226a: 681b ldr r3, [r3, #0] + 800226c: 4a26 ldr r2, [pc, #152] ; (8002308 ) + 800226e: f023 0301 bic.w r3, r3, #1 + 8002272: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002274: f7ff f91c bl 80014b0 + 8002278: 6138 str r0, [r7, #16] + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + 800227a: e008 b.n 800228e + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + 800227c: f7ff f918 bl 80014b0 + 8002280: 4602 mov r2, r0 + 8002282: 693b ldr r3, [r7, #16] + 8002284: 1ad3 subs r3, r2, r3 + 8002286: 2b02 cmp r3, #2 + 8002288: d901 bls.n 800228e + { + return HAL_TIMEOUT; + 800228a: 2303 movs r3, #3 + 800228c: e166 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + 800228e: 4b1e ldr r3, [pc, #120] ; (8002308 ) + 8002290: 681b ldr r3, [r3, #0] + 8002292: f003 0302 and.w r3, r3, #2 + 8002296: 2b00 cmp r3, #0 + 8002298: d1f0 bne.n 800227c + } + } + } + } + /*------------------------------ LSI Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) + 800229a: 687b ldr r3, [r7, #4] + 800229c: 681b ldr r3, [r3, #0] + 800229e: f003 0308 and.w r3, r3, #8 + 80022a2: 2b00 cmp r3, #0 + 80022a4: d038 beq.n 8002318 + { + /* Check the parameters */ + assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); + + /* Check the LSI State */ + if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) + 80022a6: 687b ldr r3, [r7, #4] + 80022a8: 695b ldr r3, [r3, #20] + 80022aa: 2b00 cmp r3, #0 + 80022ac: d019 beq.n 80022e2 + { + /* Enable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_ENABLE(); + 80022ae: 4b16 ldr r3, [pc, #88] ; (8002308 ) + 80022b0: 6f5b ldr r3, [r3, #116] ; 0x74 + 80022b2: 4a15 ldr r2, [pc, #84] ; (8002308 ) + 80022b4: f043 0301 orr.w r3, r3, #1 + 80022b8: 6753 str r3, [r2, #116] ; 0x74 + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 80022ba: f7ff f8f9 bl 80014b0 + 80022be: 6138 str r0, [r7, #16] + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + 80022c0: e008 b.n 80022d4 + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + 80022c2: f7ff f8f5 bl 80014b0 + 80022c6: 4602 mov r2, r0 + 80022c8: 693b ldr r3, [r7, #16] + 80022ca: 1ad3 subs r3, r2, r3 + 80022cc: 2b02 cmp r3, #2 + 80022ce: d901 bls.n 80022d4 + { + return HAL_TIMEOUT; + 80022d0: 2303 movs r3, #3 + 80022d2: e143 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + 80022d4: 4b0c ldr r3, [pc, #48] ; (8002308 ) + 80022d6: 6f5b ldr r3, [r3, #116] ; 0x74 + 80022d8: f003 0302 and.w r3, r3, #2 + 80022dc: 2b00 cmp r3, #0 + 80022de: d0f0 beq.n 80022c2 + 80022e0: e01a b.n 8002318 + } + } + else + { + /* Disable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_DISABLE(); + 80022e2: 4b09 ldr r3, [pc, #36] ; (8002308 ) + 80022e4: 6f5b ldr r3, [r3, #116] ; 0x74 + 80022e6: 4a08 ldr r2, [pc, #32] ; (8002308 ) + 80022e8: f023 0301 bic.w r3, r3, #1 + 80022ec: 6753 str r3, [r2, #116] ; 0x74 + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 80022ee: f7ff f8df bl 80014b0 + 80022f2: 6138 str r0, [r7, #16] + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + 80022f4: e00a b.n 800230c + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + 80022f6: f7ff f8db bl 80014b0 + 80022fa: 4602 mov r2, r0 + 80022fc: 693b ldr r3, [r7, #16] + 80022fe: 1ad3 subs r3, r2, r3 + 8002300: 2b02 cmp r3, #2 + 8002302: d903 bls.n 800230c + { + return HAL_TIMEOUT; + 8002304: 2303 movs r3, #3 + 8002306: e129 b.n 800255c + 8002308: 40023800 .word 0x40023800 + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + 800230c: 4b95 ldr r3, [pc, #596] ; (8002564 ) + 800230e: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002310: f003 0302 and.w r3, r3, #2 + 8002314: 2b00 cmp r3, #0 + 8002316: d1ee bne.n 80022f6 + } + } + } + } + /*------------------------------ LSE Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) + 8002318: 687b ldr r3, [r7, #4] + 800231a: 681b ldr r3, [r3, #0] + 800231c: f003 0304 and.w r3, r3, #4 + 8002320: 2b00 cmp r3, #0 + 8002322: f000 80a4 beq.w 800246e + /* 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()) + 8002326: 4b8f ldr r3, [pc, #572] ; (8002564 ) + 8002328: 6c1b ldr r3, [r3, #64] ; 0x40 + 800232a: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 800232e: 2b00 cmp r3, #0 + 8002330: d10d bne.n 800234e + { + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + 8002332: 4b8c ldr r3, [pc, #560] ; (8002564 ) + 8002334: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002336: 4a8b ldr r2, [pc, #556] ; (8002564 ) + 8002338: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 800233c: 6413 str r3, [r2, #64] ; 0x40 + 800233e: 4b89 ldr r3, [pc, #548] ; (8002564 ) + 8002340: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002342: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002346: 60fb str r3, [r7, #12] + 8002348: 68fb ldr r3, [r7, #12] + pwrclkchanged = SET; + 800234a: 2301 movs r3, #1 + 800234c: 75fb strb r3, [r7, #23] + } + + if(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) + 800234e: 4b86 ldr r3, [pc, #536] ; (8002568 ) + 8002350: 681b ldr r3, [r3, #0] + 8002352: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002356: 2b00 cmp r3, #0 + 8002358: d118 bne.n 800238c + { + /* Enable write access to Backup domain */ + PWR->CR1 |= PWR_CR1_DBP; + 800235a: 4b83 ldr r3, [pc, #524] ; (8002568 ) + 800235c: 681b ldr r3, [r3, #0] + 800235e: 4a82 ldr r2, [pc, #520] ; (8002568 ) + 8002360: f443 7380 orr.w r3, r3, #256 ; 0x100 + 8002364: 6013 str r3, [r2, #0] + + /* Wait for Backup domain Write protection disable */ + tickstart = HAL_GetTick(); + 8002366: f7ff f8a3 bl 80014b0 + 800236a: 6138 str r0, [r7, #16] + + while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) + 800236c: e008 b.n 8002380 + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + 800236e: f7ff f89f bl 80014b0 + 8002372: 4602 mov r2, r0 + 8002374: 693b ldr r3, [r7, #16] + 8002376: 1ad3 subs r3, r2, r3 + 8002378: 2b64 cmp r3, #100 ; 0x64 + 800237a: d901 bls.n 8002380 + { + return HAL_TIMEOUT; + 800237c: 2303 movs r3, #3 + 800237e: e0ed b.n 800255c + while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) + 8002380: 4b79 ldr r3, [pc, #484] ; (8002568 ) + 8002382: 681b ldr r3, [r3, #0] + 8002384: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002388: 2b00 cmp r3, #0 + 800238a: d0f0 beq.n 800236e + } + } + } + + /* Set the new LSE configuration -----------------------------------------*/ + __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); + 800238c: 687b ldr r3, [r7, #4] + 800238e: 689b ldr r3, [r3, #8] + 8002390: 2b01 cmp r3, #1 + 8002392: d106 bne.n 80023a2 + 8002394: 4b73 ldr r3, [pc, #460] ; (8002564 ) + 8002396: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002398: 4a72 ldr r2, [pc, #456] ; (8002564 ) + 800239a: f043 0301 orr.w r3, r3, #1 + 800239e: 6713 str r3, [r2, #112] ; 0x70 + 80023a0: e02d b.n 80023fe + 80023a2: 687b ldr r3, [r7, #4] + 80023a4: 689b ldr r3, [r3, #8] + 80023a6: 2b00 cmp r3, #0 + 80023a8: d10c bne.n 80023c4 + 80023aa: 4b6e ldr r3, [pc, #440] ; (8002564 ) + 80023ac: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023ae: 4a6d ldr r2, [pc, #436] ; (8002564 ) + 80023b0: f023 0301 bic.w r3, r3, #1 + 80023b4: 6713 str r3, [r2, #112] ; 0x70 + 80023b6: 4b6b ldr r3, [pc, #428] ; (8002564 ) + 80023b8: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023ba: 4a6a ldr r2, [pc, #424] ; (8002564 ) + 80023bc: f023 0304 bic.w r3, r3, #4 + 80023c0: 6713 str r3, [r2, #112] ; 0x70 + 80023c2: e01c b.n 80023fe + 80023c4: 687b ldr r3, [r7, #4] + 80023c6: 689b ldr r3, [r3, #8] + 80023c8: 2b05 cmp r3, #5 + 80023ca: d10c bne.n 80023e6 + 80023cc: 4b65 ldr r3, [pc, #404] ; (8002564 ) + 80023ce: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023d0: 4a64 ldr r2, [pc, #400] ; (8002564 ) + 80023d2: f043 0304 orr.w r3, r3, #4 + 80023d6: 6713 str r3, [r2, #112] ; 0x70 + 80023d8: 4b62 ldr r3, [pc, #392] ; (8002564 ) + 80023da: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023dc: 4a61 ldr r2, [pc, #388] ; (8002564 ) + 80023de: f043 0301 orr.w r3, r3, #1 + 80023e2: 6713 str r3, [r2, #112] ; 0x70 + 80023e4: e00b b.n 80023fe + 80023e6: 4b5f ldr r3, [pc, #380] ; (8002564 ) + 80023e8: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023ea: 4a5e ldr r2, [pc, #376] ; (8002564 ) + 80023ec: f023 0301 bic.w r3, r3, #1 + 80023f0: 6713 str r3, [r2, #112] ; 0x70 + 80023f2: 4b5c ldr r3, [pc, #368] ; (8002564 ) + 80023f4: 6f1b ldr r3, [r3, #112] ; 0x70 + 80023f6: 4a5b ldr r2, [pc, #364] ; (8002564 ) + 80023f8: f023 0304 bic.w r3, r3, #4 + 80023fc: 6713 str r3, [r2, #112] ; 0x70 + /* Check the LSE State */ + if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) + 80023fe: 687b ldr r3, [r7, #4] + 8002400: 689b ldr r3, [r3, #8] + 8002402: 2b00 cmp r3, #0 + 8002404: d015 beq.n 8002432 + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002406: f7ff f853 bl 80014b0 + 800240a: 6138 str r0, [r7, #16] + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + 800240c: e00a b.n 8002424 + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + 800240e: f7ff f84f bl 80014b0 + 8002412: 4602 mov r2, r0 + 8002414: 693b ldr r3, [r7, #16] + 8002416: 1ad3 subs r3, r2, r3 + 8002418: f241 3288 movw r2, #5000 ; 0x1388 + 800241c: 4293 cmp r3, r2 + 800241e: d901 bls.n 8002424 + { + return HAL_TIMEOUT; + 8002420: 2303 movs r3, #3 + 8002422: e09b b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + 8002424: 4b4f ldr r3, [pc, #316] ; (8002564 ) + 8002426: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002428: f003 0302 and.w r3, r3, #2 + 800242c: 2b00 cmp r3, #0 + 800242e: d0ee beq.n 800240e + 8002430: e014 b.n 800245c + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002432: f7ff f83d bl 80014b0 + 8002436: 6138 str r0, [r7, #16] + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + 8002438: e00a b.n 8002450 + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + 800243a: f7ff f839 bl 80014b0 + 800243e: 4602 mov r2, r0 + 8002440: 693b ldr r3, [r7, #16] + 8002442: 1ad3 subs r3, r2, r3 + 8002444: f241 3288 movw r2, #5000 ; 0x1388 + 8002448: 4293 cmp r3, r2 + 800244a: d901 bls.n 8002450 + { + return HAL_TIMEOUT; + 800244c: 2303 movs r3, #3 + 800244e: e085 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + 8002450: 4b44 ldr r3, [pc, #272] ; (8002564 ) + 8002452: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002454: f003 0302 and.w r3, r3, #2 + 8002458: 2b00 cmp r3, #0 + 800245a: d1ee bne.n 800243a + } + } + } + + /* Restore clock configuration if changed */ + if(pwrclkchanged == SET) + 800245c: 7dfb ldrb r3, [r7, #23] + 800245e: 2b01 cmp r3, #1 + 8002460: d105 bne.n 800246e + { + __HAL_RCC_PWR_CLK_DISABLE(); + 8002462: 4b40 ldr r3, [pc, #256] ; (8002564 ) + 8002464: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002466: 4a3f ldr r2, [pc, #252] ; (8002564 ) + 8002468: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 800246c: 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) + 800246e: 687b ldr r3, [r7, #4] + 8002470: 699b ldr r3, [r3, #24] + 8002472: 2b00 cmp r3, #0 + 8002474: d071 beq.n 800255a + { + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK) + 8002476: 4b3b ldr r3, [pc, #236] ; (8002564 ) + 8002478: 689b ldr r3, [r3, #8] + 800247a: f003 030c and.w r3, r3, #12 + 800247e: 2b08 cmp r3, #8 + 8002480: d069 beq.n 8002556 + { + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) + 8002482: 687b ldr r3, [r7, #4] + 8002484: 699b ldr r3, [r3, #24] + 8002486: 2b02 cmp r3, #2 + 8002488: d14b bne.n 8002522 +#if defined (RCC_PLLCFGR_PLLR) + assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); +#endif + + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + 800248a: 4b36 ldr r3, [pc, #216] ; (8002564 ) + 800248c: 681b ldr r3, [r3, #0] + 800248e: 4a35 ldr r2, [pc, #212] ; (8002564 ) + 8002490: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 8002494: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002496: f7ff f80b bl 80014b0 + 800249a: 6138 str r0, [r7, #16] + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + 800249c: e008 b.n 80024b0 + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + 800249e: f7ff f807 bl 80014b0 + 80024a2: 4602 mov r2, r0 + 80024a4: 693b ldr r3, [r7, #16] + 80024a6: 1ad3 subs r3, r2, r3 + 80024a8: 2b02 cmp r3, #2 + 80024aa: d901 bls.n 80024b0 + { + return HAL_TIMEOUT; + 80024ac: 2303 movs r3, #3 + 80024ae: e055 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + 80024b0: 4b2c ldr r3, [pc, #176] ; (8002564 ) + 80024b2: 681b ldr r3, [r3, #0] + 80024b4: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 80024b8: 2b00 cmp r3, #0 + 80024ba: d1f0 bne.n 800249e + } + } + + /* Configure the main PLL clock source, multiplication and division factors. */ +#if defined (RCC_PLLCFGR_PLLR) + __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource, + 80024bc: 687b ldr r3, [r7, #4] + 80024be: 69da ldr r2, [r3, #28] + 80024c0: 687b ldr r3, [r7, #4] + 80024c2: 6a1b ldr r3, [r3, #32] + 80024c4: 431a orrs r2, r3 + 80024c6: 687b ldr r3, [r7, #4] + 80024c8: 6a5b ldr r3, [r3, #36] ; 0x24 + 80024ca: 019b lsls r3, r3, #6 + 80024cc: 431a orrs r2, r3 + 80024ce: 687b ldr r3, [r7, #4] + 80024d0: 6a9b ldr r3, [r3, #40] ; 0x28 + 80024d2: 085b lsrs r3, r3, #1 + 80024d4: 3b01 subs r3, #1 + 80024d6: 041b lsls r3, r3, #16 + 80024d8: 431a orrs r2, r3 + 80024da: 687b ldr r3, [r7, #4] + 80024dc: 6adb ldr r3, [r3, #44] ; 0x2c + 80024de: 061b lsls r3, r3, #24 + 80024e0: 431a orrs r2, r3 + 80024e2: 687b ldr r3, [r7, #4] + 80024e4: 6b1b ldr r3, [r3, #48] ; 0x30 + 80024e6: 071b lsls r3, r3, #28 + 80024e8: 491e ldr r1, [pc, #120] ; (8002564 ) + 80024ea: 4313 orrs r3, r2 + 80024ec: 604b str r3, [r1, #4] + RCC_OscInitStruct->PLL.PLLP, + RCC_OscInitStruct->PLL.PLLQ); +#endif + + /* Enable the main PLL. */ + __HAL_RCC_PLL_ENABLE(); + 80024ee: 4b1d ldr r3, [pc, #116] ; (8002564 ) + 80024f0: 681b ldr r3, [r3, #0] + 80024f2: 4a1c ldr r2, [pc, #112] ; (8002564 ) + 80024f4: f043 7380 orr.w r3, r3, #16777216 ; 0x1000000 + 80024f8: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 80024fa: f7fe ffd9 bl 80014b0 + 80024fe: 6138 str r0, [r7, #16] + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + 8002500: e008 b.n 8002514 + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + 8002502: f7fe ffd5 bl 80014b0 + 8002506: 4602 mov r2, r0 + 8002508: 693b ldr r3, [r7, #16] + 800250a: 1ad3 subs r3, r2, r3 + 800250c: 2b02 cmp r3, #2 + 800250e: d901 bls.n 8002514 + { + return HAL_TIMEOUT; + 8002510: 2303 movs r3, #3 + 8002512: e023 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + 8002514: 4b13 ldr r3, [pc, #76] ; (8002564 ) + 8002516: 681b ldr r3, [r3, #0] + 8002518: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 800251c: 2b00 cmp r3, #0 + 800251e: d0f0 beq.n 8002502 + 8002520: e01b b.n 800255a + } + } + else + { + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + 8002522: 4b10 ldr r3, [pc, #64] ; (8002564 ) + 8002524: 681b ldr r3, [r3, #0] + 8002526: 4a0f ldr r2, [pc, #60] ; (8002564 ) + 8002528: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 800252c: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 800252e: f7fe ffbf bl 80014b0 + 8002532: 6138 str r0, [r7, #16] + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + 8002534: e008 b.n 8002548 + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + 8002536: f7fe ffbb bl 80014b0 + 800253a: 4602 mov r2, r0 + 800253c: 693b ldr r3, [r7, #16] + 800253e: 1ad3 subs r3, r2, r3 + 8002540: 2b02 cmp r3, #2 + 8002542: d901 bls.n 8002548 + { + return HAL_TIMEOUT; + 8002544: 2303 movs r3, #3 + 8002546: e009 b.n 800255c + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + 8002548: 4b06 ldr r3, [pc, #24] ; (8002564 ) + 800254a: 681b ldr r3, [r3, #0] + 800254c: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002550: 2b00 cmp r3, #0 + 8002552: d1f0 bne.n 8002536 + 8002554: e001 b.n 800255a + } + } + } + else + { + return HAL_ERROR; + 8002556: 2301 movs r3, #1 + 8002558: e000 b.n 800255c + } + } + return HAL_OK; + 800255a: 2300 movs r3, #0 +} + 800255c: 4618 mov r0, r3 + 800255e: 3718 adds r7, #24 + 8002560: 46bd mov sp, r7 + 8002562: bd80 pop {r7, pc} + 8002564: 40023800 .word 0x40023800 + 8002568: 40007000 .word 0x40007000 + +0800256c : + * 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) +{ + 800256c: b580 push {r7, lr} + 800256e: b084 sub sp, #16 + 8002570: af00 add r7, sp, #0 + 8002572: 6078 str r0, [r7, #4] + 8002574: 6039 str r1, [r7, #0] + uint32_t tickstart = 0; + 8002576: 2300 movs r3, #0 + 8002578: 60fb str r3, [r7, #12] + + /* Check Null pointer */ + if(RCC_ClkInitStruct == NULL) + 800257a: 687b ldr r3, [r7, #4] + 800257c: 2b00 cmp r3, #0 + 800257e: d101 bne.n 8002584 + { + return HAL_ERROR; + 8002580: 2301 movs r3, #1 + 8002582: e0ce b.n 8002722 + /* 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()) + 8002584: 4b69 ldr r3, [pc, #420] ; (800272c ) + 8002586: 681b ldr r3, [r3, #0] + 8002588: f003 030f and.w r3, r3, #15 + 800258c: 683a ldr r2, [r7, #0] + 800258e: 429a cmp r2, r3 + 8002590: d910 bls.n 80025b4 + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + 8002592: 4b66 ldr r3, [pc, #408] ; (800272c ) + 8002594: 681b ldr r3, [r3, #0] + 8002596: f023 020f bic.w r2, r3, #15 + 800259a: 4964 ldr r1, [pc, #400] ; (800272c ) + 800259c: 683b ldr r3, [r7, #0] + 800259e: 4313 orrs r3, r2 + 80025a0: 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) + 80025a2: 4b62 ldr r3, [pc, #392] ; (800272c ) + 80025a4: 681b ldr r3, [r3, #0] + 80025a6: f003 030f and.w r3, r3, #15 + 80025aa: 683a ldr r2, [r7, #0] + 80025ac: 429a cmp r2, r3 + 80025ae: d001 beq.n 80025b4 + { + return HAL_ERROR; + 80025b0: 2301 movs r3, #1 + 80025b2: e0b6 b.n 8002722 + } + } + + /*-------------------------- HCLK Configuration --------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) + 80025b4: 687b ldr r3, [r7, #4] + 80025b6: 681b ldr r3, [r3, #0] + 80025b8: f003 0302 and.w r3, r3, #2 + 80025bc: 2b00 cmp r3, #0 + 80025be: d020 beq.n 8002602 + { + /* 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) + 80025c0: 687b ldr r3, [r7, #4] + 80025c2: 681b ldr r3, [r3, #0] + 80025c4: f003 0304 and.w r3, r3, #4 + 80025c8: 2b00 cmp r3, #0 + 80025ca: d005 beq.n 80025d8 + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); + 80025cc: 4b58 ldr r3, [pc, #352] ; (8002730 ) + 80025ce: 689b ldr r3, [r3, #8] + 80025d0: 4a57 ldr r2, [pc, #348] ; (8002730 ) + 80025d2: f443 53e0 orr.w r3, r3, #7168 ; 0x1c00 + 80025d6: 6093 str r3, [r2, #8] + } + + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + 80025d8: 687b ldr r3, [r7, #4] + 80025da: 681b ldr r3, [r3, #0] + 80025dc: f003 0308 and.w r3, r3, #8 + 80025e0: 2b00 cmp r3, #0 + 80025e2: d005 beq.n 80025f0 + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); + 80025e4: 4b52 ldr r3, [pc, #328] ; (8002730 ) + 80025e6: 689b ldr r3, [r3, #8] + 80025e8: 4a51 ldr r2, [pc, #324] ; (8002730 ) + 80025ea: f443 4360 orr.w r3, r3, #57344 ; 0xe000 + 80025ee: 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); + 80025f0: 4b4f ldr r3, [pc, #316] ; (8002730 ) + 80025f2: 689b ldr r3, [r3, #8] + 80025f4: f023 02f0 bic.w r2, r3, #240 ; 0xf0 + 80025f8: 687b ldr r3, [r7, #4] + 80025fa: 689b ldr r3, [r3, #8] + 80025fc: 494c ldr r1, [pc, #304] ; (8002730 ) + 80025fe: 4313 orrs r3, r2 + 8002600: 608b str r3, [r1, #8] + } + + /*------------------------- SYSCLK Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) + 8002602: 687b ldr r3, [r7, #4] + 8002604: 681b ldr r3, [r3, #0] + 8002606: f003 0301 and.w r3, r3, #1 + 800260a: 2b00 cmp r3, #0 + 800260c: d040 beq.n 8002690 + { + assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); + + /* HSE is selected as System Clock Source */ + if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) + 800260e: 687b ldr r3, [r7, #4] + 8002610: 685b ldr r3, [r3, #4] + 8002612: 2b01 cmp r3, #1 + 8002614: d107 bne.n 8002626 + { + /* Check the HSE ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + 8002616: 4b46 ldr r3, [pc, #280] ; (8002730 ) + 8002618: 681b ldr r3, [r3, #0] + 800261a: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800261e: 2b00 cmp r3, #0 + 8002620: d115 bne.n 800264e + { + return HAL_ERROR; + 8002622: 2301 movs r3, #1 + 8002624: e07d b.n 8002722 + } + } + /* PLL is selected as System Clock Source */ + else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) + 8002626: 687b ldr r3, [r7, #4] + 8002628: 685b ldr r3, [r3, #4] + 800262a: 2b02 cmp r3, #2 + 800262c: d107 bne.n 800263e + { + /* Check the PLL ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + 800262e: 4b40 ldr r3, [pc, #256] ; (8002730 ) + 8002630: 681b ldr r3, [r3, #0] + 8002632: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002636: 2b00 cmp r3, #0 + 8002638: d109 bne.n 800264e + { + return HAL_ERROR; + 800263a: 2301 movs r3, #1 + 800263c: e071 b.n 8002722 + } + /* HSI is selected as System Clock Source */ + else + { + /* Check the HSI ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + 800263e: 4b3c ldr r3, [pc, #240] ; (8002730 ) + 8002640: 681b ldr r3, [r3, #0] + 8002642: f003 0302 and.w r3, r3, #2 + 8002646: 2b00 cmp r3, #0 + 8002648: d101 bne.n 800264e + { + return HAL_ERROR; + 800264a: 2301 movs r3, #1 + 800264c: e069 b.n 8002722 + } + } + + __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); + 800264e: 4b38 ldr r3, [pc, #224] ; (8002730 ) + 8002650: 689b ldr r3, [r3, #8] + 8002652: f023 0203 bic.w r2, r3, #3 + 8002656: 687b ldr r3, [r7, #4] + 8002658: 685b ldr r3, [r3, #4] + 800265a: 4935 ldr r1, [pc, #212] ; (8002730 ) + 800265c: 4313 orrs r3, r2 + 800265e: 608b str r3, [r1, #8] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002660: f7fe ff26 bl 80014b0 + 8002664: 60f8 str r0, [r7, #12] + + while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) + 8002666: e00a b.n 800267e + { + if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) + 8002668: f7fe ff22 bl 80014b0 + 800266c: 4602 mov r2, r0 + 800266e: 68fb ldr r3, [r7, #12] + 8002670: 1ad3 subs r3, r2, r3 + 8002672: f241 3288 movw r2, #5000 ; 0x1388 + 8002676: 4293 cmp r3, r2 + 8002678: d901 bls.n 800267e + { + return HAL_TIMEOUT; + 800267a: 2303 movs r3, #3 + 800267c: e051 b.n 8002722 + while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) + 800267e: 4b2c ldr r3, [pc, #176] ; (8002730 ) + 8002680: 689b ldr r3, [r3, #8] + 8002682: f003 020c and.w r2, r3, #12 + 8002686: 687b ldr r3, [r7, #4] + 8002688: 685b ldr r3, [r3, #4] + 800268a: 009b lsls r3, r3, #2 + 800268c: 429a cmp r2, r3 + 800268e: d1eb bne.n 8002668 + } + } + } + + /* Decreasing the number of wait states because of lower CPU frequency */ + if(FLatency < __HAL_FLASH_GET_LATENCY()) + 8002690: 4b26 ldr r3, [pc, #152] ; (800272c ) + 8002692: 681b ldr r3, [r3, #0] + 8002694: f003 030f and.w r3, r3, #15 + 8002698: 683a ldr r2, [r7, #0] + 800269a: 429a cmp r2, r3 + 800269c: d210 bcs.n 80026c0 + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + 800269e: 4b23 ldr r3, [pc, #140] ; (800272c ) + 80026a0: 681b ldr r3, [r3, #0] + 80026a2: f023 020f bic.w r2, r3, #15 + 80026a6: 4921 ldr r1, [pc, #132] ; (800272c ) + 80026a8: 683b ldr r3, [r7, #0] + 80026aa: 4313 orrs r3, r2 + 80026ac: 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) + 80026ae: 4b1f ldr r3, [pc, #124] ; (800272c ) + 80026b0: 681b ldr r3, [r3, #0] + 80026b2: f003 030f and.w r3, r3, #15 + 80026b6: 683a ldr r2, [r7, #0] + 80026b8: 429a cmp r2, r3 + 80026ba: d001 beq.n 80026c0 + { + return HAL_ERROR; + 80026bc: 2301 movs r3, #1 + 80026be: e030 b.n 8002722 + } + } + + /*-------------------------- PCLK1 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) + 80026c0: 687b ldr r3, [r7, #4] + 80026c2: 681b ldr r3, [r3, #0] + 80026c4: f003 0304 and.w r3, r3, #4 + 80026c8: 2b00 cmp r3, #0 + 80026ca: d008 beq.n 80026de + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); + 80026cc: 4b18 ldr r3, [pc, #96] ; (8002730 ) + 80026ce: 689b ldr r3, [r3, #8] + 80026d0: f423 52e0 bic.w r2, r3, #7168 ; 0x1c00 + 80026d4: 687b ldr r3, [r7, #4] + 80026d6: 68db ldr r3, [r3, #12] + 80026d8: 4915 ldr r1, [pc, #84] ; (8002730 ) + 80026da: 4313 orrs r3, r2 + 80026dc: 608b str r3, [r1, #8] + } + + /*-------------------------- PCLK2 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + 80026de: 687b ldr r3, [r7, #4] + 80026e0: 681b ldr r3, [r3, #0] + 80026e2: f003 0308 and.w r3, r3, #8 + 80026e6: 2b00 cmp r3, #0 + 80026e8: d009 beq.n 80026fe + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3)); + 80026ea: 4b11 ldr r3, [pc, #68] ; (8002730 ) + 80026ec: 689b ldr r3, [r3, #8] + 80026ee: f423 4260 bic.w r2, r3, #57344 ; 0xe000 + 80026f2: 687b ldr r3, [r7, #4] + 80026f4: 691b ldr r3, [r3, #16] + 80026f6: 00db lsls r3, r3, #3 + 80026f8: 490d ldr r1, [pc, #52] ; (8002730 ) + 80026fa: 4313 orrs r3, r2 + 80026fc: 608b str r3, [r1, #8] + } + + /* Update the SystemCoreClock global variable */ + SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; + 80026fe: f000 f81d bl 800273c + 8002702: 4601 mov r1, r0 + 8002704: 4b0a ldr r3, [pc, #40] ; (8002730 ) + 8002706: 689b ldr r3, [r3, #8] + 8002708: 091b lsrs r3, r3, #4 + 800270a: f003 030f and.w r3, r3, #15 + 800270e: 4a09 ldr r2, [pc, #36] ; (8002734 ) + 8002710: 5cd3 ldrb r3, [r2, r3] + 8002712: fa21 f303 lsr.w r3, r1, r3 + 8002716: 4a08 ldr r2, [pc, #32] ; (8002738 ) + 8002718: 6013 str r3, [r2, #0] + + /* Configure the source of time base considering new system clocks settings*/ + HAL_InitTick (TICK_INT_PRIORITY); + 800271a: 2000 movs r0, #0 + 800271c: f7fe fe84 bl 8001428 + + return HAL_OK; + 8002720: 2300 movs r3, #0 +} + 8002722: 4618 mov r0, r3 + 8002724: 3710 adds r7, #16 + 8002726: 46bd mov sp, r7 + 8002728: bd80 pop {r7, pc} + 800272a: bf00 nop + 800272c: 40023c00 .word 0x40023c00 + 8002730: 40023800 .word 0x40023800 + 8002734: 08004eac .word 0x08004eac + 8002738: 20000000 .word 0x20000000 + +0800273c : + * + * + * @retval SYSCLK frequency + */ +uint32_t HAL_RCC_GetSysClockFreq(void) +{ + 800273c: b5f0 push {r4, r5, r6, r7, lr} + 800273e: b085 sub sp, #20 + 8002740: af00 add r7, sp, #0 + uint32_t pllm = 0, pllvco = 0, pllp = 0; + 8002742: 2300 movs r3, #0 + 8002744: 607b str r3, [r7, #4] + 8002746: 2300 movs r3, #0 + 8002748: 60fb str r3, [r7, #12] + 800274a: 2300 movs r3, #0 + 800274c: 603b str r3, [r7, #0] + uint32_t sysclockfreq = 0; + 800274e: 2300 movs r3, #0 + 8002750: 60bb str r3, [r7, #8] + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + 8002752: 4b50 ldr r3, [pc, #320] ; (8002894 ) + 8002754: 689b ldr r3, [r3, #8] + 8002756: f003 030c and.w r3, r3, #12 + 800275a: 2b04 cmp r3, #4 + 800275c: d007 beq.n 800276e + 800275e: 2b08 cmp r3, #8 + 8002760: d008 beq.n 8002774 + 8002762: 2b00 cmp r3, #0 + 8002764: f040 808d bne.w 8002882 + { + case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */ + { + sysclockfreq = HSI_VALUE; + 8002768: 4b4b ldr r3, [pc, #300] ; (8002898 ) + 800276a: 60bb str r3, [r7, #8] + break; + 800276c: e08c b.n 8002888 + } + case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock source */ + { + sysclockfreq = HSE_VALUE; + 800276e: 4b4b ldr r3, [pc, #300] ; (800289c ) + 8002770: 60bb str r3, [r7, #8] + break; + 8002772: e089 b.n 8002888 + } + 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; + 8002774: 4b47 ldr r3, [pc, #284] ; (8002894 ) + 8002776: 685b ldr r3, [r3, #4] + 8002778: f003 033f and.w r3, r3, #63 ; 0x3f + 800277c: 607b str r3, [r7, #4] + if (__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLCFGR_PLLSRC_HSI) + 800277e: 4b45 ldr r3, [pc, #276] ; (8002894 ) + 8002780: 685b ldr r3, [r3, #4] + 8002782: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002786: 2b00 cmp r3, #0 + 8002788: d023 beq.n 80027d2 + { + /* 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); + 800278a: 4b42 ldr r3, [pc, #264] ; (8002894 ) + 800278c: 685b ldr r3, [r3, #4] + 800278e: 099b lsrs r3, r3, #6 + 8002790: f04f 0400 mov.w r4, #0 + 8002794: f240 11ff movw r1, #511 ; 0x1ff + 8002798: f04f 0200 mov.w r2, #0 + 800279c: ea03 0501 and.w r5, r3, r1 + 80027a0: ea04 0602 and.w r6, r4, r2 + 80027a4: 4a3d ldr r2, [pc, #244] ; (800289c ) + 80027a6: fb02 f106 mul.w r1, r2, r6 + 80027aa: 2200 movs r2, #0 + 80027ac: fb02 f205 mul.w r2, r2, r5 + 80027b0: 440a add r2, r1 + 80027b2: 493a ldr r1, [pc, #232] ; (800289c ) + 80027b4: fba5 0101 umull r0, r1, r5, r1 + 80027b8: 1853 adds r3, r2, r1 + 80027ba: 4619 mov r1, r3 + 80027bc: 687b ldr r3, [r7, #4] + 80027be: f04f 0400 mov.w r4, #0 + 80027c2: 461a mov r2, r3 + 80027c4: 4623 mov r3, r4 + 80027c6: f7fd fd37 bl 8000238 <__aeabi_uldivmod> + 80027ca: 4603 mov r3, r0 + 80027cc: 460c mov r4, r1 + 80027ce: 60fb str r3, [r7, #12] + 80027d0: e049 b.n 8002866 + } + 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); + 80027d2: 4b30 ldr r3, [pc, #192] ; (8002894 ) + 80027d4: 685b ldr r3, [r3, #4] + 80027d6: 099b lsrs r3, r3, #6 + 80027d8: f04f 0400 mov.w r4, #0 + 80027dc: f240 11ff movw r1, #511 ; 0x1ff + 80027e0: f04f 0200 mov.w r2, #0 + 80027e4: ea03 0501 and.w r5, r3, r1 + 80027e8: ea04 0602 and.w r6, r4, r2 + 80027ec: 4629 mov r1, r5 + 80027ee: 4632 mov r2, r6 + 80027f0: f04f 0300 mov.w r3, #0 + 80027f4: f04f 0400 mov.w r4, #0 + 80027f8: 0154 lsls r4, r2, #5 + 80027fa: ea44 64d1 orr.w r4, r4, r1, lsr #27 + 80027fe: 014b lsls r3, r1, #5 + 8002800: 4619 mov r1, r3 + 8002802: 4622 mov r2, r4 + 8002804: 1b49 subs r1, r1, r5 + 8002806: eb62 0206 sbc.w r2, r2, r6 + 800280a: f04f 0300 mov.w r3, #0 + 800280e: f04f 0400 mov.w r4, #0 + 8002812: 0194 lsls r4, r2, #6 + 8002814: ea44 6491 orr.w r4, r4, r1, lsr #26 + 8002818: 018b lsls r3, r1, #6 + 800281a: 1a5b subs r3, r3, r1 + 800281c: eb64 0402 sbc.w r4, r4, r2 + 8002820: f04f 0100 mov.w r1, #0 + 8002824: f04f 0200 mov.w r2, #0 + 8002828: 00e2 lsls r2, r4, #3 + 800282a: ea42 7253 orr.w r2, r2, r3, lsr #29 + 800282e: 00d9 lsls r1, r3, #3 + 8002830: 460b mov r3, r1 + 8002832: 4614 mov r4, r2 + 8002834: 195b adds r3, r3, r5 + 8002836: eb44 0406 adc.w r4, r4, r6 + 800283a: f04f 0100 mov.w r1, #0 + 800283e: f04f 0200 mov.w r2, #0 + 8002842: 02a2 lsls r2, r4, #10 + 8002844: ea42 5293 orr.w r2, r2, r3, lsr #22 + 8002848: 0299 lsls r1, r3, #10 + 800284a: 460b mov r3, r1 + 800284c: 4614 mov r4, r2 + 800284e: 4618 mov r0, r3 + 8002850: 4621 mov r1, r4 + 8002852: 687b ldr r3, [r7, #4] + 8002854: f04f 0400 mov.w r4, #0 + 8002858: 461a mov r2, r3 + 800285a: 4623 mov r3, r4 + 800285c: f7fd fcec bl 8000238 <__aeabi_uldivmod> + 8002860: 4603 mov r3, r0 + 8002862: 460c mov r4, r1 + 8002864: 60fb str r3, [r7, #12] + } + pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1 ) *2); + 8002866: 4b0b ldr r3, [pc, #44] ; (8002894 ) + 8002868: 685b ldr r3, [r3, #4] + 800286a: 0c1b lsrs r3, r3, #16 + 800286c: f003 0303 and.w r3, r3, #3 + 8002870: 3301 adds r3, #1 + 8002872: 005b lsls r3, r3, #1 + 8002874: 603b str r3, [r7, #0] + + sysclockfreq = pllvco/pllp; + 8002876: 68fa ldr r2, [r7, #12] + 8002878: 683b ldr r3, [r7, #0] + 800287a: fbb2 f3f3 udiv r3, r2, r3 + 800287e: 60bb str r3, [r7, #8] + break; + 8002880: e002 b.n 8002888 + } + default: + { + sysclockfreq = HSI_VALUE; + 8002882: 4b05 ldr r3, [pc, #20] ; (8002898 ) + 8002884: 60bb str r3, [r7, #8] + break; + 8002886: bf00 nop + } + } + return sysclockfreq; + 8002888: 68bb ldr r3, [r7, #8] +} + 800288a: 4618 mov r0, r3 + 800288c: 3714 adds r7, #20 + 800288e: 46bd mov sp, r7 + 8002890: bdf0 pop {r4, r5, r6, r7, pc} + 8002892: bf00 nop + 8002894: 40023800 .word 0x40023800 + 8002898: 00f42400 .word 0x00f42400 + 800289c: 017d7840 .word 0x017d7840 + +080028a0 : + * 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) +{ + 80028a0: b480 push {r7} + 80028a2: af00 add r7, sp, #0 + return SystemCoreClock; + 80028a4: 4b03 ldr r3, [pc, #12] ; (80028b4 ) + 80028a6: 681b ldr r3, [r3, #0] +} + 80028a8: 4618 mov r0, r3 + 80028aa: 46bd mov sp, r7 + 80028ac: f85d 7b04 ldr.w r7, [sp], #4 + 80028b0: 4770 bx lr + 80028b2: bf00 nop + 80028b4: 20000000 .word 0x20000000 + +080028b8 : + * @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) +{ + 80028b8: b580 push {r7, lr} + 80028ba: 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]); + 80028bc: f7ff fff0 bl 80028a0 + 80028c0: 4601 mov r1, r0 + 80028c2: 4b05 ldr r3, [pc, #20] ; (80028d8 ) + 80028c4: 689b ldr r3, [r3, #8] + 80028c6: 0a9b lsrs r3, r3, #10 + 80028c8: f003 0307 and.w r3, r3, #7 + 80028cc: 4a03 ldr r2, [pc, #12] ; (80028dc ) + 80028ce: 5cd3 ldrb r3, [r2, r3] + 80028d0: fa21 f303 lsr.w r3, r1, r3 +} + 80028d4: 4618 mov r0, r3 + 80028d6: bd80 pop {r7, pc} + 80028d8: 40023800 .word 0x40023800 + 80028dc: 08004ebc .word 0x08004ebc + +080028e0 : + * @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) +{ + 80028e0: b580 push {r7, lr} + 80028e2: 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]); + 80028e4: f7ff ffdc bl 80028a0 + 80028e8: 4601 mov r1, r0 + 80028ea: 4b05 ldr r3, [pc, #20] ; (8002900 ) + 80028ec: 689b ldr r3, [r3, #8] + 80028ee: 0b5b lsrs r3, r3, #13 + 80028f0: f003 0307 and.w r3, r3, #7 + 80028f4: 4a03 ldr r2, [pc, #12] ; (8002904 ) + 80028f6: 5cd3 ldrb r3, [r2, r3] + 80028f8: fa21 f303 lsr.w r3, r1, r3 +} + 80028fc: 4618 mov r0, r3 + 80028fe: bd80 pop {r7, pc} + 8002900: 40023800 .word 0x40023800 + 8002904: 08004ebc .word 0x08004ebc + +08002908 : + * the backup registers) are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + 8002908: b580 push {r7, lr} + 800290a: b088 sub sp, #32 + 800290c: af00 add r7, sp, #0 + 800290e: 6078 str r0, [r7, #4] + uint32_t tickstart = 0; + 8002910: 2300 movs r3, #0 + 8002912: 617b str r3, [r7, #20] + uint32_t tmpreg0 = 0; + 8002914: 2300 movs r3, #0 + 8002916: 613b str r3, [r7, #16] + uint32_t tmpreg1 = 0; + 8002918: 2300 movs r3, #0 + 800291a: 60fb str r3, [r7, #12] + uint32_t plli2sused = 0; + 800291c: 2300 movs r3, #0 + 800291e: 61fb str r3, [r7, #28] + uint32_t pllsaiused = 0; + 8002920: 2300 movs r3, #0 + 8002922: 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)) + 8002924: 687b ldr r3, [r7, #4] + 8002926: 681b ldr r3, [r3, #0] + 8002928: f003 0301 and.w r3, r3, #1 + 800292c: 2b00 cmp r3, #0 + 800292e: d012 beq.n 8002956 + { + /* Check the parameters */ + assert_param(IS_RCC_I2SCLKSOURCE(PeriphClkInit->I2sClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2sClockSelection); + 8002930: 4b69 ldr r3, [pc, #420] ; (8002ad8 ) + 8002932: 689b ldr r3, [r3, #8] + 8002934: 4a68 ldr r2, [pc, #416] ; (8002ad8 ) + 8002936: f423 0300 bic.w r3, r3, #8388608 ; 0x800000 + 800293a: 6093 str r3, [r2, #8] + 800293c: 4b66 ldr r3, [pc, #408] ; (8002ad8 ) + 800293e: 689a ldr r2, [r3, #8] + 8002940: 687b ldr r3, [r7, #4] + 8002942: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002944: 4964 ldr r1, [pc, #400] ; (8002ad8 ) + 8002946: 4313 orrs r3, r2 + 8002948: 608b str r3, [r1, #8] + + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sClockSelection == RCC_I2SCLKSOURCE_PLLI2S) + 800294a: 687b ldr r3, [r7, #4] + 800294c: 6b5b ldr r3, [r3, #52] ; 0x34 + 800294e: 2b00 cmp r3, #0 + 8002950: d101 bne.n 8002956 + { + plli2sused = 1; + 8002952: 2301 movs r3, #1 + 8002954: 61fb str r3, [r7, #28] + } + } + + /*------------------------------------ SAI1 configuration --------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) + 8002956: 687b ldr r3, [r7, #4] + 8002958: 681b ldr r3, [r3, #0] + 800295a: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 800295e: 2b00 cmp r3, #0 + 8002960: d017 beq.n 8002992 + { + /* Check the parameters */ + assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); + 8002962: 4b5d ldr r3, [pc, #372] ; (8002ad8 ) + 8002964: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002968: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 800296c: 687b ldr r3, [r7, #4] + 800296e: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002970: 4959 ldr r1, [pc, #356] ; (8002ad8 ) + 8002972: 4313 orrs r3, r2 + 8002974: 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) + 8002978: 687b ldr r3, [r7, #4] + 800297a: 6bdb ldr r3, [r3, #60] ; 0x3c + 800297c: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8002980: d101 bne.n 8002986 + { + plli2sused = 1; + 8002982: 2301 movs r3, #1 + 8002984: 61fb str r3, [r7, #28] + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) + 8002986: 687b ldr r3, [r7, #4] + 8002988: 6bdb ldr r3, [r3, #60] ; 0x3c + 800298a: 2b00 cmp r3, #0 + 800298c: d101 bne.n 8002992 + { + pllsaiused = 1; + 800298e: 2301 movs r3, #1 + 8002990: 61bb str r3, [r7, #24] + } + } + + /*------------------------------------ SAI2 configuration --------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) + 8002992: 687b ldr r3, [r7, #4] + 8002994: 681b ldr r3, [r3, #0] + 8002996: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 800299a: 2b00 cmp r3, #0 + 800299c: d017 beq.n 80029ce + { + /* Check the parameters */ + assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); + + /* Configure SAI2 Clock source */ + __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); + 800299e: 4b4e ldr r3, [pc, #312] ; (8002ad8 ) + 80029a0: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 80029a4: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 80029a8: 687b ldr r3, [r7, #4] + 80029aa: 6c1b ldr r3, [r3, #64] ; 0x40 + 80029ac: 494a ldr r1, [pc, #296] ; (8002ad8 ) + 80029ae: 4313 orrs r3, r2 + 80029b0: 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) + 80029b4: 687b ldr r3, [r7, #4] + 80029b6: 6c1b ldr r3, [r3, #64] ; 0x40 + 80029b8: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 80029bc: d101 bne.n 80029c2 + { + plli2sused = 1; + 80029be: 2301 movs r3, #1 + 80029c0: 61fb str r3, [r7, #28] + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) + 80029c2: 687b ldr r3, [r7, #4] + 80029c4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80029c6: 2b00 cmp r3, #0 + 80029c8: d101 bne.n 80029ce + { + pllsaiused = 1; + 80029ca: 2301 movs r3, #1 + 80029cc: 61bb str r3, [r7, #24] + } + } + + /*-------------------------------------- SPDIF-RX Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) + 80029ce: 687b ldr r3, [r7, #4] + 80029d0: 681b ldr r3, [r3, #0] + 80029d2: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 80029d6: 2b00 cmp r3, #0 + 80029d8: d001 beq.n 80029de + { + plli2sused = 1; + 80029da: 2301 movs r3, #1 + 80029dc: 61fb str r3, [r7, #28] + } + + /*------------------------------------ RTC configuration --------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + 80029de: 687b ldr r3, [r7, #4] + 80029e0: 681b ldr r3, [r3, #0] + 80029e2: f003 0320 and.w r3, r3, #32 + 80029e6: 2b00 cmp r3, #0 + 80029e8: f000 808b beq.w 8002b02 + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + 80029ec: 4b3a ldr r3, [pc, #232] ; (8002ad8 ) + 80029ee: 6c1b ldr r3, [r3, #64] ; 0x40 + 80029f0: 4a39 ldr r2, [pc, #228] ; (8002ad8 ) + 80029f2: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 80029f6: 6413 str r3, [r2, #64] ; 0x40 + 80029f8: 4b37 ldr r3, [pc, #220] ; (8002ad8 ) + 80029fa: 6c1b ldr r3, [r3, #64] ; 0x40 + 80029fc: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002a00: 60bb str r3, [r7, #8] + 8002a02: 68bb ldr r3, [r7, #8] + + /* Enable write access to Backup domain */ + PWR->CR1 |= PWR_CR1_DBP; + 8002a04: 4b35 ldr r3, [pc, #212] ; (8002adc ) + 8002a06: 681b ldr r3, [r3, #0] + 8002a08: 4a34 ldr r2, [pc, #208] ; (8002adc ) + 8002a0a: f443 7380 orr.w r3, r3, #256 ; 0x100 + 8002a0e: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002a10: f7fe fd4e bl 80014b0 + 8002a14: 6178 str r0, [r7, #20] + + /* Wait for Backup domain Write protection disable */ + while((PWR->CR1 & PWR_CR1_DBP) == RESET) + 8002a16: e008 b.n 8002a2a + { + if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) + 8002a18: f7fe fd4a bl 80014b0 + 8002a1c: 4602 mov r2, r0 + 8002a1e: 697b ldr r3, [r7, #20] + 8002a20: 1ad3 subs r3, r2, r3 + 8002a22: 2b64 cmp r3, #100 ; 0x64 + 8002a24: d901 bls.n 8002a2a + { + return HAL_TIMEOUT; + 8002a26: 2303 movs r3, #3 + 8002a28: e38d b.n 8003146 + while((PWR->CR1 & PWR_CR1_DBP) == RESET) + 8002a2a: 4b2c ldr r3, [pc, #176] ; (8002adc ) + 8002a2c: 681b ldr r3, [r3, #0] + 8002a2e: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002a32: 2b00 cmp r3, #0 + 8002a34: d0f0 beq.n 8002a18 + } + } + + /* Reset the Backup domain only if the RTC Clock source selection is modified */ + tmpreg0 = (RCC->BDCR & RCC_BDCR_RTCSEL); + 8002a36: 4b28 ldr r3, [pc, #160] ; (8002ad8 ) + 8002a38: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002a3a: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002a3e: 613b str r3, [r7, #16] + + if((tmpreg0 != 0x00000000U) && (tmpreg0 != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + 8002a40: 693b ldr r3, [r7, #16] + 8002a42: 2b00 cmp r3, #0 + 8002a44: d035 beq.n 8002ab2 + 8002a46: 687b ldr r3, [r7, #4] + 8002a48: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002a4a: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002a4e: 693a ldr r2, [r7, #16] + 8002a50: 429a cmp r2, r3 + 8002a52: d02e beq.n 8002ab2 + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg0 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + 8002a54: 4b20 ldr r3, [pc, #128] ; (8002ad8 ) + 8002a56: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002a58: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8002a5c: 613b str r3, [r7, #16] + + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + 8002a5e: 4b1e ldr r3, [pc, #120] ; (8002ad8 ) + 8002a60: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002a62: 4a1d ldr r2, [pc, #116] ; (8002ad8 ) + 8002a64: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 8002a68: 6713 str r3, [r2, #112] ; 0x70 + __HAL_RCC_BACKUPRESET_RELEASE(); + 8002a6a: 4b1b ldr r3, [pc, #108] ; (8002ad8 ) + 8002a6c: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002a6e: 4a1a ldr r2, [pc, #104] ; (8002ad8 ) + 8002a70: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002a74: 6713 str r3, [r2, #112] ; 0x70 + + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg0; + 8002a76: 4a18 ldr r2, [pc, #96] ; (8002ad8 ) + 8002a78: 693b ldr r3, [r7, #16] + 8002a7a: 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)) + 8002a7c: 4b16 ldr r3, [pc, #88] ; (8002ad8 ) + 8002a7e: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002a80: f003 0301 and.w r3, r3, #1 + 8002a84: 2b01 cmp r3, #1 + 8002a86: d114 bne.n 8002ab2 + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002a88: f7fe fd12 bl 80014b0 + 8002a8c: 6178 str r0, [r7, #20] + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + 8002a8e: e00a b.n 8002aa6 + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + 8002a90: f7fe fd0e bl 80014b0 + 8002a94: 4602 mov r2, r0 + 8002a96: 697b ldr r3, [r7, #20] + 8002a98: 1ad3 subs r3, r2, r3 + 8002a9a: f241 3288 movw r2, #5000 ; 0x1388 + 8002a9e: 4293 cmp r3, r2 + 8002aa0: d901 bls.n 8002aa6 + { + return HAL_TIMEOUT; + 8002aa2: 2303 movs r3, #3 + 8002aa4: e34f b.n 8003146 + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + 8002aa6: 4b0c ldr r3, [pc, #48] ; (8002ad8 ) + 8002aa8: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002aaa: f003 0302 and.w r3, r3, #2 + 8002aae: 2b00 cmp r3, #0 + 8002ab0: d0ee beq.n 8002a90 + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + 8002ab2: 687b ldr r3, [r7, #4] + 8002ab4: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002ab6: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002aba: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8002abe: d111 bne.n 8002ae4 + 8002ac0: 4b05 ldr r3, [pc, #20] ; (8002ad8 ) + 8002ac2: 689b ldr r3, [r3, #8] + 8002ac4: f423 12f8 bic.w r2, r3, #2031616 ; 0x1f0000 + 8002ac8: 687b ldr r3, [r7, #4] + 8002aca: 6b19 ldr r1, [r3, #48] ; 0x30 + 8002acc: 4b04 ldr r3, [pc, #16] ; (8002ae0 ) + 8002ace: 400b ands r3, r1 + 8002ad0: 4901 ldr r1, [pc, #4] ; (8002ad8 ) + 8002ad2: 4313 orrs r3, r2 + 8002ad4: 608b str r3, [r1, #8] + 8002ad6: e00b b.n 8002af0 + 8002ad8: 40023800 .word 0x40023800 + 8002adc: 40007000 .word 0x40007000 + 8002ae0: 0ffffcff .word 0x0ffffcff + 8002ae4: 4bb3 ldr r3, [pc, #716] ; (8002db4 ) + 8002ae6: 689b ldr r3, [r3, #8] + 8002ae8: 4ab2 ldr r2, [pc, #712] ; (8002db4 ) + 8002aea: f423 13f8 bic.w r3, r3, #2031616 ; 0x1f0000 + 8002aee: 6093 str r3, [r2, #8] + 8002af0: 4bb0 ldr r3, [pc, #704] ; (8002db4 ) + 8002af2: 6f1a ldr r2, [r3, #112] ; 0x70 + 8002af4: 687b ldr r3, [r7, #4] + 8002af6: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002af8: f3c3 030b ubfx r3, r3, #0, #12 + 8002afc: 49ad ldr r1, [pc, #692] ; (8002db4 ) + 8002afe: 4313 orrs r3, r2 + 8002b00: 670b str r3, [r1, #112] ; 0x70 + } + + /*------------------------------------ TIM configuration --------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + 8002b02: 687b ldr r3, [r7, #4] + 8002b04: 681b ldr r3, [r3, #0] + 8002b06: f003 0310 and.w r3, r3, #16 + 8002b0a: 2b00 cmp r3, #0 + 8002b0c: d010 beq.n 8002b30 + { + /* Check the parameters */ + assert_param(IS_RCC_TIMPRES(PeriphClkInit->TIMPresSelection)); + + /* Configure Timer Prescaler */ + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + 8002b0e: 4ba9 ldr r3, [pc, #676] ; (8002db4 ) + 8002b10: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002b14: 4aa7 ldr r2, [pc, #668] ; (8002db4 ) + 8002b16: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 8002b1a: f8c2 308c str.w r3, [r2, #140] ; 0x8c + 8002b1e: 4ba5 ldr r3, [pc, #660] ; (8002db4 ) + 8002b20: f8d3 208c ldr.w r2, [r3, #140] ; 0x8c + 8002b24: 687b ldr r3, [r7, #4] + 8002b26: 6b9b ldr r3, [r3, #56] ; 0x38 + 8002b28: 49a2 ldr r1, [pc, #648] ; (8002db4 ) + 8002b2a: 4313 orrs r3, r2 + 8002b2c: f8c1 308c str.w r3, [r1, #140] ; 0x8c + } + + /*-------------------------------------- I2C1 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C1) == RCC_PERIPHCLK_I2C1) + 8002b30: 687b ldr r3, [r7, #4] + 8002b32: 681b ldr r3, [r3, #0] + 8002b34: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8002b38: 2b00 cmp r3, #0 + 8002b3a: d00a beq.n 8002b52 + { + /* Check the parameters */ + assert_param(IS_RCC_I2C1CLKSOURCE(PeriphClkInit->I2c1ClockSelection)); + + /* Configure the I2C1 clock source */ + __HAL_RCC_I2C1_CONFIG(PeriphClkInit->I2c1ClockSelection); + 8002b3c: 4b9d ldr r3, [pc, #628] ; (8002db4 ) + 8002b3e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002b42: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8002b46: 687b ldr r3, [r7, #4] + 8002b48: 6e5b ldr r3, [r3, #100] ; 0x64 + 8002b4a: 499a ldr r1, [pc, #616] ; (8002db4 ) + 8002b4c: 4313 orrs r3, r2 + 8002b4e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- I2C2 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C2) == RCC_PERIPHCLK_I2C2) + 8002b52: 687b ldr r3, [r7, #4] + 8002b54: 681b ldr r3, [r3, #0] + 8002b56: f403 4300 and.w r3, r3, #32768 ; 0x8000 + 8002b5a: 2b00 cmp r3, #0 + 8002b5c: d00a beq.n 8002b74 + { + /* Check the parameters */ + assert_param(IS_RCC_I2C2CLKSOURCE(PeriphClkInit->I2c2ClockSelection)); + + /* Configure the I2C2 clock source */ + __HAL_RCC_I2C2_CONFIG(PeriphClkInit->I2c2ClockSelection); + 8002b5e: 4b95 ldr r3, [pc, #596] ; (8002db4 ) + 8002b60: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002b64: f423 2240 bic.w r2, r3, #786432 ; 0xc0000 + 8002b68: 687b ldr r3, [r7, #4] + 8002b6a: 6e9b ldr r3, [r3, #104] ; 0x68 + 8002b6c: 4991 ldr r1, [pc, #580] ; (8002db4 ) + 8002b6e: 4313 orrs r3, r2 + 8002b70: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- I2C3 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C3) == RCC_PERIPHCLK_I2C3) + 8002b74: 687b ldr r3, [r7, #4] + 8002b76: 681b ldr r3, [r3, #0] + 8002b78: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 8002b7c: 2b00 cmp r3, #0 + 8002b7e: d00a beq.n 8002b96 + { + /* Check the parameters */ + assert_param(IS_RCC_I2C3CLKSOURCE(PeriphClkInit->I2c3ClockSelection)); + + /* Configure the I2C3 clock source */ + __HAL_RCC_I2C3_CONFIG(PeriphClkInit->I2c3ClockSelection); + 8002b80: 4b8c ldr r3, [pc, #560] ; (8002db4 ) + 8002b82: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002b86: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 8002b8a: 687b ldr r3, [r7, #4] + 8002b8c: 6edb ldr r3, [r3, #108] ; 0x6c + 8002b8e: 4989 ldr r1, [pc, #548] ; (8002db4 ) + 8002b90: 4313 orrs r3, r2 + 8002b92: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- I2C4 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C4) == RCC_PERIPHCLK_I2C4) + 8002b96: 687b ldr r3, [r7, #4] + 8002b98: 681b ldr r3, [r3, #0] + 8002b9a: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 8002b9e: 2b00 cmp r3, #0 + 8002ba0: d00a beq.n 8002bb8 + { + /* Check the parameters */ + assert_param(IS_RCC_I2C4CLKSOURCE(PeriphClkInit->I2c4ClockSelection)); + + /* Configure the I2C4 clock source */ + __HAL_RCC_I2C4_CONFIG(PeriphClkInit->I2c4ClockSelection); + 8002ba2: 4b84 ldr r3, [pc, #528] ; (8002db4 ) + 8002ba4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002ba8: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 8002bac: 687b ldr r3, [r7, #4] + 8002bae: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002bb0: 4980 ldr r1, [pc, #512] ; (8002db4 ) + 8002bb2: 4313 orrs r3, r2 + 8002bb4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- USART1 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART1) == RCC_PERIPHCLK_USART1) + 8002bb8: 687b ldr r3, [r7, #4] + 8002bba: 681b ldr r3, [r3, #0] + 8002bbc: f003 0340 and.w r3, r3, #64 ; 0x40 + 8002bc0: 2b00 cmp r3, #0 + 8002bc2: d00a beq.n 8002bda + { + /* Check the parameters */ + assert_param(IS_RCC_USART1CLKSOURCE(PeriphClkInit->Usart1ClockSelection)); + + /* Configure the USART1 clock source */ + __HAL_RCC_USART1_CONFIG(PeriphClkInit->Usart1ClockSelection); + 8002bc4: 4b7b ldr r3, [pc, #492] ; (8002db4 ) + 8002bc6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002bca: f023 0203 bic.w r2, r3, #3 + 8002bce: 687b ldr r3, [r7, #4] + 8002bd0: 6c5b ldr r3, [r3, #68] ; 0x44 + 8002bd2: 4978 ldr r1, [pc, #480] ; (8002db4 ) + 8002bd4: 4313 orrs r3, r2 + 8002bd6: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- USART2 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART2) == RCC_PERIPHCLK_USART2) + 8002bda: 687b ldr r3, [r7, #4] + 8002bdc: 681b ldr r3, [r3, #0] + 8002bde: f003 0380 and.w r3, r3, #128 ; 0x80 + 8002be2: 2b00 cmp r3, #0 + 8002be4: d00a beq.n 8002bfc + { + /* Check the parameters */ + assert_param(IS_RCC_USART2CLKSOURCE(PeriphClkInit->Usart2ClockSelection)); + + /* Configure the USART2 clock source */ + __HAL_RCC_USART2_CONFIG(PeriphClkInit->Usart2ClockSelection); + 8002be6: 4b73 ldr r3, [pc, #460] ; (8002db4 ) + 8002be8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002bec: f023 020c bic.w r2, r3, #12 + 8002bf0: 687b ldr r3, [r7, #4] + 8002bf2: 6c9b ldr r3, [r3, #72] ; 0x48 + 8002bf4: 496f ldr r1, [pc, #444] ; (8002db4 ) + 8002bf6: 4313 orrs r3, r2 + 8002bf8: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- USART3 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART3) == RCC_PERIPHCLK_USART3) + 8002bfc: 687b ldr r3, [r7, #4] + 8002bfe: 681b ldr r3, [r3, #0] + 8002c00: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002c04: 2b00 cmp r3, #0 + 8002c06: d00a beq.n 8002c1e + { + /* Check the parameters */ + assert_param(IS_RCC_USART3CLKSOURCE(PeriphClkInit->Usart3ClockSelection)); + + /* Configure the USART3 clock source */ + __HAL_RCC_USART3_CONFIG(PeriphClkInit->Usart3ClockSelection); + 8002c08: 4b6a ldr r3, [pc, #424] ; (8002db4 ) + 8002c0a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c0e: f023 0230 bic.w r2, r3, #48 ; 0x30 + 8002c12: 687b ldr r3, [r7, #4] + 8002c14: 6cdb ldr r3, [r3, #76] ; 0x4c + 8002c16: 4967 ldr r1, [pc, #412] ; (8002db4 ) + 8002c18: 4313 orrs r3, r2 + 8002c1a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- UART4 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART4) == RCC_PERIPHCLK_UART4) + 8002c1e: 687b ldr r3, [r7, #4] + 8002c20: 681b ldr r3, [r3, #0] + 8002c22: f403 7300 and.w r3, r3, #512 ; 0x200 + 8002c26: 2b00 cmp r3, #0 + 8002c28: d00a beq.n 8002c40 + { + /* Check the parameters */ + assert_param(IS_RCC_UART4CLKSOURCE(PeriphClkInit->Uart4ClockSelection)); + + /* Configure the UART4 clock source */ + __HAL_RCC_UART4_CONFIG(PeriphClkInit->Uart4ClockSelection); + 8002c2a: 4b62 ldr r3, [pc, #392] ; (8002db4 ) + 8002c2c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c30: f023 02c0 bic.w r2, r3, #192 ; 0xc0 + 8002c34: 687b ldr r3, [r7, #4] + 8002c36: 6d1b ldr r3, [r3, #80] ; 0x50 + 8002c38: 495e ldr r1, [pc, #376] ; (8002db4 ) + 8002c3a: 4313 orrs r3, r2 + 8002c3c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- UART5 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART5) == RCC_PERIPHCLK_UART5) + 8002c40: 687b ldr r3, [r7, #4] + 8002c42: 681b ldr r3, [r3, #0] + 8002c44: f403 6380 and.w r3, r3, #1024 ; 0x400 + 8002c48: 2b00 cmp r3, #0 + 8002c4a: d00a beq.n 8002c62 + { + /* Check the parameters */ + assert_param(IS_RCC_UART5CLKSOURCE(PeriphClkInit->Uart5ClockSelection)); + + /* Configure the UART5 clock source */ + __HAL_RCC_UART5_CONFIG(PeriphClkInit->Uart5ClockSelection); + 8002c4c: 4b59 ldr r3, [pc, #356] ; (8002db4 ) + 8002c4e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c52: f423 7240 bic.w r2, r3, #768 ; 0x300 + 8002c56: 687b ldr r3, [r7, #4] + 8002c58: 6d5b ldr r3, [r3, #84] ; 0x54 + 8002c5a: 4956 ldr r1, [pc, #344] ; (8002db4 ) + 8002c5c: 4313 orrs r3, r2 + 8002c5e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- USART6 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART6) == RCC_PERIPHCLK_USART6) + 8002c62: 687b ldr r3, [r7, #4] + 8002c64: 681b ldr r3, [r3, #0] + 8002c66: f403 6300 and.w r3, r3, #2048 ; 0x800 + 8002c6a: 2b00 cmp r3, #0 + 8002c6c: d00a beq.n 8002c84 + { + /* Check the parameters */ + assert_param(IS_RCC_USART6CLKSOURCE(PeriphClkInit->Usart6ClockSelection)); + + /* Configure the USART6 clock source */ + __HAL_RCC_USART6_CONFIG(PeriphClkInit->Usart6ClockSelection); + 8002c6e: 4b51 ldr r3, [pc, #324] ; (8002db4 ) + 8002c70: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c74: f423 6240 bic.w r2, r3, #3072 ; 0xc00 + 8002c78: 687b ldr r3, [r7, #4] + 8002c7a: 6d9b ldr r3, [r3, #88] ; 0x58 + 8002c7c: 494d ldr r1, [pc, #308] ; (8002db4 ) + 8002c7e: 4313 orrs r3, r2 + 8002c80: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- UART7 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART7) == RCC_PERIPHCLK_UART7) + 8002c84: 687b ldr r3, [r7, #4] + 8002c86: 681b ldr r3, [r3, #0] + 8002c88: f403 5380 and.w r3, r3, #4096 ; 0x1000 + 8002c8c: 2b00 cmp r3, #0 + 8002c8e: d00a beq.n 8002ca6 + { + /* Check the parameters */ + assert_param(IS_RCC_UART7CLKSOURCE(PeriphClkInit->Uart7ClockSelection)); + + /* Configure the UART7 clock source */ + __HAL_RCC_UART7_CONFIG(PeriphClkInit->Uart7ClockSelection); + 8002c90: 4b48 ldr r3, [pc, #288] ; (8002db4 ) + 8002c92: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002c96: f423 5240 bic.w r2, r3, #12288 ; 0x3000 + 8002c9a: 687b ldr r3, [r7, #4] + 8002c9c: 6ddb ldr r3, [r3, #92] ; 0x5c + 8002c9e: 4945 ldr r1, [pc, #276] ; (8002db4 ) + 8002ca0: 4313 orrs r3, r2 + 8002ca2: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- UART8 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART8) == RCC_PERIPHCLK_UART8) + 8002ca6: 687b ldr r3, [r7, #4] + 8002ca8: 681b ldr r3, [r3, #0] + 8002caa: f403 5300 and.w r3, r3, #8192 ; 0x2000 + 8002cae: 2b00 cmp r3, #0 + 8002cb0: d00a beq.n 8002cc8 + { + /* Check the parameters */ + assert_param(IS_RCC_UART8CLKSOURCE(PeriphClkInit->Uart8ClockSelection)); + + /* Configure the UART8 clock source */ + __HAL_RCC_UART8_CONFIG(PeriphClkInit->Uart8ClockSelection); + 8002cb2: 4b40 ldr r3, [pc, #256] ; (8002db4 ) + 8002cb4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cb8: f423 4240 bic.w r2, r3, #49152 ; 0xc000 + 8002cbc: 687b ldr r3, [r7, #4] + 8002cbe: 6e1b ldr r3, [r3, #96] ; 0x60 + 8002cc0: 493c ldr r1, [pc, #240] ; (8002db4 ) + 8002cc2: 4313 orrs r3, r2 + 8002cc4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*--------------------------------------- CEC Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) + 8002cc8: 687b ldr r3, [r7, #4] + 8002cca: 681b ldr r3, [r3, #0] + 8002ccc: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002cd0: 2b00 cmp r3, #0 + 8002cd2: d00a beq.n 8002cea + { + /* Check the parameters */ + assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); + + /* Configure the CEC clock source */ + __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); + 8002cd4: 4b37 ldr r3, [pc, #220] ; (8002db4 ) + 8002cd6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cda: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 8002cde: 687b ldr r3, [r7, #4] + 8002ce0: 6f9b ldr r3, [r3, #120] ; 0x78 + 8002ce2: 4934 ldr r1, [pc, #208] ; (8002db4 ) + 8002ce4: 4313 orrs r3, r2 + 8002ce6: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*-------------------------------------- CK48 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + 8002cea: 687b ldr r3, [r7, #4] + 8002cec: 681b ldr r3, [r3, #0] + 8002cee: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8002cf2: 2b00 cmp r3, #0 + 8002cf4: d011 beq.n 8002d1a + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48SOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the CLK48 source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + 8002cf6: 4b2f ldr r3, [pc, #188] ; (8002db4 ) + 8002cf8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002cfc: f023 6200 bic.w r2, r3, #134217728 ; 0x8000000 + 8002d00: 687b ldr r3, [r7, #4] + 8002d02: 6fdb ldr r3, [r3, #124] ; 0x7c + 8002d04: 492b ldr r1, [pc, #172] ; (8002db4 ) + 8002d06: 4313 orrs r3, r2 + 8002d08: 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) + 8002d0c: 687b ldr r3, [r7, #4] + 8002d0e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8002d10: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 8002d14: d101 bne.n 8002d1a + { + pllsaiused = 1; + 8002d16: 2301 movs r3, #1 + 8002d18: 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) + 8002d1a: 687b ldr r3, [r7, #4] + 8002d1c: 681b ldr r3, [r3, #0] + 8002d1e: f003 0308 and.w r3, r3, #8 + 8002d22: 2b00 cmp r3, #0 + 8002d24: d001 beq.n 8002d2a + { + pllsaiused = 1; + 8002d26: 2301 movs r3, #1 + 8002d28: 61bb str r3, [r7, #24] + } +#endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ + + /*-------------------------------------- LPTIM1 Configuration -----------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) + 8002d2a: 687b ldr r3, [r7, #4] + 8002d2c: 681b ldr r3, [r3, #0] + 8002d2e: f403 2380 and.w r3, r3, #262144 ; 0x40000 + 8002d32: 2b00 cmp r3, #0 + 8002d34: d00a beq.n 8002d4c + { + /* Check the parameters */ + assert_param(IS_RCC_LPTIM1CLK(PeriphClkInit->Lptim1ClockSelection)); + + /* Configure the LTPIM1 clock source */ + __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); + 8002d36: 4b1f ldr r3, [pc, #124] ; (8002db4 ) + 8002d38: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d3c: f023 7240 bic.w r2, r3, #50331648 ; 0x3000000 + 8002d40: 687b ldr r3, [r7, #4] + 8002d42: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002d44: 491b ldr r1, [pc, #108] ; (8002db4 ) + 8002d46: 4313 orrs r3, r2 + 8002d48: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*------------------------------------- SDMMC1 Configuration ------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDMMC1) == RCC_PERIPHCLK_SDMMC1) + 8002d4c: 687b ldr r3, [r7, #4] + 8002d4e: 681b ldr r3, [r3, #0] + 8002d50: f403 0300 and.w r3, r3, #8388608 ; 0x800000 + 8002d54: 2b00 cmp r3, #0 + 8002d56: d00b beq.n 8002d70 + { + /* Check the parameters */ + assert_param(IS_RCC_SDMMC1CLKSOURCE(PeriphClkInit->Sdmmc1ClockSelection)); + + /* Configure the SDMMC1 clock source */ + __HAL_RCC_SDMMC1_CONFIG(PeriphClkInit->Sdmmc1ClockSelection); + 8002d58: 4b16 ldr r3, [pc, #88] ; (8002db4 ) + 8002d5a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d5e: f023 5280 bic.w r2, r3, #268435456 ; 0x10000000 + 8002d62: 687b ldr r3, [r7, #4] + 8002d64: f8d3 3080 ldr.w r3, [r3, #128] ; 0x80 + 8002d68: 4912 ldr r1, [pc, #72] ; (8002db4 ) + 8002d6a: 4313 orrs r3, r2 + 8002d6c: 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) + 8002d70: 687b ldr r3, [r7, #4] + 8002d72: 681b ldr r3, [r3, #0] + 8002d74: f003 6380 and.w r3, r3, #67108864 ; 0x4000000 + 8002d78: 2b00 cmp r3, #0 + 8002d7a: d00b beq.n 8002d94 + { + /* Check the parameters */ + assert_param(IS_RCC_SDMMC2CLKSOURCE(PeriphClkInit->Sdmmc2ClockSelection)); + + /* Configure the SDMMC2 clock source */ + __HAL_RCC_SDMMC2_CONFIG(PeriphClkInit->Sdmmc2ClockSelection); + 8002d7c: 4b0d ldr r3, [pc, #52] ; (8002db4 ) + 8002d7e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002d82: f023 5200 bic.w r2, r3, #536870912 ; 0x20000000 + 8002d86: 687b ldr r3, [r7, #4] + 8002d88: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002d8c: 4909 ldr r1, [pc, #36] ; (8002db4 ) + 8002d8e: 4313 orrs r3, r2 + 8002d90: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + } + + /*------------------------------------- DFSDM1 Configuration -------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) + 8002d94: 687b ldr r3, [r7, #4] + 8002d96: 681b ldr r3, [r3, #0] + 8002d98: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 8002d9c: 2b00 cmp r3, #0 + 8002d9e: d00f beq.n 8002dc0 + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); + + /* Configure the DFSDM1 interface clock source */ + __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); + 8002da0: 4b04 ldr r3, [pc, #16] ; (8002db4 ) + 8002da2: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002da6: f023 7200 bic.w r2, r3, #33554432 ; 0x2000000 + 8002daa: 687b ldr r3, [r7, #4] + 8002dac: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8002db0: e002 b.n 8002db8 + 8002db2: bf00 nop + 8002db4: 40023800 .word 0x40023800 + 8002db8: 4985 ldr r1, [pc, #532] ; (8002fd0 ) + 8002dba: 4313 orrs r3, r2 + 8002dbc: f8c1 308c str.w r3, [r1, #140] ; 0x8c + } + + /*------------------------------------- DFSDM AUDIO Configuration -------------------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) + 8002dc0: 687b ldr r3, [r7, #4] + 8002dc2: 681b ldr r3, [r3, #0] + 8002dc4: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002dc8: 2b00 cmp r3, #0 + 8002dca: d00b beq.n 8002de4 + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); + + /* Configure the DFSDM interface clock source */ + __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); + 8002dcc: 4b80 ldr r3, [pc, #512] ; (8002fd0 ) + 8002dce: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002dd2: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 8002dd6: 687b ldr r3, [r7, #4] + 8002dd8: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002ddc: 497c ldr r1, [pc, #496] ; (8002fd0 ) + 8002dde: 4313 orrs r3, r2 + 8002de0: 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)) + 8002de4: 69fb ldr r3, [r7, #28] + 8002de6: 2b01 cmp r3, #1 + 8002de8: d005 beq.n 8002df6 + 8002dea: 687b ldr r3, [r7, #4] + 8002dec: 681b ldr r3, [r3, #0] + 8002dee: f1b3 7f00 cmp.w r3, #33554432 ; 0x2000000 + 8002df2: f040 80d6 bne.w 8002fa2 + { + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + 8002df6: 4b76 ldr r3, [pc, #472] ; (8002fd0 ) + 8002df8: 681b ldr r3, [r3, #0] + 8002dfa: 4a75 ldr r2, [pc, #468] ; (8002fd0 ) + 8002dfc: f023 6380 bic.w r3, r3, #67108864 ; 0x4000000 + 8002e00: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002e02: f7fe fb55 bl 80014b0 + 8002e06: 6178 str r0, [r7, #20] + + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + 8002e08: e008 b.n 8002e1c + { + if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + 8002e0a: f7fe fb51 bl 80014b0 + 8002e0e: 4602 mov r2, r0 + 8002e10: 697b ldr r3, [r7, #20] + 8002e12: 1ad3 subs r3, r2, r3 + 8002e14: 2b64 cmp r3, #100 ; 0x64 + 8002e16: d901 bls.n 8002e1c + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + 8002e18: 2303 movs r3, #3 + 8002e1a: e194 b.n 8003146 + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + 8002e1c: 4b6c ldr r3, [pc, #432] ; (8002fd0 ) + 8002e1e: 681b ldr r3, [r3, #0] + 8002e20: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 8002e24: 2b00 cmp r3, #0 + 8002e26: d1f0 bne.n 8002e0a + + /* 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))) + 8002e28: 687b ldr r3, [r7, #4] + 8002e2a: 681b ldr r3, [r3, #0] + 8002e2c: f003 0301 and.w r3, r3, #1 + 8002e30: 2b00 cmp r3, #0 + 8002e32: d021 beq.n 8002e78 + 8002e34: 687b ldr r3, [r7, #4] + 8002e36: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002e38: 2b00 cmp r3, #0 + 8002e3a: d11d bne.n 8002e78 + { + /* 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); + 8002e3c: 4b64 ldr r3, [pc, #400] ; (8002fd0 ) + 8002e3e: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002e42: 0c1b lsrs r3, r3, #16 + 8002e44: f003 0303 and.w r3, r3, #3 + 8002e48: 613b str r3, [r7, #16] + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + 8002e4a: 4b61 ldr r3, [pc, #388] ; (8002fd0 ) + 8002e4c: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002e50: 0e1b lsrs r3, r3, #24 + 8002e52: f003 030f and.w r3, r3, #15 + 8002e56: 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); + 8002e58: 687b ldr r3, [r7, #4] + 8002e5a: 685b ldr r3, [r3, #4] + 8002e5c: 019a lsls r2, r3, #6 + 8002e5e: 693b ldr r3, [r7, #16] + 8002e60: 041b lsls r3, r3, #16 + 8002e62: 431a orrs r2, r3 + 8002e64: 68fb ldr r3, [r7, #12] + 8002e66: 061b lsls r3, r3, #24 + 8002e68: 431a orrs r2, r3 + 8002e6a: 687b ldr r3, [r7, #4] + 8002e6c: 689b ldr r3, [r3, #8] + 8002e6e: 071b lsls r3, r3, #28 + 8002e70: 4957 ldr r1, [pc, #348] ; (8002fd0 ) + 8002e72: 4313 orrs r3, r2 + 8002e74: 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)) || + 8002e78: 687b ldr r3, [r7, #4] + 8002e7a: 681b ldr r3, [r3, #0] + 8002e7c: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8002e80: 2b00 cmp r3, #0 + 8002e82: d004 beq.n 8002e8e + 8002e84: 687b ldr r3, [r7, #4] + 8002e86: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002e88: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8002e8c: d00a beq.n 8002ea4 + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) + 8002e8e: 687b ldr r3, [r7, #4] + 8002e90: 681b ldr r3, [r3, #0] + 8002e92: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || + 8002e96: 2b00 cmp r3, #0 + 8002e98: d02e beq.n 8002ef8 + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) + 8002e9a: 687b ldr r3, [r7, #4] + 8002e9c: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002e9e: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002ea2: d129 bne.n 8002ef8 + 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); + 8002ea4: 4b4a ldr r3, [pc, #296] ; (8002fd0 ) + 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] + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + 8002eb2: 4b47 ldr r3, [pc, #284] ; (8002fd0 ) + 8002eb4: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002eb8: 0f1b lsrs r3, r3, #28 + 8002eba: f003 0307 and.w r3, r3, #7 + 8002ebe: 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); + 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: 687b ldr r3, [r7, #4] + 8002ece: 68db ldr r3, [r3, #12] + 8002ed0: 061b lsls r3, r3, #24 + 8002ed2: 431a orrs r2, r3 + 8002ed4: 68fb ldr r3, [r7, #12] + 8002ed6: 071b lsls r3, r3, #28 + 8002ed8: 493d ldr r1, [pc, #244] ; (8002fd0 ) + 8002eda: 4313 orrs r3, r2 + 8002edc: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + 8002ee0: 4b3b ldr r3, [pc, #236] ; (8002fd0 ) + 8002ee2: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002ee6: f023 021f bic.w r2, r3, #31 + 8002eea: 687b ldr r3, [r7, #4] + 8002eec: 6a5b ldr r3, [r3, #36] ; 0x24 + 8002eee: 3b01 subs r3, #1 + 8002ef0: 4937 ldr r1, [pc, #220] ; (8002fd0 ) + 8002ef2: 4313 orrs r3, r2 + 8002ef4: 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) + 8002ef8: 687b ldr r3, [r7, #4] + 8002efa: 681b ldr r3, [r3, #0] + 8002efc: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8002f00: 2b00 cmp r3, #0 + 8002f02: d01d beq.n 8002f40 + { + /* 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); + 8002f04: 4b32 ldr r3, [pc, #200] ; (8002fd0 ) + 8002f06: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002f0a: 0e1b lsrs r3, r3, #24 + 8002f0c: f003 030f and.w r3, r3, #15 + 8002f10: 613b str r3, [r7, #16] + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + 8002f12: 4b2f ldr r3, [pc, #188] ; (8002fd0 ) + 8002f14: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8002f18: 0f1b lsrs r3, r3, #28 + 8002f1a: f003 0307 and.w r3, r3, #7 + 8002f1e: 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); + 8002f20: 687b ldr r3, [r7, #4] + 8002f22: 685b ldr r3, [r3, #4] + 8002f24: 019a lsls r2, r3, #6 + 8002f26: 687b ldr r3, [r7, #4] + 8002f28: 691b ldr r3, [r3, #16] + 8002f2a: 041b lsls r3, r3, #16 + 8002f2c: 431a orrs r2, r3 + 8002f2e: 693b ldr r3, [r7, #16] + 8002f30: 061b lsls r3, r3, #24 + 8002f32: 431a orrs r2, r3 + 8002f34: 68fb ldr r3, [r7, #12] + 8002f36: 071b lsls r3, r3, #28 + 8002f38: 4925 ldr r1, [pc, #148] ; (8002fd0 ) + 8002f3a: 4313 orrs r3, r2 + 8002f3c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + 8002f40: 687b ldr r3, [r7, #4] + 8002f42: 681b ldr r3, [r3, #0] + 8002f44: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002f48: 2b00 cmp r3, #0 + 8002f4a: d011 beq.n 8002f70 + 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); + 8002f4c: 687b ldr r3, [r7, #4] + 8002f4e: 685b ldr r3, [r3, #4] + 8002f50: 019a lsls r2, r3, #6 + 8002f52: 687b ldr r3, [r7, #4] + 8002f54: 691b ldr r3, [r3, #16] + 8002f56: 041b lsls r3, r3, #16 + 8002f58: 431a orrs r2, r3 + 8002f5a: 687b ldr r3, [r7, #4] + 8002f5c: 68db ldr r3, [r3, #12] + 8002f5e: 061b lsls r3, r3, #24 + 8002f60: 431a orrs r2, r3 + 8002f62: 687b ldr r3, [r7, #4] + 8002f64: 689b ldr r3, [r3, #8] + 8002f66: 071b lsls r3, r3, #28 + 8002f68: 4919 ldr r1, [pc, #100] ; (8002fd0 ) + 8002f6a: 4313 orrs r3, r2 + 8002f6c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + 8002f70: 4b17 ldr r3, [pc, #92] ; (8002fd0 ) + 8002f72: 681b ldr r3, [r3, #0] + 8002f74: 4a16 ldr r2, [pc, #88] ; (8002fd0 ) + 8002f76: f043 6380 orr.w r3, r3, #67108864 ; 0x4000000 + 8002f7a: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002f7c: f7fe fa98 bl 80014b0 + 8002f80: 6178 str r0, [r7, #20] + + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + 8002f82: e008 b.n 8002f96 + { + if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + 8002f84: f7fe fa94 bl 80014b0 + 8002f88: 4602 mov r2, r0 + 8002f8a: 697b ldr r3, [r7, #20] + 8002f8c: 1ad3 subs r3, r2, r3 + 8002f8e: 2b64 cmp r3, #100 ; 0x64 + 8002f90: d901 bls.n 8002f96 + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + 8002f92: 2303 movs r3, #3 + 8002f94: e0d7 b.n 8003146 + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + 8002f96: 4b0e ldr r3, [pc, #56] ; (8002fd0 ) + 8002f98: 681b ldr r3, [r3, #0] + 8002f9a: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 8002f9e: 2b00 cmp r3, #0 + 8002fa0: d0f0 beq.n 8002f84 + } + } + + /*-------------------------------------- PLLSAI Configuration ---------------------------------*/ + /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, LTDC or CK48 */ + if(pllsaiused == 1) + 8002fa2: 69bb ldr r3, [r7, #24] + 8002fa4: 2b01 cmp r3, #1 + 8002fa6: f040 80cd bne.w 8003144 + { + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + 8002faa: 4b09 ldr r3, [pc, #36] ; (8002fd0 ) + 8002fac: 681b ldr r3, [r3, #0] + 8002fae: 4a08 ldr r2, [pc, #32] ; (8002fd0 ) + 8002fb0: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 8002fb4: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 8002fb6: f7fe fa7b bl 80014b0 + 8002fba: 6178 str r0, [r7, #20] + + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + 8002fbc: e00a b.n 8002fd4 + { + if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + 8002fbe: f7fe fa77 bl 80014b0 + 8002fc2: 4602 mov r2, r0 + 8002fc4: 697b ldr r3, [r7, #20] + 8002fc6: 1ad3 subs r3, r2, r3 + 8002fc8: 2b64 cmp r3, #100 ; 0x64 + 8002fca: d903 bls.n 8002fd4 + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + 8002fcc: 2303 movs r3, #3 + 8002fce: e0ba b.n 8003146 + 8002fd0: 40023800 .word 0x40023800 + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + 8002fd4: 4b5e ldr r3, [pc, #376] ; (8003150 ) + 8002fd6: 681b ldr r3, [r3, #0] + 8002fd8: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 8002fdc: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 8002fe0: d0ed beq.n 8002fbe + + /* 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)) ||\ + 8002fe2: 687b ldr r3, [r7, #4] + 8002fe4: 681b ldr r3, [r3, #0] + 8002fe6: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8002fea: 2b00 cmp r3, #0 + 8002fec: d003 beq.n 8002ff6 + 8002fee: 687b ldr r3, [r7, #4] + 8002ff0: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002ff2: 2b00 cmp r3, #0 + 8002ff4: d009 beq.n 800300a + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) + 8002ff6: 687b ldr r3, [r7, #4] + 8002ff8: 681b ldr r3, [r3, #0] + 8002ffa: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) ||\ + 8002ffe: 2b00 cmp r3, #0 + 8003000: d02e beq.n 8003060 + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) + 8003002: 687b ldr r3, [r7, #4] + 8003004: 6c1b ldr r3, [r3, #64] ; 0x40 + 8003006: 2b00 cmp r3, #0 + 8003008: d12a bne.n 8003060 + 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); + 800300a: 4b51 ldr r3, [pc, #324] ; (8003150 ) + 800300c: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003010: 0c1b lsrs r3, r3, #16 + 8003012: f003 0303 and.w r3, r3, #3 + 8003016: 613b str r3, [r7, #16] + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + 8003018: 4b4d ldr r3, [pc, #308] ; (8003150 ) + 800301a: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800301e: 0f1b lsrs r3, r3, #28 + 8003020: f003 0307 and.w r3, r3, #7 + 8003024: 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); + 8003026: 687b ldr r3, [r7, #4] + 8003028: 695b ldr r3, [r3, #20] + 800302a: 019a lsls r2, r3, #6 + 800302c: 693b ldr r3, [r7, #16] + 800302e: 041b lsls r3, r3, #16 + 8003030: 431a orrs r2, r3 + 8003032: 687b ldr r3, [r7, #4] + 8003034: 699b ldr r3, [r3, #24] + 8003036: 061b lsls r3, r3, #24 + 8003038: 431a orrs r2, r3 + 800303a: 68fb ldr r3, [r7, #12] + 800303c: 071b lsls r3, r3, #28 + 800303e: 4944 ldr r1, [pc, #272] ; (8003150 ) + 8003040: 4313 orrs r3, r2 + 8003042: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + 8003046: 4b42 ldr r3, [pc, #264] ; (8003150 ) + 8003048: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 800304c: f423 52f8 bic.w r2, r3, #7936 ; 0x1f00 + 8003050: 687b ldr r3, [r7, #4] + 8003052: 6a9b ldr r3, [r3, #40] ; 0x28 + 8003054: 3b01 subs r3, #1 + 8003056: 021b lsls r3, r3, #8 + 8003058: 493d ldr r1, [pc, #244] ; (8003150 ) + 800305a: 4313 orrs r3, r2 + 800305c: 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)) + 8003060: 687b ldr r3, [r7, #4] + 8003062: 681b ldr r3, [r3, #0] + 8003064: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8003068: 2b00 cmp r3, #0 + 800306a: d022 beq.n 80030b2 + 800306c: 687b ldr r3, [r7, #4] + 800306e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8003070: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 8003074: d11d bne.n 80030b2 + { + /* 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); + 8003076: 4b36 ldr r3, [pc, #216] ; (8003150 ) + 8003078: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800307c: 0e1b lsrs r3, r3, #24 + 800307e: f003 030f and.w r3, r3, #15 + 8003082: 613b str r3, [r7, #16] + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + 8003084: 4b32 ldr r3, [pc, #200] ; (8003150 ) + 8003086: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800308a: 0f1b lsrs r3, r3, #28 + 800308c: f003 0307 and.w r3, r3, #7 + 8003090: 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); + 8003092: 687b ldr r3, [r7, #4] + 8003094: 695b ldr r3, [r3, #20] + 8003096: 019a lsls r2, r3, #6 + 8003098: 687b ldr r3, [r7, #4] + 800309a: 6a1b ldr r3, [r3, #32] + 800309c: 041b lsls r3, r3, #16 + 800309e: 431a orrs r2, r3 + 80030a0: 693b ldr r3, [r7, #16] + 80030a2: 061b lsls r3, r3, #24 + 80030a4: 431a orrs r2, r3 + 80030a6: 68fb ldr r3, [r7, #12] + 80030a8: 071b lsls r3, r3, #28 + 80030aa: 4929 ldr r1, [pc, #164] ; (8003150 ) + 80030ac: 4313 orrs r3, r2 + 80030ae: 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)) + 80030b2: 687b ldr r3, [r7, #4] + 80030b4: 681b ldr r3, [r3, #0] + 80030b6: f003 0308 and.w r3, r3, #8 + 80030ba: 2b00 cmp r3, #0 + 80030bc: d028 beq.n 8003110 + { + 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); + 80030be: 4b24 ldr r3, [pc, #144] ; (8003150 ) + 80030c0: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80030c4: 0e1b lsrs r3, r3, #24 + 80030c6: f003 030f and.w r3, r3, #15 + 80030ca: 613b str r3, [r7, #16] + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos); + 80030cc: 4b20 ldr r3, [pc, #128] ; (8003150 ) + 80030ce: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80030d2: 0c1b lsrs r3, r3, #16 + 80030d4: f003 0303 and.w r3, r3, #3 + 80030d8: 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); + 80030da: 687b ldr r3, [r7, #4] + 80030dc: 695b ldr r3, [r3, #20] + 80030de: 019a lsls r2, r3, #6 + 80030e0: 68fb ldr r3, [r7, #12] + 80030e2: 041b lsls r3, r3, #16 + 80030e4: 431a orrs r2, r3 + 80030e6: 693b ldr r3, [r7, #16] + 80030e8: 061b lsls r3, r3, #24 + 80030ea: 431a orrs r2, r3 + 80030ec: 687b ldr r3, [r7, #4] + 80030ee: 69db ldr r3, [r3, #28] + 80030f0: 071b lsls r3, r3, #28 + 80030f2: 4917 ldr r1, [pc, #92] ; (8003150 ) + 80030f4: 4313 orrs r3, r2 + 80030f6: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + + /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); + 80030fa: 4b15 ldr r3, [pc, #84] ; (8003150 ) + 80030fc: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003100: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8003104: 687b ldr r3, [r7, #4] + 8003106: 6adb ldr r3, [r3, #44] ; 0x2c + 8003108: 4911 ldr r1, [pc, #68] ; (8003150 ) + 800310a: 4313 orrs r3, r2 + 800310c: f8c1 308c str.w r3, [r1, #140] ; 0x8c + } +#endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ + + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + 8003110: 4b0f ldr r3, [pc, #60] ; (8003150 ) + 8003112: 681b ldr r3, [r3, #0] + 8003114: 4a0e ldr r2, [pc, #56] ; (8003150 ) + 8003116: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 800311a: 6013 str r3, [r2, #0] + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + 800311c: f7fe f9c8 bl 80014b0 + 8003120: 6178 str r0, [r7, #20] + + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + 8003122: e008 b.n 8003136 + { + if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + 8003124: f7fe f9c4 bl 80014b0 + 8003128: 4602 mov r2, r0 + 800312a: 697b ldr r3, [r7, #20] + 800312c: 1ad3 subs r3, r2, r3 + 800312e: 2b64 cmp r3, #100 ; 0x64 + 8003130: d901 bls.n 8003136 + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + 8003132: 2303 movs r3, #3 + 8003134: e007 b.n 8003146 + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + 8003136: 4b06 ldr r3, [pc, #24] ; (8003150 ) + 8003138: 681b ldr r3, [r3, #0] + 800313a: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 800313e: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 8003142: d1ef bne.n 8003124 + } + } + } + return HAL_OK; + 8003144: 2300 movs r3, #0 +} + 8003146: 4618 mov r0, r3 + 8003148: 3720 adds r7, #32 + 800314a: 46bd mov sp, r7 + 800314c: bd80 pop {r7, pc} + 800314e: bf00 nop + 8003150: 40023800 .word 0x40023800 + +08003154 : + * 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) +{ + 8003154: b580 push {r7, lr} + 8003156: b082 sub sp, #8 + 8003158: af00 add r7, sp, #0 + 800315a: 6078 str r0, [r7, #4] + /* Check the TIM handle allocation */ + if (htim == NULL) + 800315c: 687b ldr r3, [r7, #4] + 800315e: 2b00 cmp r3, #0 + 8003160: d101 bne.n 8003166 + { + return HAL_ERROR; + 8003162: 2301 movs r3, #1 + 8003164: e01d b.n 80031a2 + 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) + 8003166: 687b ldr r3, [r7, #4] + 8003168: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 800316c: b2db uxtb r3, r3 + 800316e: 2b00 cmp r3, #0 + 8003170: d106 bne.n 8003180 + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + 8003172: 687b ldr r3, [r7, #4] + 8003174: 2200 movs r2, #0 + 8003176: 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); + 800317a: 6878 ldr r0, [r7, #4] + 800317c: f7fd ff4a bl 8001014 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + 8003180: 687b ldr r3, [r7, #4] + 8003182: 2202 movs r2, #2 + 8003184: f883 203d strb.w r2, [r3, #61] ; 0x3d + + /* Set the Time Base configuration */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + 8003188: 687b ldr r3, [r7, #4] + 800318a: 681a ldr r2, [r3, #0] + 800318c: 687b ldr r3, [r7, #4] + 800318e: 3304 adds r3, #4 + 8003190: 4619 mov r1, r3 + 8003192: 4610 mov r0, r2 + 8003194: f000 fc90 bl 8003ab8 + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + 8003198: 687b ldr r3, [r7, #4] + 800319a: 2201 movs r2, #1 + 800319c: f883 203d strb.w r2, [r3, #61] ; 0x3d + + return HAL_OK; + 80031a0: 2300 movs r3, #0 +} + 80031a2: 4618 mov r0, r3 + 80031a4: 3708 adds r7, #8 + 80031a6: 46bd mov sp, r7 + 80031a8: bd80 pop {r7, pc} + ... + +080031ac : + * @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) +{ + 80031ac: b480 push {r7} + 80031ae: b085 sub sp, #20 + 80031b0: af00 add r7, sp, #0 + 80031b2: 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); + 80031b4: 687b ldr r3, [r7, #4] + 80031b6: 681b ldr r3, [r3, #0] + 80031b8: 68da ldr r2, [r3, #12] + 80031ba: 687b ldr r3, [r7, #4] + 80031bc: 681b ldr r3, [r3, #0] + 80031be: f042 0201 orr.w r2, r2, #1 + 80031c2: 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; + 80031c4: 687b ldr r3, [r7, #4] + 80031c6: 681b ldr r3, [r3, #0] + 80031c8: 689a ldr r2, [r3, #8] + 80031ca: 4b0c ldr r3, [pc, #48] ; (80031fc ) + 80031cc: 4013 ands r3, r2 + 80031ce: 60fb str r3, [r7, #12] + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + 80031d0: 68fb ldr r3, [r7, #12] + 80031d2: 2b06 cmp r3, #6 + 80031d4: d00b beq.n 80031ee + 80031d6: 68fb ldr r3, [r7, #12] + 80031d8: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 80031dc: d007 beq.n 80031ee + { + __HAL_TIM_ENABLE(htim); + 80031de: 687b ldr r3, [r7, #4] + 80031e0: 681b ldr r3, [r3, #0] + 80031e2: 681a ldr r2, [r3, #0] + 80031e4: 687b ldr r3, [r7, #4] + 80031e6: 681b ldr r3, [r3, #0] + 80031e8: f042 0201 orr.w r2, r2, #1 + 80031ec: 601a str r2, [r3, #0] + } + + /* Return function status */ + return HAL_OK; + 80031ee: 2300 movs r3, #0 +} + 80031f0: 4618 mov r0, r3 + 80031f2: 3714 adds r7, #20 + 80031f4: 46bd mov sp, r7 + 80031f6: f85d 7b04 ldr.w r7, [sp], #4 + 80031fa: 4770 bx lr + 80031fc: 00010007 .word 0x00010007 + +08003200 : + * 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) +{ + 8003200: b580 push {r7, lr} + 8003202: b082 sub sp, #8 + 8003204: af00 add r7, sp, #0 + 8003206: 6078 str r0, [r7, #4] + /* Check the TIM handle allocation */ + if (htim == NULL) + 8003208: 687b ldr r3, [r7, #4] + 800320a: 2b00 cmp r3, #0 + 800320c: d101 bne.n 8003212 + { + return HAL_ERROR; + 800320e: 2301 movs r3, #1 + 8003210: e01d b.n 800324e + 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) + 8003212: 687b ldr r3, [r7, #4] + 8003214: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 8003218: b2db uxtb r3, r3 + 800321a: 2b00 cmp r3, #0 + 800321c: d106 bne.n 800322c + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + 800321e: 687b ldr r3, [r7, #4] + 8003220: 2200 movs r2, #0 + 8003222: 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); + 8003226: 6878 ldr r0, [r7, #4] + 8003228: f000 f815 bl 8003256 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + 800322c: 687b ldr r3, [r7, #4] + 800322e: 2202 movs r2, #2 + 8003230: f883 203d strb.w r2, [r3, #61] ; 0x3d + + /* Init the base time for the PWM */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + 8003234: 687b ldr r3, [r7, #4] + 8003236: 681a ldr r2, [r3, #0] + 8003238: 687b ldr r3, [r7, #4] + 800323a: 3304 adds r3, #4 + 800323c: 4619 mov r1, r3 + 800323e: 4610 mov r0, r2 + 8003240: f000 fc3a bl 8003ab8 + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + 8003244: 687b ldr r3, [r7, #4] + 8003246: 2201 movs r2, #1 + 8003248: f883 203d strb.w r2, [r3, #61] ; 0x3d + + return HAL_OK; + 800324c: 2300 movs r3, #0 +} + 800324e: 4618 mov r0, r3 + 8003250: 3708 adds r7, #8 + 8003252: 46bd mov sp, r7 + 8003254: bd80 pop {r7, pc} + +08003256 : + * @brief Initializes the TIM PWM MSP. + * @param htim TIM PWM handle + * @retval None + */ +__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) +{ + 8003256: b480 push {r7} + 8003258: b083 sub sp, #12 + 800325a: af00 add r7, sp, #0 + 800325c: 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 + */ +} + 800325e: bf00 nop + 8003260: 370c adds r7, #12 + 8003262: 46bd mov sp, r7 + 8003264: f85d 7b04 ldr.w r7, [sp], #4 + 8003268: 4770 bx lr + ... + +0800326c : + * @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) +{ + 800326c: b580 push {r7, lr} + 800326e: b084 sub sp, #16 + 8003270: af00 add r7, sp, #0 + 8003272: 6078 str r0, [r7, #4] + 8003274: 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); + 8003276: 687b ldr r3, [r7, #4] + 8003278: 681b ldr r3, [r3, #0] + 800327a: 2201 movs r2, #1 + 800327c: 6839 ldr r1, [r7, #0] + 800327e: 4618 mov r0, r3 + 8003280: f000 ffb2 bl 80041e8 + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + 8003284: 687b ldr r3, [r7, #4] + 8003286: 681b ldr r3, [r3, #0] + 8003288: 4a17 ldr r2, [pc, #92] ; (80032e8 ) + 800328a: 4293 cmp r3, r2 + 800328c: d004 beq.n 8003298 + 800328e: 687b ldr r3, [r7, #4] + 8003290: 681b ldr r3, [r3, #0] + 8003292: 4a16 ldr r2, [pc, #88] ; (80032ec ) + 8003294: 4293 cmp r3, r2 + 8003296: d101 bne.n 800329c + 8003298: 2301 movs r3, #1 + 800329a: e000 b.n 800329e + 800329c: 2300 movs r3, #0 + 800329e: 2b00 cmp r3, #0 + 80032a0: d007 beq.n 80032b2 + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + 80032a2: 687b ldr r3, [r7, #4] + 80032a4: 681b ldr r3, [r3, #0] + 80032a6: 6c5a ldr r2, [r3, #68] ; 0x44 + 80032a8: 687b ldr r3, [r7, #4] + 80032aa: 681b ldr r3, [r3, #0] + 80032ac: f442 4200 orr.w r2, r2, #32768 ; 0x8000 + 80032b0: 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; + 80032b2: 687b ldr r3, [r7, #4] + 80032b4: 681b ldr r3, [r3, #0] + 80032b6: 689a ldr r2, [r3, #8] + 80032b8: 4b0d ldr r3, [pc, #52] ; (80032f0 ) + 80032ba: 4013 ands r3, r2 + 80032bc: 60fb str r3, [r7, #12] + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + 80032be: 68fb ldr r3, [r7, #12] + 80032c0: 2b06 cmp r3, #6 + 80032c2: d00b beq.n 80032dc + 80032c4: 68fb ldr r3, [r7, #12] + 80032c6: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 80032ca: d007 beq.n 80032dc + { + __HAL_TIM_ENABLE(htim); + 80032cc: 687b ldr r3, [r7, #4] + 80032ce: 681b ldr r3, [r3, #0] + 80032d0: 681a ldr r2, [r3, #0] + 80032d2: 687b ldr r3, [r7, #4] + 80032d4: 681b ldr r3, [r3, #0] + 80032d6: f042 0201 orr.w r2, r2, #1 + 80032da: 601a str r2, [r3, #0] + } + + /* Return function status */ + return HAL_OK; + 80032dc: 2300 movs r3, #0 +} + 80032de: 4618 mov r0, r3 + 80032e0: 3710 adds r7, #16 + 80032e2: 46bd mov sp, r7 + 80032e4: bd80 pop {r7, pc} + 80032e6: bf00 nop + 80032e8: 40010000 .word 0x40010000 + 80032ec: 40010400 .word 0x40010400 + 80032f0: 00010007 .word 0x00010007 + +080032f4 : + * @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) +{ + 80032f4: b580 push {r7, lr} + 80032f6: b086 sub sp, #24 + 80032f8: af00 add r7, sp, #0 + 80032fa: 6078 str r0, [r7, #4] + 80032fc: 6039 str r1, [r7, #0] + uint32_t tmpsmcr; + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Check the TIM handle allocation */ + if (htim == NULL) + 80032fe: 687b ldr r3, [r7, #4] + 8003300: 2b00 cmp r3, #0 + 8003302: d101 bne.n 8003308 + { + return HAL_ERROR; + 8003304: 2301 movs r3, #1 + 8003306: e07b b.n 8003400 + 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) + 8003308: 687b ldr r3, [r7, #4] + 800330a: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 800330e: b2db uxtb r3, r3 + 8003310: 2b00 cmp r3, #0 + 8003312: d106 bne.n 8003322 + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + 8003314: 687b ldr r3, [r7, #4] + 8003316: 2200 movs r2, #0 + 8003318: 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); + 800331c: 6878 ldr r0, [r7, #4] + 800331e: f7fd fde9 bl 8000ef4 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + 8003322: 687b ldr r3, [r7, #4] + 8003324: 2202 movs r2, #2 + 8003326: f883 203d strb.w r2, [r3, #61] ; 0x3d + + /* Reset the SMS and ECE bits */ + htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); + 800332a: 687b ldr r3, [r7, #4] + 800332c: 681b ldr r3, [r3, #0] + 800332e: 6899 ldr r1, [r3, #8] + 8003330: 687b ldr r3, [r7, #4] + 8003332: 681a ldr r2, [r3, #0] + 8003334: 4b34 ldr r3, [pc, #208] ; (8003408 ) + 8003336: 400b ands r3, r1 + 8003338: 6093 str r3, [r2, #8] + + /* Configure the Time base in the Encoder Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + 800333a: 687b ldr r3, [r7, #4] + 800333c: 681a ldr r2, [r3, #0] + 800333e: 687b ldr r3, [r7, #4] + 8003340: 3304 adds r3, #4 + 8003342: 4619 mov r1, r3 + 8003344: 4610 mov r0, r2 + 8003346: f000 fbb7 bl 8003ab8 + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + 800334a: 687b ldr r3, [r7, #4] + 800334c: 681b ldr r3, [r3, #0] + 800334e: 689b ldr r3, [r3, #8] + 8003350: 617b str r3, [r7, #20] + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = htim->Instance->CCMR1; + 8003352: 687b ldr r3, [r7, #4] + 8003354: 681b ldr r3, [r3, #0] + 8003356: 699b ldr r3, [r3, #24] + 8003358: 613b str r3, [r7, #16] + + /* Get the TIMx CCER register value */ + tmpccer = htim->Instance->CCER; + 800335a: 687b ldr r3, [r7, #4] + 800335c: 681b ldr r3, [r3, #0] + 800335e: 6a1b ldr r3, [r3, #32] + 8003360: 60fb str r3, [r7, #12] + + /* Set the encoder Mode */ + tmpsmcr |= sConfig->EncoderMode; + 8003362: 683b ldr r3, [r7, #0] + 8003364: 681b ldr r3, [r3, #0] + 8003366: 697a ldr r2, [r7, #20] + 8003368: 4313 orrs r3, r2 + 800336a: 617b str r3, [r7, #20] + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); + 800336c: 693a ldr r2, [r7, #16] + 800336e: 4b27 ldr r3, [pc, #156] ; (800340c ) + 8003370: 4013 ands r3, r2 + 8003372: 613b str r3, [r7, #16] + tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); + 8003374: 683b ldr r3, [r7, #0] + 8003376: 689a ldr r2, [r3, #8] + 8003378: 683b ldr r3, [r7, #0] + 800337a: 699b ldr r3, [r3, #24] + 800337c: 021b lsls r3, r3, #8 + 800337e: 4313 orrs r3, r2 + 8003380: 693a ldr r2, [r7, #16] + 8003382: 4313 orrs r3, r2 + 8003384: 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); + 8003386: 693a ldr r2, [r7, #16] + 8003388: 4b21 ldr r3, [pc, #132] ; (8003410 ) + 800338a: 4013 ands r3, r2 + 800338c: 613b str r3, [r7, #16] + tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); + 800338e: 693a ldr r2, [r7, #16] + 8003390: 4b20 ldr r3, [pc, #128] ; (8003414 ) + 8003392: 4013 ands r3, r2 + 8003394: 613b str r3, [r7, #16] + tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); + 8003396: 683b ldr r3, [r7, #0] + 8003398: 68da ldr r2, [r3, #12] + 800339a: 683b ldr r3, [r7, #0] + 800339c: 69db ldr r3, [r3, #28] + 800339e: 021b lsls r3, r3, #8 + 80033a0: 4313 orrs r3, r2 + 80033a2: 693a ldr r2, [r7, #16] + 80033a4: 4313 orrs r3, r2 + 80033a6: 613b str r3, [r7, #16] + tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); + 80033a8: 683b ldr r3, [r7, #0] + 80033aa: 691b ldr r3, [r3, #16] + 80033ac: 011a lsls r2, r3, #4 + 80033ae: 683b ldr r3, [r7, #0] + 80033b0: 6a1b ldr r3, [r3, #32] + 80033b2: 031b lsls r3, r3, #12 + 80033b4: 4313 orrs r3, r2 + 80033b6: 693a ldr r2, [r7, #16] + 80033b8: 4313 orrs r3, r2 + 80033ba: 613b str r3, [r7, #16] + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); + 80033bc: 68fb ldr r3, [r7, #12] + 80033be: f023 0322 bic.w r3, r3, #34 ; 0x22 + 80033c2: 60fb str r3, [r7, #12] + tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); + 80033c4: 68fb ldr r3, [r7, #12] + 80033c6: f023 0388 bic.w r3, r3, #136 ; 0x88 + 80033ca: 60fb str r3, [r7, #12] + tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); + 80033cc: 683b ldr r3, [r7, #0] + 80033ce: 685a ldr r2, [r3, #4] + 80033d0: 683b ldr r3, [r7, #0] + 80033d2: 695b ldr r3, [r3, #20] + 80033d4: 011b lsls r3, r3, #4 + 80033d6: 4313 orrs r3, r2 + 80033d8: 68fa ldr r2, [r7, #12] + 80033da: 4313 orrs r3, r2 + 80033dc: 60fb str r3, [r7, #12] + + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + 80033de: 687b ldr r3, [r7, #4] + 80033e0: 681b ldr r3, [r3, #0] + 80033e2: 697a ldr r2, [r7, #20] + 80033e4: 609a str r2, [r3, #8] + + /* Write to TIMx CCMR1 */ + htim->Instance->CCMR1 = tmpccmr1; + 80033e6: 687b ldr r3, [r7, #4] + 80033e8: 681b ldr r3, [r3, #0] + 80033ea: 693a ldr r2, [r7, #16] + 80033ec: 619a str r2, [r3, #24] + + /* Write to TIMx CCER */ + htim->Instance->CCER = tmpccer; + 80033ee: 687b ldr r3, [r7, #4] + 80033f0: 681b ldr r3, [r3, #0] + 80033f2: 68fa ldr r2, [r7, #12] + 80033f4: 621a str r2, [r3, #32] + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + 80033f6: 687b ldr r3, [r7, #4] + 80033f8: 2201 movs r2, #1 + 80033fa: f883 203d strb.w r2, [r3, #61] ; 0x3d + + return HAL_OK; + 80033fe: 2300 movs r3, #0 +} + 8003400: 4618 mov r0, r3 + 8003402: 3718 adds r7, #24 + 8003404: 46bd mov sp, r7 + 8003406: bd80 pop {r7, pc} + 8003408: fffebff8 .word 0xfffebff8 + 800340c: fffffcfc .word 0xfffffcfc + 8003410: fffff3f3 .word 0xfffff3f3 + 8003414: ffff0f0f .word 0xffff0f0f + +08003418 : + * @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) +{ + 8003418: b580 push {r7, lr} + 800341a: b082 sub sp, #8 + 800341c: af00 add r7, sp, #0 + 800341e: 6078 str r0, [r7, #4] + 8003420: 6039 str r1, [r7, #0] + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Enable the encoder interface channels */ + switch (Channel) + 8003422: 683b ldr r3, [r7, #0] + 8003424: 2b00 cmp r3, #0 + 8003426: d002 beq.n 800342e + 8003428: 2b04 cmp r3, #4 + 800342a: d008 beq.n 800343e + 800342c: e00f b.n 800344e + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + 800342e: 687b ldr r3, [r7, #4] + 8003430: 681b ldr r3, [r3, #0] + 8003432: 2201 movs r2, #1 + 8003434: 2100 movs r1, #0 + 8003436: 4618 mov r0, r3 + 8003438: f000 fed6 bl 80041e8 + break; + 800343c: e016 b.n 800346c + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + 800343e: 687b ldr r3, [r7, #4] + 8003440: 681b ldr r3, [r3, #0] + 8003442: 2201 movs r2, #1 + 8003444: 2104 movs r1, #4 + 8003446: 4618 mov r0, r3 + 8003448: f000 fece bl 80041e8 + break; + 800344c: e00e b.n 800346c + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + 800344e: 687b ldr r3, [r7, #4] + 8003450: 681b ldr r3, [r3, #0] + 8003452: 2201 movs r2, #1 + 8003454: 2100 movs r1, #0 + 8003456: 4618 mov r0, r3 + 8003458: f000 fec6 bl 80041e8 + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + 800345c: 687b ldr r3, [r7, #4] + 800345e: 681b ldr r3, [r3, #0] + 8003460: 2201 movs r2, #1 + 8003462: 2104 movs r1, #4 + 8003464: 4618 mov r0, r3 + 8003466: f000 febf bl 80041e8 + break; + 800346a: bf00 nop + } + } + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + 800346c: 687b ldr r3, [r7, #4] + 800346e: 681b ldr r3, [r3, #0] + 8003470: 681a ldr r2, [r3, #0] + 8003472: 687b ldr r3, [r7, #4] + 8003474: 681b ldr r3, [r3, #0] + 8003476: f042 0201 orr.w r2, r2, #1 + 800347a: 601a str r2, [r3, #0] + + /* Return function status */ + return HAL_OK; + 800347c: 2300 movs r3, #0 +} + 800347e: 4618 mov r0, r3 + 8003480: 3708 adds r7, #8 + 8003482: 46bd mov sp, r7 + 8003484: bd80 pop {r7, pc} + +08003486 : + * @brief This function handles TIM interrupts requests. + * @param htim TIM handle + * @retval None + */ +void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) +{ + 8003486: b580 push {r7, lr} + 8003488: b082 sub sp, #8 + 800348a: af00 add r7, sp, #0 + 800348c: 6078 str r0, [r7, #4] + /* Capture compare 1 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) + 800348e: 687b ldr r3, [r7, #4] + 8003490: 681b ldr r3, [r3, #0] + 8003492: 691b ldr r3, [r3, #16] + 8003494: f003 0302 and.w r3, r3, #2 + 8003498: 2b02 cmp r3, #2 + 800349a: d122 bne.n 80034e2 + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) + 800349c: 687b ldr r3, [r7, #4] + 800349e: 681b ldr r3, [r3, #0] + 80034a0: 68db ldr r3, [r3, #12] + 80034a2: f003 0302 and.w r3, r3, #2 + 80034a6: 2b02 cmp r3, #2 + 80034a8: d11b bne.n 80034e2 + { + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); + 80034aa: 687b ldr r3, [r7, #4] + 80034ac: 681b ldr r3, [r3, #0] + 80034ae: f06f 0202 mvn.w r2, #2 + 80034b2: 611a str r2, [r3, #16] + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + 80034b4: 687b ldr r3, [r7, #4] + 80034b6: 2201 movs r2, #1 + 80034b8: 771a strb r2, [r3, #28] + + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) + 80034ba: 687b ldr r3, [r7, #4] + 80034bc: 681b ldr r3, [r3, #0] + 80034be: 699b ldr r3, [r3, #24] + 80034c0: f003 0303 and.w r3, r3, #3 + 80034c4: 2b00 cmp r3, #0 + 80034c6: d003 beq.n 80034d0 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); + 80034c8: 6878 ldr r0, [r7, #4] + 80034ca: f000 fad7 bl 8003a7c + 80034ce: e005 b.n 80034dc + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + 80034d0: 6878 ldr r0, [r7, #4] + 80034d2: f000 fac9 bl 8003a68 + HAL_TIM_PWM_PulseFinishedCallback(htim); + 80034d6: 6878 ldr r0, [r7, #4] + 80034d8: f000 fada bl 8003a90 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + 80034dc: 687b ldr r3, [r7, #4] + 80034de: 2200 movs r2, #0 + 80034e0: 771a strb r2, [r3, #28] + } + } + } + /* Capture compare 2 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) + 80034e2: 687b ldr r3, [r7, #4] + 80034e4: 681b ldr r3, [r3, #0] + 80034e6: 691b ldr r3, [r3, #16] + 80034e8: f003 0304 and.w r3, r3, #4 + 80034ec: 2b04 cmp r3, #4 + 80034ee: d122 bne.n 8003536 + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) + 80034f0: 687b ldr r3, [r7, #4] + 80034f2: 681b ldr r3, [r3, #0] + 80034f4: 68db ldr r3, [r3, #12] + 80034f6: f003 0304 and.w r3, r3, #4 + 80034fa: 2b04 cmp r3, #4 + 80034fc: d11b bne.n 8003536 + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); + 80034fe: 687b ldr r3, [r7, #4] + 8003500: 681b ldr r3, [r3, #0] + 8003502: f06f 0204 mvn.w r2, #4 + 8003506: 611a str r2, [r3, #16] + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + 8003508: 687b ldr r3, [r7, #4] + 800350a: 2202 movs r2, #2 + 800350c: 771a strb r2, [r3, #28] + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) + 800350e: 687b ldr r3, [r7, #4] + 8003510: 681b ldr r3, [r3, #0] + 8003512: 699b ldr r3, [r3, #24] + 8003514: f403 7340 and.w r3, r3, #768 ; 0x300 + 8003518: 2b00 cmp r3, #0 + 800351a: d003 beq.n 8003524 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); + 800351c: 6878 ldr r0, [r7, #4] + 800351e: f000 faad bl 8003a7c + 8003522: e005 b.n 8003530 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + 8003524: 6878 ldr r0, [r7, #4] + 8003526: f000 fa9f bl 8003a68 + HAL_TIM_PWM_PulseFinishedCallback(htim); + 800352a: 6878 ldr r0, [r7, #4] + 800352c: f000 fab0 bl 8003a90 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + 8003530: 687b ldr r3, [r7, #4] + 8003532: 2200 movs r2, #0 + 8003534: 771a strb r2, [r3, #28] + } + } + /* Capture compare 3 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) + 8003536: 687b ldr r3, [r7, #4] + 8003538: 681b ldr r3, [r3, #0] + 800353a: 691b ldr r3, [r3, #16] + 800353c: f003 0308 and.w r3, r3, #8 + 8003540: 2b08 cmp r3, #8 + 8003542: d122 bne.n 800358a + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) + 8003544: 687b ldr r3, [r7, #4] + 8003546: 681b ldr r3, [r3, #0] + 8003548: 68db ldr r3, [r3, #12] + 800354a: f003 0308 and.w r3, r3, #8 + 800354e: 2b08 cmp r3, #8 + 8003550: d11b bne.n 800358a + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); + 8003552: 687b ldr r3, [r7, #4] + 8003554: 681b ldr r3, [r3, #0] + 8003556: f06f 0208 mvn.w r2, #8 + 800355a: 611a str r2, [r3, #16] + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + 800355c: 687b ldr r3, [r7, #4] + 800355e: 2204 movs r2, #4 + 8003560: 771a strb r2, [r3, #28] + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) + 8003562: 687b ldr r3, [r7, #4] + 8003564: 681b ldr r3, [r3, #0] + 8003566: 69db ldr r3, [r3, #28] + 8003568: f003 0303 and.w r3, r3, #3 + 800356c: 2b00 cmp r3, #0 + 800356e: d003 beq.n 8003578 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); + 8003570: 6878 ldr r0, [r7, #4] + 8003572: f000 fa83 bl 8003a7c + 8003576: e005 b.n 8003584 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + 8003578: 6878 ldr r0, [r7, #4] + 800357a: f000 fa75 bl 8003a68 + HAL_TIM_PWM_PulseFinishedCallback(htim); + 800357e: 6878 ldr r0, [r7, #4] + 8003580: f000 fa86 bl 8003a90 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + 8003584: 687b ldr r3, [r7, #4] + 8003586: 2200 movs r2, #0 + 8003588: 771a strb r2, [r3, #28] + } + } + /* Capture compare 4 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) + 800358a: 687b ldr r3, [r7, #4] + 800358c: 681b ldr r3, [r3, #0] + 800358e: 691b ldr r3, [r3, #16] + 8003590: f003 0310 and.w r3, r3, #16 + 8003594: 2b10 cmp r3, #16 + 8003596: d122 bne.n 80035de + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) + 8003598: 687b ldr r3, [r7, #4] + 800359a: 681b ldr r3, [r3, #0] + 800359c: 68db ldr r3, [r3, #12] + 800359e: f003 0310 and.w r3, r3, #16 + 80035a2: 2b10 cmp r3, #16 + 80035a4: d11b bne.n 80035de + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); + 80035a6: 687b ldr r3, [r7, #4] + 80035a8: 681b ldr r3, [r3, #0] + 80035aa: f06f 0210 mvn.w r2, #16 + 80035ae: 611a str r2, [r3, #16] + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + 80035b0: 687b ldr r3, [r7, #4] + 80035b2: 2208 movs r2, #8 + 80035b4: 771a strb r2, [r3, #28] + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) + 80035b6: 687b ldr r3, [r7, #4] + 80035b8: 681b ldr r3, [r3, #0] + 80035ba: 69db ldr r3, [r3, #28] + 80035bc: f403 7340 and.w r3, r3, #768 ; 0x300 + 80035c0: 2b00 cmp r3, #0 + 80035c2: d003 beq.n 80035cc + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); + 80035c4: 6878 ldr r0, [r7, #4] + 80035c6: f000 fa59 bl 8003a7c + 80035ca: e005 b.n 80035d8 + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + 80035cc: 6878 ldr r0, [r7, #4] + 80035ce: f000 fa4b bl 8003a68 + HAL_TIM_PWM_PulseFinishedCallback(htim); + 80035d2: 6878 ldr r0, [r7, #4] + 80035d4: f000 fa5c bl 8003a90 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + 80035d8: 687b ldr r3, [r7, #4] + 80035da: 2200 movs r2, #0 + 80035dc: 771a strb r2, [r3, #28] + } + } + /* TIM Update event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) + 80035de: 687b ldr r3, [r7, #4] + 80035e0: 681b ldr r3, [r3, #0] + 80035e2: 691b ldr r3, [r3, #16] + 80035e4: f003 0301 and.w r3, r3, #1 + 80035e8: 2b01 cmp r3, #1 + 80035ea: d10e bne.n 800360a + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) + 80035ec: 687b ldr r3, [r7, #4] + 80035ee: 681b ldr r3, [r3, #0] + 80035f0: 68db ldr r3, [r3, #12] + 80035f2: f003 0301 and.w r3, r3, #1 + 80035f6: 2b01 cmp r3, #1 + 80035f8: d107 bne.n 800360a + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); + 80035fa: 687b ldr r3, [r7, #4] + 80035fc: 681b ldr r3, [r3, #0] + 80035fe: f06f 0201 mvn.w r2, #1 + 8003602: 611a str r2, [r3, #16] +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedCallback(htim); +#else + HAL_TIM_PeriodElapsedCallback(htim); + 8003604: 6878 ldr r0, [r7, #4] + 8003606: f7fd fbff bl 8000e08 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Break input event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) + 800360a: 687b ldr r3, [r7, #4] + 800360c: 681b ldr r3, [r3, #0] + 800360e: 691b ldr r3, [r3, #16] + 8003610: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003614: 2b80 cmp r3, #128 ; 0x80 + 8003616: d10e bne.n 8003636 + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) + 8003618: 687b ldr r3, [r7, #4] + 800361a: 681b ldr r3, [r3, #0] + 800361c: 68db ldr r3, [r3, #12] + 800361e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003622: 2b80 cmp r3, #128 ; 0x80 + 8003624: d107 bne.n 8003636 + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); + 8003626: 687b ldr r3, [r7, #4] + 8003628: 681b ldr r3, [r3, #0] + 800362a: f06f 0280 mvn.w r2, #128 ; 0x80 + 800362e: 611a str r2, [r3, #16] +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->BreakCallback(htim); +#else + HAL_TIMEx_BreakCallback(htim); + 8003630: 6878 ldr r0, [r7, #4] + 8003632: f000 fe65 bl 8004300 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Break2 input event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK2) != RESET) + 8003636: 687b ldr r3, [r7, #4] + 8003638: 681b ldr r3, [r3, #0] + 800363a: 691b ldr r3, [r3, #16] + 800363c: f403 7380 and.w r3, r3, #256 ; 0x100 + 8003640: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8003644: d10e bne.n 8003664 + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) + 8003646: 687b ldr r3, [r7, #4] + 8003648: 681b ldr r3, [r3, #0] + 800364a: 68db ldr r3, [r3, #12] + 800364c: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003650: 2b80 cmp r3, #128 ; 0x80 + 8003652: d107 bne.n 8003664 + { + __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_BREAK2); + 8003654: 687b ldr r3, [r7, #4] + 8003656: 681b ldr r3, [r3, #0] + 8003658: f46f 7280 mvn.w r2, #256 ; 0x100 + 800365c: 611a str r2, [r3, #16] +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->Break2Callback(htim); +#else + HAL_TIMEx_Break2Callback(htim); + 800365e: 6878 ldr r0, [r7, #4] + 8003660: f000 fe58 bl 8004314 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Trigger detection event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) + 8003664: 687b ldr r3, [r7, #4] + 8003666: 681b ldr r3, [r3, #0] + 8003668: 691b ldr r3, [r3, #16] + 800366a: f003 0340 and.w r3, r3, #64 ; 0x40 + 800366e: 2b40 cmp r3, #64 ; 0x40 + 8003670: d10e bne.n 8003690 + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) + 8003672: 687b ldr r3, [r7, #4] + 8003674: 681b ldr r3, [r3, #0] + 8003676: 68db ldr r3, [r3, #12] + 8003678: f003 0340 and.w r3, r3, #64 ; 0x40 + 800367c: 2b40 cmp r3, #64 ; 0x40 + 800367e: d107 bne.n 8003690 + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); + 8003680: 687b ldr r3, [r7, #4] + 8003682: 681b ldr r3, [r3, #0] + 8003684: f06f 0240 mvn.w r2, #64 ; 0x40 + 8003688: 611a str r2, [r3, #16] +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerCallback(htim); +#else + HAL_TIM_TriggerCallback(htim); + 800368a: 6878 ldr r0, [r7, #4] + 800368c: f000 fa0a bl 8003aa4 +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM commutation event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) + 8003690: 687b ldr r3, [r7, #4] + 8003692: 681b ldr r3, [r3, #0] + 8003694: 691b ldr r3, [r3, #16] + 8003696: f003 0320 and.w r3, r3, #32 + 800369a: 2b20 cmp r3, #32 + 800369c: d10e bne.n 80036bc + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) + 800369e: 687b ldr r3, [r7, #4] + 80036a0: 681b ldr r3, [r3, #0] + 80036a2: 68db ldr r3, [r3, #12] + 80036a4: f003 0320 and.w r3, r3, #32 + 80036a8: 2b20 cmp r3, #32 + 80036aa: d107 bne.n 80036bc + { + __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); + 80036ac: 687b ldr r3, [r7, #4] + 80036ae: 681b ldr r3, [r3, #0] + 80036b0: f06f 0220 mvn.w r2, #32 + 80036b4: 611a str r2, [r3, #16] +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationCallback(htim); +#else + HAL_TIMEx_CommutCallback(htim); + 80036b6: 6878 ldr r0, [r7, #4] + 80036b8: f000 fe18 bl 80042ec +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } +} + 80036bc: bf00 nop + 80036be: 3708 adds r7, #8 + 80036c0: 46bd mov sp, r7 + 80036c2: bd80 pop {r7, pc} + +080036c4 : + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, + TIM_OC_InitTypeDef *sConfig, + uint32_t Channel) +{ + 80036c4: b580 push {r7, lr} + 80036c6: b084 sub sp, #16 + 80036c8: af00 add r7, sp, #0 + 80036ca: 60f8 str r0, [r7, #12] + 80036cc: 60b9 str r1, [r7, #8] + 80036ce: 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); + 80036d0: 68fb ldr r3, [r7, #12] + 80036d2: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 80036d6: 2b01 cmp r3, #1 + 80036d8: d101 bne.n 80036de + 80036da: 2302 movs r3, #2 + 80036dc: e105 b.n 80038ea + 80036de: 68fb ldr r3, [r7, #12] + 80036e0: 2201 movs r2, #1 + 80036e2: f883 203c strb.w r2, [r3, #60] ; 0x3c + + htim->State = HAL_TIM_STATE_BUSY; + 80036e6: 68fb ldr r3, [r7, #12] + 80036e8: 2202 movs r2, #2 + 80036ea: f883 203d strb.w r2, [r3, #61] ; 0x3d + + switch (Channel) + 80036ee: 687b ldr r3, [r7, #4] + 80036f0: 2b14 cmp r3, #20 + 80036f2: f200 80f0 bhi.w 80038d6 + 80036f6: a201 add r2, pc, #4 ; (adr r2, 80036fc ) + 80036f8: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 80036fc: 08003751 .word 0x08003751 + 8003700: 080038d7 .word 0x080038d7 + 8003704: 080038d7 .word 0x080038d7 + 8003708: 080038d7 .word 0x080038d7 + 800370c: 08003791 .word 0x08003791 + 8003710: 080038d7 .word 0x080038d7 + 8003714: 080038d7 .word 0x080038d7 + 8003718: 080038d7 .word 0x080038d7 + 800371c: 080037d3 .word 0x080037d3 + 8003720: 080038d7 .word 0x080038d7 + 8003724: 080038d7 .word 0x080038d7 + 8003728: 080038d7 .word 0x080038d7 + 800372c: 08003813 .word 0x08003813 + 8003730: 080038d7 .word 0x080038d7 + 8003734: 080038d7 .word 0x080038d7 + 8003738: 080038d7 .word 0x080038d7 + 800373c: 08003855 .word 0x08003855 + 8003740: 080038d7 .word 0x080038d7 + 8003744: 080038d7 .word 0x080038d7 + 8003748: 080038d7 .word 0x080038d7 + 800374c: 08003895 .word 0x08003895 + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Configure the Channel 1 in PWM mode */ + TIM_OC1_SetConfig(htim->Instance, sConfig); + 8003750: 68fb ldr r3, [r7, #12] + 8003752: 681b ldr r3, [r3, #0] + 8003754: 68b9 ldr r1, [r7, #8] + 8003756: 4618 mov r0, r3 + 8003758: f000 fa4e bl 8003bf8 + + /* Set the Preload enable bit for channel1 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; + 800375c: 68fb ldr r3, [r7, #12] + 800375e: 681b ldr r3, [r3, #0] + 8003760: 699a ldr r2, [r3, #24] + 8003762: 68fb ldr r3, [r7, #12] + 8003764: 681b ldr r3, [r3, #0] + 8003766: f042 0208 orr.w r2, r2, #8 + 800376a: 619a str r2, [r3, #24] + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; + 800376c: 68fb ldr r3, [r7, #12] + 800376e: 681b ldr r3, [r3, #0] + 8003770: 699a ldr r2, [r3, #24] + 8003772: 68fb ldr r3, [r7, #12] + 8003774: 681b ldr r3, [r3, #0] + 8003776: f022 0204 bic.w r2, r2, #4 + 800377a: 619a str r2, [r3, #24] + htim->Instance->CCMR1 |= sConfig->OCFastMode; + 800377c: 68fb ldr r3, [r7, #12] + 800377e: 681b ldr r3, [r3, #0] + 8003780: 6999 ldr r1, [r3, #24] + 8003782: 68bb ldr r3, [r7, #8] + 8003784: 691a ldr r2, [r3, #16] + 8003786: 68fb ldr r3, [r7, #12] + 8003788: 681b ldr r3, [r3, #0] + 800378a: 430a orrs r2, r1 + 800378c: 619a str r2, [r3, #24] + break; + 800378e: e0a3 b.n 80038d8 + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Configure the Channel 2 in PWM mode */ + TIM_OC2_SetConfig(htim->Instance, sConfig); + 8003790: 68fb ldr r3, [r7, #12] + 8003792: 681b ldr r3, [r3, #0] + 8003794: 68b9 ldr r1, [r7, #8] + 8003796: 4618 mov r0, r3 + 8003798: f000 faa0 bl 8003cdc + + /* Set the Preload enable bit for channel2 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; + 800379c: 68fb ldr r3, [r7, #12] + 800379e: 681b ldr r3, [r3, #0] + 80037a0: 699a ldr r2, [r3, #24] + 80037a2: 68fb ldr r3, [r7, #12] + 80037a4: 681b ldr r3, [r3, #0] + 80037a6: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 80037aa: 619a str r2, [r3, #24] + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; + 80037ac: 68fb ldr r3, [r7, #12] + 80037ae: 681b ldr r3, [r3, #0] + 80037b0: 699a ldr r2, [r3, #24] + 80037b2: 68fb ldr r3, [r7, #12] + 80037b4: 681b ldr r3, [r3, #0] + 80037b6: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 80037ba: 619a str r2, [r3, #24] + htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; + 80037bc: 68fb ldr r3, [r7, #12] + 80037be: 681b ldr r3, [r3, #0] + 80037c0: 6999 ldr r1, [r3, #24] + 80037c2: 68bb ldr r3, [r7, #8] + 80037c4: 691b ldr r3, [r3, #16] + 80037c6: 021a lsls r2, r3, #8 + 80037c8: 68fb ldr r3, [r7, #12] + 80037ca: 681b ldr r3, [r3, #0] + 80037cc: 430a orrs r2, r1 + 80037ce: 619a str r2, [r3, #24] + break; + 80037d0: e082 b.n 80038d8 + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Configure the Channel 3 in PWM mode */ + TIM_OC3_SetConfig(htim->Instance, sConfig); + 80037d2: 68fb ldr r3, [r7, #12] + 80037d4: 681b ldr r3, [r3, #0] + 80037d6: 68b9 ldr r1, [r7, #8] + 80037d8: 4618 mov r0, r3 + 80037da: f000 faf7 bl 8003dcc + + /* Set the Preload enable bit for channel3 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; + 80037de: 68fb ldr r3, [r7, #12] + 80037e0: 681b ldr r3, [r3, #0] + 80037e2: 69da ldr r2, [r3, #28] + 80037e4: 68fb ldr r3, [r7, #12] + 80037e6: 681b ldr r3, [r3, #0] + 80037e8: f042 0208 orr.w r2, r2, #8 + 80037ec: 61da str r2, [r3, #28] + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; + 80037ee: 68fb ldr r3, [r7, #12] + 80037f0: 681b ldr r3, [r3, #0] + 80037f2: 69da ldr r2, [r3, #28] + 80037f4: 68fb ldr r3, [r7, #12] + 80037f6: 681b ldr r3, [r3, #0] + 80037f8: f022 0204 bic.w r2, r2, #4 + 80037fc: 61da str r2, [r3, #28] + htim->Instance->CCMR2 |= sConfig->OCFastMode; + 80037fe: 68fb ldr r3, [r7, #12] + 8003800: 681b ldr r3, [r3, #0] + 8003802: 69d9 ldr r1, [r3, #28] + 8003804: 68bb ldr r3, [r7, #8] + 8003806: 691a ldr r2, [r3, #16] + 8003808: 68fb ldr r3, [r7, #12] + 800380a: 681b ldr r3, [r3, #0] + 800380c: 430a orrs r2, r1 + 800380e: 61da str r2, [r3, #28] + break; + 8003810: e062 b.n 80038d8 + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Configure the Channel 4 in PWM mode */ + TIM_OC4_SetConfig(htim->Instance, sConfig); + 8003812: 68fb ldr r3, [r7, #12] + 8003814: 681b ldr r3, [r3, #0] + 8003816: 68b9 ldr r1, [r7, #8] + 8003818: 4618 mov r0, r3 + 800381a: f000 fb4d bl 8003eb8 + + /* Set the Preload enable bit for channel4 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; + 800381e: 68fb ldr r3, [r7, #12] + 8003820: 681b ldr r3, [r3, #0] + 8003822: 69da ldr r2, [r3, #28] + 8003824: 68fb ldr r3, [r7, #12] + 8003826: 681b ldr r3, [r3, #0] + 8003828: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 800382c: 61da str r2, [r3, #28] + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; + 800382e: 68fb ldr r3, [r7, #12] + 8003830: 681b ldr r3, [r3, #0] + 8003832: 69da ldr r2, [r3, #28] + 8003834: 68fb ldr r3, [r7, #12] + 8003836: 681b ldr r3, [r3, #0] + 8003838: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 800383c: 61da str r2, [r3, #28] + htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; + 800383e: 68fb ldr r3, [r7, #12] + 8003840: 681b ldr r3, [r3, #0] + 8003842: 69d9 ldr r1, [r3, #28] + 8003844: 68bb ldr r3, [r7, #8] + 8003846: 691b ldr r3, [r3, #16] + 8003848: 021a lsls r2, r3, #8 + 800384a: 68fb ldr r3, [r7, #12] + 800384c: 681b ldr r3, [r3, #0] + 800384e: 430a orrs r2, r1 + 8003850: 61da str r2, [r3, #28] + break; + 8003852: e041 b.n 80038d8 + { + /* Check the parameters */ + assert_param(IS_TIM_CC5_INSTANCE(htim->Instance)); + + /* Configure the Channel 5 in PWM mode */ + TIM_OC5_SetConfig(htim->Instance, sConfig); + 8003854: 68fb ldr r3, [r7, #12] + 8003856: 681b ldr r3, [r3, #0] + 8003858: 68b9 ldr r1, [r7, #8] + 800385a: 4618 mov r0, r3 + 800385c: f000 fb84 bl 8003f68 + + /* Set the Preload enable bit for channel5*/ + htim->Instance->CCMR3 |= TIM_CCMR3_OC5PE; + 8003860: 68fb ldr r3, [r7, #12] + 8003862: 681b ldr r3, [r3, #0] + 8003864: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003866: 68fb ldr r3, [r7, #12] + 8003868: 681b ldr r3, [r3, #0] + 800386a: f042 0208 orr.w r2, r2, #8 + 800386e: 655a str r2, [r3, #84] ; 0x54 + + /* Configure the Output Fast mode */ + htim->Instance->CCMR3 &= ~TIM_CCMR3_OC5FE; + 8003870: 68fb ldr r3, [r7, #12] + 8003872: 681b ldr r3, [r3, #0] + 8003874: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003876: 68fb ldr r3, [r7, #12] + 8003878: 681b ldr r3, [r3, #0] + 800387a: f022 0204 bic.w r2, r2, #4 + 800387e: 655a str r2, [r3, #84] ; 0x54 + htim->Instance->CCMR3 |= sConfig->OCFastMode; + 8003880: 68fb ldr r3, [r7, #12] + 8003882: 681b ldr r3, [r3, #0] + 8003884: 6d59 ldr r1, [r3, #84] ; 0x54 + 8003886: 68bb ldr r3, [r7, #8] + 8003888: 691a ldr r2, [r3, #16] + 800388a: 68fb ldr r3, [r7, #12] + 800388c: 681b ldr r3, [r3, #0] + 800388e: 430a orrs r2, r1 + 8003890: 655a str r2, [r3, #84] ; 0x54 + break; + 8003892: e021 b.n 80038d8 + { + /* Check the parameters */ + assert_param(IS_TIM_CC6_INSTANCE(htim->Instance)); + + /* Configure the Channel 6 in PWM mode */ + TIM_OC6_SetConfig(htim->Instance, sConfig); + 8003894: 68fb ldr r3, [r7, #12] + 8003896: 681b ldr r3, [r3, #0] + 8003898: 68b9 ldr r1, [r7, #8] + 800389a: 4618 mov r0, r3 + 800389c: f000 fbb6 bl 800400c + + /* Set the Preload enable bit for channel6 */ + htim->Instance->CCMR3 |= TIM_CCMR3_OC6PE; + 80038a0: 68fb ldr r3, [r7, #12] + 80038a2: 681b ldr r3, [r3, #0] + 80038a4: 6d5a ldr r2, [r3, #84] ; 0x54 + 80038a6: 68fb ldr r3, [r7, #12] + 80038a8: 681b ldr r3, [r3, #0] + 80038aa: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 80038ae: 655a str r2, [r3, #84] ; 0x54 + + /* Configure the Output Fast mode */ + htim->Instance->CCMR3 &= ~TIM_CCMR3_OC6FE; + 80038b0: 68fb ldr r3, [r7, #12] + 80038b2: 681b ldr r3, [r3, #0] + 80038b4: 6d5a ldr r2, [r3, #84] ; 0x54 + 80038b6: 68fb ldr r3, [r7, #12] + 80038b8: 681b ldr r3, [r3, #0] + 80038ba: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 80038be: 655a str r2, [r3, #84] ; 0x54 + htim->Instance->CCMR3 |= sConfig->OCFastMode << 8U; + 80038c0: 68fb ldr r3, [r7, #12] + 80038c2: 681b ldr r3, [r3, #0] + 80038c4: 6d59 ldr r1, [r3, #84] ; 0x54 + 80038c6: 68bb ldr r3, [r7, #8] + 80038c8: 691b ldr r3, [r3, #16] + 80038ca: 021a lsls r2, r3, #8 + 80038cc: 68fb ldr r3, [r7, #12] + 80038ce: 681b ldr r3, [r3, #0] + 80038d0: 430a orrs r2, r1 + 80038d2: 655a str r2, [r3, #84] ; 0x54 + break; + 80038d4: e000 b.n 80038d8 + } + + default: + break; + 80038d6: bf00 nop + } + + htim->State = HAL_TIM_STATE_READY; + 80038d8: 68fb ldr r3, [r7, #12] + 80038da: 2201 movs r2, #1 + 80038dc: f883 203d strb.w r2, [r3, #61] ; 0x3d + + __HAL_UNLOCK(htim); + 80038e0: 68fb ldr r3, [r7, #12] + 80038e2: 2200 movs r2, #0 + 80038e4: f883 203c strb.w r2, [r3, #60] ; 0x3c + + return HAL_OK; + 80038e8: 2300 movs r3, #0 +} + 80038ea: 4618 mov r0, r3 + 80038ec: 3710 adds r7, #16 + 80038ee: 46bd mov sp, r7 + 80038f0: bd80 pop {r7, pc} + 80038f2: bf00 nop + +080038f4 : + * @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) +{ + 80038f4: b580 push {r7, lr} + 80038f6: b084 sub sp, #16 + 80038f8: af00 add r7, sp, #0 + 80038fa: 6078 str r0, [r7, #4] + 80038fc: 6039 str r1, [r7, #0] + uint32_t tmpsmcr; + + /* Process Locked */ + __HAL_LOCK(htim); + 80038fe: 687b ldr r3, [r7, #4] + 8003900: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8003904: 2b01 cmp r3, #1 + 8003906: d101 bne.n 800390c + 8003908: 2302 movs r3, #2 + 800390a: e0a6 b.n 8003a5a + 800390c: 687b ldr r3, [r7, #4] + 800390e: 2201 movs r2, #1 + 8003910: f883 203c strb.w r2, [r3, #60] ; 0x3c + + htim->State = HAL_TIM_STATE_BUSY; + 8003914: 687b ldr r3, [r7, #4] + 8003916: 2202 movs r2, #2 + 8003918: 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; + 800391c: 687b ldr r3, [r7, #4] + 800391e: 681b ldr r3, [r3, #0] + 8003920: 689b ldr r3, [r3, #8] + 8003922: 60fb str r3, [r7, #12] + tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); + 8003924: 68fa ldr r2, [r7, #12] + 8003926: 4b4f ldr r3, [pc, #316] ; (8003a64 ) + 8003928: 4013 ands r3, r2 + 800392a: 60fb str r3, [r7, #12] + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + 800392c: 68fb ldr r3, [r7, #12] + 800392e: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 8003932: 60fb str r3, [r7, #12] + htim->Instance->SMCR = tmpsmcr; + 8003934: 687b ldr r3, [r7, #4] + 8003936: 681b ldr r3, [r3, #0] + 8003938: 68fa ldr r2, [r7, #12] + 800393a: 609a str r2, [r3, #8] + + switch (sClockSourceConfig->ClockSource) + 800393c: 683b ldr r3, [r7, #0] + 800393e: 681b ldr r3, [r3, #0] + 8003940: 2b40 cmp r3, #64 ; 0x40 + 8003942: d067 beq.n 8003a14 + 8003944: 2b40 cmp r3, #64 ; 0x40 + 8003946: d80b bhi.n 8003960 + 8003948: 2b10 cmp r3, #16 + 800394a: d073 beq.n 8003a34 + 800394c: 2b10 cmp r3, #16 + 800394e: d802 bhi.n 8003956 + 8003950: 2b00 cmp r3, #0 + 8003952: d06f beq.n 8003a34 + TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); + break; + } + + default: + break; + 8003954: e078 b.n 8003a48 + switch (sClockSourceConfig->ClockSource) + 8003956: 2b20 cmp r3, #32 + 8003958: d06c beq.n 8003a34 + 800395a: 2b30 cmp r3, #48 ; 0x30 + 800395c: d06a beq.n 8003a34 + break; + 800395e: e073 b.n 8003a48 + switch (sClockSourceConfig->ClockSource) + 8003960: 2b70 cmp r3, #112 ; 0x70 + 8003962: d00d beq.n 8003980 + 8003964: 2b70 cmp r3, #112 ; 0x70 + 8003966: d804 bhi.n 8003972 + 8003968: 2b50 cmp r3, #80 ; 0x50 + 800396a: d033 beq.n 80039d4 + 800396c: 2b60 cmp r3, #96 ; 0x60 + 800396e: d041 beq.n 80039f4 + break; + 8003970: e06a b.n 8003a48 + switch (sClockSourceConfig->ClockSource) + 8003972: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8003976: d066 beq.n 8003a46 + 8003978: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 800397c: d017 beq.n 80039ae + break; + 800397e: e063 b.n 8003a48 + TIM_ETR_SetConfig(htim->Instance, + 8003980: 687b ldr r3, [r7, #4] + 8003982: 6818 ldr r0, [r3, #0] + 8003984: 683b ldr r3, [r7, #0] + 8003986: 6899 ldr r1, [r3, #8] + 8003988: 683b ldr r3, [r7, #0] + 800398a: 685a ldr r2, [r3, #4] + 800398c: 683b ldr r3, [r7, #0] + 800398e: 68db ldr r3, [r3, #12] + 8003990: f000 fc0a bl 80041a8 + tmpsmcr = htim->Instance->SMCR; + 8003994: 687b ldr r3, [r7, #4] + 8003996: 681b ldr r3, [r3, #0] + 8003998: 689b ldr r3, [r3, #8] + 800399a: 60fb str r3, [r7, #12] + tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); + 800399c: 68fb ldr r3, [r7, #12] + 800399e: f043 0377 orr.w r3, r3, #119 ; 0x77 + 80039a2: 60fb str r3, [r7, #12] + htim->Instance->SMCR = tmpsmcr; + 80039a4: 687b ldr r3, [r7, #4] + 80039a6: 681b ldr r3, [r3, #0] + 80039a8: 68fa ldr r2, [r7, #12] + 80039aa: 609a str r2, [r3, #8] + break; + 80039ac: e04c b.n 8003a48 + TIM_ETR_SetConfig(htim->Instance, + 80039ae: 687b ldr r3, [r7, #4] + 80039b0: 6818 ldr r0, [r3, #0] + 80039b2: 683b ldr r3, [r7, #0] + 80039b4: 6899 ldr r1, [r3, #8] + 80039b6: 683b ldr r3, [r7, #0] + 80039b8: 685a ldr r2, [r3, #4] + 80039ba: 683b ldr r3, [r7, #0] + 80039bc: 68db ldr r3, [r3, #12] + 80039be: f000 fbf3 bl 80041a8 + htim->Instance->SMCR |= TIM_SMCR_ECE; + 80039c2: 687b ldr r3, [r7, #4] + 80039c4: 681b ldr r3, [r3, #0] + 80039c6: 689a ldr r2, [r3, #8] + 80039c8: 687b ldr r3, [r7, #4] + 80039ca: 681b ldr r3, [r3, #0] + 80039cc: f442 4280 orr.w r2, r2, #16384 ; 0x4000 + 80039d0: 609a str r2, [r3, #8] + break; + 80039d2: e039 b.n 8003a48 + TIM_TI1_ConfigInputStage(htim->Instance, + 80039d4: 687b ldr r3, [r7, #4] + 80039d6: 6818 ldr r0, [r3, #0] + 80039d8: 683b ldr r3, [r7, #0] + 80039da: 6859 ldr r1, [r3, #4] + 80039dc: 683b ldr r3, [r7, #0] + 80039de: 68db ldr r3, [r3, #12] + 80039e0: 461a mov r2, r3 + 80039e2: f000 fb67 bl 80040b4 + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); + 80039e6: 687b ldr r3, [r7, #4] + 80039e8: 681b ldr r3, [r3, #0] + 80039ea: 2150 movs r1, #80 ; 0x50 + 80039ec: 4618 mov r0, r3 + 80039ee: f000 fbc0 bl 8004172 + break; + 80039f2: e029 b.n 8003a48 + TIM_TI2_ConfigInputStage(htim->Instance, + 80039f4: 687b ldr r3, [r7, #4] + 80039f6: 6818 ldr r0, [r3, #0] + 80039f8: 683b ldr r3, [r7, #0] + 80039fa: 6859 ldr r1, [r3, #4] + 80039fc: 683b ldr r3, [r7, #0] + 80039fe: 68db ldr r3, [r3, #12] + 8003a00: 461a mov r2, r3 + 8003a02: f000 fb86 bl 8004112 + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); + 8003a06: 687b ldr r3, [r7, #4] + 8003a08: 681b ldr r3, [r3, #0] + 8003a0a: 2160 movs r1, #96 ; 0x60 + 8003a0c: 4618 mov r0, r3 + 8003a0e: f000 fbb0 bl 8004172 + break; + 8003a12: e019 b.n 8003a48 + TIM_TI1_ConfigInputStage(htim->Instance, + 8003a14: 687b ldr r3, [r7, #4] + 8003a16: 6818 ldr r0, [r3, #0] + 8003a18: 683b ldr r3, [r7, #0] + 8003a1a: 6859 ldr r1, [r3, #4] + 8003a1c: 683b ldr r3, [r7, #0] + 8003a1e: 68db ldr r3, [r3, #12] + 8003a20: 461a mov r2, r3 + 8003a22: f000 fb47 bl 80040b4 + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); + 8003a26: 687b ldr r3, [r7, #4] + 8003a28: 681b ldr r3, [r3, #0] + 8003a2a: 2140 movs r1, #64 ; 0x40 + 8003a2c: 4618 mov r0, r3 + 8003a2e: f000 fba0 bl 8004172 + break; + 8003a32: e009 b.n 8003a48 + TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); + 8003a34: 687b ldr r3, [r7, #4] + 8003a36: 681a ldr r2, [r3, #0] + 8003a38: 683b ldr r3, [r7, #0] + 8003a3a: 681b ldr r3, [r3, #0] + 8003a3c: 4619 mov r1, r3 + 8003a3e: 4610 mov r0, r2 + 8003a40: f000 fb97 bl 8004172 + break; + 8003a44: e000 b.n 8003a48 + break; + 8003a46: bf00 nop + } + htim->State = HAL_TIM_STATE_READY; + 8003a48: 687b ldr r3, [r7, #4] + 8003a4a: 2201 movs r2, #1 + 8003a4c: f883 203d strb.w r2, [r3, #61] ; 0x3d + + __HAL_UNLOCK(htim); + 8003a50: 687b ldr r3, [r7, #4] + 8003a52: 2200 movs r2, #0 + 8003a54: f883 203c strb.w r2, [r3, #60] ; 0x3c + + return HAL_OK; + 8003a58: 2300 movs r3, #0 +} + 8003a5a: 4618 mov r0, r3 + 8003a5c: 3710 adds r7, #16 + 8003a5e: 46bd mov sp, r7 + 8003a60: bd80 pop {r7, pc} + 8003a62: bf00 nop + 8003a64: fffeff88 .word 0xfffeff88 + +08003a68 : + * @brief Output Compare callback in non-blocking mode + * @param htim TIM OC handle + * @retval None + */ +__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) +{ + 8003a68: b480 push {r7} + 8003a6a: b083 sub sp, #12 + 8003a6c: af00 add r7, sp, #0 + 8003a6e: 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 + */ +} + 8003a70: bf00 nop + 8003a72: 370c adds r7, #12 + 8003a74: 46bd mov sp, r7 + 8003a76: f85d 7b04 ldr.w r7, [sp], #4 + 8003a7a: 4770 bx lr + +08003a7c : + * @brief Input Capture callback in non-blocking mode + * @param htim TIM IC handle + * @retval None + */ +__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) +{ + 8003a7c: b480 push {r7} + 8003a7e: b083 sub sp, #12 + 8003a80: af00 add r7, sp, #0 + 8003a82: 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 + */ +} + 8003a84: bf00 nop + 8003a86: 370c adds r7, #12 + 8003a88: 46bd mov sp, r7 + 8003a8a: f85d 7b04 ldr.w r7, [sp], #4 + 8003a8e: 4770 bx lr + +08003a90 : + * @brief PWM Pulse finished callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) +{ + 8003a90: b480 push {r7} + 8003a92: b083 sub sp, #12 + 8003a94: af00 add r7, sp, #0 + 8003a96: 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 + */ +} + 8003a98: bf00 nop + 8003a9a: 370c adds r7, #12 + 8003a9c: 46bd mov sp, r7 + 8003a9e: f85d 7b04 ldr.w r7, [sp], #4 + 8003aa2: 4770 bx lr + +08003aa4 : + * @brief Hall Trigger detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) +{ + 8003aa4: b480 push {r7} + 8003aa6: b083 sub sp, #12 + 8003aa8: af00 add r7, sp, #0 + 8003aaa: 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 + */ +} + 8003aac: bf00 nop + 8003aae: 370c adds r7, #12 + 8003ab0: 46bd mov sp, r7 + 8003ab2: f85d 7b04 ldr.w r7, [sp], #4 + 8003ab6: 4770 bx lr + +08003ab8 : + * @param TIMx TIM peripheral + * @param Structure TIM Base configuration structure + * @retval None + */ +void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) +{ + 8003ab8: b480 push {r7} + 8003aba: b085 sub sp, #20 + 8003abc: af00 add r7, sp, #0 + 8003abe: 6078 str r0, [r7, #4] + 8003ac0: 6039 str r1, [r7, #0] + uint32_t tmpcr1; + tmpcr1 = TIMx->CR1; + 8003ac2: 687b ldr r3, [r7, #4] + 8003ac4: 681b ldr r3, [r3, #0] + 8003ac6: 60fb str r3, [r7, #12] + + /* Set TIM Time Base Unit parameters ---------------------------------------*/ + if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) + 8003ac8: 687b ldr r3, [r7, #4] + 8003aca: 4a40 ldr r2, [pc, #256] ; (8003bcc ) + 8003acc: 4293 cmp r3, r2 + 8003ace: d013 beq.n 8003af8 + 8003ad0: 687b ldr r3, [r7, #4] + 8003ad2: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003ad6: d00f beq.n 8003af8 + 8003ad8: 687b ldr r3, [r7, #4] + 8003ada: 4a3d ldr r2, [pc, #244] ; (8003bd0 ) + 8003adc: 4293 cmp r3, r2 + 8003ade: d00b beq.n 8003af8 + 8003ae0: 687b ldr r3, [r7, #4] + 8003ae2: 4a3c ldr r2, [pc, #240] ; (8003bd4 ) + 8003ae4: 4293 cmp r3, r2 + 8003ae6: d007 beq.n 8003af8 + 8003ae8: 687b ldr r3, [r7, #4] + 8003aea: 4a3b ldr r2, [pc, #236] ; (8003bd8 ) + 8003aec: 4293 cmp r3, r2 + 8003aee: d003 beq.n 8003af8 + 8003af0: 687b ldr r3, [r7, #4] + 8003af2: 4a3a ldr r2, [pc, #232] ; (8003bdc ) + 8003af4: 4293 cmp r3, r2 + 8003af6: d108 bne.n 8003b0a + { + /* Select the Counter Mode */ + tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); + 8003af8: 68fb ldr r3, [r7, #12] + 8003afa: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8003afe: 60fb str r3, [r7, #12] + tmpcr1 |= Structure->CounterMode; + 8003b00: 683b ldr r3, [r7, #0] + 8003b02: 685b ldr r3, [r3, #4] + 8003b04: 68fa ldr r2, [r7, #12] + 8003b06: 4313 orrs r3, r2 + 8003b08: 60fb str r3, [r7, #12] + } + + if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) + 8003b0a: 687b ldr r3, [r7, #4] + 8003b0c: 4a2f ldr r2, [pc, #188] ; (8003bcc ) + 8003b0e: 4293 cmp r3, r2 + 8003b10: d02b beq.n 8003b6a + 8003b12: 687b ldr r3, [r7, #4] + 8003b14: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003b18: d027 beq.n 8003b6a + 8003b1a: 687b ldr r3, [r7, #4] + 8003b1c: 4a2c ldr r2, [pc, #176] ; (8003bd0 ) + 8003b1e: 4293 cmp r3, r2 + 8003b20: d023 beq.n 8003b6a + 8003b22: 687b ldr r3, [r7, #4] + 8003b24: 4a2b ldr r2, [pc, #172] ; (8003bd4 ) + 8003b26: 4293 cmp r3, r2 + 8003b28: d01f beq.n 8003b6a + 8003b2a: 687b ldr r3, [r7, #4] + 8003b2c: 4a2a ldr r2, [pc, #168] ; (8003bd8 ) + 8003b2e: 4293 cmp r3, r2 + 8003b30: d01b beq.n 8003b6a + 8003b32: 687b ldr r3, [r7, #4] + 8003b34: 4a29 ldr r2, [pc, #164] ; (8003bdc ) + 8003b36: 4293 cmp r3, r2 + 8003b38: d017 beq.n 8003b6a + 8003b3a: 687b ldr r3, [r7, #4] + 8003b3c: 4a28 ldr r2, [pc, #160] ; (8003be0 ) + 8003b3e: 4293 cmp r3, r2 + 8003b40: d013 beq.n 8003b6a + 8003b42: 687b ldr r3, [r7, #4] + 8003b44: 4a27 ldr r2, [pc, #156] ; (8003be4 ) + 8003b46: 4293 cmp r3, r2 + 8003b48: d00f beq.n 8003b6a + 8003b4a: 687b ldr r3, [r7, #4] + 8003b4c: 4a26 ldr r2, [pc, #152] ; (8003be8 ) + 8003b4e: 4293 cmp r3, r2 + 8003b50: d00b beq.n 8003b6a + 8003b52: 687b ldr r3, [r7, #4] + 8003b54: 4a25 ldr r2, [pc, #148] ; (8003bec ) + 8003b56: 4293 cmp r3, r2 + 8003b58: d007 beq.n 8003b6a + 8003b5a: 687b ldr r3, [r7, #4] + 8003b5c: 4a24 ldr r2, [pc, #144] ; (8003bf0 ) + 8003b5e: 4293 cmp r3, r2 + 8003b60: d003 beq.n 8003b6a + 8003b62: 687b ldr r3, [r7, #4] + 8003b64: 4a23 ldr r2, [pc, #140] ; (8003bf4 ) + 8003b66: 4293 cmp r3, r2 + 8003b68: d108 bne.n 8003b7c + { + /* Set the clock division */ + tmpcr1 &= ~TIM_CR1_CKD; + 8003b6a: 68fb ldr r3, [r7, #12] + 8003b6c: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003b70: 60fb str r3, [r7, #12] + tmpcr1 |= (uint32_t)Structure->ClockDivision; + 8003b72: 683b ldr r3, [r7, #0] + 8003b74: 68db ldr r3, [r3, #12] + 8003b76: 68fa ldr r2, [r7, #12] + 8003b78: 4313 orrs r3, r2 + 8003b7a: 60fb str r3, [r7, #12] + } + + /* Set the auto-reload preload */ + MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); + 8003b7c: 68fb ldr r3, [r7, #12] + 8003b7e: f023 0280 bic.w r2, r3, #128 ; 0x80 + 8003b82: 683b ldr r3, [r7, #0] + 8003b84: 695b ldr r3, [r3, #20] + 8003b86: 4313 orrs r3, r2 + 8003b88: 60fb str r3, [r7, #12] + + TIMx->CR1 = tmpcr1; + 8003b8a: 687b ldr r3, [r7, #4] + 8003b8c: 68fa ldr r2, [r7, #12] + 8003b8e: 601a str r2, [r3, #0] + + /* Set the Autoreload value */ + TIMx->ARR = (uint32_t)Structure->Period ; + 8003b90: 683b ldr r3, [r7, #0] + 8003b92: 689a ldr r2, [r3, #8] + 8003b94: 687b ldr r3, [r7, #4] + 8003b96: 62da str r2, [r3, #44] ; 0x2c + + /* Set the Prescaler value */ + TIMx->PSC = Structure->Prescaler; + 8003b98: 683b ldr r3, [r7, #0] + 8003b9a: 681a ldr r2, [r3, #0] + 8003b9c: 687b ldr r3, [r7, #4] + 8003b9e: 629a str r2, [r3, #40] ; 0x28 + + if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) + 8003ba0: 687b ldr r3, [r7, #4] + 8003ba2: 4a0a ldr r2, [pc, #40] ; (8003bcc ) + 8003ba4: 4293 cmp r3, r2 + 8003ba6: d003 beq.n 8003bb0 + 8003ba8: 687b ldr r3, [r7, #4] + 8003baa: 4a0c ldr r2, [pc, #48] ; (8003bdc ) + 8003bac: 4293 cmp r3, r2 + 8003bae: d103 bne.n 8003bb8 + { + /* Set the Repetition Counter value */ + TIMx->RCR = Structure->RepetitionCounter; + 8003bb0: 683b ldr r3, [r7, #0] + 8003bb2: 691a ldr r2, [r3, #16] + 8003bb4: 687b ldr r3, [r7, #4] + 8003bb6: 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; + 8003bb8: 687b ldr r3, [r7, #4] + 8003bba: 2201 movs r2, #1 + 8003bbc: 615a str r2, [r3, #20] +} + 8003bbe: bf00 nop + 8003bc0: 3714 adds r7, #20 + 8003bc2: 46bd mov sp, r7 + 8003bc4: f85d 7b04 ldr.w r7, [sp], #4 + 8003bc8: 4770 bx lr + 8003bca: bf00 nop + 8003bcc: 40010000 .word 0x40010000 + 8003bd0: 40000400 .word 0x40000400 + 8003bd4: 40000800 .word 0x40000800 + 8003bd8: 40000c00 .word 0x40000c00 + 8003bdc: 40010400 .word 0x40010400 + 8003be0: 40014000 .word 0x40014000 + 8003be4: 40014400 .word 0x40014400 + 8003be8: 40014800 .word 0x40014800 + 8003bec: 40001800 .word 0x40001800 + 8003bf0: 40001c00 .word 0x40001c00 + 8003bf4: 40002000 .word 0x40002000 + +08003bf8 : + * @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) +{ + 8003bf8: b480 push {r7} + 8003bfa: b087 sub sp, #28 + 8003bfc: af00 add r7, sp, #0 + 8003bfe: 6078 str r0, [r7, #4] + 8003c00: 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; + 8003c02: 687b ldr r3, [r7, #4] + 8003c04: 6a1b ldr r3, [r3, #32] + 8003c06: f023 0201 bic.w r2, r3, #1 + 8003c0a: 687b ldr r3, [r7, #4] + 8003c0c: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8003c0e: 687b ldr r3, [r7, #4] + 8003c10: 6a1b ldr r3, [r3, #32] + 8003c12: 617b str r3, [r7, #20] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8003c14: 687b ldr r3, [r7, #4] + 8003c16: 685b ldr r3, [r3, #4] + 8003c18: 613b str r3, [r7, #16] + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + 8003c1a: 687b ldr r3, [r7, #4] + 8003c1c: 699b ldr r3, [r3, #24] + 8003c1e: 60fb str r3, [r7, #12] + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= ~TIM_CCMR1_OC1M; + 8003c20: 68fa ldr r2, [r7, #12] + 8003c22: 4b2b ldr r3, [pc, #172] ; (8003cd0 ) + 8003c24: 4013 ands r3, r2 + 8003c26: 60fb str r3, [r7, #12] + tmpccmrx &= ~TIM_CCMR1_CC1S; + 8003c28: 68fb ldr r3, [r7, #12] + 8003c2a: f023 0303 bic.w r3, r3, #3 + 8003c2e: 60fb str r3, [r7, #12] + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + 8003c30: 683b ldr r3, [r7, #0] + 8003c32: 681b ldr r3, [r3, #0] + 8003c34: 68fa ldr r2, [r7, #12] + 8003c36: 4313 orrs r3, r2 + 8003c38: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC1P; + 8003c3a: 697b ldr r3, [r7, #20] + 8003c3c: f023 0302 bic.w r3, r3, #2 + 8003c40: 617b str r3, [r7, #20] + /* Set the Output Compare Polarity */ + tmpccer |= OC_Config->OCPolarity; + 8003c42: 683b ldr r3, [r7, #0] + 8003c44: 689b ldr r3, [r3, #8] + 8003c46: 697a ldr r2, [r7, #20] + 8003c48: 4313 orrs r3, r2 + 8003c4a: 617b str r3, [r7, #20] + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) + 8003c4c: 687b ldr r3, [r7, #4] + 8003c4e: 4a21 ldr r2, [pc, #132] ; (8003cd4 ) + 8003c50: 4293 cmp r3, r2 + 8003c52: d003 beq.n 8003c5c + 8003c54: 687b ldr r3, [r7, #4] + 8003c56: 4a20 ldr r2, [pc, #128] ; (8003cd8 ) + 8003c58: 4293 cmp r3, r2 + 8003c5a: d10c bne.n 8003c76 + { + /* Check parameters */ + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC1NP; + 8003c5c: 697b ldr r3, [r7, #20] + 8003c5e: f023 0308 bic.w r3, r3, #8 + 8003c62: 617b str r3, [r7, #20] + /* Set the Output N Polarity */ + tmpccer |= OC_Config->OCNPolarity; + 8003c64: 683b ldr r3, [r7, #0] + 8003c66: 68db ldr r3, [r3, #12] + 8003c68: 697a ldr r2, [r7, #20] + 8003c6a: 4313 orrs r3, r2 + 8003c6c: 617b str r3, [r7, #20] + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC1NE; + 8003c6e: 697b ldr r3, [r7, #20] + 8003c70: f023 0304 bic.w r3, r3, #4 + 8003c74: 617b str r3, [r7, #20] + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 8003c76: 687b ldr r3, [r7, #4] + 8003c78: 4a16 ldr r2, [pc, #88] ; (8003cd4 ) + 8003c7a: 4293 cmp r3, r2 + 8003c7c: d003 beq.n 8003c86 + 8003c7e: 687b ldr r3, [r7, #4] + 8003c80: 4a15 ldr r2, [pc, #84] ; (8003cd8 ) + 8003c82: 4293 cmp r3, r2 + 8003c84: d111 bne.n 8003caa + /* 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; + 8003c86: 693b ldr r3, [r7, #16] + 8003c88: f423 7380 bic.w r3, r3, #256 ; 0x100 + 8003c8c: 613b str r3, [r7, #16] + tmpcr2 &= ~TIM_CR2_OIS1N; + 8003c8e: 693b ldr r3, [r7, #16] + 8003c90: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8003c94: 613b str r3, [r7, #16] + /* Set the Output Idle state */ + tmpcr2 |= OC_Config->OCIdleState; + 8003c96: 683b ldr r3, [r7, #0] + 8003c98: 695b ldr r3, [r3, #20] + 8003c9a: 693a ldr r2, [r7, #16] + 8003c9c: 4313 orrs r3, r2 + 8003c9e: 613b str r3, [r7, #16] + /* Set the Output N Idle state */ + tmpcr2 |= OC_Config->OCNIdleState; + 8003ca0: 683b ldr r3, [r7, #0] + 8003ca2: 699b ldr r3, [r3, #24] + 8003ca4: 693a ldr r2, [r7, #16] + 8003ca6: 4313 orrs r3, r2 + 8003ca8: 613b str r3, [r7, #16] + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8003caa: 687b ldr r3, [r7, #4] + 8003cac: 693a ldr r2, [r7, #16] + 8003cae: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + 8003cb0: 687b ldr r3, [r7, #4] + 8003cb2: 68fa ldr r2, [r7, #12] + 8003cb4: 619a str r2, [r3, #24] + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = OC_Config->Pulse; + 8003cb6: 683b ldr r3, [r7, #0] + 8003cb8: 685a ldr r2, [r3, #4] + 8003cba: 687b ldr r3, [r7, #4] + 8003cbc: 635a str r2, [r3, #52] ; 0x34 + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8003cbe: 687b ldr r3, [r7, #4] + 8003cc0: 697a ldr r2, [r7, #20] + 8003cc2: 621a str r2, [r3, #32] +} + 8003cc4: bf00 nop + 8003cc6: 371c adds r7, #28 + 8003cc8: 46bd mov sp, r7 + 8003cca: f85d 7b04 ldr.w r7, [sp], #4 + 8003cce: 4770 bx lr + 8003cd0: fffeff8f .word 0xfffeff8f + 8003cd4: 40010000 .word 0x40010000 + 8003cd8: 40010400 .word 0x40010400 + +08003cdc : + * @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) +{ + 8003cdc: b480 push {r7} + 8003cde: b087 sub sp, #28 + 8003ce0: af00 add r7, sp, #0 + 8003ce2: 6078 str r0, [r7, #4] + 8003ce4: 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; + 8003ce6: 687b ldr r3, [r7, #4] + 8003ce8: 6a1b ldr r3, [r3, #32] + 8003cea: f023 0210 bic.w r2, r3, #16 + 8003cee: 687b ldr r3, [r7, #4] + 8003cf0: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8003cf2: 687b ldr r3, [r7, #4] + 8003cf4: 6a1b ldr r3, [r3, #32] + 8003cf6: 617b str r3, [r7, #20] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8003cf8: 687b ldr r3, [r7, #4] + 8003cfa: 685b ldr r3, [r3, #4] + 8003cfc: 613b str r3, [r7, #16] + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + 8003cfe: 687b ldr r3, [r7, #4] + 8003d00: 699b ldr r3, [r3, #24] + 8003d02: 60fb str r3, [r7, #12] + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR1_OC2M; + 8003d04: 68fa ldr r2, [r7, #12] + 8003d06: 4b2e ldr r3, [pc, #184] ; (8003dc0 ) + 8003d08: 4013 ands r3, r2 + 8003d0a: 60fb str r3, [r7, #12] + tmpccmrx &= ~TIM_CCMR1_CC2S; + 8003d0c: 68fb ldr r3, [r7, #12] + 8003d0e: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003d12: 60fb str r3, [r7, #12] + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + 8003d14: 683b ldr r3, [r7, #0] + 8003d16: 681b ldr r3, [r3, #0] + 8003d18: 021b lsls r3, r3, #8 + 8003d1a: 68fa ldr r2, [r7, #12] + 8003d1c: 4313 orrs r3, r2 + 8003d1e: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC2P; + 8003d20: 697b ldr r3, [r7, #20] + 8003d22: f023 0320 bic.w r3, r3, #32 + 8003d26: 617b str r3, [r7, #20] + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 4U); + 8003d28: 683b ldr r3, [r7, #0] + 8003d2a: 689b ldr r3, [r3, #8] + 8003d2c: 011b lsls r3, r3, #4 + 8003d2e: 697a ldr r2, [r7, #20] + 8003d30: 4313 orrs r3, r2 + 8003d32: 617b str r3, [r7, #20] + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) + 8003d34: 687b ldr r3, [r7, #4] + 8003d36: 4a23 ldr r2, [pc, #140] ; (8003dc4 ) + 8003d38: 4293 cmp r3, r2 + 8003d3a: d003 beq.n 8003d44 + 8003d3c: 687b ldr r3, [r7, #4] + 8003d3e: 4a22 ldr r2, [pc, #136] ; (8003dc8 ) + 8003d40: 4293 cmp r3, r2 + 8003d42: d10d bne.n 8003d60 + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC2NP; + 8003d44: 697b ldr r3, [r7, #20] + 8003d46: f023 0380 bic.w r3, r3, #128 ; 0x80 + 8003d4a: 617b str r3, [r7, #20] + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 4U); + 8003d4c: 683b ldr r3, [r7, #0] + 8003d4e: 68db ldr r3, [r3, #12] + 8003d50: 011b lsls r3, r3, #4 + 8003d52: 697a ldr r2, [r7, #20] + 8003d54: 4313 orrs r3, r2 + 8003d56: 617b str r3, [r7, #20] + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC2NE; + 8003d58: 697b ldr r3, [r7, #20] + 8003d5a: f023 0340 bic.w r3, r3, #64 ; 0x40 + 8003d5e: 617b str r3, [r7, #20] + + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 8003d60: 687b ldr r3, [r7, #4] + 8003d62: 4a18 ldr r2, [pc, #96] ; (8003dc4 ) + 8003d64: 4293 cmp r3, r2 + 8003d66: d003 beq.n 8003d70 + 8003d68: 687b ldr r3, [r7, #4] + 8003d6a: 4a17 ldr r2, [pc, #92] ; (8003dc8 ) + 8003d6c: 4293 cmp r3, r2 + 8003d6e: d113 bne.n 8003d98 + /* 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; + 8003d70: 693b ldr r3, [r7, #16] + 8003d72: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 8003d76: 613b str r3, [r7, #16] + tmpcr2 &= ~TIM_CR2_OIS2N; + 8003d78: 693b ldr r3, [r7, #16] + 8003d7a: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 8003d7e: 613b str r3, [r7, #16] + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 2U); + 8003d80: 683b ldr r3, [r7, #0] + 8003d82: 695b ldr r3, [r3, #20] + 8003d84: 009b lsls r3, r3, #2 + 8003d86: 693a ldr r2, [r7, #16] + 8003d88: 4313 orrs r3, r2 + 8003d8a: 613b str r3, [r7, #16] + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 2U); + 8003d8c: 683b ldr r3, [r7, #0] + 8003d8e: 699b ldr r3, [r3, #24] + 8003d90: 009b lsls r3, r3, #2 + 8003d92: 693a ldr r2, [r7, #16] + 8003d94: 4313 orrs r3, r2 + 8003d96: 613b str r3, [r7, #16] + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8003d98: 687b ldr r3, [r7, #4] + 8003d9a: 693a ldr r2, [r7, #16] + 8003d9c: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + 8003d9e: 687b ldr r3, [r7, #4] + 8003da0: 68fa ldr r2, [r7, #12] + 8003da2: 619a str r2, [r3, #24] + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = OC_Config->Pulse; + 8003da4: 683b ldr r3, [r7, #0] + 8003da6: 685a ldr r2, [r3, #4] + 8003da8: 687b ldr r3, [r7, #4] + 8003daa: 639a str r2, [r3, #56] ; 0x38 + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8003dac: 687b ldr r3, [r7, #4] + 8003dae: 697a ldr r2, [r7, #20] + 8003db0: 621a str r2, [r3, #32] +} + 8003db2: bf00 nop + 8003db4: 371c adds r7, #28 + 8003db6: 46bd mov sp, r7 + 8003db8: f85d 7b04 ldr.w r7, [sp], #4 + 8003dbc: 4770 bx lr + 8003dbe: bf00 nop + 8003dc0: feff8fff .word 0xfeff8fff + 8003dc4: 40010000 .word 0x40010000 + 8003dc8: 40010400 .word 0x40010400 + +08003dcc : + * @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) +{ + 8003dcc: b480 push {r7} + 8003dce: b087 sub sp, #28 + 8003dd0: af00 add r7, sp, #0 + 8003dd2: 6078 str r0, [r7, #4] + 8003dd4: 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; + 8003dd6: 687b ldr r3, [r7, #4] + 8003dd8: 6a1b ldr r3, [r3, #32] + 8003dda: f423 7280 bic.w r2, r3, #256 ; 0x100 + 8003dde: 687b ldr r3, [r7, #4] + 8003de0: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8003de2: 687b ldr r3, [r7, #4] + 8003de4: 6a1b ldr r3, [r3, #32] + 8003de6: 617b str r3, [r7, #20] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8003de8: 687b ldr r3, [r7, #4] + 8003dea: 685b ldr r3, [r3, #4] + 8003dec: 613b str r3, [r7, #16] + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + 8003dee: 687b ldr r3, [r7, #4] + 8003df0: 69db ldr r3, [r3, #28] + 8003df2: 60fb str r3, [r7, #12] + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR2_OC3M; + 8003df4: 68fa ldr r2, [r7, #12] + 8003df6: 4b2d ldr r3, [pc, #180] ; (8003eac ) + 8003df8: 4013 ands r3, r2 + 8003dfa: 60fb str r3, [r7, #12] + tmpccmrx &= ~TIM_CCMR2_CC3S; + 8003dfc: 68fb ldr r3, [r7, #12] + 8003dfe: f023 0303 bic.w r3, r3, #3 + 8003e02: 60fb str r3, [r7, #12] + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + 8003e04: 683b ldr r3, [r7, #0] + 8003e06: 681b ldr r3, [r3, #0] + 8003e08: 68fa ldr r2, [r7, #12] + 8003e0a: 4313 orrs r3, r2 + 8003e0c: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC3P; + 8003e0e: 697b ldr r3, [r7, #20] + 8003e10: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8003e14: 617b str r3, [r7, #20] + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 8U); + 8003e16: 683b ldr r3, [r7, #0] + 8003e18: 689b ldr r3, [r3, #8] + 8003e1a: 021b lsls r3, r3, #8 + 8003e1c: 697a ldr r2, [r7, #20] + 8003e1e: 4313 orrs r3, r2 + 8003e20: 617b str r3, [r7, #20] + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) + 8003e22: 687b ldr r3, [r7, #4] + 8003e24: 4a22 ldr r2, [pc, #136] ; (8003eb0 ) + 8003e26: 4293 cmp r3, r2 + 8003e28: d003 beq.n 8003e32 + 8003e2a: 687b ldr r3, [r7, #4] + 8003e2c: 4a21 ldr r2, [pc, #132] ; (8003eb4 ) + 8003e2e: 4293 cmp r3, r2 + 8003e30: d10d bne.n 8003e4e + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC3NP; + 8003e32: 697b ldr r3, [r7, #20] + 8003e34: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 8003e38: 617b str r3, [r7, #20] + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 8U); + 8003e3a: 683b ldr r3, [r7, #0] + 8003e3c: 68db ldr r3, [r3, #12] + 8003e3e: 021b lsls r3, r3, #8 + 8003e40: 697a ldr r2, [r7, #20] + 8003e42: 4313 orrs r3, r2 + 8003e44: 617b str r3, [r7, #20] + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC3NE; + 8003e46: 697b ldr r3, [r7, #20] + 8003e48: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 8003e4c: 617b str r3, [r7, #20] + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 8003e4e: 687b ldr r3, [r7, #4] + 8003e50: 4a17 ldr r2, [pc, #92] ; (8003eb0 ) + 8003e52: 4293 cmp r3, r2 + 8003e54: d003 beq.n 8003e5e + 8003e56: 687b ldr r3, [r7, #4] + 8003e58: 4a16 ldr r2, [pc, #88] ; (8003eb4 ) + 8003e5a: 4293 cmp r3, r2 + 8003e5c: d113 bne.n 8003e86 + /* 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; + 8003e5e: 693b ldr r3, [r7, #16] + 8003e60: f423 5380 bic.w r3, r3, #4096 ; 0x1000 + 8003e64: 613b str r3, [r7, #16] + tmpcr2 &= ~TIM_CR2_OIS3N; + 8003e66: 693b ldr r3, [r7, #16] + 8003e68: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 8003e6c: 613b str r3, [r7, #16] + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 4U); + 8003e6e: 683b ldr r3, [r7, #0] + 8003e70: 695b ldr r3, [r3, #20] + 8003e72: 011b lsls r3, r3, #4 + 8003e74: 693a ldr r2, [r7, #16] + 8003e76: 4313 orrs r3, r2 + 8003e78: 613b str r3, [r7, #16] + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 4U); + 8003e7a: 683b ldr r3, [r7, #0] + 8003e7c: 699b ldr r3, [r3, #24] + 8003e7e: 011b lsls r3, r3, #4 + 8003e80: 693a ldr r2, [r7, #16] + 8003e82: 4313 orrs r3, r2 + 8003e84: 613b str r3, [r7, #16] + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8003e86: 687b ldr r3, [r7, #4] + 8003e88: 693a ldr r2, [r7, #16] + 8003e8a: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + 8003e8c: 687b ldr r3, [r7, #4] + 8003e8e: 68fa ldr r2, [r7, #12] + 8003e90: 61da str r2, [r3, #28] + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = OC_Config->Pulse; + 8003e92: 683b ldr r3, [r7, #0] + 8003e94: 685a ldr r2, [r3, #4] + 8003e96: 687b ldr r3, [r7, #4] + 8003e98: 63da str r2, [r3, #60] ; 0x3c + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8003e9a: 687b ldr r3, [r7, #4] + 8003e9c: 697a ldr r2, [r7, #20] + 8003e9e: 621a str r2, [r3, #32] +} + 8003ea0: bf00 nop + 8003ea2: 371c adds r7, #28 + 8003ea4: 46bd mov sp, r7 + 8003ea6: f85d 7b04 ldr.w r7, [sp], #4 + 8003eaa: 4770 bx lr + 8003eac: fffeff8f .word 0xfffeff8f + 8003eb0: 40010000 .word 0x40010000 + 8003eb4: 40010400 .word 0x40010400 + +08003eb8 : + * @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) +{ + 8003eb8: b480 push {r7} + 8003eba: b087 sub sp, #28 + 8003ebc: af00 add r7, sp, #0 + 8003ebe: 6078 str r0, [r7, #4] + 8003ec0: 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; + 8003ec2: 687b ldr r3, [r7, #4] + 8003ec4: 6a1b ldr r3, [r3, #32] + 8003ec6: f423 5280 bic.w r2, r3, #4096 ; 0x1000 + 8003eca: 687b ldr r3, [r7, #4] + 8003ecc: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8003ece: 687b ldr r3, [r7, #4] + 8003ed0: 6a1b ldr r3, [r3, #32] + 8003ed2: 613b str r3, [r7, #16] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8003ed4: 687b ldr r3, [r7, #4] + 8003ed6: 685b ldr r3, [r3, #4] + 8003ed8: 617b str r3, [r7, #20] + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + 8003eda: 687b ldr r3, [r7, #4] + 8003edc: 69db ldr r3, [r3, #28] + 8003ede: 60fb str r3, [r7, #12] + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= ~TIM_CCMR2_OC4M; + 8003ee0: 68fa ldr r2, [r7, #12] + 8003ee2: 4b1e ldr r3, [pc, #120] ; (8003f5c ) + 8003ee4: 4013 ands r3, r2 + 8003ee6: 60fb str r3, [r7, #12] + tmpccmrx &= ~TIM_CCMR2_CC4S; + 8003ee8: 68fb ldr r3, [r7, #12] + 8003eea: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003eee: 60fb str r3, [r7, #12] + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + 8003ef0: 683b ldr r3, [r7, #0] + 8003ef2: 681b ldr r3, [r3, #0] + 8003ef4: 021b lsls r3, r3, #8 + 8003ef6: 68fa ldr r2, [r7, #12] + 8003ef8: 4313 orrs r3, r2 + 8003efa: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC4P; + 8003efc: 693b ldr r3, [r7, #16] + 8003efe: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 8003f02: 613b str r3, [r7, #16] + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 12U); + 8003f04: 683b ldr r3, [r7, #0] + 8003f06: 689b ldr r3, [r3, #8] + 8003f08: 031b lsls r3, r3, #12 + 8003f0a: 693a ldr r2, [r7, #16] + 8003f0c: 4313 orrs r3, r2 + 8003f0e: 613b str r3, [r7, #16] + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 8003f10: 687b ldr r3, [r7, #4] + 8003f12: 4a13 ldr r2, [pc, #76] ; (8003f60 ) + 8003f14: 4293 cmp r3, r2 + 8003f16: d003 beq.n 8003f20 + 8003f18: 687b ldr r3, [r7, #4] + 8003f1a: 4a12 ldr r2, [pc, #72] ; (8003f64 ) + 8003f1c: 4293 cmp r3, r2 + 8003f1e: d109 bne.n 8003f34 + { + /* Check parameters */ + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS4; + 8003f20: 697b ldr r3, [r7, #20] + 8003f22: f423 4380 bic.w r3, r3, #16384 ; 0x4000 + 8003f26: 617b str r3, [r7, #20] + + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 6U); + 8003f28: 683b ldr r3, [r7, #0] + 8003f2a: 695b ldr r3, [r3, #20] + 8003f2c: 019b lsls r3, r3, #6 + 8003f2e: 697a ldr r2, [r7, #20] + 8003f30: 4313 orrs r3, r2 + 8003f32: 617b str r3, [r7, #20] + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8003f34: 687b ldr r3, [r7, #4] + 8003f36: 697a ldr r2, [r7, #20] + 8003f38: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + 8003f3a: 687b ldr r3, [r7, #4] + 8003f3c: 68fa ldr r2, [r7, #12] + 8003f3e: 61da str r2, [r3, #28] + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = OC_Config->Pulse; + 8003f40: 683b ldr r3, [r7, #0] + 8003f42: 685a ldr r2, [r3, #4] + 8003f44: 687b ldr r3, [r7, #4] + 8003f46: 641a str r2, [r3, #64] ; 0x40 + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8003f48: 687b ldr r3, [r7, #4] + 8003f4a: 693a ldr r2, [r7, #16] + 8003f4c: 621a str r2, [r3, #32] +} + 8003f4e: bf00 nop + 8003f50: 371c adds r7, #28 + 8003f52: 46bd mov sp, r7 + 8003f54: f85d 7b04 ldr.w r7, [sp], #4 + 8003f58: 4770 bx lr + 8003f5a: bf00 nop + 8003f5c: feff8fff .word 0xfeff8fff + 8003f60: 40010000 .word 0x40010000 + 8003f64: 40010400 .word 0x40010400 + +08003f68 : + * @param OC_Config The ouput configuration structure + * @retval None + */ +static void TIM_OC5_SetConfig(TIM_TypeDef *TIMx, + TIM_OC_InitTypeDef *OC_Config) +{ + 8003f68: b480 push {r7} + 8003f6a: b087 sub sp, #28 + 8003f6c: af00 add r7, sp, #0 + 8003f6e: 6078 str r0, [r7, #4] + 8003f70: 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; + 8003f72: 687b ldr r3, [r7, #4] + 8003f74: 6a1b ldr r3, [r3, #32] + 8003f76: f423 3280 bic.w r2, r3, #65536 ; 0x10000 + 8003f7a: 687b ldr r3, [r7, #4] + 8003f7c: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8003f7e: 687b ldr r3, [r7, #4] + 8003f80: 6a1b ldr r3, [r3, #32] + 8003f82: 613b str r3, [r7, #16] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8003f84: 687b ldr r3, [r7, #4] + 8003f86: 685b ldr r3, [r3, #4] + 8003f88: 617b str r3, [r7, #20] + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR3; + 8003f8a: 687b ldr r3, [r7, #4] + 8003f8c: 6d5b ldr r3, [r3, #84] ; 0x54 + 8003f8e: 60fb str r3, [r7, #12] + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= ~(TIM_CCMR3_OC5M); + 8003f90: 68fa ldr r2, [r7, #12] + 8003f92: 4b1b ldr r3, [pc, #108] ; (8004000 ) + 8003f94: 4013 ands r3, r2 + 8003f96: 60fb str r3, [r7, #12] + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + 8003f98: 683b ldr r3, [r7, #0] + 8003f9a: 681b ldr r3, [r3, #0] + 8003f9c: 68fa ldr r2, [r7, #12] + 8003f9e: 4313 orrs r3, r2 + 8003fa0: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC5P; + 8003fa2: 693b ldr r3, [r7, #16] + 8003fa4: f423 3300 bic.w r3, r3, #131072 ; 0x20000 + 8003fa8: 613b str r3, [r7, #16] + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 16U); + 8003faa: 683b ldr r3, [r7, #0] + 8003fac: 689b ldr r3, [r3, #8] + 8003fae: 041b lsls r3, r3, #16 + 8003fb0: 693a ldr r2, [r7, #16] + 8003fb2: 4313 orrs r3, r2 + 8003fb4: 613b str r3, [r7, #16] + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 8003fb6: 687b ldr r3, [r7, #4] + 8003fb8: 4a12 ldr r2, [pc, #72] ; (8004004 ) + 8003fba: 4293 cmp r3, r2 + 8003fbc: d003 beq.n 8003fc6 + 8003fbe: 687b ldr r3, [r7, #4] + 8003fc0: 4a11 ldr r2, [pc, #68] ; (8004008 ) + 8003fc2: 4293 cmp r3, r2 + 8003fc4: d109 bne.n 8003fda + { + /* Reset the Output Compare IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS5; + 8003fc6: 697b ldr r3, [r7, #20] + 8003fc8: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8003fcc: 617b str r3, [r7, #20] + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 8U); + 8003fce: 683b ldr r3, [r7, #0] + 8003fd0: 695b ldr r3, [r3, #20] + 8003fd2: 021b lsls r3, r3, #8 + 8003fd4: 697a ldr r2, [r7, #20] + 8003fd6: 4313 orrs r3, r2 + 8003fd8: 617b str r3, [r7, #20] + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8003fda: 687b ldr r3, [r7, #4] + 8003fdc: 697a ldr r2, [r7, #20] + 8003fde: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR3 */ + TIMx->CCMR3 = tmpccmrx; + 8003fe0: 687b ldr r3, [r7, #4] + 8003fe2: 68fa ldr r2, [r7, #12] + 8003fe4: 655a str r2, [r3, #84] ; 0x54 + + /* Set the Capture Compare Register value */ + TIMx->CCR5 = OC_Config->Pulse; + 8003fe6: 683b ldr r3, [r7, #0] + 8003fe8: 685a ldr r2, [r3, #4] + 8003fea: 687b ldr r3, [r7, #4] + 8003fec: 659a str r2, [r3, #88] ; 0x58 + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8003fee: 687b ldr r3, [r7, #4] + 8003ff0: 693a ldr r2, [r7, #16] + 8003ff2: 621a str r2, [r3, #32] +} + 8003ff4: bf00 nop + 8003ff6: 371c adds r7, #28 + 8003ff8: 46bd mov sp, r7 + 8003ffa: f85d 7b04 ldr.w r7, [sp], #4 + 8003ffe: 4770 bx lr + 8004000: fffeff8f .word 0xfffeff8f + 8004004: 40010000 .word 0x40010000 + 8004008: 40010400 .word 0x40010400 + +0800400c : + * @param OC_Config The ouput configuration structure + * @retval None + */ +static void TIM_OC6_SetConfig(TIM_TypeDef *TIMx, + TIM_OC_InitTypeDef *OC_Config) +{ + 800400c: b480 push {r7} + 800400e: b087 sub sp, #28 + 8004010: af00 add r7, sp, #0 + 8004012: 6078 str r0, [r7, #4] + 8004014: 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; + 8004016: 687b ldr r3, [r7, #4] + 8004018: 6a1b ldr r3, [r3, #32] + 800401a: f423 1280 bic.w r2, r3, #1048576 ; 0x100000 + 800401e: 687b ldr r3, [r7, #4] + 8004020: 621a str r2, [r3, #32] + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + 8004022: 687b ldr r3, [r7, #4] + 8004024: 6a1b ldr r3, [r3, #32] + 8004026: 613b str r3, [r7, #16] + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + 8004028: 687b ldr r3, [r7, #4] + 800402a: 685b ldr r3, [r3, #4] + 800402c: 617b str r3, [r7, #20] + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR3; + 800402e: 687b ldr r3, [r7, #4] + 8004030: 6d5b ldr r3, [r3, #84] ; 0x54 + 8004032: 60fb str r3, [r7, #12] + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= ~(TIM_CCMR3_OC6M); + 8004034: 68fa ldr r2, [r7, #12] + 8004036: 4b1c ldr r3, [pc, #112] ; (80040a8 ) + 8004038: 4013 ands r3, r2 + 800403a: 60fb str r3, [r7, #12] + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + 800403c: 683b ldr r3, [r7, #0] + 800403e: 681b ldr r3, [r3, #0] + 8004040: 021b lsls r3, r3, #8 + 8004042: 68fa ldr r2, [r7, #12] + 8004044: 4313 orrs r3, r2 + 8004046: 60fb str r3, [r7, #12] + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC6P; + 8004048: 693b ldr r3, [r7, #16] + 800404a: f423 1300 bic.w r3, r3, #2097152 ; 0x200000 + 800404e: 613b str r3, [r7, #16] + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 20U); + 8004050: 683b ldr r3, [r7, #0] + 8004052: 689b ldr r3, [r3, #8] + 8004054: 051b lsls r3, r3, #20 + 8004056: 693a ldr r2, [r7, #16] + 8004058: 4313 orrs r3, r2 + 800405a: 613b str r3, [r7, #16] + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + 800405c: 687b ldr r3, [r7, #4] + 800405e: 4a13 ldr r2, [pc, #76] ; (80040ac ) + 8004060: 4293 cmp r3, r2 + 8004062: d003 beq.n 800406c + 8004064: 687b ldr r3, [r7, #4] + 8004066: 4a12 ldr r2, [pc, #72] ; (80040b0 ) + 8004068: 4293 cmp r3, r2 + 800406a: d109 bne.n 8004080 + { + /* Reset the Output Compare IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS6; + 800406c: 697b ldr r3, [r7, #20] + 800406e: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8004072: 617b str r3, [r7, #20] + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 10U); + 8004074: 683b ldr r3, [r7, #0] + 8004076: 695b ldr r3, [r3, #20] + 8004078: 029b lsls r3, r3, #10 + 800407a: 697a ldr r2, [r7, #20] + 800407c: 4313 orrs r3, r2 + 800407e: 617b str r3, [r7, #20] + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + 8004080: 687b ldr r3, [r7, #4] + 8004082: 697a ldr r2, [r7, #20] + 8004084: 605a str r2, [r3, #4] + + /* Write to TIMx CCMR3 */ + TIMx->CCMR3 = tmpccmrx; + 8004086: 687b ldr r3, [r7, #4] + 8004088: 68fa ldr r2, [r7, #12] + 800408a: 655a str r2, [r3, #84] ; 0x54 + + /* Set the Capture Compare Register value */ + TIMx->CCR6 = OC_Config->Pulse; + 800408c: 683b ldr r3, [r7, #0] + 800408e: 685a ldr r2, [r3, #4] + 8004090: 687b ldr r3, [r7, #4] + 8004092: 65da str r2, [r3, #92] ; 0x5c + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; + 8004094: 687b ldr r3, [r7, #4] + 8004096: 693a ldr r2, [r7, #16] + 8004098: 621a str r2, [r3, #32] +} + 800409a: bf00 nop + 800409c: 371c adds r7, #28 + 800409e: 46bd mov sp, r7 + 80040a0: f85d 7b04 ldr.w r7, [sp], #4 + 80040a4: 4770 bx lr + 80040a6: bf00 nop + 80040a8: feff8fff .word 0xfeff8fff + 80040ac: 40010000 .word 0x40010000 + 80040b0: 40010400 .word 0x40010400 + +080040b4 : + * @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) +{ + 80040b4: b480 push {r7} + 80040b6: b087 sub sp, #28 + 80040b8: af00 add r7, sp, #0 + 80040ba: 60f8 str r0, [r7, #12] + 80040bc: 60b9 str r1, [r7, #8] + 80040be: 607a str r2, [r7, #4] + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 1: Reset the CC1E Bit */ + tmpccer = TIMx->CCER; + 80040c0: 68fb ldr r3, [r7, #12] + 80040c2: 6a1b ldr r3, [r3, #32] + 80040c4: 617b str r3, [r7, #20] + TIMx->CCER &= ~TIM_CCER_CC1E; + 80040c6: 68fb ldr r3, [r7, #12] + 80040c8: 6a1b ldr r3, [r3, #32] + 80040ca: f023 0201 bic.w r2, r3, #1 + 80040ce: 68fb ldr r3, [r7, #12] + 80040d0: 621a str r2, [r3, #32] + tmpccmr1 = TIMx->CCMR1; + 80040d2: 68fb ldr r3, [r7, #12] + 80040d4: 699b ldr r3, [r3, #24] + 80040d6: 613b str r3, [r7, #16] + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + 80040d8: 693b ldr r3, [r7, #16] + 80040da: f023 03f0 bic.w r3, r3, #240 ; 0xf0 + 80040de: 613b str r3, [r7, #16] + tmpccmr1 |= (TIM_ICFilter << 4U); + 80040e0: 687b ldr r3, [r7, #4] + 80040e2: 011b lsls r3, r3, #4 + 80040e4: 693a ldr r2, [r7, #16] + 80040e6: 4313 orrs r3, r2 + 80040e8: 613b str r3, [r7, #16] + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + 80040ea: 697b ldr r3, [r7, #20] + 80040ec: f023 030a bic.w r3, r3, #10 + 80040f0: 617b str r3, [r7, #20] + tmpccer |= TIM_ICPolarity; + 80040f2: 697a ldr r2, [r7, #20] + 80040f4: 68bb ldr r3, [r7, #8] + 80040f6: 4313 orrs r3, r2 + 80040f8: 617b str r3, [r7, #20] + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + 80040fa: 68fb ldr r3, [r7, #12] + 80040fc: 693a ldr r2, [r7, #16] + 80040fe: 619a str r2, [r3, #24] + TIMx->CCER = tmpccer; + 8004100: 68fb ldr r3, [r7, #12] + 8004102: 697a ldr r2, [r7, #20] + 8004104: 621a str r2, [r3, #32] +} + 8004106: bf00 nop + 8004108: 371c adds r7, #28 + 800410a: 46bd mov sp, r7 + 800410c: f85d 7b04 ldr.w r7, [sp], #4 + 8004110: 4770 bx lr + +08004112 : + * @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) +{ + 8004112: b480 push {r7} + 8004114: b087 sub sp, #28 + 8004116: af00 add r7, sp, #0 + 8004118: 60f8 str r0, [r7, #12] + 800411a: 60b9 str r1, [r7, #8] + 800411c: 607a str r2, [r7, #4] + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + 800411e: 68fb ldr r3, [r7, #12] + 8004120: 6a1b ldr r3, [r3, #32] + 8004122: f023 0210 bic.w r2, r3, #16 + 8004126: 68fb ldr r3, [r7, #12] + 8004128: 621a str r2, [r3, #32] + tmpccmr1 = TIMx->CCMR1; + 800412a: 68fb ldr r3, [r7, #12] + 800412c: 699b ldr r3, [r3, #24] + 800412e: 617b str r3, [r7, #20] + tmpccer = TIMx->CCER; + 8004130: 68fb ldr r3, [r7, #12] + 8004132: 6a1b ldr r3, [r3, #32] + 8004134: 613b str r3, [r7, #16] + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC2F; + 8004136: 697b ldr r3, [r7, #20] + 8004138: f423 4370 bic.w r3, r3, #61440 ; 0xf000 + 800413c: 617b str r3, [r7, #20] + tmpccmr1 |= (TIM_ICFilter << 12U); + 800413e: 687b ldr r3, [r7, #4] + 8004140: 031b lsls r3, r3, #12 + 8004142: 697a ldr r2, [r7, #20] + 8004144: 4313 orrs r3, r2 + 8004146: 617b str r3, [r7, #20] + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + 8004148: 693b ldr r3, [r7, #16] + 800414a: f023 03a0 bic.w r3, r3, #160 ; 0xa0 + 800414e: 613b str r3, [r7, #16] + tmpccer |= (TIM_ICPolarity << 4U); + 8004150: 68bb ldr r3, [r7, #8] + 8004152: 011b lsls r3, r3, #4 + 8004154: 693a ldr r2, [r7, #16] + 8004156: 4313 orrs r3, r2 + 8004158: 613b str r3, [r7, #16] + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + 800415a: 68fb ldr r3, [r7, #12] + 800415c: 697a ldr r2, [r7, #20] + 800415e: 619a str r2, [r3, #24] + TIMx->CCER = tmpccer; + 8004160: 68fb ldr r3, [r7, #12] + 8004162: 693a ldr r2, [r7, #16] + 8004164: 621a str r2, [r3, #32] +} + 8004166: bf00 nop + 8004168: 371c adds r7, #28 + 800416a: 46bd mov sp, r7 + 800416c: f85d 7b04 ldr.w r7, [sp], #4 + 8004170: 4770 bx lr + +08004172 : + * @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) +{ + 8004172: b480 push {r7} + 8004174: b085 sub sp, #20 + 8004176: af00 add r7, sp, #0 + 8004178: 6078 str r0, [r7, #4] + 800417a: 6039 str r1, [r7, #0] + uint32_t tmpsmcr; + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + 800417c: 687b ldr r3, [r7, #4] + 800417e: 689b ldr r3, [r3, #8] + 8004180: 60fb str r3, [r7, #12] + /* Reset the TS Bits */ + tmpsmcr &= ~TIM_SMCR_TS; + 8004182: 68fb ldr r3, [r7, #12] + 8004184: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8004188: 60fb str r3, [r7, #12] + /* Set the Input Trigger source and the slave mode*/ + tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); + 800418a: 683a ldr r2, [r7, #0] + 800418c: 68fb ldr r3, [r7, #12] + 800418e: 4313 orrs r3, r2 + 8004190: f043 0307 orr.w r3, r3, #7 + 8004194: 60fb str r3, [r7, #12] + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + 8004196: 687b ldr r3, [r7, #4] + 8004198: 68fa ldr r2, [r7, #12] + 800419a: 609a str r2, [r3, #8] +} + 800419c: bf00 nop + 800419e: 3714 adds r7, #20 + 80041a0: 46bd mov sp, r7 + 80041a2: f85d 7b04 ldr.w r7, [sp], #4 + 80041a6: 4770 bx lr + +080041a8 : + * 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) +{ + 80041a8: b480 push {r7} + 80041aa: b087 sub sp, #28 + 80041ac: af00 add r7, sp, #0 + 80041ae: 60f8 str r0, [r7, #12] + 80041b0: 60b9 str r1, [r7, #8] + 80041b2: 607a str r2, [r7, #4] + 80041b4: 603b str r3, [r7, #0] + uint32_t tmpsmcr; + + tmpsmcr = TIMx->SMCR; + 80041b6: 68fb ldr r3, [r7, #12] + 80041b8: 689b ldr r3, [r3, #8] + 80041ba: 617b str r3, [r7, #20] + + /* Reset the ETR Bits */ + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + 80041bc: 697b ldr r3, [r7, #20] + 80041be: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 80041c2: 617b str r3, [r7, #20] + + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); + 80041c4: 683b ldr r3, [r7, #0] + 80041c6: 021a lsls r2, r3, #8 + 80041c8: 687b ldr r3, [r7, #4] + 80041ca: 431a orrs r2, r3 + 80041cc: 68bb ldr r3, [r7, #8] + 80041ce: 4313 orrs r3, r2 + 80041d0: 697a ldr r2, [r7, #20] + 80041d2: 4313 orrs r3, r2 + 80041d4: 617b str r3, [r7, #20] + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + 80041d6: 68fb ldr r3, [r7, #12] + 80041d8: 697a ldr r2, [r7, #20] + 80041da: 609a str r2, [r3, #8] +} + 80041dc: bf00 nop + 80041de: 371c adds r7, #28 + 80041e0: 46bd mov sp, r7 + 80041e2: f85d 7b04 ldr.w r7, [sp], #4 + 80041e6: 4770 bx lr + +080041e8 : + * @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) +{ + 80041e8: b480 push {r7} + 80041ea: b087 sub sp, #28 + 80041ec: af00 add r7, sp, #0 + 80041ee: 60f8 str r0, [r7, #12] + 80041f0: 60b9 str r1, [r7, #8] + 80041f2: 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 */ + 80041f4: 68bb ldr r3, [r7, #8] + 80041f6: f003 031f and.w r3, r3, #31 + 80041fa: 2201 movs r2, #1 + 80041fc: fa02 f303 lsl.w r3, r2, r3 + 8004200: 617b str r3, [r7, #20] + + /* Reset the CCxE Bit */ + TIMx->CCER &= ~tmp; + 8004202: 68fb ldr r3, [r7, #12] + 8004204: 6a1a ldr r2, [r3, #32] + 8004206: 697b ldr r3, [r7, #20] + 8004208: 43db mvns r3, r3 + 800420a: 401a ands r2, r3 + 800420c: 68fb ldr r3, [r7, #12] + 800420e: 621a str r2, [r3, #32] + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ + 8004210: 68fb ldr r3, [r7, #12] + 8004212: 6a1a ldr r2, [r3, #32] + 8004214: 68bb ldr r3, [r7, #8] + 8004216: f003 031f and.w r3, r3, #31 + 800421a: 6879 ldr r1, [r7, #4] + 800421c: fa01 f303 lsl.w r3, r1, r3 + 8004220: 431a orrs r2, r3 + 8004222: 68fb ldr r3, [r7, #12] + 8004224: 621a str r2, [r3, #32] +} + 8004226: bf00 nop + 8004228: 371c adds r7, #28 + 800422a: 46bd mov sp, r7 + 800422c: f85d 7b04 ldr.w r7, [sp], #4 + 8004230: 4770 bx lr + ... + +08004234 : + * mode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, + TIM_MasterConfigTypeDef *sMasterConfig) +{ + 8004234: b480 push {r7} + 8004236: b085 sub sp, #20 + 8004238: af00 add r7, sp, #0 + 800423a: 6078 str r0, [r7, #4] + 800423c: 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); + 800423e: 687b ldr r3, [r7, #4] + 8004240: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8004244: 2b01 cmp r3, #1 + 8004246: d101 bne.n 800424c + 8004248: 2302 movs r3, #2 + 800424a: e045 b.n 80042d8 + 800424c: 687b ldr r3, [r7, #4] + 800424e: 2201 movs r2, #1 + 8004250: f883 203c strb.w r2, [r3, #60] ; 0x3c + + /* Change the handler state */ + htim->State = HAL_TIM_STATE_BUSY; + 8004254: 687b ldr r3, [r7, #4] + 8004256: 2202 movs r2, #2 + 8004258: f883 203d strb.w r2, [r3, #61] ; 0x3d + + /* Get the TIMx CR2 register value */ + tmpcr2 = htim->Instance->CR2; + 800425c: 687b ldr r3, [r7, #4] + 800425e: 681b ldr r3, [r3, #0] + 8004260: 685b ldr r3, [r3, #4] + 8004262: 60fb str r3, [r7, #12] + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + 8004264: 687b ldr r3, [r7, #4] + 8004266: 681b ldr r3, [r3, #0] + 8004268: 689b ldr r3, [r3, #8] + 800426a: 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)) + 800426c: 687b ldr r3, [r7, #4] + 800426e: 681b ldr r3, [r3, #0] + 8004270: 4a1c ldr r2, [pc, #112] ; (80042e4 ) + 8004272: 4293 cmp r3, r2 + 8004274: d004 beq.n 8004280 + 8004276: 687b ldr r3, [r7, #4] + 8004278: 681b ldr r3, [r3, #0] + 800427a: 4a1b ldr r2, [pc, #108] ; (80042e8 ) + 800427c: 4293 cmp r3, r2 + 800427e: d108 bne.n 8004292 + { + /* Check the parameters */ + assert_param(IS_TIM_TRGO2_SOURCE(sMasterConfig->MasterOutputTrigger2)); + + /* Clear the MMS2 bits */ + tmpcr2 &= ~TIM_CR2_MMS2; + 8004280: 68fb ldr r3, [r7, #12] + 8004282: f423 0370 bic.w r3, r3, #15728640 ; 0xf00000 + 8004286: 60fb str r3, [r7, #12] + /* Select the TRGO2 source*/ + tmpcr2 |= sMasterConfig->MasterOutputTrigger2; + 8004288: 683b ldr r3, [r7, #0] + 800428a: 685b ldr r3, [r3, #4] + 800428c: 68fa ldr r2, [r7, #12] + 800428e: 4313 orrs r3, r2 + 8004290: 60fb str r3, [r7, #12] + } + + /* Reset the MMS Bits */ + tmpcr2 &= ~TIM_CR2_MMS; + 8004292: 68fb ldr r3, [r7, #12] + 8004294: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8004298: 60fb str r3, [r7, #12] + /* Select the TRGO source */ + tmpcr2 |= sMasterConfig->MasterOutputTrigger; + 800429a: 683b ldr r3, [r7, #0] + 800429c: 681b ldr r3, [r3, #0] + 800429e: 68fa ldr r2, [r7, #12] + 80042a0: 4313 orrs r3, r2 + 80042a2: 60fb str r3, [r7, #12] + + /* Reset the MSM Bit */ + tmpsmcr &= ~TIM_SMCR_MSM; + 80042a4: 68bb ldr r3, [r7, #8] + 80042a6: f023 0380 bic.w r3, r3, #128 ; 0x80 + 80042aa: 60bb str r3, [r7, #8] + /* Set master mode */ + tmpsmcr |= sMasterConfig->MasterSlaveMode; + 80042ac: 683b ldr r3, [r7, #0] + 80042ae: 689b ldr r3, [r3, #8] + 80042b0: 68ba ldr r2, [r7, #8] + 80042b2: 4313 orrs r3, r2 + 80042b4: 60bb str r3, [r7, #8] + + /* Update TIMx CR2 */ + htim->Instance->CR2 = tmpcr2; + 80042b6: 687b ldr r3, [r7, #4] + 80042b8: 681b ldr r3, [r3, #0] + 80042ba: 68fa ldr r2, [r7, #12] + 80042bc: 605a str r2, [r3, #4] + + /* Update TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + 80042be: 687b ldr r3, [r7, #4] + 80042c0: 681b ldr r3, [r3, #0] + 80042c2: 68ba ldr r2, [r7, #8] + 80042c4: 609a str r2, [r3, #8] + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + 80042c6: 687b ldr r3, [r7, #4] + 80042c8: 2201 movs r2, #1 + 80042ca: f883 203d strb.w r2, [r3, #61] ; 0x3d + + __HAL_UNLOCK(htim); + 80042ce: 687b ldr r3, [r7, #4] + 80042d0: 2200 movs r2, #0 + 80042d2: f883 203c strb.w r2, [r3, #60] ; 0x3c + + return HAL_OK; + 80042d6: 2300 movs r3, #0 +} + 80042d8: 4618 mov r0, r3 + 80042da: 3714 adds r7, #20 + 80042dc: 46bd mov sp, r7 + 80042de: f85d 7b04 ldr.w r7, [sp], #4 + 80042e2: 4770 bx lr + 80042e4: 40010000 .word 0x40010000 + 80042e8: 40010400 .word 0x40010400 + +080042ec : + * @brief Hall commutation changed callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) +{ + 80042ec: b480 push {r7} + 80042ee: b083 sub sp, #12 + 80042f0: af00 add r7, sp, #0 + 80042f2: 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 + */ +} + 80042f4: bf00 nop + 80042f6: 370c adds r7, #12 + 80042f8: 46bd mov sp, r7 + 80042fa: f85d 7b04 ldr.w r7, [sp], #4 + 80042fe: 4770 bx lr + +08004300 : + * @brief Hall Break detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) +{ + 8004300: b480 push {r7} + 8004302: b083 sub sp, #12 + 8004304: af00 add r7, sp, #0 + 8004306: 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 + */ +} + 8004308: bf00 nop + 800430a: 370c adds r7, #12 + 800430c: 46bd mov sp, r7 + 800430e: f85d 7b04 ldr.w r7, [sp], #4 + 8004312: 4770 bx lr + +08004314 : + * @brief Hall Break2 detection callback in non blocking mode + * @param htim: TIM handle + * @retval None + */ +__weak void HAL_TIMEx_Break2Callback(TIM_HandleTypeDef *htim) +{ + 8004314: b480 push {r7} + 8004316: b083 sub sp, #12 + 8004318: af00 add r7, sp, #0 + 800431a: 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 + */ +} + 800431c: bf00 nop + 800431e: 370c adds r7, #12 + 8004320: 46bd mov sp, r7 + 8004322: f85d 7b04 ldr.w r7, [sp], #4 + 8004326: 4770 bx lr + +08004328 : + * 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) +{ + 8004328: b580 push {r7, lr} + 800432a: b082 sub sp, #8 + 800432c: af00 add r7, sp, #0 + 800432e: 6078 str r0, [r7, #4] + /* Check the UART handle allocation */ + if (huart == NULL) + 8004330: 687b ldr r3, [r7, #4] + 8004332: 2b00 cmp r3, #0 + 8004334: d101 bne.n 800433a + { + return HAL_ERROR; + 8004336: 2301 movs r3, #1 + 8004338: e040 b.n 80043bc + { + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + } + + if (huart->gState == HAL_UART_STATE_RESET) + 800433a: 687b ldr r3, [r7, #4] + 800433c: 6f5b ldr r3, [r3, #116] ; 0x74 + 800433e: 2b00 cmp r3, #0 + 8004340: d106 bne.n 8004350 + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + 8004342: 687b ldr r3, [r7, #4] + 8004344: 2200 movs r2, #0 + 8004346: 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); + 800434a: 6878 ldr r0, [r7, #4] + 800434c: f7fc fef0 bl 8001130 +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + 8004350: 687b ldr r3, [r7, #4] + 8004352: 2224 movs r2, #36 ; 0x24 + 8004354: 675a str r2, [r3, #116] ; 0x74 + + /* Disable the Peripheral */ + __HAL_UART_DISABLE(huart); + 8004356: 687b ldr r3, [r7, #4] + 8004358: 681b ldr r3, [r3, #0] + 800435a: 681a ldr r2, [r3, #0] + 800435c: 687b ldr r3, [r7, #4] + 800435e: 681b ldr r3, [r3, #0] + 8004360: f022 0201 bic.w r2, r2, #1 + 8004364: 601a str r2, [r3, #0] + + /* Set the UART Communication parameters */ + if (UART_SetConfig(huart) == HAL_ERROR) + 8004366: 6878 ldr r0, [r7, #4] + 8004368: f000 f95c bl 8004624 + 800436c: 4603 mov r3, r0 + 800436e: 2b01 cmp r3, #1 + 8004370: d101 bne.n 8004376 + { + return HAL_ERROR; + 8004372: 2301 movs r3, #1 + 8004374: e022 b.n 80043bc + } + + if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT) + 8004376: 687b ldr r3, [r7, #4] + 8004378: 6a5b ldr r3, [r3, #36] ; 0x24 + 800437a: 2b00 cmp r3, #0 + 800437c: d002 beq.n 8004384 + { + UART_AdvFeatureConfig(huart); + 800437e: 6878 ldr r0, [r7, #4] + 8004380: f000 fbf4 bl 8004b6c + } + + /* 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)); + 8004384: 687b ldr r3, [r7, #4] + 8004386: 681b ldr r3, [r3, #0] + 8004388: 685a ldr r2, [r3, #4] + 800438a: 687b ldr r3, [r7, #4] + 800438c: 681b ldr r3, [r3, #0] + 800438e: f422 4290 bic.w r2, r2, #18432 ; 0x4800 + 8004392: 605a str r2, [r3, #4] + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + 8004394: 687b ldr r3, [r7, #4] + 8004396: 681b ldr r3, [r3, #0] + 8004398: 689a ldr r2, [r3, #8] + 800439a: 687b ldr r3, [r7, #4] + 800439c: 681b ldr r3, [r3, #0] + 800439e: f022 022a bic.w r2, r2, #42 ; 0x2a + 80043a2: 609a str r2, [r3, #8] + + /* Enable the Peripheral */ + __HAL_UART_ENABLE(huart); + 80043a4: 687b ldr r3, [r7, #4] + 80043a6: 681b ldr r3, [r3, #0] + 80043a8: 681a ldr r2, [r3, #0] + 80043aa: 687b ldr r3, [r7, #4] + 80043ac: 681b ldr r3, [r3, #0] + 80043ae: f042 0201 orr.w r2, r2, #1 + 80043b2: 601a str r2, [r3, #0] + + /* TEACK and/or REACK to check before moving huart->gState and huart->RxState to Ready */ + return (UART_CheckIdleState(huart)); + 80043b4: 6878 ldr r0, [r7, #4] + 80043b6: f000 fc7b bl 8004cb0 + 80043ba: 4603 mov r3, r0 +} + 80043bc: 4618 mov r0, r3 + 80043be: 3708 adds r7, #8 + 80043c0: 46bd mov sp, r7 + 80043c2: bd80 pop {r7, pc} + +080043c4 : + * @brief Handle UART interrupt request. + * @param huart UART handle. + * @retval None + */ +void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) +{ + 80043c4: b580 push {r7, lr} + 80043c6: b088 sub sp, #32 + 80043c8: af00 add r7, sp, #0 + 80043ca: 6078 str r0, [r7, #4] + uint32_t isrflags = READ_REG(huart->Instance->ISR); + 80043cc: 687b ldr r3, [r7, #4] + 80043ce: 681b ldr r3, [r3, #0] + 80043d0: 69db ldr r3, [r3, #28] + 80043d2: 61fb str r3, [r7, #28] + uint32_t cr1its = READ_REG(huart->Instance->CR1); + 80043d4: 687b ldr r3, [r7, #4] + 80043d6: 681b ldr r3, [r3, #0] + 80043d8: 681b ldr r3, [r3, #0] + 80043da: 61bb str r3, [r7, #24] + uint32_t cr3its = READ_REG(huart->Instance->CR3); + 80043dc: 687b ldr r3, [r7, #4] + 80043de: 681b ldr r3, [r3, #0] + 80043e0: 689b ldr r3, [r3, #8] + 80043e2: 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)); + 80043e4: 69fb ldr r3, [r7, #28] + 80043e6: f003 030f and.w r3, r3, #15 + 80043ea: 613b str r3, [r7, #16] + if (errorflags == 0U) + 80043ec: 693b ldr r3, [r7, #16] + 80043ee: 2b00 cmp r3, #0 + 80043f0: d113 bne.n 800441a + { + /* UART in mode Receiver ---------------------------------------------------*/ + if (((isrflags & USART_ISR_RXNE) != 0U) + 80043f2: 69fb ldr r3, [r7, #28] + 80043f4: f003 0320 and.w r3, r3, #32 + 80043f8: 2b00 cmp r3, #0 + 80043fa: d00e beq.n 800441a + && ((cr1its & USART_CR1_RXNEIE) != 0U)) + 80043fc: 69bb ldr r3, [r7, #24] + 80043fe: f003 0320 and.w r3, r3, #32 + 8004402: 2b00 cmp r3, #0 + 8004404: d009 beq.n 800441a + { + if (huart->RxISR != NULL) + 8004406: 687b ldr r3, [r7, #4] + 8004408: 6e1b ldr r3, [r3, #96] ; 0x60 + 800440a: 2b00 cmp r3, #0 + 800440c: f000 80eb beq.w 80045e6 + { + huart->RxISR(huart); + 8004410: 687b ldr r3, [r7, #4] + 8004412: 6e1b ldr r3, [r3, #96] ; 0x60 + 8004414: 6878 ldr r0, [r7, #4] + 8004416: 4798 blx r3 + } + return; + 8004418: e0e5 b.n 80045e6 + } + } + + /* If some errors occur */ + if ((errorflags != 0U) + 800441a: 693b ldr r3, [r7, #16] + 800441c: 2b00 cmp r3, #0 + 800441e: f000 80c0 beq.w 80045a2 + && (((cr3its & USART_CR3_EIE) != 0U) + 8004422: 697b ldr r3, [r7, #20] + 8004424: f003 0301 and.w r3, r3, #1 + 8004428: 2b00 cmp r3, #0 + 800442a: d105 bne.n 8004438 + || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != 0U))) + 800442c: 69bb ldr r3, [r7, #24] + 800442e: f403 7390 and.w r3, r3, #288 ; 0x120 + 8004432: 2b00 cmp r3, #0 + 8004434: f000 80b5 beq.w 80045a2 + { + /* UART parity error interrupt occurred -------------------------------------*/ + if (((isrflags & USART_ISR_PE) != 0U) && ((cr1its & USART_CR1_PEIE) != 0U)) + 8004438: 69fb ldr r3, [r7, #28] + 800443a: f003 0301 and.w r3, r3, #1 + 800443e: 2b00 cmp r3, #0 + 8004440: d00e beq.n 8004460 + 8004442: 69bb ldr r3, [r7, #24] + 8004444: f403 7380 and.w r3, r3, #256 ; 0x100 + 8004448: 2b00 cmp r3, #0 + 800444a: d009 beq.n 8004460 + { + __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_PEF); + 800444c: 687b ldr r3, [r7, #4] + 800444e: 681b ldr r3, [r3, #0] + 8004450: 2201 movs r2, #1 + 8004452: 621a str r2, [r3, #32] + + huart->ErrorCode |= HAL_UART_ERROR_PE; + 8004454: 687b ldr r3, [r7, #4] + 8004456: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004458: f043 0201 orr.w r2, r3, #1 + 800445c: 687b ldr r3, [r7, #4] + 800445e: 67da str r2, [r3, #124] ; 0x7c + } + + /* UART frame error interrupt occurred --------------------------------------*/ + if (((isrflags & USART_ISR_FE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) + 8004460: 69fb ldr r3, [r7, #28] + 8004462: f003 0302 and.w r3, r3, #2 + 8004466: 2b00 cmp r3, #0 + 8004468: d00e beq.n 8004488 + 800446a: 697b ldr r3, [r7, #20] + 800446c: f003 0301 and.w r3, r3, #1 + 8004470: 2b00 cmp r3, #0 + 8004472: d009 beq.n 8004488 + { + __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_FEF); + 8004474: 687b ldr r3, [r7, #4] + 8004476: 681b ldr r3, [r3, #0] + 8004478: 2202 movs r2, #2 + 800447a: 621a str r2, [r3, #32] + + huart->ErrorCode |= HAL_UART_ERROR_FE; + 800447c: 687b ldr r3, [r7, #4] + 800447e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004480: f043 0204 orr.w r2, r3, #4 + 8004484: 687b ldr r3, [r7, #4] + 8004486: 67da str r2, [r3, #124] ; 0x7c + } + + /* UART noise error interrupt occurred --------------------------------------*/ + if (((isrflags & USART_ISR_NE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) + 8004488: 69fb ldr r3, [r7, #28] + 800448a: f003 0304 and.w r3, r3, #4 + 800448e: 2b00 cmp r3, #0 + 8004490: d00e beq.n 80044b0 + 8004492: 697b ldr r3, [r7, #20] + 8004494: f003 0301 and.w r3, r3, #1 + 8004498: 2b00 cmp r3, #0 + 800449a: d009 beq.n 80044b0 + { + __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_NEF); + 800449c: 687b ldr r3, [r7, #4] + 800449e: 681b ldr r3, [r3, #0] + 80044a0: 2204 movs r2, #4 + 80044a2: 621a str r2, [r3, #32] + + huart->ErrorCode |= HAL_UART_ERROR_NE; + 80044a4: 687b ldr r3, [r7, #4] + 80044a6: 6fdb ldr r3, [r3, #124] ; 0x7c + 80044a8: f043 0202 orr.w r2, r3, #2 + 80044ac: 687b ldr r3, [r7, #4] + 80044ae: 67da str r2, [r3, #124] ; 0x7c + } + + /* UART Over-Run interrupt occurred -----------------------------------------*/ + if (((isrflags & USART_ISR_ORE) != 0U) + 80044b0: 69fb ldr r3, [r7, #28] + 80044b2: f003 0308 and.w r3, r3, #8 + 80044b6: 2b00 cmp r3, #0 + 80044b8: d013 beq.n 80044e2 + && (((cr1its & USART_CR1_RXNEIE) != 0U) || + 80044ba: 69bb ldr r3, [r7, #24] + 80044bc: f003 0320 and.w r3, r3, #32 + 80044c0: 2b00 cmp r3, #0 + 80044c2: d104 bne.n 80044ce + ((cr3its & USART_CR3_EIE) != 0U))) + 80044c4: 697b ldr r3, [r7, #20] + 80044c6: f003 0301 and.w r3, r3, #1 + && (((cr1its & USART_CR1_RXNEIE) != 0U) || + 80044ca: 2b00 cmp r3, #0 + 80044cc: d009 beq.n 80044e2 + { + __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_OREF); + 80044ce: 687b ldr r3, [r7, #4] + 80044d0: 681b ldr r3, [r3, #0] + 80044d2: 2208 movs r2, #8 + 80044d4: 621a str r2, [r3, #32] + + huart->ErrorCode |= HAL_UART_ERROR_ORE; + 80044d6: 687b ldr r3, [r7, #4] + 80044d8: 6fdb ldr r3, [r3, #124] ; 0x7c + 80044da: f043 0208 orr.w r2, r3, #8 + 80044de: 687b ldr r3, [r7, #4] + 80044e0: 67da str r2, [r3, #124] ; 0x7c + } + + /* Call UART Error Call back function if need be --------------------------*/ + if (huart->ErrorCode != HAL_UART_ERROR_NONE) + 80044e2: 687b ldr r3, [r7, #4] + 80044e4: 6fdb ldr r3, [r3, #124] ; 0x7c + 80044e6: 2b00 cmp r3, #0 + 80044e8: d07f beq.n 80045ea + { + /* UART in mode Receiver ---------------------------------------------------*/ + if (((isrflags & USART_ISR_RXNE) != 0U) + 80044ea: 69fb ldr r3, [r7, #28] + 80044ec: f003 0320 and.w r3, r3, #32 + 80044f0: 2b00 cmp r3, #0 + 80044f2: d00c beq.n 800450e + && ((cr1its & USART_CR1_RXNEIE) != 0U)) + 80044f4: 69bb ldr r3, [r7, #24] + 80044f6: f003 0320 and.w r3, r3, #32 + 80044fa: 2b00 cmp r3, #0 + 80044fc: d007 beq.n 800450e + { + if (huart->RxISR != NULL) + 80044fe: 687b ldr r3, [r7, #4] + 8004500: 6e1b ldr r3, [r3, #96] ; 0x60 + 8004502: 2b00 cmp r3, #0 + 8004504: d003 beq.n 800450e + { + huart->RxISR(huart); + 8004506: 687b ldr r3, [r7, #4] + 8004508: 6e1b ldr r3, [r3, #96] ; 0x60 + 800450a: 6878 ldr r0, [r7, #4] + 800450c: 4798 blx r3 + } + } + + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + errorcode = huart->ErrorCode; + 800450e: 687b ldr r3, [r7, #4] + 8004510: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004512: 60fb str r3, [r7, #12] + if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || + 8004514: 687b ldr r3, [r7, #4] + 8004516: 681b ldr r3, [r3, #0] + 8004518: 689b ldr r3, [r3, #8] + 800451a: f003 0340 and.w r3, r3, #64 ; 0x40 + 800451e: 2b40 cmp r3, #64 ; 0x40 + 8004520: d004 beq.n 800452c + ((errorcode & HAL_UART_ERROR_ORE) != 0U)) + 8004522: 68fb ldr r3, [r7, #12] + 8004524: f003 0308 and.w r3, r3, #8 + if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || + 8004528: 2b00 cmp r3, #0 + 800452a: d031 beq.n 8004590 + { + /* 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); + 800452c: 6878 ldr r0, [r7, #4] + 800452e: f000 fc36 bl 8004d9e + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + 8004532: 687b ldr r3, [r7, #4] + 8004534: 681b ldr r3, [r3, #0] + 8004536: 689b ldr r3, [r3, #8] + 8004538: f003 0340 and.w r3, r3, #64 ; 0x40 + 800453c: 2b40 cmp r3, #64 ; 0x40 + 800453e: d123 bne.n 8004588 + { + CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + 8004540: 687b ldr r3, [r7, #4] + 8004542: 681b ldr r3, [r3, #0] + 8004544: 689a ldr r2, [r3, #8] + 8004546: 687b ldr r3, [r7, #4] + 8004548: 681b ldr r3, [r3, #0] + 800454a: f022 0240 bic.w r2, r2, #64 ; 0x40 + 800454e: 609a str r2, [r3, #8] + + /* Abort the UART DMA Rx channel */ + if (huart->hdmarx != NULL) + 8004550: 687b ldr r3, [r7, #4] + 8004552: 6edb ldr r3, [r3, #108] ; 0x6c + 8004554: 2b00 cmp r3, #0 + 8004556: d013 beq.n 8004580 + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; + 8004558: 687b ldr r3, [r7, #4] + 800455a: 6edb ldr r3, [r3, #108] ; 0x6c + 800455c: 4a26 ldr r2, [pc, #152] ; (80045f8 ) + 800455e: 651a str r2, [r3, #80] ; 0x50 + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + 8004560: 687b ldr r3, [r7, #4] + 8004562: 6edb ldr r3, [r3, #108] ; 0x6c + 8004564: 4618 mov r0, r3 + 8004566: f7fd f96f bl 8001848 + 800456a: 4603 mov r3, r0 + 800456c: 2b00 cmp r3, #0 + 800456e: d016 beq.n 800459e + { + /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ + huart->hdmarx->XferAbortCallback(huart->hdmarx); + 8004570: 687b ldr r3, [r7, #4] + 8004572: 6edb ldr r3, [r3, #108] ; 0x6c + 8004574: 6d1b ldr r3, [r3, #80] ; 0x50 + 8004576: 687a ldr r2, [r7, #4] + 8004578: 6ed2 ldr r2, [r2, #108] ; 0x6c + 800457a: 4610 mov r0, r2 + 800457c: 4798 blx r3 + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + 800457e: e00e b.n 800459e +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); + 8004580: 6878 ldr r0, [r7, #4] + 8004582: f000 f845 bl 8004610 + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + 8004586: e00a b.n 800459e +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); + 8004588: 6878 ldr r0, [r7, #4] + 800458a: f000 f841 bl 8004610 + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + 800458e: e006 b.n 800459e +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); + 8004590: 6878 ldr r0, [r7, #4] + 8004592: f000 f83d bl 8004610 +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + 8004596: 687b ldr r3, [r7, #4] + 8004598: 2200 movs r2, #0 + 800459a: 67da str r2, [r3, #124] ; 0x7c + } + } + return; + 800459c: e025 b.n 80045ea + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + 800459e: bf00 nop + return; + 80045a0: e023 b.n 80045ea + + } /* End if some error occurs */ + + /* UART in mode Transmitter ------------------------------------------------*/ + if (((isrflags & USART_ISR_TXE) != 0U) + 80045a2: 69fb ldr r3, [r7, #28] + 80045a4: f003 0380 and.w r3, r3, #128 ; 0x80 + 80045a8: 2b00 cmp r3, #0 + 80045aa: d00d beq.n 80045c8 + && ((cr1its & USART_CR1_TXEIE) != 0U)) + 80045ac: 69bb ldr r3, [r7, #24] + 80045ae: f003 0380 and.w r3, r3, #128 ; 0x80 + 80045b2: 2b00 cmp r3, #0 + 80045b4: d008 beq.n 80045c8 + { + if (huart->TxISR != NULL) + 80045b6: 687b ldr r3, [r7, #4] + 80045b8: 6e5b ldr r3, [r3, #100] ; 0x64 + 80045ba: 2b00 cmp r3, #0 + 80045bc: d017 beq.n 80045ee + { + huart->TxISR(huart); + 80045be: 687b ldr r3, [r7, #4] + 80045c0: 6e5b ldr r3, [r3, #100] ; 0x64 + 80045c2: 6878 ldr r0, [r7, #4] + 80045c4: 4798 blx r3 + } + return; + 80045c6: e012 b.n 80045ee + } + + /* UART in mode Transmitter (transmission end) -----------------------------*/ + if (((isrflags & USART_ISR_TC) != 0U) && ((cr1its & USART_CR1_TCIE) != 0U)) + 80045c8: 69fb ldr r3, [r7, #28] + 80045ca: f003 0340 and.w r3, r3, #64 ; 0x40 + 80045ce: 2b00 cmp r3, #0 + 80045d0: d00e beq.n 80045f0 + 80045d2: 69bb ldr r3, [r7, #24] + 80045d4: f003 0340 and.w r3, r3, #64 ; 0x40 + 80045d8: 2b00 cmp r3, #0 + 80045da: d009 beq.n 80045f0 + { + UART_EndTransmit_IT(huart); + 80045dc: 6878 ldr r0, [r7, #4] + 80045de: f000 fc14 bl 8004e0a + return; + 80045e2: bf00 nop + 80045e4: e004 b.n 80045f0 + return; + 80045e6: bf00 nop + 80045e8: e002 b.n 80045f0 + return; + 80045ea: bf00 nop + 80045ec: e000 b.n 80045f0 + return; + 80045ee: bf00 nop + } + +} + 80045f0: 3720 adds r7, #32 + 80045f2: 46bd mov sp, r7 + 80045f4: bd80 pop {r7, pc} + 80045f6: bf00 nop + 80045f8: 08004ddf .word 0x08004ddf + +080045fc : + * @brief Tx Transfer completed callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) +{ + 80045fc: b480 push {r7} + 80045fe: b083 sub sp, #12 + 8004600: af00 add r7, sp, #0 + 8004602: 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. + */ +} + 8004604: bf00 nop + 8004606: 370c adds r7, #12 + 8004608: 46bd mov sp, r7 + 800460a: f85d 7b04 ldr.w r7, [sp], #4 + 800460e: 4770 bx lr + +08004610 : + * @brief UART error callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) +{ + 8004610: b480 push {r7} + 8004612: b083 sub sp, #12 + 8004614: af00 add r7, sp, #0 + 8004616: 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. + */ +} + 8004618: bf00 nop + 800461a: 370c adds r7, #12 + 800461c: 46bd mov sp, r7 + 800461e: f85d 7b04 ldr.w r7, [sp], #4 + 8004622: 4770 bx lr + +08004624 : + * @brief Configure the UART peripheral. + * @param huart UART handle. + * @retval HAL status + */ +HAL_StatusTypeDef UART_SetConfig(UART_HandleTypeDef *huart) +{ + 8004624: b580 push {r7, lr} + 8004626: b088 sub sp, #32 + 8004628: af00 add r7, sp, #0 + 800462a: 6078 str r0, [r7, #4] + uint32_t tmpreg; + uint16_t brrtemp; + UART_ClockSourceTypeDef clocksource; + uint32_t usartdiv = 0x00000000U; + 800462c: 2300 movs r3, #0 + 800462e: 61bb str r3, [r7, #24] + HAL_StatusTypeDef ret = HAL_OK; + 8004630: 2300 movs r3, #0 + 8004632: 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 ; + 8004634: 687b ldr r3, [r7, #4] + 8004636: 689a ldr r2, [r3, #8] + 8004638: 687b ldr r3, [r7, #4] + 800463a: 691b ldr r3, [r3, #16] + 800463c: 431a orrs r2, r3 + 800463e: 687b ldr r3, [r7, #4] + 8004640: 695b ldr r3, [r3, #20] + 8004642: 431a orrs r2, r3 + 8004644: 687b ldr r3, [r7, #4] + 8004646: 69db ldr r3, [r3, #28] + 8004648: 4313 orrs r3, r2 + 800464a: 613b str r3, [r7, #16] + MODIFY_REG(huart->Instance->CR1, USART_CR1_FIELDS, tmpreg); + 800464c: 687b ldr r3, [r7, #4] + 800464e: 681b ldr r3, [r3, #0] + 8004650: 681a ldr r2, [r3, #0] + 8004652: 4bb1 ldr r3, [pc, #708] ; (8004918 ) + 8004654: 4013 ands r3, r2 + 8004656: 687a ldr r2, [r7, #4] + 8004658: 6812 ldr r2, [r2, #0] + 800465a: 6939 ldr r1, [r7, #16] + 800465c: 430b orrs r3, r1 + 800465e: 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); + 8004660: 687b ldr r3, [r7, #4] + 8004662: 681b ldr r3, [r3, #0] + 8004664: 685b ldr r3, [r3, #4] + 8004666: f423 5140 bic.w r1, r3, #12288 ; 0x3000 + 800466a: 687b ldr r3, [r7, #4] + 800466c: 68da ldr r2, [r3, #12] + 800466e: 687b ldr r3, [r7, #4] + 8004670: 681b ldr r3, [r3, #0] + 8004672: 430a orrs r2, r1 + 8004674: 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; + 8004676: 687b ldr r3, [r7, #4] + 8004678: 699b ldr r3, [r3, #24] + 800467a: 613b str r3, [r7, #16] + + tmpreg |= huart->Init.OneBitSampling; + 800467c: 687b ldr r3, [r7, #4] + 800467e: 6a1b ldr r3, [r3, #32] + 8004680: 693a ldr r2, [r7, #16] + 8004682: 4313 orrs r3, r2 + 8004684: 613b str r3, [r7, #16] + MODIFY_REG(huart->Instance->CR3, USART_CR3_FIELDS, tmpreg); + 8004686: 687b ldr r3, [r7, #4] + 8004688: 681b ldr r3, [r3, #0] + 800468a: 689b ldr r3, [r3, #8] + 800468c: f423 6130 bic.w r1, r3, #2816 ; 0xb00 + 8004690: 687b ldr r3, [r7, #4] + 8004692: 681b ldr r3, [r3, #0] + 8004694: 693a ldr r2, [r7, #16] + 8004696: 430a orrs r2, r1 + 8004698: 609a str r2, [r3, #8] + + + /*-------------------------- USART BRR Configuration -----------------------*/ + UART_GETCLOCKSOURCE(huart, clocksource); + 800469a: 687b ldr r3, [r7, #4] + 800469c: 681b ldr r3, [r3, #0] + 800469e: 4a9f ldr r2, [pc, #636] ; (800491c ) + 80046a0: 4293 cmp r3, r2 + 80046a2: d121 bne.n 80046e8 + 80046a4: 4b9e ldr r3, [pc, #632] ; (8004920 ) + 80046a6: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80046aa: f003 0303 and.w r3, r3, #3 + 80046ae: 2b03 cmp r3, #3 + 80046b0: d816 bhi.n 80046e0 + 80046b2: a201 add r2, pc, #4 ; (adr r2, 80046b8 ) + 80046b4: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 80046b8: 080046c9 .word 0x080046c9 + 80046bc: 080046d5 .word 0x080046d5 + 80046c0: 080046cf .word 0x080046cf + 80046c4: 080046db .word 0x080046db + 80046c8: 2301 movs r3, #1 + 80046ca: 77fb strb r3, [r7, #31] + 80046cc: e151 b.n 8004972 + 80046ce: 2302 movs r3, #2 + 80046d0: 77fb strb r3, [r7, #31] + 80046d2: e14e b.n 8004972 + 80046d4: 2304 movs r3, #4 + 80046d6: 77fb strb r3, [r7, #31] + 80046d8: e14b b.n 8004972 + 80046da: 2308 movs r3, #8 + 80046dc: 77fb strb r3, [r7, #31] + 80046de: e148 b.n 8004972 + 80046e0: 2310 movs r3, #16 + 80046e2: 77fb strb r3, [r7, #31] + 80046e4: bf00 nop + 80046e6: e144 b.n 8004972 + 80046e8: 687b ldr r3, [r7, #4] + 80046ea: 681b ldr r3, [r3, #0] + 80046ec: 4a8d ldr r2, [pc, #564] ; (8004924 ) + 80046ee: 4293 cmp r3, r2 + 80046f0: d134 bne.n 800475c + 80046f2: 4b8b ldr r3, [pc, #556] ; (8004920 ) + 80046f4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80046f8: f003 030c and.w r3, r3, #12 + 80046fc: 2b0c cmp r3, #12 + 80046fe: d829 bhi.n 8004754 + 8004700: a201 add r2, pc, #4 ; (adr r2, 8004708 ) + 8004702: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004706: bf00 nop + 8004708: 0800473d .word 0x0800473d + 800470c: 08004755 .word 0x08004755 + 8004710: 08004755 .word 0x08004755 + 8004714: 08004755 .word 0x08004755 + 8004718: 08004749 .word 0x08004749 + 800471c: 08004755 .word 0x08004755 + 8004720: 08004755 .word 0x08004755 + 8004724: 08004755 .word 0x08004755 + 8004728: 08004743 .word 0x08004743 + 800472c: 08004755 .word 0x08004755 + 8004730: 08004755 .word 0x08004755 + 8004734: 08004755 .word 0x08004755 + 8004738: 0800474f .word 0x0800474f + 800473c: 2300 movs r3, #0 + 800473e: 77fb strb r3, [r7, #31] + 8004740: e117 b.n 8004972 + 8004742: 2302 movs r3, #2 + 8004744: 77fb strb r3, [r7, #31] + 8004746: e114 b.n 8004972 + 8004748: 2304 movs r3, #4 + 800474a: 77fb strb r3, [r7, #31] + 800474c: e111 b.n 8004972 + 800474e: 2308 movs r3, #8 + 8004750: 77fb strb r3, [r7, #31] + 8004752: e10e b.n 8004972 + 8004754: 2310 movs r3, #16 + 8004756: 77fb strb r3, [r7, #31] + 8004758: bf00 nop + 800475a: e10a b.n 8004972 + 800475c: 687b ldr r3, [r7, #4] + 800475e: 681b ldr r3, [r3, #0] + 8004760: 4a71 ldr r2, [pc, #452] ; (8004928 ) + 8004762: 4293 cmp r3, r2 + 8004764: d120 bne.n 80047a8 + 8004766: 4b6e ldr r3, [pc, #440] ; (8004920 ) + 8004768: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 800476c: f003 0330 and.w r3, r3, #48 ; 0x30 + 8004770: 2b10 cmp r3, #16 + 8004772: d00f beq.n 8004794 + 8004774: 2b10 cmp r3, #16 + 8004776: d802 bhi.n 800477e + 8004778: 2b00 cmp r3, #0 + 800477a: d005 beq.n 8004788 + 800477c: e010 b.n 80047a0 + 800477e: 2b20 cmp r3, #32 + 8004780: d005 beq.n 800478e + 8004782: 2b30 cmp r3, #48 ; 0x30 + 8004784: d009 beq.n 800479a + 8004786: e00b b.n 80047a0 + 8004788: 2300 movs r3, #0 + 800478a: 77fb strb r3, [r7, #31] + 800478c: e0f1 b.n 8004972 + 800478e: 2302 movs r3, #2 + 8004790: 77fb strb r3, [r7, #31] + 8004792: e0ee b.n 8004972 + 8004794: 2304 movs r3, #4 + 8004796: 77fb strb r3, [r7, #31] + 8004798: e0eb b.n 8004972 + 800479a: 2308 movs r3, #8 + 800479c: 77fb strb r3, [r7, #31] + 800479e: e0e8 b.n 8004972 + 80047a0: 2310 movs r3, #16 + 80047a2: 77fb strb r3, [r7, #31] + 80047a4: bf00 nop + 80047a6: e0e4 b.n 8004972 + 80047a8: 687b ldr r3, [r7, #4] + 80047aa: 681b ldr r3, [r3, #0] + 80047ac: 4a5f ldr r2, [pc, #380] ; (800492c ) + 80047ae: 4293 cmp r3, r2 + 80047b0: d120 bne.n 80047f4 + 80047b2: 4b5b ldr r3, [pc, #364] ; (8004920 ) + 80047b4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80047b8: f003 03c0 and.w r3, r3, #192 ; 0xc0 + 80047bc: 2b40 cmp r3, #64 ; 0x40 + 80047be: d00f beq.n 80047e0 + 80047c0: 2b40 cmp r3, #64 ; 0x40 + 80047c2: d802 bhi.n 80047ca + 80047c4: 2b00 cmp r3, #0 + 80047c6: d005 beq.n 80047d4 + 80047c8: e010 b.n 80047ec + 80047ca: 2b80 cmp r3, #128 ; 0x80 + 80047cc: d005 beq.n 80047da + 80047ce: 2bc0 cmp r3, #192 ; 0xc0 + 80047d0: d009 beq.n 80047e6 + 80047d2: e00b b.n 80047ec + 80047d4: 2300 movs r3, #0 + 80047d6: 77fb strb r3, [r7, #31] + 80047d8: e0cb b.n 8004972 + 80047da: 2302 movs r3, #2 + 80047dc: 77fb strb r3, [r7, #31] + 80047de: e0c8 b.n 8004972 + 80047e0: 2304 movs r3, #4 + 80047e2: 77fb strb r3, [r7, #31] + 80047e4: e0c5 b.n 8004972 + 80047e6: 2308 movs r3, #8 + 80047e8: 77fb strb r3, [r7, #31] + 80047ea: e0c2 b.n 8004972 + 80047ec: 2310 movs r3, #16 + 80047ee: 77fb strb r3, [r7, #31] + 80047f0: bf00 nop + 80047f2: e0be b.n 8004972 + 80047f4: 687b ldr r3, [r7, #4] + 80047f6: 681b ldr r3, [r3, #0] + 80047f8: 4a4d ldr r2, [pc, #308] ; (8004930 ) + 80047fa: 4293 cmp r3, r2 + 80047fc: d124 bne.n 8004848 + 80047fe: 4b48 ldr r3, [pc, #288] ; (8004920 ) + 8004800: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004804: f403 7340 and.w r3, r3, #768 ; 0x300 + 8004808: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 800480c: d012 beq.n 8004834 + 800480e: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8004812: d802 bhi.n 800481a + 8004814: 2b00 cmp r3, #0 + 8004816: d007 beq.n 8004828 + 8004818: e012 b.n 8004840 + 800481a: f5b3 7f00 cmp.w r3, #512 ; 0x200 + 800481e: d006 beq.n 800482e + 8004820: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8004824: d009 beq.n 800483a + 8004826: e00b b.n 8004840 + 8004828: 2300 movs r3, #0 + 800482a: 77fb strb r3, [r7, #31] + 800482c: e0a1 b.n 8004972 + 800482e: 2302 movs r3, #2 + 8004830: 77fb strb r3, [r7, #31] + 8004832: e09e b.n 8004972 + 8004834: 2304 movs r3, #4 + 8004836: 77fb strb r3, [r7, #31] + 8004838: e09b b.n 8004972 + 800483a: 2308 movs r3, #8 + 800483c: 77fb strb r3, [r7, #31] + 800483e: e098 b.n 8004972 + 8004840: 2310 movs r3, #16 + 8004842: 77fb strb r3, [r7, #31] + 8004844: bf00 nop + 8004846: e094 b.n 8004972 + 8004848: 687b ldr r3, [r7, #4] + 800484a: 681b ldr r3, [r3, #0] + 800484c: 4a39 ldr r2, [pc, #228] ; (8004934 ) + 800484e: 4293 cmp r3, r2 + 8004850: d124 bne.n 800489c + 8004852: 4b33 ldr r3, [pc, #204] ; (8004920 ) + 8004854: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004858: f403 6340 and.w r3, r3, #3072 ; 0xc00 + 800485c: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004860: d012 beq.n 8004888 + 8004862: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004866: d802 bhi.n 800486e + 8004868: 2b00 cmp r3, #0 + 800486a: d007 beq.n 800487c + 800486c: e012 b.n 8004894 + 800486e: f5b3 6f00 cmp.w r3, #2048 ; 0x800 + 8004872: d006 beq.n 8004882 + 8004874: f5b3 6f40 cmp.w r3, #3072 ; 0xc00 + 8004878: d009 beq.n 800488e + 800487a: e00b b.n 8004894 + 800487c: 2301 movs r3, #1 + 800487e: 77fb strb r3, [r7, #31] + 8004880: e077 b.n 8004972 + 8004882: 2302 movs r3, #2 + 8004884: 77fb strb r3, [r7, #31] + 8004886: e074 b.n 8004972 + 8004888: 2304 movs r3, #4 + 800488a: 77fb strb r3, [r7, #31] + 800488c: e071 b.n 8004972 + 800488e: 2308 movs r3, #8 + 8004890: 77fb strb r3, [r7, #31] + 8004892: e06e b.n 8004972 + 8004894: 2310 movs r3, #16 + 8004896: 77fb strb r3, [r7, #31] + 8004898: bf00 nop + 800489a: e06a b.n 8004972 + 800489c: 687b ldr r3, [r7, #4] + 800489e: 681b ldr r3, [r3, #0] + 80048a0: 4a25 ldr r2, [pc, #148] ; (8004938 ) + 80048a2: 4293 cmp r3, r2 + 80048a4: d124 bne.n 80048f0 + 80048a6: 4b1e ldr r3, [pc, #120] ; (8004920 ) + 80048a8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80048ac: f403 5340 and.w r3, r3, #12288 ; 0x3000 + 80048b0: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 80048b4: d012 beq.n 80048dc + 80048b6: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 80048ba: d802 bhi.n 80048c2 + 80048bc: 2b00 cmp r3, #0 + 80048be: d007 beq.n 80048d0 + 80048c0: e012 b.n 80048e8 + 80048c2: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 80048c6: d006 beq.n 80048d6 + 80048c8: f5b3 5f40 cmp.w r3, #12288 ; 0x3000 + 80048cc: d009 beq.n 80048e2 + 80048ce: e00b b.n 80048e8 + 80048d0: 2300 movs r3, #0 + 80048d2: 77fb strb r3, [r7, #31] + 80048d4: e04d b.n 8004972 + 80048d6: 2302 movs r3, #2 + 80048d8: 77fb strb r3, [r7, #31] + 80048da: e04a b.n 8004972 + 80048dc: 2304 movs r3, #4 + 80048de: 77fb strb r3, [r7, #31] + 80048e0: e047 b.n 8004972 + 80048e2: 2308 movs r3, #8 + 80048e4: 77fb strb r3, [r7, #31] + 80048e6: e044 b.n 8004972 + 80048e8: 2310 movs r3, #16 + 80048ea: 77fb strb r3, [r7, #31] + 80048ec: bf00 nop + 80048ee: e040 b.n 8004972 + 80048f0: 687b ldr r3, [r7, #4] + 80048f2: 681b ldr r3, [r3, #0] + 80048f4: 4a11 ldr r2, [pc, #68] ; (800493c ) + 80048f6: 4293 cmp r3, r2 + 80048f8: d139 bne.n 800496e + 80048fa: 4b09 ldr r3, [pc, #36] ; (8004920 ) + 80048fc: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004900: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8004904: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 8004908: d027 beq.n 800495a + 800490a: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 800490e: d817 bhi.n 8004940 + 8004910: 2b00 cmp r3, #0 + 8004912: d01c beq.n 800494e + 8004914: e027 b.n 8004966 + 8004916: bf00 nop + 8004918: efff69f3 .word 0xefff69f3 + 800491c: 40011000 .word 0x40011000 + 8004920: 40023800 .word 0x40023800 + 8004924: 40004400 .word 0x40004400 + 8004928: 40004800 .word 0x40004800 + 800492c: 40004c00 .word 0x40004c00 + 8004930: 40005000 .word 0x40005000 + 8004934: 40011400 .word 0x40011400 + 8004938: 40007800 .word 0x40007800 + 800493c: 40007c00 .word 0x40007c00 + 8004940: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 8004944: d006 beq.n 8004954 + 8004946: f5b3 4f40 cmp.w r3, #49152 ; 0xc000 + 800494a: d009 beq.n 8004960 + 800494c: e00b b.n 8004966 + 800494e: 2300 movs r3, #0 + 8004950: 77fb strb r3, [r7, #31] + 8004952: e00e b.n 8004972 + 8004954: 2302 movs r3, #2 + 8004956: 77fb strb r3, [r7, #31] + 8004958: e00b b.n 8004972 + 800495a: 2304 movs r3, #4 + 800495c: 77fb strb r3, [r7, #31] + 800495e: e008 b.n 8004972 + 8004960: 2308 movs r3, #8 + 8004962: 77fb strb r3, [r7, #31] + 8004964: e005 b.n 8004972 + 8004966: 2310 movs r3, #16 + 8004968: 77fb strb r3, [r7, #31] + 800496a: bf00 nop + 800496c: e001 b.n 8004972 + 800496e: 2310 movs r3, #16 + 8004970: 77fb strb r3, [r7, #31] + + if (huart->Init.OverSampling == UART_OVERSAMPLING_8) + 8004972: 687b ldr r3, [r7, #4] + 8004974: 69db ldr r3, [r3, #28] + 8004976: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 800497a: d17c bne.n 8004a76 + { + switch (clocksource) + 800497c: 7ffb ldrb r3, [r7, #31] + 800497e: 2b08 cmp r3, #8 + 8004980: d859 bhi.n 8004a36 + 8004982: a201 add r2, pc, #4 ; (adr r2, 8004988 ) + 8004984: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004988: 080049ad .word 0x080049ad + 800498c: 080049cb .word 0x080049cb + 8004990: 080049e9 .word 0x080049e9 + 8004994: 08004a37 .word 0x08004a37 + 8004998: 08004a01 .word 0x08004a01 + 800499c: 08004a37 .word 0x08004a37 + 80049a0: 08004a37 .word 0x08004a37 + 80049a4: 08004a37 .word 0x08004a37 + 80049a8: 08004a1f .word 0x08004a1f + { + case UART_CLOCKSOURCE_PCLK1: + usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); + 80049ac: f7fd ff84 bl 80028b8 + 80049b0: 4603 mov r3, r0 + 80049b2: 005a lsls r2, r3, #1 + 80049b4: 687b ldr r3, [r7, #4] + 80049b6: 685b ldr r3, [r3, #4] + 80049b8: 085b lsrs r3, r3, #1 + 80049ba: 441a add r2, r3 + 80049bc: 687b ldr r3, [r7, #4] + 80049be: 685b ldr r3, [r3, #4] + 80049c0: fbb2 f3f3 udiv r3, r2, r3 + 80049c4: b29b uxth r3, r3 + 80049c6: 61bb str r3, [r7, #24] + break; + 80049c8: e038 b.n 8004a3c + case UART_CLOCKSOURCE_PCLK2: + usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); + 80049ca: f7fd ff89 bl 80028e0 + 80049ce: 4603 mov r3, r0 + 80049d0: 005a lsls r2, r3, #1 + 80049d2: 687b ldr r3, [r7, #4] + 80049d4: 685b ldr r3, [r3, #4] + 80049d6: 085b lsrs r3, r3, #1 + 80049d8: 441a add r2, r3 + 80049da: 687b ldr r3, [r7, #4] + 80049dc: 685b ldr r3, [r3, #4] + 80049de: fbb2 f3f3 udiv r3, r2, r3 + 80049e2: b29b uxth r3, r3 + 80049e4: 61bb str r3, [r7, #24] + break; + 80049e6: e029 b.n 8004a3c + case UART_CLOCKSOURCE_HSI: + usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HSI_VALUE, huart->Init.BaudRate)); + 80049e8: 687b ldr r3, [r7, #4] + 80049ea: 685b ldr r3, [r3, #4] + 80049ec: 085a lsrs r2, r3, #1 + 80049ee: 4b5d ldr r3, [pc, #372] ; (8004b64 ) + 80049f0: 4413 add r3, r2 + 80049f2: 687a ldr r2, [r7, #4] + 80049f4: 6852 ldr r2, [r2, #4] + 80049f6: fbb3 f3f2 udiv r3, r3, r2 + 80049fa: b29b uxth r3, r3 + 80049fc: 61bb str r3, [r7, #24] + break; + 80049fe: e01d b.n 8004a3c + case UART_CLOCKSOURCE_SYSCLK: + usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); + 8004a00: f7fd fe9c bl 800273c + 8004a04: 4603 mov r3, r0 + 8004a06: 005a lsls r2, r3, #1 + 8004a08: 687b ldr r3, [r7, #4] + 8004a0a: 685b ldr r3, [r3, #4] + 8004a0c: 085b lsrs r3, r3, #1 + 8004a0e: 441a add r2, r3 + 8004a10: 687b ldr r3, [r7, #4] + 8004a12: 685b ldr r3, [r3, #4] + 8004a14: fbb2 f3f3 udiv r3, r2, r3 + 8004a18: b29b uxth r3, r3 + 8004a1a: 61bb str r3, [r7, #24] + break; + 8004a1c: e00e b.n 8004a3c + case UART_CLOCKSOURCE_LSE: + usartdiv = (uint16_t)(UART_DIV_SAMPLING8(LSE_VALUE, huart->Init.BaudRate)); + 8004a1e: 687b ldr r3, [r7, #4] + 8004a20: 685b ldr r3, [r3, #4] + 8004a22: 085b lsrs r3, r3, #1 + 8004a24: f503 3280 add.w r2, r3, #65536 ; 0x10000 + 8004a28: 687b ldr r3, [r7, #4] + 8004a2a: 685b ldr r3, [r3, #4] + 8004a2c: fbb2 f3f3 udiv r3, r2, r3 + 8004a30: b29b uxth r3, r3 + 8004a32: 61bb str r3, [r7, #24] + break; + 8004a34: e002 b.n 8004a3c + case UART_CLOCKSOURCE_UNDEFINED: + default: + ret = HAL_ERROR; + 8004a36: 2301 movs r3, #1 + 8004a38: 75fb strb r3, [r7, #23] + break; + 8004a3a: bf00 nop + } + + /* USARTDIV must be greater than or equal to 0d16 */ + if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) + 8004a3c: 69bb ldr r3, [r7, #24] + 8004a3e: 2b0f cmp r3, #15 + 8004a40: d916 bls.n 8004a70 + 8004a42: 69bb ldr r3, [r7, #24] + 8004a44: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8004a48: d212 bcs.n 8004a70 + { + brrtemp = (uint16_t)(usartdiv & 0xFFF0U); + 8004a4a: 69bb ldr r3, [r7, #24] + 8004a4c: b29b uxth r3, r3 + 8004a4e: f023 030f bic.w r3, r3, #15 + 8004a52: 81fb strh r3, [r7, #14] + brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U); + 8004a54: 69bb ldr r3, [r7, #24] + 8004a56: 085b lsrs r3, r3, #1 + 8004a58: b29b uxth r3, r3 + 8004a5a: f003 0307 and.w r3, r3, #7 + 8004a5e: b29a uxth r2, r3 + 8004a60: 89fb ldrh r3, [r7, #14] + 8004a62: 4313 orrs r3, r2 + 8004a64: 81fb strh r3, [r7, #14] + huart->Instance->BRR = brrtemp; + 8004a66: 687b ldr r3, [r7, #4] + 8004a68: 681b ldr r3, [r3, #0] + 8004a6a: 89fa ldrh r2, [r7, #14] + 8004a6c: 60da str r2, [r3, #12] + 8004a6e: e06e b.n 8004b4e + } + else + { + ret = HAL_ERROR; + 8004a70: 2301 movs r3, #1 + 8004a72: 75fb strb r3, [r7, #23] + 8004a74: e06b b.n 8004b4e + } + } + else + { + switch (clocksource) + 8004a76: 7ffb ldrb r3, [r7, #31] + 8004a78: 2b08 cmp r3, #8 + 8004a7a: d857 bhi.n 8004b2c + 8004a7c: a201 add r2, pc, #4 ; (adr r2, 8004a84 ) + 8004a7e: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004a82: bf00 nop + 8004a84: 08004aa9 .word 0x08004aa9 + 8004a88: 08004ac5 .word 0x08004ac5 + 8004a8c: 08004ae1 .word 0x08004ae1 + 8004a90: 08004b2d .word 0x08004b2d + 8004a94: 08004af9 .word 0x08004af9 + 8004a98: 08004b2d .word 0x08004b2d + 8004a9c: 08004b2d .word 0x08004b2d + 8004aa0: 08004b2d .word 0x08004b2d + 8004aa4: 08004b15 .word 0x08004b15 + { + case UART_CLOCKSOURCE_PCLK1: + usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); + 8004aa8: f7fd ff06 bl 80028b8 + 8004aac: 4602 mov r2, r0 + 8004aae: 687b ldr r3, [r7, #4] + 8004ab0: 685b ldr r3, [r3, #4] + 8004ab2: 085b lsrs r3, r3, #1 + 8004ab4: 441a add r2, r3 + 8004ab6: 687b ldr r3, [r7, #4] + 8004ab8: 685b ldr r3, [r3, #4] + 8004aba: fbb2 f3f3 udiv r3, r2, r3 + 8004abe: b29b uxth r3, r3 + 8004ac0: 61bb str r3, [r7, #24] + break; + 8004ac2: e036 b.n 8004b32 + case UART_CLOCKSOURCE_PCLK2: + usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); + 8004ac4: f7fd ff0c bl 80028e0 + 8004ac8: 4602 mov r2, r0 + 8004aca: 687b ldr r3, [r7, #4] + 8004acc: 685b ldr r3, [r3, #4] + 8004ace: 085b lsrs r3, r3, #1 + 8004ad0: 441a add r2, r3 + 8004ad2: 687b ldr r3, [r7, #4] + 8004ad4: 685b ldr r3, [r3, #4] + 8004ad6: fbb2 f3f3 udiv r3, r2, r3 + 8004ada: b29b uxth r3, r3 + 8004adc: 61bb str r3, [r7, #24] + break; + 8004ade: e028 b.n 8004b32 + case UART_CLOCKSOURCE_HSI: + usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HSI_VALUE, huart->Init.BaudRate)); + 8004ae0: 687b ldr r3, [r7, #4] + 8004ae2: 685b ldr r3, [r3, #4] + 8004ae4: 085a lsrs r2, r3, #1 + 8004ae6: 4b20 ldr r3, [pc, #128] ; (8004b68 ) + 8004ae8: 4413 add r3, r2 + 8004aea: 687a ldr r2, [r7, #4] + 8004aec: 6852 ldr r2, [r2, #4] + 8004aee: fbb3 f3f2 udiv r3, r3, r2 + 8004af2: b29b uxth r3, r3 + 8004af4: 61bb str r3, [r7, #24] + break; + 8004af6: e01c b.n 8004b32 + case UART_CLOCKSOURCE_SYSCLK: + usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); + 8004af8: f7fd fe20 bl 800273c + 8004afc: 4602 mov r2, r0 + 8004afe: 687b ldr r3, [r7, #4] + 8004b00: 685b ldr r3, [r3, #4] + 8004b02: 085b lsrs r3, r3, #1 + 8004b04: 441a add r2, r3 + 8004b06: 687b ldr r3, [r7, #4] + 8004b08: 685b ldr r3, [r3, #4] + 8004b0a: fbb2 f3f3 udiv r3, r2, r3 + 8004b0e: b29b uxth r3, r3 + 8004b10: 61bb str r3, [r7, #24] + break; + 8004b12: e00e b.n 8004b32 + case UART_CLOCKSOURCE_LSE: + usartdiv = (uint16_t)(UART_DIV_SAMPLING16(LSE_VALUE, huart->Init.BaudRate)); + 8004b14: 687b ldr r3, [r7, #4] + 8004b16: 685b ldr r3, [r3, #4] + 8004b18: 085b lsrs r3, r3, #1 + 8004b1a: f503 4200 add.w r2, r3, #32768 ; 0x8000 + 8004b1e: 687b ldr r3, [r7, #4] + 8004b20: 685b ldr r3, [r3, #4] + 8004b22: fbb2 f3f3 udiv r3, r2, r3 + 8004b26: b29b uxth r3, r3 + 8004b28: 61bb str r3, [r7, #24] + break; + 8004b2a: e002 b.n 8004b32 + case UART_CLOCKSOURCE_UNDEFINED: + default: + ret = HAL_ERROR; + 8004b2c: 2301 movs r3, #1 + 8004b2e: 75fb strb r3, [r7, #23] + break; + 8004b30: bf00 nop + } + + /* USARTDIV must be greater than or equal to 0d16 */ + if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) + 8004b32: 69bb ldr r3, [r7, #24] + 8004b34: 2b0f cmp r3, #15 + 8004b36: d908 bls.n 8004b4a + 8004b38: 69bb ldr r3, [r7, #24] + 8004b3a: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8004b3e: d204 bcs.n 8004b4a + { + huart->Instance->BRR = usartdiv; + 8004b40: 687b ldr r3, [r7, #4] + 8004b42: 681b ldr r3, [r3, #0] + 8004b44: 69ba ldr r2, [r7, #24] + 8004b46: 60da str r2, [r3, #12] + 8004b48: e001 b.n 8004b4e + } + else + { + ret = HAL_ERROR; + 8004b4a: 2301 movs r3, #1 + 8004b4c: 75fb strb r3, [r7, #23] + } + } + + + /* Clear ISR function pointers */ + huart->RxISR = NULL; + 8004b4e: 687b ldr r3, [r7, #4] + 8004b50: 2200 movs r2, #0 + 8004b52: 661a str r2, [r3, #96] ; 0x60 + huart->TxISR = NULL; + 8004b54: 687b ldr r3, [r7, #4] + 8004b56: 2200 movs r2, #0 + 8004b58: 665a str r2, [r3, #100] ; 0x64 + + return ret; + 8004b5a: 7dfb ldrb r3, [r7, #23] +} + 8004b5c: 4618 mov r0, r3 + 8004b5e: 3720 adds r7, #32 + 8004b60: 46bd mov sp, r7 + 8004b62: bd80 pop {r7, pc} + 8004b64: 01e84800 .word 0x01e84800 + 8004b68: 00f42400 .word 0x00f42400 + +08004b6c : + * @brief Configure the UART peripheral advanced features. + * @param huart UART handle. + * @retval None + */ +void UART_AdvFeatureConfig(UART_HandleTypeDef *huart) +{ + 8004b6c: b480 push {r7} + 8004b6e: b083 sub sp, #12 + 8004b70: af00 add r7, sp, #0 + 8004b72: 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)) + 8004b74: 687b ldr r3, [r7, #4] + 8004b76: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004b78: f003 0301 and.w r3, r3, #1 + 8004b7c: 2b00 cmp r3, #0 + 8004b7e: d00a beq.n 8004b96 + { + assert_param(IS_UART_ADVFEATURE_TXINV(huart->AdvancedInit.TxPinLevelInvert)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_TXINV, huart->AdvancedInit.TxPinLevelInvert); + 8004b80: 687b ldr r3, [r7, #4] + 8004b82: 681b ldr r3, [r3, #0] + 8004b84: 685b ldr r3, [r3, #4] + 8004b86: f423 3100 bic.w r1, r3, #131072 ; 0x20000 + 8004b8a: 687b ldr r3, [r7, #4] + 8004b8c: 6a9a ldr r2, [r3, #40] ; 0x28 + 8004b8e: 687b ldr r3, [r7, #4] + 8004b90: 681b ldr r3, [r3, #0] + 8004b92: 430a orrs r2, r1 + 8004b94: 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)) + 8004b96: 687b ldr r3, [r7, #4] + 8004b98: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004b9a: f003 0302 and.w r3, r3, #2 + 8004b9e: 2b00 cmp r3, #0 + 8004ba0: d00a beq.n 8004bb8 + { + assert_param(IS_UART_ADVFEATURE_RXINV(huart->AdvancedInit.RxPinLevelInvert)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_RXINV, huart->AdvancedInit.RxPinLevelInvert); + 8004ba2: 687b ldr r3, [r7, #4] + 8004ba4: 681b ldr r3, [r3, #0] + 8004ba6: 685b ldr r3, [r3, #4] + 8004ba8: f423 3180 bic.w r1, r3, #65536 ; 0x10000 + 8004bac: 687b ldr r3, [r7, #4] + 8004bae: 6ada ldr r2, [r3, #44] ; 0x2c + 8004bb0: 687b ldr r3, [r7, #4] + 8004bb2: 681b ldr r3, [r3, #0] + 8004bb4: 430a orrs r2, r1 + 8004bb6: 605a str r2, [r3, #4] + } + + /* if required, configure data inversion */ + if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_DATAINVERT_INIT)) + 8004bb8: 687b ldr r3, [r7, #4] + 8004bba: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004bbc: f003 0304 and.w r3, r3, #4 + 8004bc0: 2b00 cmp r3, #0 + 8004bc2: d00a beq.n 8004bda + { + assert_param(IS_UART_ADVFEATURE_DATAINV(huart->AdvancedInit.DataInvert)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_DATAINV, huart->AdvancedInit.DataInvert); + 8004bc4: 687b ldr r3, [r7, #4] + 8004bc6: 681b ldr r3, [r3, #0] + 8004bc8: 685b ldr r3, [r3, #4] + 8004bca: f423 2180 bic.w r1, r3, #262144 ; 0x40000 + 8004bce: 687b ldr r3, [r7, #4] + 8004bd0: 6b1a ldr r2, [r3, #48] ; 0x30 + 8004bd2: 687b ldr r3, [r7, #4] + 8004bd4: 681b ldr r3, [r3, #0] + 8004bd6: 430a orrs r2, r1 + 8004bd8: 605a str r2, [r3, #4] + } + + /* if required, configure RX/TX pins swap */ + if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_SWAP_INIT)) + 8004bda: 687b ldr r3, [r7, #4] + 8004bdc: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004bde: f003 0308 and.w r3, r3, #8 + 8004be2: 2b00 cmp r3, #0 + 8004be4: d00a beq.n 8004bfc + { + assert_param(IS_UART_ADVFEATURE_SWAP(huart->AdvancedInit.Swap)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_SWAP, huart->AdvancedInit.Swap); + 8004be6: 687b ldr r3, [r7, #4] + 8004be8: 681b ldr r3, [r3, #0] + 8004bea: 685b ldr r3, [r3, #4] + 8004bec: f423 4100 bic.w r1, r3, #32768 ; 0x8000 + 8004bf0: 687b ldr r3, [r7, #4] + 8004bf2: 6b5a ldr r2, [r3, #52] ; 0x34 + 8004bf4: 687b ldr r3, [r7, #4] + 8004bf6: 681b ldr r3, [r3, #0] + 8004bf8: 430a orrs r2, r1 + 8004bfa: 605a str r2, [r3, #4] + } + + /* if required, configure RX overrun detection disabling */ + if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXOVERRUNDISABLE_INIT)) + 8004bfc: 687b ldr r3, [r7, #4] + 8004bfe: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004c00: f003 0310 and.w r3, r3, #16 + 8004c04: 2b00 cmp r3, #0 + 8004c06: d00a beq.n 8004c1e + { + assert_param(IS_UART_OVERRUN(huart->AdvancedInit.OverrunDisable)); + MODIFY_REG(huart->Instance->CR3, USART_CR3_OVRDIS, huart->AdvancedInit.OverrunDisable); + 8004c08: 687b ldr r3, [r7, #4] + 8004c0a: 681b ldr r3, [r3, #0] + 8004c0c: 689b ldr r3, [r3, #8] + 8004c0e: f423 5180 bic.w r1, r3, #4096 ; 0x1000 + 8004c12: 687b ldr r3, [r7, #4] + 8004c14: 6b9a ldr r2, [r3, #56] ; 0x38 + 8004c16: 687b ldr r3, [r7, #4] + 8004c18: 681b ldr r3, [r3, #0] + 8004c1a: 430a orrs r2, r1 + 8004c1c: 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)) + 8004c1e: 687b ldr r3, [r7, #4] + 8004c20: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004c22: f003 0320 and.w r3, r3, #32 + 8004c26: 2b00 cmp r3, #0 + 8004c28: d00a beq.n 8004c40 + { + assert_param(IS_UART_ADVFEATURE_DMAONRXERROR(huart->AdvancedInit.DMADisableonRxError)); + MODIFY_REG(huart->Instance->CR3, USART_CR3_DDRE, huart->AdvancedInit.DMADisableonRxError); + 8004c2a: 687b ldr r3, [r7, #4] + 8004c2c: 681b ldr r3, [r3, #0] + 8004c2e: 689b ldr r3, [r3, #8] + 8004c30: f423 5100 bic.w r1, r3, #8192 ; 0x2000 + 8004c34: 687b ldr r3, [r7, #4] + 8004c36: 6bda ldr r2, [r3, #60] ; 0x3c + 8004c38: 687b ldr r3, [r7, #4] + 8004c3a: 681b ldr r3, [r3, #0] + 8004c3c: 430a orrs r2, r1 + 8004c3e: 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)) + 8004c40: 687b ldr r3, [r7, #4] + 8004c42: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004c44: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004c48: 2b00 cmp r3, #0 + 8004c4a: d01a beq.n 8004c82 + { + 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); + 8004c4c: 687b ldr r3, [r7, #4] + 8004c4e: 681b ldr r3, [r3, #0] + 8004c50: 685b ldr r3, [r3, #4] + 8004c52: f423 1180 bic.w r1, r3, #1048576 ; 0x100000 + 8004c56: 687b ldr r3, [r7, #4] + 8004c58: 6c1a ldr r2, [r3, #64] ; 0x40 + 8004c5a: 687b ldr r3, [r7, #4] + 8004c5c: 681b ldr r3, [r3, #0] + 8004c5e: 430a orrs r2, r1 + 8004c60: 605a str r2, [r3, #4] + /* set auto Baudrate detection parameters if detection is enabled */ + if (huart->AdvancedInit.AutoBaudRateEnable == UART_ADVFEATURE_AUTOBAUDRATE_ENABLE) + 8004c62: 687b ldr r3, [r7, #4] + 8004c64: 6c1b ldr r3, [r3, #64] ; 0x40 + 8004c66: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8004c6a: d10a bne.n 8004c82 + { + assert_param(IS_UART_ADVFEATURE_AUTOBAUDRATEMODE(huart->AdvancedInit.AutoBaudRateMode)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_ABRMODE, huart->AdvancedInit.AutoBaudRateMode); + 8004c6c: 687b ldr r3, [r7, #4] + 8004c6e: 681b ldr r3, [r3, #0] + 8004c70: 685b ldr r3, [r3, #4] + 8004c72: f423 01c0 bic.w r1, r3, #6291456 ; 0x600000 + 8004c76: 687b ldr r3, [r7, #4] + 8004c78: 6c5a ldr r2, [r3, #68] ; 0x44 + 8004c7a: 687b ldr r3, [r7, #4] + 8004c7c: 681b ldr r3, [r3, #0] + 8004c7e: 430a orrs r2, r1 + 8004c80: 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)) + 8004c82: 687b ldr r3, [r7, #4] + 8004c84: 6a5b ldr r3, [r3, #36] ; 0x24 + 8004c86: f003 0380 and.w r3, r3, #128 ; 0x80 + 8004c8a: 2b00 cmp r3, #0 + 8004c8c: d00a beq.n 8004ca4 + { + assert_param(IS_UART_ADVFEATURE_MSBFIRST(huart->AdvancedInit.MSBFirst)); + MODIFY_REG(huart->Instance->CR2, USART_CR2_MSBFIRST, huart->AdvancedInit.MSBFirst); + 8004c8e: 687b ldr r3, [r7, #4] + 8004c90: 681b ldr r3, [r3, #0] + 8004c92: 685b ldr r3, [r3, #4] + 8004c94: f423 2100 bic.w r1, r3, #524288 ; 0x80000 + 8004c98: 687b ldr r3, [r7, #4] + 8004c9a: 6c9a ldr r2, [r3, #72] ; 0x48 + 8004c9c: 687b ldr r3, [r7, #4] + 8004c9e: 681b ldr r3, [r3, #0] + 8004ca0: 430a orrs r2, r1 + 8004ca2: 605a str r2, [r3, #4] + } +} + 8004ca4: bf00 nop + 8004ca6: 370c adds r7, #12 + 8004ca8: 46bd mov sp, r7 + 8004caa: f85d 7b04 ldr.w r7, [sp], #4 + 8004cae: 4770 bx lr + +08004cb0 : + * @brief Check the UART Idle State. + * @param huart UART handle. + * @retval HAL status + */ +HAL_StatusTypeDef UART_CheckIdleState(UART_HandleTypeDef *huart) +{ + 8004cb0: b580 push {r7, lr} + 8004cb2: b086 sub sp, #24 + 8004cb4: af02 add r7, sp, #8 + 8004cb6: 6078 str r0, [r7, #4] + uint32_t tickstart; + + /* Initialize the UART ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + 8004cb8: 687b ldr r3, [r7, #4] + 8004cba: 2200 movs r2, #0 + 8004cbc: 67da str r2, [r3, #124] ; 0x7c + + /* Init tickstart for timeout managment*/ + tickstart = HAL_GetTick(); + 8004cbe: f7fc fbf7 bl 80014b0 + 8004cc2: 60f8 str r0, [r7, #12] + + /* Check if the Transmitter is enabled */ + if ((huart->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE) + 8004cc4: 687b ldr r3, [r7, #4] + 8004cc6: 681b ldr r3, [r3, #0] + 8004cc8: 681b ldr r3, [r3, #0] + 8004cca: f003 0308 and.w r3, r3, #8 + 8004cce: 2b08 cmp r3, #8 + 8004cd0: d10e bne.n 8004cf0 + { + /* Wait until TEACK flag is set */ + if (UART_WaitOnFlagUntilTimeout(huart, USART_ISR_TEACK, RESET, tickstart, HAL_UART_TIMEOUT_VALUE) != HAL_OK) + 8004cd2: f06f 437e mvn.w r3, #4261412864 ; 0xfe000000 + 8004cd6: 9300 str r3, [sp, #0] + 8004cd8: 68fb ldr r3, [r7, #12] + 8004cda: 2200 movs r2, #0 + 8004cdc: f44f 1100 mov.w r1, #2097152 ; 0x200000 + 8004ce0: 6878 ldr r0, [r7, #4] + 8004ce2: f000 f814 bl 8004d0e + 8004ce6: 4603 mov r3, r0 + 8004ce8: 2b00 cmp r3, #0 + 8004cea: d001 beq.n 8004cf0 + { + /* Timeout occurred */ + return HAL_TIMEOUT; + 8004cec: 2303 movs r3, #3 + 8004cee: e00a b.n 8004d06 + } + } + + /* Initialize the UART State */ + huart->gState = HAL_UART_STATE_READY; + 8004cf0: 687b ldr r3, [r7, #4] + 8004cf2: 2220 movs r2, #32 + 8004cf4: 675a str r2, [r3, #116] ; 0x74 + huart->RxState = HAL_UART_STATE_READY; + 8004cf6: 687b ldr r3, [r7, #4] + 8004cf8: 2220 movs r2, #32 + 8004cfa: 679a str r2, [r3, #120] ; 0x78 + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + 8004cfc: 687b ldr r3, [r7, #4] + 8004cfe: 2200 movs r2, #0 + 8004d00: f883 2070 strb.w r2, [r3, #112] ; 0x70 + + return HAL_OK; + 8004d04: 2300 movs r3, #0 +} + 8004d06: 4618 mov r0, r3 + 8004d08: 3710 adds r7, #16 + 8004d0a: 46bd mov sp, r7 + 8004d0c: bd80 pop {r7, pc} + +08004d0e : + * @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) +{ + 8004d0e: b580 push {r7, lr} + 8004d10: b084 sub sp, #16 + 8004d12: af00 add r7, sp, #0 + 8004d14: 60f8 str r0, [r7, #12] + 8004d16: 60b9 str r1, [r7, #8] + 8004d18: 603b str r3, [r7, #0] + 8004d1a: 4613 mov r3, r2 + 8004d1c: 71fb strb r3, [r7, #7] + /* Wait until flag is set */ + while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) + 8004d1e: e02a b.n 8004d76 + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + 8004d20: 69bb ldr r3, [r7, #24] + 8004d22: f1b3 3fff cmp.w r3, #4294967295 ; 0xffffffff + 8004d26: d026 beq.n 8004d76 + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + 8004d28: f7fc fbc2 bl 80014b0 + 8004d2c: 4602 mov r2, r0 + 8004d2e: 683b ldr r3, [r7, #0] + 8004d30: 1ad3 subs r3, r2, r3 + 8004d32: 69ba ldr r2, [r7, #24] + 8004d34: 429a cmp r2, r3 + 8004d36: d302 bcc.n 8004d3e + 8004d38: 69bb ldr r3, [r7, #24] + 8004d3a: 2b00 cmp r3, #0 + 8004d3c: d11b bne.n 8004d76 + { + /* 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)); + 8004d3e: 68fb ldr r3, [r7, #12] + 8004d40: 681b ldr r3, [r3, #0] + 8004d42: 681a ldr r2, [r3, #0] + 8004d44: 68fb ldr r3, [r7, #12] + 8004d46: 681b ldr r3, [r3, #0] + 8004d48: f422 72d0 bic.w r2, r2, #416 ; 0x1a0 + 8004d4c: 601a str r2, [r3, #0] + CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + 8004d4e: 68fb ldr r3, [r7, #12] + 8004d50: 681b ldr r3, [r3, #0] + 8004d52: 689a ldr r2, [r3, #8] + 8004d54: 68fb ldr r3, [r7, #12] + 8004d56: 681b ldr r3, [r3, #0] + 8004d58: f022 0201 bic.w r2, r2, #1 + 8004d5c: 609a str r2, [r3, #8] + + huart->gState = HAL_UART_STATE_READY; + 8004d5e: 68fb ldr r3, [r7, #12] + 8004d60: 2220 movs r2, #32 + 8004d62: 675a str r2, [r3, #116] ; 0x74 + huart->RxState = HAL_UART_STATE_READY; + 8004d64: 68fb ldr r3, [r7, #12] + 8004d66: 2220 movs r2, #32 + 8004d68: 679a str r2, [r3, #120] ; 0x78 + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + 8004d6a: 68fb ldr r3, [r7, #12] + 8004d6c: 2200 movs r2, #0 + 8004d6e: f883 2070 strb.w r2, [r3, #112] ; 0x70 + + return HAL_TIMEOUT; + 8004d72: 2303 movs r3, #3 + 8004d74: e00f b.n 8004d96 + while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) + 8004d76: 68fb ldr r3, [r7, #12] + 8004d78: 681b ldr r3, [r3, #0] + 8004d7a: 69da ldr r2, [r3, #28] + 8004d7c: 68bb ldr r3, [r7, #8] + 8004d7e: 4013 ands r3, r2 + 8004d80: 68ba ldr r2, [r7, #8] + 8004d82: 429a cmp r2, r3 + 8004d84: bf0c ite eq + 8004d86: 2301 moveq r3, #1 + 8004d88: 2300 movne r3, #0 + 8004d8a: b2db uxtb r3, r3 + 8004d8c: 461a mov r2, r3 + 8004d8e: 79fb ldrb r3, [r7, #7] + 8004d90: 429a cmp r2, r3 + 8004d92: d0c5 beq.n 8004d20 + } + } + } + return HAL_OK; + 8004d94: 2300 movs r3, #0 +} + 8004d96: 4618 mov r0, r3 + 8004d98: 3710 adds r7, #16 + 8004d9a: 46bd mov sp, r7 + 8004d9c: bd80 pop {r7, pc} + +08004d9e : + * @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) +{ + 8004d9e: b480 push {r7} + 8004da0: b083 sub sp, #12 + 8004da2: af00 add r7, sp, #0 + 8004da4: 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)); + 8004da6: 687b ldr r3, [r7, #4] + 8004da8: 681b ldr r3, [r3, #0] + 8004daa: 681a ldr r2, [r3, #0] + 8004dac: 687b ldr r3, [r7, #4] + 8004dae: 681b ldr r3, [r3, #0] + 8004db0: f422 7290 bic.w r2, r2, #288 ; 0x120 + 8004db4: 601a str r2, [r3, #0] + CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + 8004db6: 687b ldr r3, [r7, #4] + 8004db8: 681b ldr r3, [r3, #0] + 8004dba: 689a ldr r2, [r3, #8] + 8004dbc: 687b ldr r3, [r7, #4] + 8004dbe: 681b ldr r3, [r3, #0] + 8004dc0: f022 0201 bic.w r2, r2, #1 + 8004dc4: 609a str r2, [r3, #8] + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + 8004dc6: 687b ldr r3, [r7, #4] + 8004dc8: 2220 movs r2, #32 + 8004dca: 679a str r2, [r3, #120] ; 0x78 + + /* Reset RxIsr function pointer */ + huart->RxISR = NULL; + 8004dcc: 687b ldr r3, [r7, #4] + 8004dce: 2200 movs r2, #0 + 8004dd0: 661a str r2, [r3, #96] ; 0x60 +} + 8004dd2: bf00 nop + 8004dd4: 370c adds r7, #12 + 8004dd6: 46bd mov sp, r7 + 8004dd8: f85d 7b04 ldr.w r7, [sp], #4 + 8004ddc: 4770 bx lr + +08004dde : + * (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) +{ + 8004dde: b580 push {r7, lr} + 8004de0: b084 sub sp, #16 + 8004de2: af00 add r7, sp, #0 + 8004de4: 6078 str r0, [r7, #4] + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)(hdma->Parent); + 8004de6: 687b ldr r3, [r7, #4] + 8004de8: 6b9b ldr r3, [r3, #56] ; 0x38 + 8004dea: 60fb str r3, [r7, #12] + huart->RxXferCount = 0U; + 8004dec: 68fb ldr r3, [r7, #12] + 8004dee: 2200 movs r2, #0 + 8004df0: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + huart->TxXferCount = 0U; + 8004df4: 68fb ldr r3, [r7, #12] + 8004df6: 2200 movs r2, #0 + 8004df8: 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); + 8004dfc: 68f8 ldr r0, [r7, #12] + 8004dfe: f7ff fc07 bl 8004610 +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + 8004e02: bf00 nop + 8004e04: 3710 adds r7, #16 + 8004e06: 46bd mov sp, r7 + 8004e08: bd80 pop {r7, pc} + +08004e0a : + * @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) +{ + 8004e0a: b580 push {r7, lr} + 8004e0c: b082 sub sp, #8 + 8004e0e: af00 add r7, sp, #0 + 8004e10: 6078 str r0, [r7, #4] + /* Disable the UART Transmit Complete Interrupt */ + CLEAR_BIT(huart->Instance->CR1, USART_CR1_TCIE); + 8004e12: 687b ldr r3, [r7, #4] + 8004e14: 681b ldr r3, [r3, #0] + 8004e16: 681a ldr r2, [r3, #0] + 8004e18: 687b ldr r3, [r7, #4] + 8004e1a: 681b ldr r3, [r3, #0] + 8004e1c: f022 0240 bic.w r2, r2, #64 ; 0x40 + 8004e20: 601a str r2, [r3, #0] + + /* Tx process is ended, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + 8004e22: 687b ldr r3, [r7, #4] + 8004e24: 2220 movs r2, #32 + 8004e26: 675a str r2, [r3, #116] ; 0x74 + + /* Cleat TxISR function pointer */ + huart->TxISR = NULL; + 8004e28: 687b ldr r3, [r7, #4] + 8004e2a: 2200 movs r2, #0 + 8004e2c: 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); + 8004e2e: 6878 ldr r0, [r7, #4] + 8004e30: f7ff fbe4 bl 80045fc +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + 8004e34: bf00 nop + 8004e36: 3708 adds r7, #8 + 8004e38: 46bd mov sp, r7 + 8004e3a: bd80 pop {r7, pc} + +08004e3c <__libc_init_array>: + 8004e3c: b570 push {r4, r5, r6, lr} + 8004e3e: 4e0d ldr r6, [pc, #52] ; (8004e74 <__libc_init_array+0x38>) + 8004e40: 4c0d ldr r4, [pc, #52] ; (8004e78 <__libc_init_array+0x3c>) + 8004e42: 1ba4 subs r4, r4, r6 + 8004e44: 10a4 asrs r4, r4, #2 + 8004e46: 2500 movs r5, #0 + 8004e48: 42a5 cmp r5, r4 + 8004e4a: d109 bne.n 8004e60 <__libc_init_array+0x24> + 8004e4c: 4e0b ldr r6, [pc, #44] ; (8004e7c <__libc_init_array+0x40>) + 8004e4e: 4c0c ldr r4, [pc, #48] ; (8004e80 <__libc_init_array+0x44>) + 8004e50: f000 f820 bl 8004e94 <_init> + 8004e54: 1ba4 subs r4, r4, r6 + 8004e56: 10a4 asrs r4, r4, #2 + 8004e58: 2500 movs r5, #0 + 8004e5a: 42a5 cmp r5, r4 + 8004e5c: d105 bne.n 8004e6a <__libc_init_array+0x2e> + 8004e5e: bd70 pop {r4, r5, r6, pc} + 8004e60: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 8004e64: 4798 blx r3 + 8004e66: 3501 adds r5, #1 + 8004e68: e7ee b.n 8004e48 <__libc_init_array+0xc> + 8004e6a: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 8004e6e: 4798 blx r3 + 8004e70: 3501 adds r5, #1 + 8004e72: e7f2 b.n 8004e5a <__libc_init_array+0x1e> + 8004e74: 08004ed4 .word 0x08004ed4 + 8004e78: 08004ed4 .word 0x08004ed4 + 8004e7c: 08004ed4 .word 0x08004ed4 + 8004e80: 08004edc .word 0x08004edc + +08004e84 : + 8004e84: 4402 add r2, r0 + 8004e86: 4603 mov r3, r0 + 8004e88: 4293 cmp r3, r2 + 8004e8a: d100 bne.n 8004e8e + 8004e8c: 4770 bx lr + 8004e8e: f803 1b01 strb.w r1, [r3], #1 + 8004e92: e7f9 b.n 8004e88 + +08004e94 <_init>: + 8004e94: b5f8 push {r3, r4, r5, r6, r7, lr} + 8004e96: bf00 nop + 8004e98: bcf8 pop {r3, r4, r5, r6, r7} + 8004e9a: bc08 pop {r3} + 8004e9c: 469e mov lr, r3 + 8004e9e: 4770 bx lr + +08004ea0 <_fini>: + 8004ea0: b5f8 push {r3, r4, r5, r6, r7, lr} + 8004ea2: bf00 nop + 8004ea4: bcf8 pop {r3, r4, r5, r6, r7} + 8004ea6: bc08 pop {r3} + 8004ea8: 469e mov lr, r3 + 8004eaa: 4770 bx lr diff --git a/otto_controller_source/Debug/sources.mk b/otto_controller_source/Debug/sources.mk new file mode 100644 index 0000000..ab6831f --- /dev/null +++ b/otto_controller_source/Debug/sources.mk @@ -0,0 +1,32 @@ +################################################################################ +# Automatically-generated file. Do not edit! +################################################################################ + +ELF_SRCS := +C_UPPER_SRCS := +CXX_SRCS := +C++_SRCS := +OBJ_SRCS := +S_SRCS := +CC_SRCS := +C_SRCS := +CPP_SRCS := +S_UPPER_SRCS := +O_SRCS := +CC_DEPS := +SIZE_OUTPUT := +OBJDUMP_LIST := +C++_DEPS := +EXECUTABLES := +OBJS := +C_UPPER_DEPS := +CXX_DEPS := +C_DEPS := +CPP_DEPS := + +# Every subdirectory with source files must be described here +SUBDIRS := \ +Core/Src \ +Core/Startup \ +Drivers/STM32F7xx_HAL_Driver/Src \ + -- 2.52.0