From: Federica Di Lauro Date: Thu, 23 Jan 2020 08:14:56 +0000 (+0100) Subject: fix motor_controller X-Git-Url: http://git.leonardobizzoni.com/?a=commitdiff_plain;h=39dab49a23b4b5ef6380e4690ddfa3b9267078ed;p=pioneer-stm32 fix motor_controller --- diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/communication_utils.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/communication_utils.h index 0733705..9694b3b 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/communication_utils.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/communication_utils.h @@ -12,7 +12,9 @@ typedef struct __attribute__((packed)) { typedef struct __attribute__((packed)) { float pid_select; - float pid_setpoint; + float pid_setpoint_fixed; + float pid_setpoint_lin; + float pid_setpoint_ang; float pid_kp; float pid_ki; float pid_kd; diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/constants.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/constants.h index 4d921bd..8f34181 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/constants.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/constants.h @@ -4,8 +4,7 @@ #define BASELINE 0.3 //distance between wheels in meters #define MAX_DUTY_CYCLE 790 #define TICKS_PER_REVOLUTION 74000 //x2 resolution -#define WHEEL_CIRCUMFERENCE 0.7539 //in meters - - +#define RIGHT_WHEEL_CIRCUMFERENCE 0.8 //in meters +#define LEFT_WHEEL_CIRCUMFERENCE 0.78 //in meters #endif diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/encoder.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/encoder.h index 7b079bd..5792c92 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/encoder.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/encoder.h @@ -10,12 +10,14 @@ class Encoder { uint32_t previous_millis_; uint32_t current_millis_; int32_t ticks_; //if negative the wheel is going backwards + float wheel_circumference_; Encoder() { timer_ = NULL; + wheel_circumference_ = 0; } - Encoder(TIM_HandleTypeDef *timer); + Encoder(TIM_HandleTypeDef *timer, float wheel_circ); void Setup(); diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/motor_controller.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/motor_controller.h index 43ef1c8..c4b5e8d 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/motor_controller.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/motor_controller.h @@ -51,9 +51,12 @@ class MotorController { __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); } + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); + } void brake() { + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); } diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/odometry.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/odometry.h index 6ede504..2d13eeb 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/odometry.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/odometry.h @@ -1,40 +1,31 @@ -#ifndef ODOMETRY_CALC_H -#define ODOMETRY_CALC_H +#ifndef ODOMETRY_H +#define ODOMETRY_H -#include "main.h" -#include "encoder.h" +#include "constants.h" class Odometry { - public: - Encoder left_encoder_; - Encoder right_encoder_; + private: + + float left_velocity_; + float right_velocity_; - float linear_velocity; - float angular_velocity; - int delta_time; + public: Odometry() { - left_encoder_ = NULL; - right_encoder_ = NULL; + left_velocity_ = 0; + right_velocity_ = 0; } - Odometry(Encoder left, Encoder right) { - - left_encoder_ = left; - right_encoder_ = right; + void UpdateValues(float linear_vel, float angular_vel) { + left_velocity_ = linear_vel - (BASELINE * angular_vel)/2; + right_velocity_ = 2 * linear_vel - left_velocity_; } - 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; + float GetLeftVelocity(){ + return left_velocity_; + } + float GetRightVelocity(){ + return right_velocity_; } }; diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Inc/pid.h b/utils/pid_tuning/otto_pid_tuning/Core/Inc/pid.h index 66d2b1e..7663f6b 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Inc/pid.h +++ b/utils/pid_tuning/otto_pid_tuning/Core/Inc/pid.h @@ -14,7 +14,7 @@ class Pid { float setpoint_; //needed for integrative term - int error_sum_; + float error_sum_; //needed for derivative term float previous_error_; @@ -72,10 +72,10 @@ class Pid { int integer_output = static_cast (output); - if(integer_output > this->max_) - integer_output = this->max_; - else if (integer_output < this->min_) - integer_output = this->min_; +// if(integer_output > this->max_) +// integer_output = this->max_; +// else if (integer_output < this->min_) +// integer_output = this->min_; return integer_output; diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Src/encoder.cpp b/utils/pid_tuning/otto_pid_tuning/Core/Src/encoder.cpp index 71e438a..b826703 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Src/encoder.cpp +++ b/utils/pid_tuning/otto_pid_tuning/Core/Src/encoder.cpp @@ -1,7 +1,8 @@ #include "encoder.h" -Encoder::Encoder(TIM_HandleTypeDef *timer) { +Encoder::Encoder(TIM_HandleTypeDef *timer, float wheel_circ) { timer_ = timer; + wheel_circumference_ = wheel_circ; } void Encoder::Setup() { @@ -20,14 +21,14 @@ void Encoder::UpdateValues() { float Encoder::GetMeters() { this->UpdateValues(); - float meters = ((float) this->ticks_ * WHEEL_CIRCUMFERENCE) + float meters = ((float) this->ticks_ * this->wheel_circumference_) / TICKS_PER_REVOLUTION; return meters; } float Encoder::GetLinearVelocity() { this->UpdateValues(); - float meters = ((float) this->ticks_ * WHEEL_CIRCUMFERENCE) + float meters = ((float) this->ticks_ * this->wheel_circumference_) / TICKS_PER_REVOLUTION; float deltaTime = this->current_millis_ - this->previous_millis_; if (deltaTime == 0) diff --git a/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp b/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp index 0ef6272..ebad4e5 100644 --- a/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp +++ b/utils/pid_tuning/otto_pid_tuning/Core/Src/main.cpp @@ -29,6 +29,7 @@ #include "motor_controller.h" #include "pid.h" #include "communication_utils.h" +#include "constants.h" /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ @@ -58,21 +59,19 @@ UART_HandleTypeDef huart6; /* USER CODE BEGIN PV */ //Odometry -Encoder right_encoder = Encoder(&htim5); -Encoder left_encoder = Encoder(&htim2); -Odometry odom = Odometry(left_encoder, right_encoder); - -float left_velocity; -float right_velocity; - -float baseline = 0.3; +Encoder right_encoder = Encoder(&htim5, RIGHT_WHEEL_CIRCUMFERENCE); +Encoder left_encoder = Encoder(&htim2, LEFT_WHEEL_CIRCUMFERENCE); +Odometry odom = Odometry(); +float left_velocity = 0; +float right_velocity = 0; //PID - Pid left_pid(0, 0, 0); Pid right_pid(0, 0, 0); Pid cross_pid(0, 0, 0); - +float left_setpoint; +float right_setpoint; +float cross_setpoint; int left_dutycycle; int right_dutycycle; @@ -93,7 +92,6 @@ sleep2_Pin, //Communication uint8_t *tx_buffer; uint8_t *rx_buffer; - pid_setup_msg input_msg; plot_msg output_msg; @@ -127,14 +125,12 @@ static void MX_NVIC_Init(void); /* USER CODE END 0 */ /** - * @brief The application entry point. - * @retval int - */ -int main(void) -{ + * @brief The application entry point. + * @retval int + */ +int main(void) { /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ - /* MCU Configuration--------------------------------------------------------*/ @@ -171,11 +167,14 @@ int main(void) left_motor.setup(); right_motor.setup(); + left_motor.coast(); + right_motor.coast(); + tx_buffer = (uint8_t*) &output_msg; rx_buffer = (uint8_t*) &input_msg; //Enables UART RX interrupt - HAL_UART_Receive_IT(&huart6, rx_buffer, 20); + HAL_UART_Receive_IT(&huart6, rx_buffer, 28); /* USER CODE END 2 */ @@ -190,56 +189,51 @@ int main(void) } /** - * @brief System Clock Configuration - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_OscInitTypeDef RCC_OscInitStruct = {0}; - RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) { + RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; + RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; /** Configure the main internal regulator output voltage - */ + */ __HAL_RCC_PWR_CLK_ENABLE(); __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); /** Initializes the CPU, AHB and APB busses clocks - */ + */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) - { + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { Error_Handler(); } /** Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK - |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) - { + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { Error_Handler(); } PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - { + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { Error_Handler(); } } /** - * @brief NVIC Configuration. - * @retval None - */ -static void MX_NVIC_Init(void) -{ + * @brief NVIC Configuration. + * @retval None + */ +static void MX_NVIC_Init(void) { /* TIM3_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM3_IRQn, 2, 1); HAL_NVIC_EnableIRQ(TIM3_IRQn); @@ -252,19 +246,18 @@ static void MX_NVIC_Init(void) } /** - * @brief TIM2 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM2_Init(void) -{ + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) { /* USER CODE BEGIN TIM2_Init 0 */ /* USER CODE END TIM2_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = {0}; - TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_Encoder_InitTypeDef sConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; /* USER CODE BEGIN TIM2_Init 1 */ @@ -284,14 +277,12 @@ static void MX_TIM2_Init(void) sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) - { + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) - { + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN TIM2_Init 2 */ @@ -301,19 +292,18 @@ static void MX_TIM2_Init(void) } /** - * @brief TIM3 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM3_Init(void) -{ + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) { /* USER CODE BEGIN TIM3_Init 0 */ /* USER CODE END TIM3_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = {0}; - TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; /* USER CODE BEGIN TIM3_Init 1 */ @@ -324,19 +314,16 @@ static void MX_TIM3_Init(void) htim3.Init.Period = 159; htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim3) != HAL_OK) - { + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) - { + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) - { + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN TIM3_Init 2 */ @@ -346,20 +333,19 @@ static void MX_TIM3_Init(void) } /** - * @brief TIM4 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM4_Init(void) -{ + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) { /* USER CODE BEGIN TIM4_Init 0 */ /* USER CODE END TIM4_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = {0}; - TIM_MasterConfigTypeDef sMasterConfig = {0}; - TIM_OC_InitTypeDef sConfigOC = {0}; + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + TIM_OC_InitTypeDef sConfigOC = { 0 }; /* USER CODE BEGIN TIM4_Init 1 */ @@ -370,35 +356,29 @@ static void MX_TIM4_Init(void) htim4.Init.Period = 799; htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim4) != HAL_OK) - { + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { Error_Handler(); } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) - { + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { Error_Handler(); } - if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) - { + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) - { + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) { Error_Handler(); } sConfigOC.OCMode = TIM_OCMODE_PWM1; sConfigOC.Pulse = 0; sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) - { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) { Error_Handler(); } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) - { + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN TIM4_Init 2 */ @@ -409,19 +389,18 @@ static void MX_TIM4_Init(void) } /** - * @brief TIM5 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM5_Init(void) -{ + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) { /* USER CODE BEGIN TIM5_Init 0 */ /* USER CODE END TIM5_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = {0}; - TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_Encoder_InitTypeDef sConfig = { 0 }; + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; /* USER CODE BEGIN TIM5_Init 1 */ @@ -441,14 +420,12 @@ static void MX_TIM5_Init(void) sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; sConfig.IC2Prescaler = TIM_ICPSC_DIV1; sConfig.IC2Filter = 0; - if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) - { + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) - { + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN TIM5_Init 2 */ @@ -458,18 +435,17 @@ static void MX_TIM5_Init(void) } /** - * @brief TIM6 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM6_Init(void) -{ + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) { /* USER CODE BEGIN TIM6_Init 0 */ /* USER CODE END TIM6_Init 0 */ - TIM_MasterConfigTypeDef sMasterConfig = {0}; + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; /* USER CODE BEGIN TIM6_Init 1 */ @@ -479,14 +455,12 @@ static void MX_TIM6_Init(void) htim6.Init.CounterMode = TIM_COUNTERMODE_UP; htim6.Init.Period = 799; htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - if (HAL_TIM_Base_Init(&htim6) != HAL_OK) - { + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { Error_Handler(); } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) - { + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN TIM6_Init 2 */ @@ -496,12 +470,11 @@ static void MX_TIM6_Init(void) } /** - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) -{ + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) { /* USER CODE BEGIN USART6_Init 0 */ @@ -520,8 +493,7 @@ static void MX_USART6_UART_Init(void) huart6.Init.OverSampling = UART_OVERSAMPLING_16; huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - if (HAL_UART_Init(&huart6) != HAL_OK) - { + if (HAL_UART_Init(&huart6) != HAL_OK) { Error_Handler(); } /* USER CODE BEGIN USART6_Init 2 */ @@ -531,13 +503,12 @@ static void MX_USART6_UART_Init(void) } /** - * @brief GPIO Initialization Function - * @param None - * @retval None - */ -static void MX_GPIO_Init(void) -{ - GPIO_InitTypeDef GPIO_InitStruct = {0}; + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) { + GPIO_InitTypeDef GPIO_InitStruct = { 0 }; /* GPIO Ports Clock Enable */ __HAL_RCC_GPIOC_CLK_ENABLE(); @@ -548,10 +519,10 @@ static void MX_GPIO_Init(void) __HAL_RCC_GPIOB_CLK_ENABLE(); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin, GPIO_PIN_RESET); + HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, sleep2_Pin|sleep1_Pin, GPIO_PIN_SET); + HAL_GPIO_WritePin(GPIOF, sleep2_Pin | sleep1_Pin, GPIO_PIN_SET); /*Configure GPIO pin : user_button_Pin */ GPIO_InitStruct.Pin = user_button_Pin; @@ -578,14 +549,14 @@ static void MX_GPIO_Init(void) HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); /*Configure GPIO pins : dir2_Pin dir1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin; + GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); /*Configure GPIO pins : sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = sleep2_Pin|sleep1_Pin; + GPIO_InitStruct.Pin = sleep2_Pin | sleep1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; @@ -625,7 +596,25 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { HAL_UART_Transmit(&huart6, tx_buffer, 4, 100); } if (mode == 3) { - //TODO cross pid + + left_velocity = left_encoder.GetLinearVelocity(); + left_dutycycle = left_pid.update(left_velocity); + left_motor.set_speed(left_dutycycle); + + right_velocity = right_encoder.GetLinearVelocity(); + right_dutycycle = right_pid.update(right_velocity); + right_motor.set_speed(right_dutycycle); + + float difference = left_velocity - right_velocity; + + int cross_dutycycle = cross_pid.update(difference); + + left_dutycycle += cross_dutycycle; + right_dutycycle -= cross_dutycycle; + + output_msg.velocity = difference; + HAL_UART_Transmit(&huart6, tx_buffer, 4, 100); + } } @@ -640,15 +629,29 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) { if (input_msg.pid_select == 1) { left_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - left_pid.set(input_msg.pid_setpoint); + left_pid.set(input_msg.pid_setpoint_fixed); } else if (input_msg.pid_select == 2) { right_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - right_pid.set(input_msg.pid_setpoint); + right_pid.set(input_msg.pid_setpoint_fixed); } else if (input_msg.pid_select == 3) { + left_pid.config(180, 200, 0); + right_pid.config(185, 195, 0); + cross_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - cross_pid.set(input_msg.pid_setpoint); + + odom.UpdateValues(input_msg.pid_setpoint_lin, input_msg.pid_setpoint_ang); + + left_setpoint = input_msg.pid_setpoint_lin + - (BASELINE * input_msg.pid_setpoint_ang) / 2; + right_setpoint = 2 * input_msg.pid_setpoint_lin - left_setpoint; + + left_pid.set(left_setpoint); + right_pid.set(right_setpoint); + + cross_setpoint = left_setpoint - right_setpoint; + cross_pid.set(cross_setpoint); } } @@ -672,11 +675,10 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { /* USER CODE END 4 */ /** - * @brief This function is executed in case of error occurrence. - * @retval None - */ -void Error_Handler(void) -{ + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) { /* USER CODE BEGIN Error_Handler_Debug */ /* User can add his own implementation to report the HAL error return state */ diff --git a/utils/pid_tuning/otto_pid_tuning/Debug/otto_pid_tuning.list b/utils/pid_tuning/otto_pid_tuning/Debug/otto_pid_tuning.list index ef25a64..eec4efe 100644 --- a/utils/pid_tuning/otto_pid_tuning/Debug/otto_pid_tuning.list +++ b/utils/pid_tuning/otto_pid_tuning/Debug/otto_pid_tuning.list @@ -5,45 +5,45 @@ Sections: Idx Name Size VMA LMA File off Algn 0 .isr_vector 000001f8 08000000 08000000 00010000 2**0 CONTENTS, ALLOC, LOAD, READONLY, DATA - 1 .text 00005364 080001f8 080001f8 000101f8 2**2 + 1 .text 000053e8 080001f8 080001f8 000101f8 2**3 CONTENTS, ALLOC, LOAD, READONLY, CODE - 2 .rodata 00000018 0800555c 0800555c 0001555c 2**2 + 2 .rodata 00000018 080055e0 080055e0 000155e0 2**2 CONTENTS, ALLOC, LOAD, READONLY, DATA - 3 .ARM.extab 00000000 08005574 08005574 00020010 2**0 + 3 .ARM.extab 00000000 080055f8 080055f8 00020010 2**0 CONTENTS - 4 .ARM 00000008 08005574 08005574 00015574 2**2 + 4 .ARM 00000008 080055f8 080055f8 000155f8 2**2 CONTENTS, ALLOC, LOAD, READONLY, DATA - 5 .preinit_array 00000000 0800557c 0800557c 00020010 2**0 + 5 .preinit_array 00000000 08005600 08005600 00020010 2**0 CONTENTS, ALLOC, LOAD, DATA - 6 .init_array 00000008 0800557c 0800557c 0001557c 2**2 + 6 .init_array 00000008 08005600 08005600 00015600 2**2 CONTENTS, ALLOC, LOAD, DATA - 7 .fini_array 00000004 08005584 08005584 00015584 2**2 + 7 .fini_array 00000004 08005608 08005608 00015608 2**2 CONTENTS, ALLOC, LOAD, DATA - 8 .data 00000010 20000000 08005588 00020000 2**2 + 8 .data 00000010 20000000 0800560c 00020000 2**2 CONTENTS, ALLOC, LOAD, DATA - 9 .bss 00001aa8 20000010 08005598 00020010 2**2 + 9 .bss 000002fc 20000010 0800561c 00020010 2**2 ALLOC - 10 ._user_heap_stack 00000600 20001ab8 08005598 00021ab8 2**0 + 10 ._user_heap_stack 00000604 2000030c 0800561c 0002030c 2**0 ALLOC 11 .ARM.attributes 0000002e 00000000 00000000 00020010 2**0 CONTENTS, READONLY - 12 .debug_info 0000dc04 00000000 00000000 0002003e 2**0 + 12 .debug_info 0000dba6 00000000 00000000 0002003e 2**0 CONTENTS, READONLY, DEBUGGING - 13 .debug_abbrev 00001ea2 00000000 00000000 0002dc42 2**0 + 13 .debug_abbrev 00001e30 00000000 00000000 0002dbe4 2**0 CONTENTS, READONLY, DEBUGGING - 14 .debug_aranges 00000d60 00000000 00000000 0002fae8 2**3 + 14 .debug_aranges 00000d60 00000000 00000000 0002fa18 2**3 CONTENTS, READONLY, DEBUGGING - 15 .debug_ranges 00000c78 00000000 00000000 00030848 2**3 + 15 .debug_ranges 00000c78 00000000 00000000 00030778 2**3 CONTENTS, READONLY, DEBUGGING - 16 .debug_macro 0002820c 00000000 00000000 000314c0 2**0 + 16 .debug_macro 00028237 00000000 00000000 000313f0 2**0 CONTENTS, READONLY, DEBUGGING - 17 .debug_line 00009b90 00000000 00000000 000596cc 2**0 + 17 .debug_line 00009a73 00000000 00000000 00059627 2**0 CONTENTS, READONLY, DEBUGGING - 18 .debug_str 000f1d25 00000000 00000000 0006325c 2**0 + 18 .debug_str 000f1e07 00000000 00000000 0006309a 2**0 CONTENTS, READONLY, DEBUGGING - 19 .comment 0000007b 00000000 00000000 00154f81 2**0 + 19 .comment 0000007b 00000000 00000000 00154ea1 2**0 CONTENTS, READONLY - 20 .debug_frame 00003844 00000000 00000000 00154ffc 2**2 + 20 .debug_frame 00003830 00000000 00000000 00154f1c 2**2 CONTENTS, READONLY, DEBUGGING Disassembly of section .text: @@ -62,7 +62,7 @@ Disassembly of section .text: 800020e: bd10 pop {r4, pc} 8000210: 20000010 .word 0x20000010 8000214: 00000000 .word 0x00000000 - 8000218: 08005544 .word 0x08005544 + 8000218: 080055c8 .word 0x080055c8 0800021c : 800021c: b508 push {r3, lr} @@ -74,7 +74,7 @@ Disassembly of section .text: 800022a: bd08 pop {r3, pc} 800022c: 00000000 .word 0x00000000 8000230: 20000014 .word 0x20000014 - 8000234: 08005544 .word 0x08005544 + 8000234: 080055c8 .word 0x080055c8 08000238 <__aeabi_uldivmod>: 8000238: b953 cbnz r3, 8000250 <__aeabi_uldivmod+0x18> @@ -355,7 +355,7 @@ Disassembly of section .text: 08000538 <_ZN7Encoder8GetCountEv>: - Encoder(TIM_HandleTypeDef *timer); + Encoder(TIM_HandleTypeDef *timer, float wheel_circ); void Setup(); @@ -408,13608 +408,13554 @@ Disassembly of section .text: 800057e: 46bd mov sp, r7 8000580: f85d 7b04 ldr.w r7, [sp], #4 8000584: 4770 bx lr - ... -08000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef>: +08000586 <_ZN7EncoderC1EP17TIM_HandleTypeDeff>: #include "encoder.h" -Encoder::Encoder(TIM_HandleTypeDef *timer) { - 8000588: b480 push {r7} - 800058a: b083 sub sp, #12 - 800058c: af00 add r7, sp, #0 - 800058e: 6078 str r0, [r7, #4] - 8000590: 6039 str r1, [r7, #0] - 8000592: 687b ldr r3, [r7, #4] - 8000594: 4a08 ldr r2, [pc, #32] ; (80005b8 <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x30>) - 8000596: 611a str r2, [r3, #16] - 8000598: 687b ldr r3, [r7, #4] - 800059a: 4a08 ldr r2, [pc, #32] ; (80005bc <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x34>) - 800059c: 615a str r2, [r3, #20] - 800059e: 687b ldr r3, [r7, #4] - 80005a0: 4a07 ldr r2, [pc, #28] ; (80005c0 <_ZN7EncoderC1EP17TIM_HandleTypeDef+0x38>) - 80005a2: 619a str r2, [r3, #24] +Encoder::Encoder(TIM_HandleTypeDef *timer, float wheel_circ) { + 8000586: b480 push {r7} + 8000588: b085 sub sp, #20 + 800058a: af00 add r7, sp, #0 + 800058c: 60f8 str r0, [r7, #12] + 800058e: 60b9 str r1, [r7, #8] + 8000590: ed87 0a01 vstr s0, [r7, #4] timer_ = timer; - 80005a4: 687b ldr r3, [r7, #4] - 80005a6: 683a ldr r2, [r7, #0] - 80005a8: 601a str r2, [r3, #0] + 8000594: 68fb ldr r3, [r7, #12] + 8000596: 68ba ldr r2, [r7, #8] + 8000598: 601a str r2, [r3, #0] + wheel_circumference_ = wheel_circ; + 800059a: 68fb ldr r3, [r7, #12] + 800059c: 687a ldr r2, [r7, #4] + 800059e: 611a str r2, [r3, #16] } - 80005aa: 687b ldr r3, [r7, #4] - 80005ac: 4618 mov r0, r3 - 80005ae: 370c adds r7, #12 - 80005b0: 46bd mov sp, r7 - 80005b2: f85d 7b04 ldr.w r7, [sp], #4 - 80005b6: 4770 bx lr - 80005b8: 00012110 .word 0x00012110 - 80005bc: 40490fd0 .word 0x40490fd0 - 80005c0: 3f40ff97 .word 0x3f40ff97 - -080005c4 <_ZN7Encoder5SetupEv>: + 80005a0: 68fb ldr r3, [r7, #12] + 80005a2: 4618 mov r0, r3 + 80005a4: 3714 adds r7, #20 + 80005a6: 46bd mov sp, r7 + 80005a8: f85d 7b04 ldr.w r7, [sp], #4 + 80005ac: 4770 bx lr + +080005ae <_ZN7Encoder5SetupEv>: void Encoder::Setup() { - 80005c4: b580 push {r7, lr} - 80005c6: b082 sub sp, #8 - 80005c8: af00 add r7, sp, #0 - 80005ca: 6078 str r0, [r7, #4] + 80005ae: b580 push {r7, lr} + 80005b0: b082 sub sp, #8 + 80005b2: af00 add r7, sp, #0 + 80005b4: 6078 str r0, [r7, #4] HAL_TIM_Encoder_Start(timer_, TIM_CHANNEL_ALL); - 80005cc: 687b ldr r3, [r7, #4] - 80005ce: 681b ldr r3, [r3, #0] - 80005d0: 213c movs r1, #60 ; 0x3c - 80005d2: 4618 mov r0, r3 - 80005d4: f003 f89e bl 8003714 + 80005b6: 687b ldr r3, [r7, #4] + 80005b8: 681b ldr r3, [r3, #0] + 80005ba: 213c movs r1, #60 ; 0x3c + 80005bc: 4618 mov r0, r3 + 80005be: f003 f8eb bl 8003798 this->ResetCount(); - 80005d8: 6878 ldr r0, [r7, #4] - 80005da: f7ff ffc2 bl 8000562 <_ZN7Encoder10ResetCountEv> + 80005c2: 6878 ldr r0, [r7, #4] + 80005c4: f7ff ffcd bl 8000562 <_ZN7Encoder10ResetCountEv> this->previous_millis_ = 0; - 80005de: 687b ldr r3, [r7, #4] - 80005e0: 2200 movs r2, #0 - 80005e2: 605a str r2, [r3, #4] + 80005c8: 687b ldr r3, [r7, #4] + 80005ca: 2200 movs r2, #0 + 80005cc: 605a str r2, [r3, #4] this->current_millis_ = HAL_GetTick(); - 80005e4: f001 fbb2 bl 8001d4c - 80005e8: 4602 mov r2, r0 - 80005ea: 687b ldr r3, [r7, #4] - 80005ec: 609a str r2, [r3, #8] + 80005ce: f001 fbff bl 8001dd0 + 80005d2: 4602 mov r2, r0 + 80005d4: 687b ldr r3, [r7, #4] + 80005d6: 609a str r2, [r3, #8] } - 80005ee: bf00 nop - 80005f0: 3708 adds r7, #8 - 80005f2: 46bd mov sp, r7 - 80005f4: bd80 pop {r7, pc} + 80005d8: bf00 nop + 80005da: 3708 adds r7, #8 + 80005dc: 46bd mov sp, r7 + 80005de: bd80 pop {r7, pc} -080005f6 <_ZN7Encoder12UpdateValuesEv>: +080005e0 <_ZN7Encoder12UpdateValuesEv>: void Encoder::UpdateValues() { - 80005f6: b580 push {r7, lr} - 80005f8: b082 sub sp, #8 - 80005fa: af00 add r7, sp, #0 - 80005fc: 6078 str r0, [r7, #4] + 80005e0: b580 push {r7, lr} + 80005e2: b082 sub sp, #8 + 80005e4: af00 add r7, sp, #0 + 80005e6: 6078 str r0, [r7, #4] this->previous_millis_ = this->current_millis_; - 80005fe: 687b ldr r3, [r7, #4] - 8000600: 689a ldr r2, [r3, #8] - 8000602: 687b ldr r3, [r7, #4] - 8000604: 605a str r2, [r3, #4] + 80005e8: 687b ldr r3, [r7, #4] + 80005ea: 689a ldr r2, [r3, #8] + 80005ec: 687b ldr r3, [r7, #4] + 80005ee: 605a str r2, [r3, #4] this->current_millis_ = HAL_GetTick(); - 8000606: f001 fba1 bl 8001d4c - 800060a: 4602 mov r2, r0 - 800060c: 687b ldr r3, [r7, #4] - 800060e: 609a str r2, [r3, #8] + 80005f0: f001 fbee bl 8001dd0 + 80005f4: 4602 mov r2, r0 + 80005f6: 687b ldr r3, [r7, #4] + 80005f8: 609a str r2, [r3, #8] this->ticks_ = this->GetCount(); - 8000610: 6878 ldr r0, [r7, #4] - 8000612: f7ff ff91 bl 8000538 <_ZN7Encoder8GetCountEv> - 8000616: 4602 mov r2, r0 - 8000618: 687b ldr r3, [r7, #4] - 800061a: 60da str r2, [r3, #12] + 80005fa: 6878 ldr r0, [r7, #4] + 80005fc: f7ff ff9c bl 8000538 <_ZN7Encoder8GetCountEv> + 8000600: 4602 mov r2, r0 + 8000602: 687b ldr r3, [r7, #4] + 8000604: 60da str r2, [r3, #12] this->ResetCount(); - 800061c: 6878 ldr r0, [r7, #4] - 800061e: f7ff ffa0 bl 8000562 <_ZN7Encoder10ResetCountEv> + 8000606: 6878 ldr r0, [r7, #4] + 8000608: f7ff ffab bl 8000562 <_ZN7Encoder10ResetCountEv> } - 8000622: bf00 nop - 8000624: 3708 adds r7, #8 - 8000626: 46bd mov sp, r7 - 8000628: bd80 pop {r7, pc} - ... - -0800062c <_ZN7Encoder17GetLinearVelocityEv>: - float meters = ((float) this->ticks_ * kWheelCircumference) - / kTicksPerRevolution; + 800060c: bf00 nop + 800060e: 3708 adds r7, #8 + 8000610: 46bd mov sp, r7 + 8000612: bd80 pop {r7, pc} + +08000614 <_ZN7Encoder17GetLinearVelocityEv>: + float meters = ((float) this->ticks_ * this->wheel_circumference_) + / TICKS_PER_REVOLUTION; return meters; } float Encoder::GetLinearVelocity() { - 800062c: b580 push {r7, lr} - 800062e: b086 sub sp, #24 - 8000630: af00 add r7, sp, #0 - 8000632: 6078 str r0, [r7, #4] + 8000614: b580 push {r7, lr} + 8000616: b086 sub sp, #24 + 8000618: af00 add r7, sp, #0 + 800061a: 6078 str r0, [r7, #4] this->UpdateValues(); - 8000634: 6878 ldr r0, [r7, #4] - 8000636: f7ff ffde bl 80005f6 <_ZN7Encoder12UpdateValuesEv> - float meters = ((float) this->ticks_ * kWheelCircumference) - 800063a: 687b ldr r3, [r7, #4] - 800063c: 68db ldr r3, [r3, #12] - 800063e: ee07 3a90 vmov s15, r3 - 8000642: eeb8 7ae7 vcvt.f32.s32 s14, s15 - 8000646: 687b ldr r3, [r7, #4] - 8000648: edd3 7a06 vldr s15, [r3, #24] - 800064c: ee67 6a27 vmul.f32 s13, s14, s15 - / kTicksPerRevolution; - 8000650: 687b ldr r3, [r7, #4] - 8000652: 691b ldr r3, [r3, #16] - 8000654: ee07 3a90 vmov s15, r3 - 8000658: eeb8 7a67 vcvt.f32.u32 s14, s15 - float meters = ((float) this->ticks_ * kWheelCircumference) - 800065c: eec6 7a87 vdiv.f32 s15, s13, s14 - 8000660: edc7 7a05 vstr s15, [r7, #20] + 800061c: 6878 ldr r0, [r7, #4] + 800061e: f7ff ffdf bl 80005e0 <_ZN7Encoder12UpdateValuesEv> + float meters = ((float) this->ticks_ * this->wheel_circumference_) + 8000622: 687b ldr r3, [r7, #4] + 8000624: 68db ldr r3, [r3, #12] + 8000626: ee07 3a90 vmov s15, r3 + 800062a: eeb8 7ae7 vcvt.f32.s32 s14, s15 + 800062e: 687b ldr r3, [r7, #4] + 8000630: edd3 7a04 vldr s15, [r3, #16] + 8000634: ee27 7a27 vmul.f32 s14, s14, s15 + 8000638: eddf 6a17 vldr s13, [pc, #92] ; 8000698 <_ZN7Encoder17GetLinearVelocityEv+0x84> + 800063c: eec7 7a26 vdiv.f32 s15, s14, s13 + 8000640: edc7 7a05 vstr s15, [r7, #20] + / TICKS_PER_REVOLUTION; float deltaTime = this->current_millis_ - this->previous_millis_; - 8000664: 687b ldr r3, [r7, #4] - 8000666: 689a ldr r2, [r3, #8] - 8000668: 687b ldr r3, [r7, #4] - 800066a: 685b ldr r3, [r3, #4] - 800066c: 1ad3 subs r3, r2, r3 - 800066e: ee07 3a90 vmov s15, r3 - 8000672: eef8 7a67 vcvt.f32.u32 s15, s15 - 8000676: edc7 7a04 vstr s15, [r7, #16] + 8000644: 687b ldr r3, [r7, #4] + 8000646: 689a ldr r2, [r3, #8] + 8000648: 687b ldr r3, [r7, #4] + 800064a: 685b ldr r3, [r3, #4] + 800064c: 1ad3 subs r3, r2, r3 + 800064e: ee07 3a90 vmov s15, r3 + 8000652: eef8 7a67 vcvt.f32.u32 s15, s15 + 8000656: edc7 7a04 vstr s15, [r7, #16] if (deltaTime == 0) - 800067a: edd7 7a04 vldr s15, [r7, #16] - 800067e: eef5 7a40 vcmp.f32 s15, #0.0 - 8000682: eef1 fa10 vmrs APSR_nzcv, fpscr - 8000686: d102 bne.n 800068e <_ZN7Encoder17GetLinearVelocityEv+0x62> + 800065a: edd7 7a04 vldr s15, [r7, #16] + 800065e: eef5 7a40 vcmp.f32 s15, #0.0 + 8000662: eef1 fa10 vmrs APSR_nzcv, fpscr + 8000666: d102 bne.n 800066e <_ZN7Encoder17GetLinearVelocityEv+0x5a> return 0; - 8000688: f04f 0300 mov.w r3, #0 - 800068c: e00c b.n 80006a8 <_ZN7Encoder17GetLinearVelocityEv+0x7c> + 8000668: f04f 0300 mov.w r3, #0 + 800066c: e00c b.n 8000688 <_ZN7Encoder17GetLinearVelocityEv+0x74> float linear_velocity = (meters / (deltaTime / 1000)); - 800068e: edd7 7a04 vldr s15, [r7, #16] - 8000692: eddf 6a09 vldr s13, [pc, #36] ; 80006b8 <_ZN7Encoder17GetLinearVelocityEv+0x8c> - 8000696: ee87 7aa6 vdiv.f32 s14, s15, s13 - 800069a: edd7 6a05 vldr s13, [r7, #20] - 800069e: eec6 7a87 vdiv.f32 s15, s13, s14 - 80006a2: edc7 7a03 vstr s15, [r7, #12] + 800066e: edd7 7a04 vldr s15, [r7, #16] + 8000672: eddf 6a0a vldr s13, [pc, #40] ; 800069c <_ZN7Encoder17GetLinearVelocityEv+0x88> + 8000676: ee87 7aa6 vdiv.f32 s14, s15, s13 + 800067a: edd7 6a05 vldr s13, [r7, #20] + 800067e: eec6 7a87 vdiv.f32 s15, s13, s14 + 8000682: edc7 7a03 vstr s15, [r7, #12] return linear_velocity; - 80006a6: 68fb ldr r3, [r7, #12] - 80006a8: ee07 3a90 vmov s15, r3 + 8000686: 68fb ldr r3, [r7, #12] + 8000688: ee07 3a90 vmov s15, r3 } - 80006ac: eeb0 0a67 vmov.f32 s0, s15 - 80006b0: 3718 adds r7, #24 - 80006b2: 46bd mov sp, r7 - 80006b4: bd80 pop {r7, pc} - 80006b6: bf00 nop - 80006b8: 447a0000 .word 0x447a0000 - -080006bc <_ZN7EncoderC1Ev>: - Encoder() { - 80006bc: b480 push {r7} - 80006be: b083 sub sp, #12 - 80006c0: af00 add r7, sp, #0 - 80006c2: 6078 str r0, [r7, #4] - 80006c4: 687b ldr r3, [r7, #4] - 80006c6: 4a09 ldr r2, [pc, #36] ; (80006ec <_ZN7EncoderC1Ev+0x30>) - 80006c8: 611a str r2, [r3, #16] - 80006ca: 687b ldr r3, [r7, #4] - 80006cc: 4a08 ldr r2, [pc, #32] ; (80006f0 <_ZN7EncoderC1Ev+0x34>) - 80006ce: 615a str r2, [r3, #20] - 80006d0: 687b ldr r3, [r7, #4] - 80006d2: 4a08 ldr r2, [pc, #32] ; (80006f4 <_ZN7EncoderC1Ev+0x38>) - 80006d4: 619a str r2, [r3, #24] - timer_ = NULL; - 80006d6: 687b ldr r3, [r7, #4] - 80006d8: 2200 movs r2, #0 - 80006da: 601a str r2, [r3, #0] - } - 80006dc: 687b ldr r3, [r7, #4] - 80006de: 4618 mov r0, r3 - 80006e0: 370c adds r7, #12 - 80006e2: 46bd mov sp, r7 - 80006e4: f85d 7b04 ldr.w r7, [sp], #4 - 80006e8: 4770 bx lr - 80006ea: bf00 nop - 80006ec: 00012110 .word 0x00012110 - 80006f0: 40490fd0 .word 0x40490fd0 - 80006f4: 3f40ff97 .word 0x3f40ff97 - -080006f8 <_ZN8OdometryC1E7EncoderS0_>: - left_encoder_ = NULL; - right_encoder_ = NULL; - kBaseline = 0.35; //in meters - } - - Odometry(Encoder left, Encoder right) { - 80006f8: b084 sub sp, #16 - 80006fa: b5b0 push {r4, r5, r7, lr} - 80006fc: b082 sub sp, #8 - 80006fe: af00 add r7, sp, #0 - 8000700: 6078 str r0, [r7, #4] - 8000702: f107 001c add.w r0, r7, #28 - 8000706: e880 000e stmia.w r0, {r1, r2, r3} - 800070a: 687b ldr r3, [r7, #4] - 800070c: 4618 mov r0, r3 - 800070e: f7ff ffd5 bl 80006bc <_ZN7EncoderC1Ev> - 8000712: 687b ldr r3, [r7, #4] - 8000714: 331c adds r3, #28 - 8000716: 4618 mov r0, r3 - 8000718: f7ff ffd0 bl 80006bc <_ZN7EncoderC1Ev> - - left_encoder_ = left; - 800071c: 687b ldr r3, [r7, #4] - 800071e: 461d mov r5, r3 - 8000720: f107 041c add.w r4, r7, #28 - 8000724: cc0f ldmia r4!, {r0, r1, r2, r3} - 8000726: c50f stmia r5!, {r0, r1, r2, r3} - 8000728: e894 0007 ldmia.w r4, {r0, r1, r2} - 800072c: e885 0007 stmia.w r5, {r0, r1, r2} - right_encoder_ = right; - 8000730: 687b ldr r3, [r7, #4] - 8000732: f103 041c add.w r4, r3, #28 - 8000736: f107 0538 add.w r5, r7, #56 ; 0x38 - 800073a: cd0f ldmia r5!, {r0, r1, r2, r3} - 800073c: c40f stmia r4!, {r0, r1, r2, r3} - 800073e: e895 0007 ldmia.w r5, {r0, r1, r2} - 8000742: e884 0007 stmia.w r4, {r0, r1, r2} - kBaseline = 0.35; //in meters - 8000746: 687b ldr r3, [r7, #4] - 8000748: 4a04 ldr r2, [pc, #16] ; (800075c <_ZN8OdometryC1E7EncoderS0_+0x64>) - 800074a: 639a str r2, [r3, #56] ; 0x38 - } - 800074c: 687b ldr r3, [r7, #4] - 800074e: 4618 mov r0, r3 - 8000750: 3708 adds r7, #8 - 8000752: 46bd mov sp, r7 - 8000754: e8bd 40b0 ldmia.w sp!, {r4, r5, r7, lr} - 8000758: b004 add sp, #16 - 800075a: 4770 bx lr - 800075c: 3eb33333 .word 0x3eb33333 - -08000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm>: + 800068c: eeb0 0a67 vmov.f32 s0, s15 + 8000690: 3718 adds r7, #24 + 8000692: 46bd mov sp, r7 + 8000694: bd80 pop {r7, pc} + 8000696: bf00 nop + 8000698: 47908800 .word 0x47908800 + 800069c: 447a0000 .word 0x447a0000 + +080006a0 <_ZN8OdometryC1Ev>: + float left_velocity_; + float right_velocity_; + + + public: + Odometry() { + 80006a0: b480 push {r7} + 80006a2: b083 sub sp, #12 + 80006a4: af00 add r7, sp, #0 + 80006a6: 6078 str r0, [r7, #4] + left_velocity_ = 0; + 80006a8: 687b ldr r3, [r7, #4] + 80006aa: f04f 0200 mov.w r2, #0 + 80006ae: 601a str r2, [r3, #0] + right_velocity_ = 0; + 80006b0: 687b ldr r3, [r7, #4] + 80006b2: f04f 0200 mov.w r2, #0 + 80006b6: 605a str r2, [r3, #4] + } + 80006b8: 687b ldr r3, [r7, #4] + 80006ba: 4618 mov r0, r3 + 80006bc: 370c adds r7, #12 + 80006be: 46bd mov sp, r7 + 80006c0: f85d 7b04 ldr.w r7, [sp], #4 + 80006c4: 4770 bx lr + ... + +080006c8 <_ZN8Odometry12UpdateValuesEff>: + + void UpdateValues(float linear_vel, float angular_vel) { + 80006c8: b480 push {r7} + 80006ca: b085 sub sp, #20 + 80006cc: af00 add r7, sp, #0 + 80006ce: 60f8 str r0, [r7, #12] + 80006d0: ed87 0a02 vstr s0, [r7, #8] + 80006d4: edc7 0a01 vstr s1, [r7, #4] + left_velocity_ = linear_vel - (BASELINE * angular_vel)/2; + 80006d8: edd7 7a02 vldr s15, [r7, #8] + 80006dc: eeb7 6ae7 vcvt.f64.f32 d6, s15 + 80006e0: edd7 7a01 vldr s15, [r7, #4] + 80006e4: eeb7 7ae7 vcvt.f64.f32 d7, s15 + 80006e8: ed9f 5b11 vldr d5, [pc, #68] ; 8000730 <_ZN8Odometry12UpdateValuesEff+0x68> + 80006ec: ee27 5b05 vmul.f64 d5, d7, d5 + 80006f0: eeb0 4b00 vmov.f64 d4, #0 ; 0x40000000 2.0 + 80006f4: ee85 7b04 vdiv.f64 d7, d5, d4 + 80006f8: ee36 7b47 vsub.f64 d7, d6, d7 + 80006fc: eef7 7bc7 vcvt.f32.f64 s15, d7 + 8000700: 68fb ldr r3, [r7, #12] + 8000702: edc3 7a00 vstr s15, [r3] + right_velocity_ = 2 * linear_vel - left_velocity_; + 8000706: edd7 7a02 vldr s15, [r7, #8] + 800070a: ee37 7aa7 vadd.f32 s14, s15, s15 + 800070e: 68fb ldr r3, [r7, #12] + 8000710: edd3 7a00 vldr s15, [r3] + 8000714: ee77 7a67 vsub.f32 s15, s14, s15 + 8000718: 68fb ldr r3, [r7, #12] + 800071a: edc3 7a01 vstr s15, [r3, #4] + } + 800071e: bf00 nop + 8000720: 3714 adds r7, #20 + 8000722: 46bd mov sp, r7 + 8000724: f85d 7b04 ldr.w r7, [sp], #4 + 8000728: 4770 bx lr + 800072a: bf00 nop + 800072c: f3af 8000 nop.w + 8000730: 33333333 .word 0x33333333 + 8000734: 3fd33333 .word 0x3fd33333 + +08000738 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm>: 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, - 8000760: b480 push {r7} - 8000762: b085 sub sp, #20 - 8000764: af00 add r7, sp, #0 - 8000766: 60f8 str r0, [r7, #12] - 8000768: 60b9 str r1, [r7, #8] - 800076a: 603b str r3, [r7, #0] - 800076c: 4613 mov r3, r2 - 800076e: 80fb strh r3, [r7, #6] + 8000738: b480 push {r7} + 800073a: b085 sub sp, #20 + 800073c: af00 add r7, sp, #0 + 800073e: 60f8 str r0, [r7, #12] + 8000740: 60b9 str r1, [r7, #8] + 8000742: 603b str r3, [r7, #0] + 8000744: 4613 mov r3, r2 + 8000746: 80fb strh r3, [r7, #6] GPIO_TypeDef *dir_gpio_port, uint16_t dir_pin, TIM_HandleTypeDef *pwm_timer, uint32_t pwm_channel) { this->sleep_gpio_port_ = sleep_gpio_port; - 8000770: 68fb ldr r3, [r7, #12] - 8000772: 68ba ldr r2, [r7, #8] - 8000774: 601a str r2, [r3, #0] + 8000748: 68fb ldr r3, [r7, #12] + 800074a: 68ba ldr r2, [r7, #8] + 800074c: 601a str r2, [r3, #0] this->sleep_pin_ = sleep_pin; - 8000776: 68fb ldr r3, [r7, #12] - 8000778: 88fa ldrh r2, [r7, #6] - 800077a: 809a strh r2, [r3, #4] + 800074e: 68fb ldr r3, [r7, #12] + 8000750: 88fa ldrh r2, [r7, #6] + 8000752: 809a strh r2, [r3, #4] this->dir_gpio_port_ = dir_gpio_port; - 800077c: 68fb ldr r3, [r7, #12] - 800077e: 683a ldr r2, [r7, #0] - 8000780: 609a str r2, [r3, #8] + 8000754: 68fb ldr r3, [r7, #12] + 8000756: 683a ldr r2, [r7, #0] + 8000758: 609a str r2, [r3, #8] this->dir_pin_ = dir_pin; - 8000782: 68fb ldr r3, [r7, #12] - 8000784: 8b3a ldrh r2, [r7, #24] - 8000786: 819a strh r2, [r3, #12] + 800075a: 68fb ldr r3, [r7, #12] + 800075c: 8b3a ldrh r2, [r7, #24] + 800075e: 819a strh r2, [r3, #12] this->pwm_timer_ = pwm_timer; - 8000788: 68fb ldr r3, [r7, #12] - 800078a: 69fa ldr r2, [r7, #28] - 800078c: 611a str r2, [r3, #16] + 8000760: 68fb ldr r3, [r7, #12] + 8000762: 69fa ldr r2, [r7, #28] + 8000764: 611a str r2, [r3, #16] this->pwm_channel_ = pwm_channel; - 800078e: 68fb ldr r3, [r7, #12] - 8000790: 6a3a ldr r2, [r7, #32] - 8000792: 615a str r2, [r3, #20] + 8000766: 68fb ldr r3, [r7, #12] + 8000768: 6a3a ldr r2, [r7, #32] + 800076a: 615a str r2, [r3, #20] } - 8000794: 68fb ldr r3, [r7, #12] - 8000796: 4618 mov r0, r3 - 8000798: 3714 adds r7, #20 - 800079a: 46bd mov sp, r7 - 800079c: f85d 7b04 ldr.w r7, [sp], #4 - 80007a0: 4770 bx lr + 800076c: 68fb ldr r3, [r7, #12] + 800076e: 4618 mov r0, r3 + 8000770: 3714 adds r7, #20 + 8000772: 46bd mov sp, r7 + 8000774: f85d 7b04 ldr.w r7, [sp], #4 + 8000778: 4770 bx lr -080007a2 <_ZN15MotorController5setupEv>: +0800077a <_ZN15MotorController5setupEv>: void setup() { - 80007a2: b580 push {r7, lr} - 80007a4: b082 sub sp, #8 - 80007a6: af00 add r7, sp, #0 - 80007a8: 6078 str r0, [r7, #4] + 800077a: b580 push {r7, lr} + 800077c: b082 sub sp, #8 + 800077e: af00 add r7, sp, #0 + 8000780: 6078 str r0, [r7, #4] HAL_TIM_PWM_Start(pwm_timer_, pwm_channel_); - 80007aa: 687b ldr r3, [r7, #4] - 80007ac: 691a ldr r2, [r3, #16] - 80007ae: 687b ldr r3, [r7, #4] - 80007b0: 695b ldr r3, [r3, #20] - 80007b2: 4619 mov r1, r3 - 80007b4: 4610 mov r0, r2 - 80007b6: f002 fed7 bl 8003568 - } - 80007ba: bf00 nop - 80007bc: 3708 adds r7, #8 - 80007be: 46bd mov sp, r7 - 80007c0: bd80 pop {r7, pc} + 8000782: 687b ldr r3, [r7, #4] + 8000784: 691a ldr r2, [r3, #16] + 8000786: 687b ldr r3, [r7, #4] + 8000788: 695b ldr r3, [r3, #20] + 800078a: 4619 mov r1, r3 + 800078c: 4610 mov r0, r2 + 800078e: f002 ff2d bl 80035ec + } + 8000792: bf00 nop + 8000794: 3708 adds r7, #8 + 8000796: 46bd mov sp, r7 + 8000798: bd80 pop {r7, pc} ... -080007c4 <_ZN15MotorController9set_speedEi>: +0800079c <_ZN15MotorController9set_speedEi>: void set_speed(int duty_cycle) { - 80007c4: b580 push {r7, lr} - 80007c6: b082 sub sp, #8 - 80007c8: af00 add r7, sp, #0 - 80007ca: 6078 str r0, [r7, #4] - 80007cc: 6039 str r1, [r7, #0] + 800079c: b580 push {r7, lr} + 800079e: b082 sub sp, #8 + 80007a0: af00 add r7, sp, #0 + 80007a2: 6078 str r0, [r7, #4] + 80007a4: 6039 str r1, [r7, #0] if (duty_cycle >= 0) { - 80007ce: 683b ldr r3, [r7, #0] - 80007d0: 2b00 cmp r3, #0 - 80007d2: f2c0 8083 blt.w 80008dc <_ZN15MotorController9set_speedEi+0x118> -// HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); + 80007a6: 683b ldr r3, [r7, #0] + 80007a8: 2b00 cmp r3, #0 + 80007aa: f2c0 8083 blt.w 80008b4 <_ZN15MotorController9set_speedEi+0x118> + //set direction to forward HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_SET); - 80007d6: 687b ldr r3, [r7, #4] - 80007d8: 6898 ldr r0, [r3, #8] - 80007da: 687b ldr r3, [r7, #4] - 80007dc: 899b ldrh r3, [r3, #12] - 80007de: 2201 movs r2, #1 - 80007e0: 4619 mov r1, r3 - 80007e2: f001 fd9d bl 8002320 - if (duty_cycle > 790) - 80007e6: 683b ldr r3, [r7, #0] - 80007e8: f240 3216 movw r2, #790 ; 0x316 - 80007ec: 4293 cmp r3, r2 - 80007ee: dd3d ble.n 800086c <_ZN15MotorController9set_speedEi+0xa8> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 80007f0: 687b ldr r3, [r7, #4] - 80007f2: 695b ldr r3, [r3, #20] - 80007f4: 2b00 cmp r3, #0 - 80007f6: d106 bne.n 8000806 <_ZN15MotorController9set_speedEi+0x42> - 80007f8: 687b ldr r3, [r7, #4] - 80007fa: 691b ldr r3, [r3, #16] - 80007fc: 681b ldr r3, [r3, #0] - 80007fe: f240 3216 movw r2, #790 ; 0x316 - 8000802: 635a str r2, [r3, #52] ; 0x34 - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); + 80007ae: 687b ldr r3, [r7, #4] + 80007b0: 6898 ldr r0, [r3, #8] + 80007b2: 687b ldr r3, [r7, #4] + 80007b4: 899b ldrh r3, [r3, #12] + 80007b6: 2201 movs r2, #1 + 80007b8: 4619 mov r1, r3 + 80007ba: f001 fdf3 bl 80023a4 + + //check if duty_cycle exceeds maximum + if (duty_cycle > MAX_DUTY_CYCLE) + 80007be: 683b ldr r3, [r7, #0] + 80007c0: f240 3216 movw r2, #790 ; 0x316 + 80007c4: 4293 cmp r3, r2 + 80007c6: dd3d ble.n 8000844 <_ZN15MotorController9set_speedEi+0xa8> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, MAX_DUTY_CYCLE); + 80007c8: 687b ldr r3, [r7, #4] + 80007ca: 695b ldr r3, [r3, #20] + 80007cc: 2b00 cmp r3, #0 + 80007ce: d106 bne.n 80007de <_ZN15MotorController9set_speedEi+0x42> + 80007d0: 687b ldr r3, [r7, #4] + 80007d2: 691b ldr r3, [r3, #16] + 80007d4: 681b ldr r3, [r3, #0] + 80007d6: f240 3216 movw r2, #790 ; 0x316 + 80007da: 635a str r2, [r3, #52] ; 0x34 + 80007dc: e0f5 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80007de: 687b ldr r3, [r7, #4] + 80007e0: 695b ldr r3, [r3, #20] + 80007e2: 2b04 cmp r3, #4 + 80007e4: d106 bne.n 80007f4 <_ZN15MotorController9set_speedEi+0x58> + 80007e6: 687b ldr r3, [r7, #4] + 80007e8: 691b ldr r3, [r3, #16] + 80007ea: 681b ldr r3, [r3, #0] + 80007ec: f240 3216 movw r2, #790 ; 0x316 + 80007f0: 639a str r2, [r3, #56] ; 0x38 + 80007f2: e0ea b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80007f4: 687b ldr r3, [r7, #4] + 80007f6: 695b ldr r3, [r3, #20] + 80007f8: 2b08 cmp r3, #8 + 80007fa: d106 bne.n 800080a <_ZN15MotorController9set_speedEi+0x6e> + 80007fc: 687b ldr r3, [r7, #4] + 80007fe: 691b ldr r3, [r3, #16] + 8000800: 681b ldr r3, [r3, #0] + 8000802: f240 3216 movw r2, #790 ; 0x316 + 8000806: 63da str r2, [r3, #60] ; 0x3c + 8000808: e0df b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 800080a: 687b ldr r3, [r7, #4] + 800080c: 695b ldr r3, [r3, #20] + 800080e: 2b0c cmp r3, #12 + 8000810: d106 bne.n 8000820 <_ZN15MotorController9set_speedEi+0x84> + 8000812: 687b ldr r3, [r7, #4] + 8000814: 691b ldr r3, [r3, #16] + 8000816: 681b ldr r3, [r3, #0] + 8000818: f240 3216 movw r2, #790 ; 0x316 + 800081c: 641a str r2, [r3, #64] ; 0x40 + 800081e: e0d4 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000820: 687b ldr r3, [r7, #4] + 8000822: 695b ldr r3, [r3, #20] + 8000824: 2b10 cmp r3, #16 + 8000826: d106 bne.n 8000836 <_ZN15MotorController9set_speedEi+0x9a> + 8000828: 687b ldr r3, [r7, #4] + 800082a: 691b ldr r3, [r3, #16] + 800082c: 681b ldr r3, [r3, #0] + 800082e: f240 3216 movw r2, #790 ; 0x316 + 8000832: 659a str r2, [r3, #88] ; 0x58 + 8000834: e0c9 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000836: 687b ldr r3, [r7, #4] + 8000838: 691b ldr r3, [r3, #16] + 800083a: 681b ldr r3, [r3, #0] + 800083c: f240 3216 movw r2, #790 ; 0x316 + 8000840: 65da str r2, [r3, #92] ; 0x5c + 8000842: e0c2 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> else - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - } - - } - 8000804: e0f5 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000806: 687b ldr r3, [r7, #4] - 8000808: 695b ldr r3, [r3, #20] - 800080a: 2b04 cmp r3, #4 - 800080c: d106 bne.n 800081c <_ZN15MotorController9set_speedEi+0x58> - 800080e: 687b ldr r3, [r7, #4] - 8000810: 691b ldr r3, [r3, #16] - 8000812: 681b ldr r3, [r3, #0] - 8000814: f240 3216 movw r2, #790 ; 0x316 - 8000818: 639a str r2, [r3, #56] ; 0x38 - } - 800081a: e0ea b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800081c: 687b ldr r3, [r7, #4] - 800081e: 695b ldr r3, [r3, #20] - 8000820: 2b08 cmp r3, #8 - 8000822: d106 bne.n 8000832 <_ZN15MotorController9set_speedEi+0x6e> - 8000824: 687b ldr r3, [r7, #4] - 8000826: 691b ldr r3, [r3, #16] - 8000828: 681b ldr r3, [r3, #0] - 800082a: f240 3216 movw r2, #790 ; 0x316 - 800082e: 63da str r2, [r3, #60] ; 0x3c - } - 8000830: e0df b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000832: 687b ldr r3, [r7, #4] - 8000834: 695b ldr r3, [r3, #20] - 8000836: 2b0c cmp r3, #12 - 8000838: d106 bne.n 8000848 <_ZN15MotorController9set_speedEi+0x84> - 800083a: 687b ldr r3, [r7, #4] - 800083c: 691b ldr r3, [r3, #16] - 800083e: 681b ldr r3, [r3, #0] - 8000840: f240 3216 movw r2, #790 ; 0x316 - 8000844: 641a str r2, [r3, #64] ; 0x40 - } - 8000846: e0d4 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000848: 687b ldr r3, [r7, #4] - 800084a: 695b ldr r3, [r3, #20] - 800084c: 2b10 cmp r3, #16 - 800084e: d106 bne.n 800085e <_ZN15MotorController9set_speedEi+0x9a> - 8000850: 687b ldr r3, [r7, #4] - 8000852: 691b ldr r3, [r3, #16] - 8000854: 681b ldr r3, [r3, #0] - 8000856: f240 3216 movw r2, #790 ; 0x316 - 800085a: 659a str r2, [r3, #88] ; 0x58 - } - 800085c: e0c9 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800085e: 687b ldr r3, [r7, #4] - 8000860: 691b ldr r3, [r3, #16] - 8000862: 681b ldr r3, [r3, #0] - 8000864: f240 3216 movw r2, #790 ; 0x316 - 8000868: 65da str r2, [r3, #92] ; 0x5c - } - 800086a: e0c2 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); + 8000844: 687b ldr r3, [r7, #4] + 8000846: 695b ldr r3, [r3, #20] + 8000848: 2b00 cmp r3, #0 + 800084a: d105 bne.n 8000858 <_ZN15MotorController9set_speedEi+0xbc> + 800084c: 683a ldr r2, [r7, #0] + 800084e: 687b ldr r3, [r7, #4] + 8000850: 691b ldr r3, [r3, #16] + 8000852: 681b ldr r3, [r3, #0] + 8000854: 635a str r2, [r3, #52] ; 0x34 + 8000856: e0b8 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000858: 687b ldr r3, [r7, #4] + 800085a: 695b ldr r3, [r3, #20] + 800085c: 2b04 cmp r3, #4 + 800085e: d105 bne.n 800086c <_ZN15MotorController9set_speedEi+0xd0> + 8000860: 683a ldr r2, [r7, #0] + 8000862: 687b ldr r3, [r7, #4] + 8000864: 691b ldr r3, [r3, #16] + 8000866: 681b ldr r3, [r3, #0] + 8000868: 639a str r2, [r3, #56] ; 0x38 + 800086a: e0ae b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> 800086c: 687b ldr r3, [r7, #4] 800086e: 695b ldr r3, [r3, #20] - 8000870: 2b00 cmp r3, #0 - 8000872: d105 bne.n 8000880 <_ZN15MotorController9set_speedEi+0xbc> + 8000870: 2b08 cmp r3, #8 + 8000872: d105 bne.n 8000880 <_ZN15MotorController9set_speedEi+0xe4> 8000874: 683a ldr r2, [r7, #0] 8000876: 687b ldr r3, [r7, #4] 8000878: 691b ldr r3, [r3, #16] 800087a: 681b ldr r3, [r3, #0] - 800087c: 635a str r2, [r3, #52] ; 0x34 - } - 800087e: e0b8 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); + 800087c: 63da str r2, [r3, #60] ; 0x3c + 800087e: e0a4 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> 8000880: 687b ldr r3, [r7, #4] 8000882: 695b ldr r3, [r3, #20] - 8000884: 2b04 cmp r3, #4 - 8000886: d105 bne.n 8000894 <_ZN15MotorController9set_speedEi+0xd0> + 8000884: 2b0c cmp r3, #12 + 8000886: d105 bne.n 8000894 <_ZN15MotorController9set_speedEi+0xf8> 8000888: 683a ldr r2, [r7, #0] 800088a: 687b ldr r3, [r7, #4] 800088c: 691b ldr r3, [r3, #16] 800088e: 681b ldr r3, [r3, #0] - 8000890: 639a str r2, [r3, #56] ; 0x38 - } - 8000892: e0ae b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); + 8000890: 641a str r2, [r3, #64] ; 0x40 + 8000892: e09a b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> 8000894: 687b ldr r3, [r7, #4] 8000896: 695b ldr r3, [r3, #20] - 8000898: 2b08 cmp r3, #8 - 800089a: d105 bne.n 80008a8 <_ZN15MotorController9set_speedEi+0xe4> + 8000898: 2b10 cmp r3, #16 + 800089a: d105 bne.n 80008a8 <_ZN15MotorController9set_speedEi+0x10c> 800089c: 683a ldr r2, [r7, #0] 800089e: 687b ldr r3, [r7, #4] 80008a0: 691b ldr r3, [r3, #16] 80008a2: 681b ldr r3, [r3, #0] - 80008a4: 63da str r2, [r3, #60] ; 0x3c - } - 80008a6: e0a4 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008a8: 687b ldr r3, [r7, #4] - 80008aa: 695b ldr r3, [r3, #20] - 80008ac: 2b0c cmp r3, #12 - 80008ae: d105 bne.n 80008bc <_ZN15MotorController9set_speedEi+0xf8> - 80008b0: 683a ldr r2, [r7, #0] - 80008b2: 687b ldr r3, [r7, #4] - 80008b4: 691b ldr r3, [r3, #16] - 80008b6: 681b ldr r3, [r3, #0] - 80008b8: 641a str r2, [r3, #64] ; 0x40 - } - 80008ba: e09a b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008bc: 687b ldr r3, [r7, #4] - 80008be: 695b ldr r3, [r3, #20] - 80008c0: 2b10 cmp r3, #16 - 80008c2: d105 bne.n 80008d0 <_ZN15MotorController9set_speedEi+0x10c> - 80008c4: 683a ldr r2, [r7, #0] - 80008c6: 687b ldr r3, [r7, #4] - 80008c8: 691b ldr r3, [r3, #16] - 80008ca: 681b ldr r3, [r3, #0] - 80008cc: 659a str r2, [r3, #88] ; 0x58 - } - 80008ce: e090 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, duty_cycle); - 80008d0: 683a ldr r2, [r7, #0] - 80008d2: 687b ldr r3, [r7, #4] - 80008d4: 691b ldr r3, [r3, #16] - 80008d6: 681b ldr r3, [r3, #0] - 80008d8: 65da str r2, [r3, #92] ; 0x5c - } - 80008da: e08a b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - } else if (duty_cycle < 100){ - 80008dc: 683b ldr r3, [r7, #0] - 80008de: 2b63 cmp r3, #99 ; 0x63 - 80008e0: f300 8087 bgt.w 80009f2 <_ZN15MotorController9set_speedEi+0x22e> + 80008a4: 659a str r2, [r3, #88] ; 0x58 + 80008a6: e090 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80008a8: 683a ldr r2, [r7, #0] + 80008aa: 687b ldr r3, [r7, #4] + 80008ac: 691b ldr r3, [r3, #16] + 80008ae: 681b ldr r3, [r3, #0] + 80008b0: 65da str r2, [r3, #92] ; 0x5c + 80008b2: e08a b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + + } else if (duty_cycle < 0){ + 80008b4: 683b ldr r3, [r7, #0] + 80008b6: 2b00 cmp r3, #0 + 80008b8: f280 8087 bge.w 80009ca <_ZN15MotorController9set_speedEi+0x22e> + //set direction to backwards HAL_GPIO_WritePin(dir_gpio_port_, dir_pin_, GPIO_PIN_RESET); - 80008e4: 687b ldr r3, [r7, #4] - 80008e6: 6898 ldr r0, [r3, #8] - 80008e8: 687b ldr r3, [r7, #4] - 80008ea: 899b ldrh r3, [r3, #12] - 80008ec: 2200 movs r2, #0 - 80008ee: 4619 mov r1, r3 - 80008f0: f001 fd16 bl 8002320 - if (duty_cycle < -790) - 80008f4: 683b ldr r3, [r7, #0] - 80008f6: 4a41 ldr r2, [pc, #260] ; (80009fc <_ZN15MotorController9set_speedEi+0x238>) - 80008f8: 4293 cmp r3, r2 - 80008fa: da3d bge.n 8000978 <_ZN15MotorController9set_speedEi+0x1b4> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 80008fc: 687b ldr r3, [r7, #4] - 80008fe: 695b ldr r3, [r3, #20] - 8000900: 2b00 cmp r3, #0 - 8000902: d106 bne.n 8000912 <_ZN15MotorController9set_speedEi+0x14e> - 8000904: 687b ldr r3, [r7, #4] - 8000906: 691b ldr r3, [r3, #16] - 8000908: 681b ldr r3, [r3, #0] - 800090a: f240 3216 movw r2, #790 ; 0x316 - 800090e: 635a str r2, [r3, #52] ; 0x34 - } - 8000910: e06f b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000912: 687b ldr r3, [r7, #4] - 8000914: 695b ldr r3, [r3, #20] - 8000916: 2b04 cmp r3, #4 - 8000918: d106 bne.n 8000928 <_ZN15MotorController9set_speedEi+0x164> - 800091a: 687b ldr r3, [r7, #4] - 800091c: 691b ldr r3, [r3, #16] - 800091e: 681b ldr r3, [r3, #0] - 8000920: f240 3216 movw r2, #790 ; 0x316 - 8000924: 639a str r2, [r3, #56] ; 0x38 - } - 8000926: e064 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000928: 687b ldr r3, [r7, #4] - 800092a: 695b ldr r3, [r3, #20] - 800092c: 2b08 cmp r3, #8 - 800092e: d106 bne.n 800093e <_ZN15MotorController9set_speedEi+0x17a> - 8000930: 687b ldr r3, [r7, #4] - 8000932: 691b ldr r3, [r3, #16] - 8000934: 681b ldr r3, [r3, #0] - 8000936: f240 3216 movw r2, #790 ; 0x316 - 800093a: 63da str r2, [r3, #60] ; 0x3c - } - 800093c: e059 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800093e: 687b ldr r3, [r7, #4] - 8000940: 695b ldr r3, [r3, #20] - 8000942: 2b0c cmp r3, #12 - 8000944: d106 bne.n 8000954 <_ZN15MotorController9set_speedEi+0x190> - 8000946: 687b ldr r3, [r7, #4] - 8000948: 691b ldr r3, [r3, #16] - 800094a: 681b ldr r3, [r3, #0] - 800094c: f240 3216 movw r2, #790 ; 0x316 - 8000950: 641a str r2, [r3, #64] ; 0x40 - } - 8000952: e04e b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 8000954: 687b ldr r3, [r7, #4] - 8000956: 695b ldr r3, [r3, #20] - 8000958: 2b10 cmp r3, #16 - 800095a: d106 bne.n 800096a <_ZN15MotorController9set_speedEi+0x1a6> + 80008bc: 687b ldr r3, [r7, #4] + 80008be: 6898 ldr r0, [r3, #8] + 80008c0: 687b ldr r3, [r7, #4] + 80008c2: 899b ldrh r3, [r3, #12] + 80008c4: 2200 movs r2, #0 + 80008c6: 4619 mov r1, r3 + 80008c8: f001 fd6c bl 80023a4 + + //check if duty_cycle is lower than minimum + if (duty_cycle < -MAX_DUTY_CYCLE) + 80008cc: 683b ldr r3, [r7, #0] + 80008ce: 4a45 ldr r2, [pc, #276] ; (80009e4 <_ZN15MotorController9set_speedEi+0x248>) + 80008d0: 4293 cmp r3, r2 + 80008d2: da3d bge.n 8000950 <_ZN15MotorController9set_speedEi+0x1b4> + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, MAX_DUTY_CYCLE); + 80008d4: 687b ldr r3, [r7, #4] + 80008d6: 695b ldr r3, [r3, #20] + 80008d8: 2b00 cmp r3, #0 + 80008da: d106 bne.n 80008ea <_ZN15MotorController9set_speedEi+0x14e> + 80008dc: 687b ldr r3, [r7, #4] + 80008de: 691b ldr r3, [r3, #16] + 80008e0: 681b ldr r3, [r3, #0] + 80008e2: f240 3216 movw r2, #790 ; 0x316 + 80008e6: 635a str r2, [r3, #52] ; 0x34 + 80008e8: e06f b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80008ea: 687b ldr r3, [r7, #4] + 80008ec: 695b ldr r3, [r3, #20] + 80008ee: 2b04 cmp r3, #4 + 80008f0: d106 bne.n 8000900 <_ZN15MotorController9set_speedEi+0x164> + 80008f2: 687b ldr r3, [r7, #4] + 80008f4: 691b ldr r3, [r3, #16] + 80008f6: 681b ldr r3, [r3, #0] + 80008f8: f240 3216 movw r2, #790 ; 0x316 + 80008fc: 639a str r2, [r3, #56] ; 0x38 + 80008fe: e064 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000900: 687b ldr r3, [r7, #4] + 8000902: 695b ldr r3, [r3, #20] + 8000904: 2b08 cmp r3, #8 + 8000906: d106 bne.n 8000916 <_ZN15MotorController9set_speedEi+0x17a> + 8000908: 687b ldr r3, [r7, #4] + 800090a: 691b ldr r3, [r3, #16] + 800090c: 681b ldr r3, [r3, #0] + 800090e: f240 3216 movw r2, #790 ; 0x316 + 8000912: 63da str r2, [r3, #60] ; 0x3c + 8000914: e059 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000916: 687b ldr r3, [r7, #4] + 8000918: 695b ldr r3, [r3, #20] + 800091a: 2b0c cmp r3, #12 + 800091c: d106 bne.n 800092c <_ZN15MotorController9set_speedEi+0x190> + 800091e: 687b ldr r3, [r7, #4] + 8000920: 691b ldr r3, [r3, #16] + 8000922: 681b ldr r3, [r3, #0] + 8000924: f240 3216 movw r2, #790 ; 0x316 + 8000928: 641a str r2, [r3, #64] ; 0x40 + 800092a: e04e b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 800092c: 687b ldr r3, [r7, #4] + 800092e: 695b ldr r3, [r3, #20] + 8000930: 2b10 cmp r3, #16 + 8000932: d106 bne.n 8000942 <_ZN15MotorController9set_speedEi+0x1a6> + 8000934: 687b ldr r3, [r7, #4] + 8000936: 691b ldr r3, [r3, #16] + 8000938: 681b ldr r3, [r3, #0] + 800093a: f240 3216 movw r2, #790 ; 0x316 + 800093e: 659a str r2, [r3, #88] ; 0x58 + 8000940: e043 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000942: 687b ldr r3, [r7, #4] + 8000944: 691b ldr r3, [r3, #16] + 8000946: 681b ldr r3, [r3, #0] + 8000948: f240 3216 movw r2, #790 ; 0x316 + 800094c: 65da str r2, [r3, #92] ; 0x5c + 800094e: e03c b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + else + //invert sign to make duty_cycle positive + __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); + 8000950: 687b ldr r3, [r7, #4] + 8000952: 695b ldr r3, [r3, #20] + 8000954: 2b00 cmp r3, #0 + 8000956: d106 bne.n 8000966 <_ZN15MotorController9set_speedEi+0x1ca> + 8000958: 683b ldr r3, [r7, #0] + 800095a: 425a negs r2, r3 800095c: 687b ldr r3, [r7, #4] 800095e: 691b ldr r3, [r3, #16] 8000960: 681b ldr r3, [r3, #0] - 8000962: f240 3216 movw r2, #790 ; 0x316 - 8000966: 659a str r2, [r3, #88] ; 0x58 - } - 8000968: e043 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 790); - 800096a: 687b ldr r3, [r7, #4] - 800096c: 691b ldr r3, [r3, #16] - 800096e: 681b ldr r3, [r3, #0] - 8000970: f240 3216 movw r2, #790 ; 0x316 - 8000974: 65da str r2, [r3, #92] ; 0x5c - } - 8000976: e03c b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 8000978: 687b ldr r3, [r7, #4] - 800097a: 695b ldr r3, [r3, #20] - 800097c: 2b00 cmp r3, #0 - 800097e: d106 bne.n 800098e <_ZN15MotorController9set_speedEi+0x1ca> - 8000980: 683b ldr r3, [r7, #0] - 8000982: 425a negs r2, r3 - 8000984: 687b ldr r3, [r7, #4] - 8000986: 691b ldr r3, [r3, #16] - 8000988: 681b ldr r3, [r3, #0] - 800098a: 635a str r2, [r3, #52] ; 0x34 - } - 800098c: e031 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 800098e: 687b ldr r3, [r7, #4] - 8000990: 695b ldr r3, [r3, #20] - 8000992: 2b04 cmp r3, #4 - 8000994: d106 bne.n 80009a4 <_ZN15MotorController9set_speedEi+0x1e0> - 8000996: 683b ldr r3, [r7, #0] - 8000998: 425a negs r2, r3 - 800099a: 687b ldr r3, [r7, #4] - 800099c: 691b ldr r3, [r3, #16] - 800099e: 681b ldr r3, [r3, #0] - 80009a0: 639a str r2, [r3, #56] ; 0x38 - } - 80009a2: e026 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009a4: 687b ldr r3, [r7, #4] - 80009a6: 695b ldr r3, [r3, #20] - 80009a8: 2b08 cmp r3, #8 - 80009aa: d106 bne.n 80009ba <_ZN15MotorController9set_speedEi+0x1f6> - 80009ac: 683b ldr r3, [r7, #0] - 80009ae: 425a negs r2, r3 - 80009b0: 687b ldr r3, [r7, #4] - 80009b2: 691b ldr r3, [r3, #16] - 80009b4: 681b ldr r3, [r3, #0] - 80009b6: 63da str r2, [r3, #60] ; 0x3c - } - 80009b8: e01b b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009ba: 687b ldr r3, [r7, #4] - 80009bc: 695b ldr r3, [r3, #20] - 80009be: 2b0c cmp r3, #12 - 80009c0: d106 bne.n 80009d0 <_ZN15MotorController9set_speedEi+0x20c> - 80009c2: 683b ldr r3, [r7, #0] - 80009c4: 425a negs r2, r3 - 80009c6: 687b ldr r3, [r7, #4] - 80009c8: 691b ldr r3, [r3, #16] - 80009ca: 681b ldr r3, [r3, #0] - 80009cc: 641a str r2, [r3, #64] ; 0x40 - } - 80009ce: e010 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009d0: 687b ldr r3, [r7, #4] - 80009d2: 695b ldr r3, [r3, #20] - 80009d4: 2b10 cmp r3, #16 - 80009d6: d106 bne.n 80009e6 <_ZN15MotorController9set_speedEi+0x222> - 80009d8: 683b ldr r3, [r7, #0] - 80009da: 425a negs r2, r3 - 80009dc: 687b ldr r3, [r7, #4] - 80009de: 691b ldr r3, [r3, #16] - 80009e0: 681b ldr r3, [r3, #0] - 80009e2: 659a str r2, [r3, #88] ; 0x58 - } - 80009e4: e005 b.n 80009f2 <_ZN15MotorController9set_speedEi+0x22e> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, -duty_cycle); - 80009e6: 683b ldr r3, [r7, #0] - 80009e8: 425a negs r2, r3 - 80009ea: 687b ldr r3, [r7, #4] - 80009ec: 691b ldr r3, [r3, #16] - 80009ee: 681b ldr r3, [r3, #0] - 80009f0: 65da str r2, [r3, #92] ; 0x5c - } - 80009f2: bf00 nop - 80009f4: 3708 adds r7, #8 - 80009f6: 46bd mov sp, r7 - 80009f8: bd80 pop {r7, pc} - 80009fa: bf00 nop - 80009fc: fffffcea .word 0xfffffcea - -08000a00 <_ZN15MotorController5brakeEv>: + 8000962: 635a str r2, [r3, #52] ; 0x34 + 8000964: e031 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000966: 687b ldr r3, [r7, #4] + 8000968: 695b ldr r3, [r3, #20] + 800096a: 2b04 cmp r3, #4 + 800096c: d106 bne.n 800097c <_ZN15MotorController9set_speedEi+0x1e0> + 800096e: 683b ldr r3, [r7, #0] + 8000970: 425a negs r2, r3 + 8000972: 687b ldr r3, [r7, #4] + 8000974: 691b ldr r3, [r3, #16] + 8000976: 681b ldr r3, [r3, #0] + 8000978: 639a str r2, [r3, #56] ; 0x38 + 800097a: e026 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 800097c: 687b ldr r3, [r7, #4] + 800097e: 695b ldr r3, [r3, #20] + 8000980: 2b08 cmp r3, #8 + 8000982: d106 bne.n 8000992 <_ZN15MotorController9set_speedEi+0x1f6> + 8000984: 683b ldr r3, [r7, #0] + 8000986: 425a negs r2, r3 + 8000988: 687b ldr r3, [r7, #4] + 800098a: 691b ldr r3, [r3, #16] + 800098c: 681b ldr r3, [r3, #0] + 800098e: 63da str r2, [r3, #60] ; 0x3c + 8000990: e01b b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 8000992: 687b ldr r3, [r7, #4] + 8000994: 695b ldr r3, [r3, #20] + 8000996: 2b0c cmp r3, #12 + 8000998: d106 bne.n 80009a8 <_ZN15MotorController9set_speedEi+0x20c> + 800099a: 683b ldr r3, [r7, #0] + 800099c: 425a negs r2, r3 + 800099e: 687b ldr r3, [r7, #4] + 80009a0: 691b ldr r3, [r3, #16] + 80009a2: 681b ldr r3, [r3, #0] + 80009a4: 641a str r2, [r3, #64] ; 0x40 + 80009a6: e010 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80009a8: 687b ldr r3, [r7, #4] + 80009aa: 695b ldr r3, [r3, #20] + 80009ac: 2b10 cmp r3, #16 + 80009ae: d106 bne.n 80009be <_ZN15MotorController9set_speedEi+0x222> + 80009b0: 683b ldr r3, [r7, #0] + 80009b2: 425a negs r2, r3 + 80009b4: 687b ldr r3, [r7, #4] + 80009b6: 691b ldr r3, [r3, #16] + 80009b8: 681b ldr r3, [r3, #0] + 80009ba: 659a str r2, [r3, #88] ; 0x58 + 80009bc: e005 b.n 80009ca <_ZN15MotorController9set_speedEi+0x22e> + 80009be: 683b ldr r3, [r7, #0] + 80009c0: 425a negs r2, r3 + 80009c2: 687b ldr r3, [r7, #4] + 80009c4: 691b ldr r3, [r3, #16] + 80009c6: 681b ldr r3, [r3, #0] + 80009c8: 65da str r2, [r3, #92] ; 0x5c + } + + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); + 80009ca: 687b ldr r3, [r7, #4] + 80009cc: 6818 ldr r0, [r3, #0] + 80009ce: 687b ldr r3, [r7, #4] + 80009d0: 889b ldrh r3, [r3, #4] + 80009d2: 2201 movs r2, #1 + 80009d4: 4619 mov r1, r3 + 80009d6: f001 fce5 bl 80023a4 + } + 80009da: bf00 nop + 80009dc: 3708 adds r7, #8 + 80009de: 46bd mov sp, r7 + 80009e0: bd80 pop {r7, pc} + 80009e2: bf00 nop + 80009e4: fffffcea .word 0xfffffcea + +080009e8 <_ZN15MotorController5coastEv>: void brake() { - 8000a00: b480 push {r7} - 8000a02: b083 sub sp, #12 - 8000a04: af00 add r7, sp, #0 - 8000a06: 6078 str r0, [r7, #4] - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a08: 687b ldr r3, [r7, #4] - 8000a0a: 695b ldr r3, [r3, #20] - 8000a0c: 2b00 cmp r3, #0 - 8000a0e: d105 bne.n 8000a1c <_ZN15MotorController5brakeEv+0x1c> - 8000a10: 687b ldr r3, [r7, #4] - 8000a12: 691b ldr r3, [r3, #16] - 8000a14: 681b ldr r3, [r3, #0] - 8000a16: 2200 movs r2, #0 - 8000a18: 635a str r2, [r3, #52] ; 0x34 - } - 8000a1a: e02c b.n 8000a76 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a1c: 687b ldr r3, [r7, #4] - 8000a1e: 695b ldr r3, [r3, #20] - 8000a20: 2b04 cmp r3, #4 - 8000a22: d105 bne.n 8000a30 <_ZN15MotorController5brakeEv+0x30> - 8000a24: 687b ldr r3, [r7, #4] - 8000a26: 691b ldr r3, [r3, #16] - 8000a28: 681b ldr r3, [r3, #0] - 8000a2a: 2200 movs r2, #0 - 8000a2c: 639a str r2, [r3, #56] ; 0x38 - } - 8000a2e: e022 b.n 8000a76 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a30: 687b ldr r3, [r7, #4] - 8000a32: 695b ldr r3, [r3, #20] - 8000a34: 2b08 cmp r3, #8 - 8000a36: d105 bne.n 8000a44 <_ZN15MotorController5brakeEv+0x44> - 8000a38: 687b ldr r3, [r7, #4] - 8000a3a: 691b ldr r3, [r3, #16] - 8000a3c: 681b ldr r3, [r3, #0] - 8000a3e: 2200 movs r2, #0 - 8000a40: 63da str r2, [r3, #60] ; 0x3c - } - 8000a42: e018 b.n 8000a76 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a44: 687b ldr r3, [r7, #4] - 8000a46: 695b ldr r3, [r3, #20] - 8000a48: 2b0c cmp r3, #12 - 8000a4a: d105 bne.n 8000a58 <_ZN15MotorController5brakeEv+0x58> - 8000a4c: 687b ldr r3, [r7, #4] - 8000a4e: 691b ldr r3, [r3, #16] - 8000a50: 681b ldr r3, [r3, #0] - 8000a52: 2200 movs r2, #0 - 8000a54: 641a str r2, [r3, #64] ; 0x40 - } - 8000a56: e00e b.n 8000a76 <_ZN15MotorController5brakeEv+0x76> + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_SET); __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a58: 687b ldr r3, [r7, #4] - 8000a5a: 695b ldr r3, [r3, #20] - 8000a5c: 2b10 cmp r3, #16 - 8000a5e: d105 bne.n 8000a6c <_ZN15MotorController5brakeEv+0x6c> - 8000a60: 687b ldr r3, [r7, #4] - 8000a62: 691b ldr r3, [r3, #16] - 8000a64: 681b ldr r3, [r3, #0] - 8000a66: 2200 movs r2, #0 - 8000a68: 659a str r2, [r3, #88] ; 0x58 - } - 8000a6a: e004 b.n 8000a76 <_ZN15MotorController5brakeEv+0x76> - __HAL_TIM_SET_COMPARE(pwm_timer_, pwm_channel_, 0); - 8000a6c: 687b ldr r3, [r7, #4] - 8000a6e: 691b ldr r3, [r3, #16] - 8000a70: 681b ldr r3, [r3, #0] - 8000a72: 2200 movs r2, #0 - 8000a74: 65da str r2, [r3, #92] ; 0x5c - } - 8000a76: bf00 nop - 8000a78: 370c adds r7, #12 - 8000a7a: 46bd mov sp, r7 - 8000a7c: f85d 7b04 ldr.w r7, [sp], #4 - 8000a80: 4770 bx lr - ... + } -08000a84 <_ZN3PidC1Efff>: + void coast() { + 80009e8: b580 push {r7, lr} + 80009ea: b082 sub sp, #8 + 80009ec: af00 add r7, sp, #0 + 80009ee: 6078 str r0, [r7, #4] + HAL_GPIO_WritePin(sleep_gpio_port_, sleep_pin_, GPIO_PIN_RESET); + 80009f0: 687b ldr r3, [r7, #4] + 80009f2: 6818 ldr r0, [r3, #0] + 80009f4: 687b ldr r3, [r7, #4] + 80009f6: 889b ldrh r3, [r3, #4] + 80009f8: 2200 movs r2, #0 + 80009fa: 4619 mov r1, r3 + 80009fc: f001 fcd2 bl 80023a4 + } + 8000a00: bf00 nop + 8000a02: 3708 adds r7, #8 + 8000a04: 46bd mov sp, r7 + 8000a06: bd80 pop {r7, pc} + +08000a08 <_ZN3PidC1Efff>: float previous_error_; int min_; int max_; Pid(float kp, float ki, float kd) { - 8000a84: b480 push {r7} - 8000a86: b087 sub sp, #28 - 8000a88: af00 add r7, sp, #0 - 8000a8a: 60f8 str r0, [r7, #12] - 8000a8c: ed87 0a02 vstr s0, [r7, #8] - 8000a90: edc7 0a01 vstr s1, [r7, #4] - 8000a94: ed87 1a00 vstr s2, [r7] + 8000a08: b480 push {r7} + 8000a0a: b085 sub sp, #20 + 8000a0c: af00 add r7, sp, #0 + 8000a0e: 60f8 str r0, [r7, #12] + 8000a10: ed87 0a02 vstr s0, [r7, #8] + 8000a14: edc7 0a01 vstr s1, [r7, #4] + 8000a18: ed87 1a00 vstr s2, [r7] this->kp_ = kp; - 8000a98: 68fb ldr r3, [r7, #12] - 8000a9a: 68ba ldr r2, [r7, #8] - 8000a9c: 601a str r2, [r3, #0] + 8000a1c: 68fb ldr r3, [r7, #12] + 8000a1e: 68ba ldr r2, [r7, #8] + 8000a20: 601a str r2, [r3, #0] this->ki_ = ki; - 8000a9e: 68fb ldr r3, [r7, #12] - 8000aa0: 687a ldr r2, [r7, #4] - 8000aa2: 605a str r2, [r3, #4] + 8000a22: 68fb ldr r3, [r7, #12] + 8000a24: 687a ldr r2, [r7, #4] + 8000a26: 605a str r2, [r3, #4] this->kd_ = kd; - 8000aa4: 68fb ldr r3, [r7, #12] - 8000aa6: 683a ldr r2, [r7, #0] - 8000aa8: 609a str r2, [r3, #8] + 8000a28: 68fb ldr r3, [r7, #12] + 8000a2a: 683a ldr r2, [r7, #0] + 8000a2c: 609a str r2, [r3, #8] this->error_ = 0; - 8000aaa: 68fb ldr r3, [r7, #12] - 8000aac: f04f 0200 mov.w r2, #0 - 8000ab0: 60da str r2, [r3, #12] + 8000a2e: 68fb ldr r3, [r7, #12] + 8000a30: f04f 0200 mov.w r2, #0 + 8000a34: 60da str r2, [r3, #12] this->setpoint_ = 0; - 8000ab2: 68fb ldr r3, [r7, #12] - 8000ab4: f04f 0200 mov.w r2, #0 - 8000ab8: 611a str r2, [r3, #16] + 8000a36: 68fb ldr r3, [r7, #12] + 8000a38: f04f 0200 mov.w r2, #0 + 8000a3c: 611a str r2, [r3, #16] this->previous_error_ = 0; - 8000aba: 68fb ldr r3, [r7, #12] - 8000abc: f503 63fd add.w r3, r3, #2024 ; 0x7e8 - 8000ac0: f04f 0200 mov.w r2, #0 - 8000ac4: 601a str r2, [r3, #0] - this->error_sum_index_ = 0; - 8000ac6: 68fb ldr r3, [r7, #12] - 8000ac8: 2200 movs r2, #0 - 8000aca: f8c3 27e4 str.w r2, [r3, #2020] ; 0x7e4 - - for (int i = 0; i < WINDOW_SIZE; i++) { - 8000ace: 2300 movs r3, #0 - 8000ad0: 617b str r3, [r7, #20] - 8000ad2: 697b ldr r3, [r7, #20] - 8000ad4: f5b3 7ffa cmp.w r3, #500 ; 0x1f4 - 8000ad8: da0c bge.n 8000af4 <_ZN3PidC1Efff+0x70> - this->error_sum_array_[i] = 0; - 8000ada: 68fa ldr r2, [r7, #12] - 8000adc: 697b ldr r3, [r7, #20] - 8000ade: 3304 adds r3, #4 - 8000ae0: 009b lsls r3, r3, #2 - 8000ae2: 4413 add r3, r2 - 8000ae4: 3304 adds r3, #4 - 8000ae6: f04f 0200 mov.w r2, #0 - 8000aea: 601a str r2, [r3, #0] - for (int i = 0; i < WINDOW_SIZE; i++) { - 8000aec: 697b ldr r3, [r7, #20] - 8000aee: 3301 adds r3, #1 - 8000af0: 617b str r3, [r7, #20] - 8000af2: e7ee b.n 8000ad2 <_ZN3PidC1Efff+0x4e> - } - - this->min_ = -790; - 8000af4: 68fb ldr r3, [r7, #12] - 8000af6: 4a07 ldr r2, [pc, #28] ; (8000b14 <_ZN3PidC1Efff+0x90>) - 8000af8: f8c3 27ec str.w r2, [r3, #2028] ; 0x7ec - this->max_ = 790; - 8000afc: 68fb ldr r3, [r7, #12] - 8000afe: f240 3216 movw r2, #790 ; 0x316 - 8000b02: f8c3 27f0 str.w r2, [r3, #2032] ; 0x7f0 - - } - 8000b06: 68fb ldr r3, [r7, #12] - 8000b08: 4618 mov r0, r3 - 8000b0a: 371c adds r7, #28 - 8000b0c: 46bd mov sp, r7 - 8000b0e: f85d 7b04 ldr.w r7, [sp], #4 - 8000b12: 4770 bx lr - 8000b14: fffffcea .word 0xfffffcea - -08000b18 <_ZN3Pid6configEfff>: + 8000a3e: 68fb ldr r3, [r7, #12] + 8000a40: f04f 0200 mov.w r2, #0 + 8000a44: 619a str r2, [r3, #24] + this->error_sum_ = 0; + 8000a46: 68fb ldr r3, [r7, #12] + 8000a48: f04f 0200 mov.w r2, #0 + 8000a4c: 615a str r2, [r3, #20] + + this->min_ = -MAX_DUTY_CYCLE; + 8000a4e: 68fb ldr r3, [r7, #12] + 8000a50: 4a06 ldr r2, [pc, #24] ; (8000a6c <_ZN3PidC1Efff+0x64>) + 8000a52: 61da str r2, [r3, #28] + this->max_ = MAX_DUTY_CYCLE; + 8000a54: 68fb ldr r3, [r7, #12] + 8000a56: f240 3216 movw r2, #790 ; 0x316 + 8000a5a: 621a str r2, [r3, #32] + + } + 8000a5c: 68fb ldr r3, [r7, #12] + 8000a5e: 4618 mov r0, r3 + 8000a60: 3714 adds r7, #20 + 8000a62: 46bd mov sp, r7 + 8000a64: f85d 7b04 ldr.w r7, [sp], #4 + 8000a68: 4770 bx lr + 8000a6a: bf00 nop + 8000a6c: fffffcea .word 0xfffffcea + +08000a70 <_ZN3Pid6configEfff>: void config(float kp, float ki, float kd) { - 8000b18: b480 push {r7} - 8000b1a: b087 sub sp, #28 - 8000b1c: af00 add r7, sp, #0 - 8000b1e: 60f8 str r0, [r7, #12] - 8000b20: ed87 0a02 vstr s0, [r7, #8] - 8000b24: edc7 0a01 vstr s1, [r7, #4] - 8000b28: ed87 1a00 vstr s2, [r7] + 8000a70: b480 push {r7} + 8000a72: b085 sub sp, #20 + 8000a74: af00 add r7, sp, #0 + 8000a76: 60f8 str r0, [r7, #12] + 8000a78: ed87 0a02 vstr s0, [r7, #8] + 8000a7c: edc7 0a01 vstr s1, [r7, #4] + 8000a80: ed87 1a00 vstr s2, [r7] this->kp_ = kp; - 8000b2c: 68fb ldr r3, [r7, #12] - 8000b2e: 68ba ldr r2, [r7, #8] - 8000b30: 601a str r2, [r3, #0] + 8000a84: 68fb ldr r3, [r7, #12] + 8000a86: 68ba ldr r2, [r7, #8] + 8000a88: 601a str r2, [r3, #0] this->ki_ = ki; - 8000b32: 68fb ldr r3, [r7, #12] - 8000b34: 687a ldr r2, [r7, #4] - 8000b36: 605a str r2, [r3, #4] + 8000a8a: 68fb ldr r3, [r7, #12] + 8000a8c: 687a ldr r2, [r7, #4] + 8000a8e: 605a str r2, [r3, #4] this->kd_ = kd; - 8000b38: 68fb ldr r3, [r7, #12] - 8000b3a: 683a ldr r2, [r7, #0] - 8000b3c: 609a str r2, [r3, #8] + 8000a90: 68fb ldr r3, [r7, #12] + 8000a92: 683a ldr r2, [r7, #0] + 8000a94: 609a str r2, [r3, #8] this->error_ = 0; - 8000b3e: 68fb ldr r3, [r7, #12] - 8000b40: f04f 0200 mov.w r2, #0 - 8000b44: 60da str r2, [r3, #12] + 8000a96: 68fb ldr r3, [r7, #12] + 8000a98: f04f 0200 mov.w r2, #0 + 8000a9c: 60da str r2, [r3, #12] this->setpoint_ = 0; - 8000b46: 68fb ldr r3, [r7, #12] - 8000b48: f04f 0200 mov.w r2, #0 - 8000b4c: 611a str r2, [r3, #16] + 8000a9e: 68fb ldr r3, [r7, #12] + 8000aa0: f04f 0200 mov.w r2, #0 + 8000aa4: 611a str r2, [r3, #16] this->previous_error_ = 0; - 8000b4e: 68fb ldr r3, [r7, #12] - 8000b50: f503 63fd add.w r3, r3, #2024 ; 0x7e8 - 8000b54: f04f 0200 mov.w r2, #0 - 8000b58: 601a str r2, [r3, #0] - this->error_sum_index_ = 0; - 8000b5a: 68fb ldr r3, [r7, #12] - 8000b5c: 2200 movs r2, #0 - 8000b5e: f8c3 27e4 str.w r2, [r3, #2020] ; 0x7e4 - - for (int i = 0; i < WINDOW_SIZE; i++) { - 8000b62: 2300 movs r3, #0 - 8000b64: 617b str r3, [r7, #20] - 8000b66: 697b ldr r3, [r7, #20] - 8000b68: f5b3 7ffa cmp.w r3, #500 ; 0x1f4 - 8000b6c: da0c bge.n 8000b88 <_ZN3Pid6configEfff+0x70> - this->error_sum_array_[i] = 0; - 8000b6e: 68fa ldr r2, [r7, #12] - 8000b70: 697b ldr r3, [r7, #20] - 8000b72: 3304 adds r3, #4 - 8000b74: 009b lsls r3, r3, #2 - 8000b76: 4413 add r3, r2 - 8000b78: 3304 adds r3, #4 - 8000b7a: f04f 0200 mov.w r2, #0 - 8000b7e: 601a str r2, [r3, #0] - for (int i = 0; i < WINDOW_SIZE; i++) { - 8000b80: 697b ldr r3, [r7, #20] - 8000b82: 3301 adds r3, #1 - 8000b84: 617b str r3, [r7, #20] - 8000b86: e7ee b.n 8000b66 <_ZN3Pid6configEfff+0x4e> - } + 8000aa6: 68fb ldr r3, [r7, #12] + 8000aa8: f04f 0200 mov.w r2, #0 + 8000aac: 619a str r2, [r3, #24] + this->error_sum_ = 0; + 8000aae: 68fb ldr r3, [r7, #12] + 8000ab0: f04f 0200 mov.w r2, #0 + 8000ab4: 615a str r2, [r3, #20] + } - 8000b88: bf00 nop - 8000b8a: 371c adds r7, #28 - 8000b8c: 46bd mov sp, r7 - 8000b8e: f85d 7b04 ldr.w r7, [sp], #4 - 8000b92: 4770 bx lr + 8000ab6: bf00 nop + 8000ab8: 3714 adds r7, #20 + 8000aba: 46bd mov sp, r7 + 8000abc: f85d 7b04 ldr.w r7, [sp], #4 + 8000ac0: 4770 bx lr -08000b94 <_ZN3Pid3setEf>: +08000ac2 <_ZN3Pid3setEf>: void set(float setpoint) { - 8000b94: b480 push {r7} - 8000b96: b083 sub sp, #12 - 8000b98: af00 add r7, sp, #0 - 8000b9a: 6078 str r0, [r7, #4] - 8000b9c: ed87 0a00 vstr s0, [r7] + 8000ac2: b480 push {r7} + 8000ac4: b083 sub sp, #12 + 8000ac6: af00 add r7, sp, #0 + 8000ac8: 6078 str r0, [r7, #4] + 8000aca: ed87 0a00 vstr s0, [r7] this->setpoint_ = setpoint; - 8000ba0: 687b ldr r3, [r7, #4] - 8000ba2: 683a ldr r2, [r7, #0] - 8000ba4: 611a str r2, [r3, #16] + 8000ace: 687b ldr r3, [r7, #4] + 8000ad0: 683a ldr r2, [r7, #0] + 8000ad2: 611a str r2, [r3, #16] } - 8000ba6: bf00 nop - 8000ba8: 370c adds r7, #12 - 8000baa: 46bd mov sp, r7 - 8000bac: f85d 7b04 ldr.w r7, [sp], #4 - 8000bb0: 4770 bx lr + 8000ad4: bf00 nop + 8000ad6: 370c adds r7, #12 + 8000ad8: 46bd mov sp, r7 + 8000ada: f85d 7b04 ldr.w r7, [sp], #4 + 8000ade: 4770 bx lr -08000bb2 <_ZN3Pid6updateEf>: +08000ae0 <_ZN3Pid6updateEf>: int update(float measure) { - 8000bb2: b480 push {r7} - 8000bb4: b085 sub sp, #20 - 8000bb6: af00 add r7, sp, #0 - 8000bb8: 6078 str r0, [r7, #4] - 8000bba: ed87 0a00 vstr s0, [r7] + 8000ae0: b480 push {r7} + 8000ae2: b085 sub sp, #20 + 8000ae4: af00 add r7, sp, #0 + 8000ae6: 6078 str r0, [r7, #4] + 8000ae8: ed87 0a00 vstr s0, [r7] this->error_ = this->setpoint_ - measure; - 8000bbe: 687b ldr r3, [r7, #4] - 8000bc0: ed93 7a04 vldr s14, [r3, #16] - 8000bc4: edd7 7a00 vldr s15, [r7] - 8000bc8: ee77 7a67 vsub.f32 s15, s14, s15 - 8000bcc: 687b ldr r3, [r7, #4] - 8000bce: edc3 7a03 vstr s15, [r3, #12] + 8000aec: 687b ldr r3, [r7, #4] + 8000aee: ed93 7a04 vldr s14, [r3, #16] + 8000af2: edd7 7a00 vldr s15, [r7] + 8000af6: ee77 7a67 vsub.f32 s15, s14, s15 + 8000afa: 687b ldr r3, [r7, #4] + 8000afc: edc3 7a03 vstr s15, [r3, #12] //proportional term float output = this->error_ * this->kp_; - 8000bd2: 687b ldr r3, [r7, #4] - 8000bd4: ed93 7a03 vldr s14, [r3, #12] - 8000bd8: 687b ldr r3, [r7, #4] - 8000bda: edd3 7a00 vldr s15, [r3] - 8000bde: ee67 7a27 vmul.f32 s15, s14, s15 - 8000be2: edc7 7a02 vstr s15, [r7, #8] -// -// output += error_sum * this->ki_; + 8000b00: 687b ldr r3, [r7, #4] + 8000b02: ed93 7a03 vldr s14, [r3, #12] + 8000b06: 687b ldr r3, [r7, #4] + 8000b08: edd3 7a00 vldr s15, [r3] + 8000b0c: ee67 7a27 vmul.f32 s15, s14, s15 + 8000b10: edc7 7a03 vstr s15, [r7, #12] //integral term without windup - - error_sum_array_[0] += this->error_; - 8000be6: 687b ldr r3, [r7, #4] - 8000be8: ed93 7a05 vldr s14, [r3, #20] - 8000bec: 687b ldr r3, [r7, #4] - 8000bee: edd3 7a03 vldr s15, [r3, #12] - 8000bf2: ee77 7a27 vadd.f32 s15, s14, s15 - 8000bf6: 687b ldr r3, [r7, #4] - 8000bf8: edc3 7a05 vstr s15, [r3, #20] - output += error_sum_array_[0] * this->ki_; - 8000bfc: 687b ldr r3, [r7, #4] - 8000bfe: ed93 7a05 vldr s14, [r3, #20] - 8000c02: 687b ldr r3, [r7, #4] - 8000c04: edd3 7a01 vldr s15, [r3, #4] - 8000c08: ee67 7a27 vmul.f32 s15, s14, s15 - 8000c0c: ed97 7a02 vldr s14, [r7, #8] - 8000c10: ee77 7a27 vadd.f32 s15, s14, s15 - 8000c14: edc7 7a02 vstr s15, [r7, #8] - - + error_sum_ += this->error_; + 8000b14: 687b ldr r3, [r7, #4] + 8000b16: ed93 7a05 vldr s14, [r3, #20] + 8000b1a: 687b ldr r3, [r7, #4] + 8000b1c: edd3 7a03 vldr s15, [r3, #12] + 8000b20: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b24: 687b ldr r3, [r7, #4] + 8000b26: edc3 7a05 vstr s15, [r3, #20] + output += error_sum_ * this->ki_; + 8000b2a: 687b ldr r3, [r7, #4] + 8000b2c: ed93 7a05 vldr s14, [r3, #20] + 8000b30: 687b ldr r3, [r7, #4] + 8000b32: edd3 7a01 vldr s15, [r3, #4] + 8000b36: ee67 7a27 vmul.f32 s15, s14, s15 + 8000b3a: ed97 7a03 vldr s14, [r7, #12] + 8000b3e: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b42: edc7 7a03 vstr s15, [r7, #12] //derivative term output += (this->error_ - this->previous_error_) * kd_; - 8000c18: 687b ldr r3, [r7, #4] - 8000c1a: ed93 7a03 vldr s14, [r3, #12] - 8000c1e: 687b ldr r3, [r7, #4] - 8000c20: f503 63fd add.w r3, r3, #2024 ; 0x7e8 - 8000c24: edd3 7a00 vldr s15, [r3] - 8000c28: ee37 7a67 vsub.f32 s14, s14, s15 - 8000c2c: 687b ldr r3, [r7, #4] - 8000c2e: edd3 7a02 vldr s15, [r3, #8] - 8000c32: ee67 7a27 vmul.f32 s15, s14, s15 - 8000c36: ed97 7a02 vldr s14, [r7, #8] - 8000c3a: ee77 7a27 vadd.f32 s15, s14, s15 - 8000c3e: edc7 7a02 vstr s15, [r7, #8] + 8000b46: 687b ldr r3, [r7, #4] + 8000b48: ed93 7a03 vldr s14, [r3, #12] + 8000b4c: 687b ldr r3, [r7, #4] + 8000b4e: edd3 7a06 vldr s15, [r3, #24] + 8000b52: ee37 7a67 vsub.f32 s14, s14, s15 + 8000b56: 687b ldr r3, [r7, #4] + 8000b58: edd3 7a02 vldr s15, [r3, #8] + 8000b5c: ee67 7a27 vmul.f32 s15, s14, s15 + 8000b60: ed97 7a03 vldr s14, [r7, #12] + 8000b64: ee77 7a27 vadd.f32 s15, s14, s15 + 8000b68: edc7 7a03 vstr s15, [r7, #12] this->previous_error_ = this->error_; - 8000c42: 687b ldr r3, [r7, #4] - 8000c44: 68da ldr r2, [r3, #12] - 8000c46: 687b ldr r3, [r7, #4] - 8000c48: f503 63fd add.w r3, r3, #2024 ; 0x7e8 - 8000c4c: 601a str r2, [r3, #0] + 8000b6c: 687b ldr r3, [r7, #4] + 8000b6e: 68da ldr r2, [r3, #12] + 8000b70: 687b ldr r3, [r7, #4] + 8000b72: 619a str r2, [r3, #24] int integer_output = static_cast (output); - 8000c4e: edd7 7a02 vldr s15, [r7, #8] - 8000c52: eefd 7ae7 vcvt.s32.f32 s15, s15 - 8000c56: ee17 3a90 vmov r3, s15 - 8000c5a: 60fb str r3, [r7, #12] - - if(integer_output > this->max_) - 8000c5c: 687b ldr r3, [r7, #4] - 8000c5e: f8d3 37f0 ldr.w r3, [r3, #2032] ; 0x7f0 - 8000c62: 68fa ldr r2, [r7, #12] - 8000c64: 429a cmp r2, r3 - 8000c66: dd04 ble.n 8000c72 <_ZN3Pid6updateEf+0xc0> - integer_output = this->max_; - 8000c68: 687b ldr r3, [r7, #4] - 8000c6a: f8d3 37f0 ldr.w r3, [r3, #2032] ; 0x7f0 - 8000c6e: 60fb str r3, [r7, #12] - 8000c70: e009 b.n 8000c86 <_ZN3Pid6updateEf+0xd4> - else if (integer_output < this->min_) - 8000c72: 687b ldr r3, [r7, #4] - 8000c74: f8d3 37ec ldr.w r3, [r3, #2028] ; 0x7ec - 8000c78: 68fa ldr r2, [r7, #12] - 8000c7a: 429a cmp r2, r3 - 8000c7c: da03 bge.n 8000c86 <_ZN3Pid6updateEf+0xd4> - integer_output = this->min_; - 8000c7e: 687b ldr r3, [r7, #4] - 8000c80: f8d3 37ec ldr.w r3, [r3, #2028] ; 0x7ec - 8000c84: 60fb str r3, [r7, #12] + 8000b74: edd7 7a03 vldr s15, [r7, #12] + 8000b78: eefd 7ae7 vcvt.s32.f32 s15, s15 + 8000b7c: ee17 3a90 vmov r3, s15 + 8000b80: 60bb str r3, [r7, #8] +// if(integer_output > this->max_) +// integer_output = this->max_; +// else if (integer_output < this->min_) +// integer_output = this->min_; return integer_output; - 8000c86: 68fb ldr r3, [r7, #12] + 8000b82: 68bb ldr r3, [r7, #8] } - 8000c88: 4618 mov r0, r3 - 8000c8a: 3714 adds r7, #20 - 8000c8c: 46bd mov sp, r7 - 8000c8e: f85d 7b04 ldr.w r7, [sp], #4 - 8000c92: 4770 bx lr + 8000b84: 4618 mov r0, r3 + 8000b86: 3714 adds r7, #20 + 8000b88: 46bd mov sp, r7 + 8000b8a: f85d 7b04 ldr.w r7, [sp], #4 + 8000b8e: 4770 bx lr + +08000b90
: -08000c94
: /** - * @brief The application entry point. - * @retval int - */ -int main(void) -{ - 8000c94: b580 push {r7, lr} - 8000c96: af00 add r7, sp, #0 - + * @brief The application entry point. + * @retval int + */ +int main(void) { + 8000b90: b580 push {r7, lr} + 8000b92: af00 add r7, sp, #0 + /* USER CODE END 1 */ /* MCU Configuration--------------------------------------------------------*/ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ HAL_Init(); - 8000c98: f001 f807 bl 8001caa + 8000b94: f001 f8cb bl 8001d2e /* USER CODE BEGIN Init */ /* USER CODE END Init */ /* Configure the system clock */ SystemClock_Config(); - 8000c9c: f000 f83c bl 8000d18 <_Z18SystemClock_Configv> + 8000b98: f000 f842 bl 8000c20 <_Z18SystemClock_Configv> /* USER CODE BEGIN SysInit */ /* USER CODE END SysInit */ /* Initialize all configured peripherals */ MX_GPIO_Init(); - 8000ca0: f000 fb14 bl 80012cc <_ZL12MX_GPIO_Initv> + 8000b9c: f000 fb1a bl 80011d4 <_ZL12MX_GPIO_Initv> MX_TIM2_Init(); - 8000ca4: f000 f8de bl 8000e64 <_ZL12MX_TIM2_Initv> + 8000ba0: f000 f8e4 bl 8000d6c <_ZL12MX_TIM2_Initv> MX_TIM3_Init(); - 8000ca8: f000 f93a bl 8000f20 <_ZL12MX_TIM3_Initv> + 8000ba4: f000 f940 bl 8000e28 <_ZL12MX_TIM3_Initv> MX_TIM4_Init(); - 8000cac: f000 f996 bl 8000fdc <_ZL12MX_TIM4_Initv> + 8000ba8: f000 f99c bl 8000ee4 <_ZL12MX_TIM4_Initv> MX_TIM5_Init(); - 8000cb0: f000 fa34 bl 800111c <_ZL12MX_TIM5_Initv> + 8000bac: f000 fa3a bl 8001024 <_ZL12MX_TIM5_Initv> MX_USART6_UART_Init(); - 8000cb4: f000 fad4 bl 8001260 <_ZL19MX_USART6_UART_Initv> + 8000bb0: f000 fada bl 8001168 <_ZL19MX_USART6_UART_Initv> MX_TIM6_Init(); - 8000cb8: f000 fa90 bl 80011dc <_ZL12MX_TIM6_Initv> + 8000bb4: f000 fa96 bl 80010e4 <_ZL12MX_TIM6_Initv> /* Initialize interrupts */ MX_NVIC_Init(); - 8000cbc: f000 f8b6 bl 8000e2c <_ZL12MX_NVIC_Initv> + 8000bb8: f000 f8bc bl 8000d34 <_ZL12MX_NVIC_Initv> /* USER CODE BEGIN 2 */ left_encoder.Setup(); - 8000cc0: 480c ldr r0, [pc, #48] ; (8000cf4 ) - 8000cc2: f7ff fc7f bl 80005c4 <_ZN7Encoder5SetupEv> + 8000bbc: 480f ldr r0, [pc, #60] ; (8000bfc ) + 8000bbe: f7ff fcf6 bl 80005ae <_ZN7Encoder5SetupEv> right_encoder.Setup(); - 8000cc6: 480c ldr r0, [pc, #48] ; (8000cf8 ) - 8000cc8: f7ff fc7c bl 80005c4 <_ZN7Encoder5SetupEv> + 8000bc2: 480f ldr r0, [pc, #60] ; (8000c00 ) + 8000bc4: f7ff fcf3 bl 80005ae <_ZN7Encoder5SetupEv> left_motor.setup(); - 8000ccc: 480b ldr r0, [pc, #44] ; (8000cfc ) - 8000cce: f7ff fd68 bl 80007a2 <_ZN15MotorController5setupEv> + 8000bc8: 480e ldr r0, [pc, #56] ; (8000c04 ) + 8000bca: f7ff fdd6 bl 800077a <_ZN15MotorController5setupEv> right_motor.setup(); - 8000cd2: 480b ldr r0, [pc, #44] ; (8000d00 ) - 8000cd4: f7ff fd65 bl 80007a2 <_ZN15MotorController5setupEv> + 8000bce: 480e ldr r0, [pc, #56] ; (8000c08 ) + 8000bd0: f7ff fdd3 bl 800077a <_ZN15MotorController5setupEv> + + left_motor.coast(); + 8000bd4: 480b ldr r0, [pc, #44] ; (8000c04 ) + 8000bd6: f7ff ff07 bl 80009e8 <_ZN15MotorController5coastEv> + right_motor.coast(); + 8000bda: 480b ldr r0, [pc, #44] ; (8000c08 ) + 8000bdc: f7ff ff04 bl 80009e8 <_ZN15MotorController5coastEv> tx_buffer = (uint8_t*) &output_msg; - 8000cd8: 4b0a ldr r3, [pc, #40] ; (8000d04 ) - 8000cda: 4a0b ldr r2, [pc, #44] ; (8000d08 ) - 8000cdc: 601a str r2, [r3, #0] + 8000be0: 4b0a ldr r3, [pc, #40] ; (8000c0c ) + 8000be2: 4a0b ldr r2, [pc, #44] ; (8000c10 ) + 8000be4: 601a str r2, [r3, #0] rx_buffer = (uint8_t*) &input_msg; - 8000cde: 4b0b ldr r3, [pc, #44] ; (8000d0c ) - 8000ce0: 4a0b ldr r2, [pc, #44] ; (8000d10 ) - 8000ce2: 601a str r2, [r3, #0] + 8000be6: 4b0b ldr r3, [pc, #44] ; (8000c14 ) + 8000be8: 4a0b ldr r2, [pc, #44] ; (8000c18 ) + 8000bea: 601a str r2, [r3, #0] //Enables UART RX interrupt - HAL_UART_Receive_IT(&huart6, rx_buffer, 20); - 8000ce4: 4b09 ldr r3, [pc, #36] ; (8000d0c ) - 8000ce6: 681b ldr r3, [r3, #0] - 8000ce8: 2214 movs r2, #20 - 8000cea: 4619 mov r1, r3 - 8000cec: 4809 ldr r0, [pc, #36] ; (8000d14 ) - 8000cee: f003 fd79 bl 80047e4 + HAL_UART_Receive_IT(&huart6, rx_buffer, 28); + 8000bec: 4b09 ldr r3, [pc, #36] ; (8000c14 ) + 8000bee: 681b ldr r3, [r3, #0] + 8000bf0: 221c movs r2, #28 + 8000bf2: 4619 mov r1, r3 + 8000bf4: 4809 ldr r0, [pc, #36] ; (8000c1c ) + 8000bf6: f003 fe37 bl 8004868 /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { - 8000cf2: e7fe b.n 8000cf2 - 8000cf4: 20000208 .word 0x20000208 - 8000cf8: 200001ec .word 0x200001ec - 8000cfc: 20001a70 .word 0x20001a70 - 8000d00: 20001a58 .word 0x20001a58 - 8000d04: 20001a88 .word 0x20001a88 - 8000d08: 20001aa4 .word 0x20001aa4 - 8000d0c: 20001a8c .word 0x20001a8c - 8000d10: 20001a90 .word 0x20001a90 - 8000d14: 2000016c .word 0x2000016c - -08000d18 <_Z18SystemClock_Configv>: + 8000bfa: e7fe b.n 8000bfa + 8000bfc: 20000200 .word 0x20000200 + 8000c00: 200001ec .word 0x200001ec + 8000c04: 200002bc .word 0x200002bc + 8000c08: 200002a4 .word 0x200002a4 + 8000c0c: 200002d4 .word 0x200002d4 + 8000c10: 200002f8 .word 0x200002f8 + 8000c14: 200002d8 .word 0x200002d8 + 8000c18: 200002dc .word 0x200002dc + 8000c1c: 2000016c .word 0x2000016c + +08000c20 <_Z18SystemClock_Configv>: + /** - * @brief System Clock Configuration - * @retval None - */ -void SystemClock_Config(void) -{ - 8000d18: b580 push {r7, lr} - 8000d1a: b0b8 sub sp, #224 ; 0xe0 - 8000d1c: af00 add r7, sp, #0 - RCC_OscInitTypeDef RCC_OscInitStruct = {0}; - 8000d1e: f107 03ac add.w r3, r7, #172 ; 0xac - 8000d22: 2234 movs r2, #52 ; 0x34 - 8000d24: 2100 movs r1, #0 - 8000d26: 4618 mov r0, r3 - 8000d28: f004 fc04 bl 8005534 - RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; - 8000d2c: f107 0398 add.w r3, r7, #152 ; 0x98 - 8000d30: 2200 movs r2, #0 - 8000d32: 601a str r2, [r3, #0] - 8000d34: 605a str r2, [r3, #4] - 8000d36: 609a str r2, [r3, #8] - 8000d38: 60da str r2, [r3, #12] - 8000d3a: 611a str r2, [r3, #16] - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; - 8000d3c: f107 0308 add.w r3, r7, #8 - 8000d40: 2290 movs r2, #144 ; 0x90 - 8000d42: 2100 movs r1, #0 - 8000d44: 4618 mov r0, r3 - 8000d46: f004 fbf5 bl 8005534 + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) { + 8000c20: b580 push {r7, lr} + 8000c22: b0b8 sub sp, #224 ; 0xe0 + 8000c24: af00 add r7, sp, #0 + RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; + 8000c26: f107 03ac add.w r3, r7, #172 ; 0xac + 8000c2a: 2234 movs r2, #52 ; 0x34 + 8000c2c: 2100 movs r1, #0 + 8000c2e: 4618 mov r0, r3 + 8000c30: f004 fcc2 bl 80055b8 + RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; + 8000c34: f107 0398 add.w r3, r7, #152 ; 0x98 + 8000c38: 2200 movs r2, #0 + 8000c3a: 601a str r2, [r3, #0] + 8000c3c: 605a str r2, [r3, #4] + 8000c3e: 609a str r2, [r3, #8] + 8000c40: 60da str r2, [r3, #12] + 8000c42: 611a str r2, [r3, #16] + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; + 8000c44: f107 0308 add.w r3, r7, #8 + 8000c48: 2290 movs r2, #144 ; 0x90 + 8000c4a: 2100 movs r1, #0 + 8000c4c: 4618 mov r0, r3 + 8000c4e: f004 fcb3 bl 80055b8 /** Configure the main internal regulator output voltage - */ + */ __HAL_RCC_PWR_CLK_ENABLE(); - 8000d4a: 4b36 ldr r3, [pc, #216] ; (8000e24 <_Z18SystemClock_Configv+0x10c>) - 8000d4c: 6c1b ldr r3, [r3, #64] ; 0x40 - 8000d4e: 4a35 ldr r2, [pc, #212] ; (8000e24 <_Z18SystemClock_Configv+0x10c>) - 8000d50: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8000d54: 6413 str r3, [r2, #64] ; 0x40 - 8000d56: 4b33 ldr r3, [pc, #204] ; (8000e24 <_Z18SystemClock_Configv+0x10c>) - 8000d58: 6c1b ldr r3, [r3, #64] ; 0x40 - 8000d5a: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8000d5e: 607b str r3, [r7, #4] - 8000d60: 687b ldr r3, [r7, #4] + 8000c52: 4b36 ldr r3, [pc, #216] ; (8000d2c <_Z18SystemClock_Configv+0x10c>) + 8000c54: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000c56: 4a35 ldr r2, [pc, #212] ; (8000d2c <_Z18SystemClock_Configv+0x10c>) + 8000c58: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8000c5c: 6413 str r3, [r2, #64] ; 0x40 + 8000c5e: 4b33 ldr r3, [pc, #204] ; (8000d2c <_Z18SystemClock_Configv+0x10c>) + 8000c60: 6c1b ldr r3, [r3, #64] ; 0x40 + 8000c62: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8000c66: 607b str r3, [r7, #4] + 8000c68: 687b ldr r3, [r7, #4] __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3); - 8000d62: 4b31 ldr r3, [pc, #196] ; (8000e28 <_Z18SystemClock_Configv+0x110>) - 8000d64: 681b ldr r3, [r3, #0] - 8000d66: f423 4340 bic.w r3, r3, #49152 ; 0xc000 - 8000d6a: 4a2f ldr r2, [pc, #188] ; (8000e28 <_Z18SystemClock_Configv+0x110>) - 8000d6c: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 8000d70: 6013 str r3, [r2, #0] - 8000d72: 4b2d ldr r3, [pc, #180] ; (8000e28 <_Z18SystemClock_Configv+0x110>) - 8000d74: 681b ldr r3, [r3, #0] - 8000d76: f403 4340 and.w r3, r3, #49152 ; 0xc000 - 8000d7a: 603b str r3, [r7, #0] - 8000d7c: 683b ldr r3, [r7, #0] + 8000c6a: 4b31 ldr r3, [pc, #196] ; (8000d30 <_Z18SystemClock_Configv+0x110>) + 8000c6c: 681b ldr r3, [r3, #0] + 8000c6e: f423 4340 bic.w r3, r3, #49152 ; 0xc000 + 8000c72: 4a2f ldr r2, [pc, #188] ; (8000d30 <_Z18SystemClock_Configv+0x110>) + 8000c74: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8000c78: 6013 str r3, [r2, #0] + 8000c7a: 4b2d ldr r3, [pc, #180] ; (8000d30 <_Z18SystemClock_Configv+0x110>) + 8000c7c: 681b ldr r3, [r3, #0] + 8000c7e: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8000c82: 603b str r3, [r7, #0] + 8000c84: 683b ldr r3, [r7, #0] /** Initializes the CPU, AHB and APB busses clocks - */ + */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; - 8000d7e: 2302 movs r3, #2 - 8000d80: f8c7 30ac str.w r3, [r7, #172] ; 0xac + 8000c86: 2302 movs r3, #2 + 8000c88: f8c7 30ac str.w r3, [r7, #172] ; 0xac RCC_OscInitStruct.HSIState = RCC_HSI_ON; - 8000d84: 2301 movs r3, #1 - 8000d86: f8c7 30b8 str.w r3, [r7, #184] ; 0xb8 + 8000c8c: 2301 movs r3, #1 + 8000c8e: f8c7 30b8 str.w r3, [r7, #184] ; 0xb8 RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; - 8000d8a: 2310 movs r3, #16 - 8000d8c: f8c7 30bc str.w r3, [r7, #188] ; 0xbc + 8000c92: 2310 movs r3, #16 + 8000c94: f8c7 30bc str.w r3, [r7, #188] ; 0xbc RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - 8000d90: 2300 movs r3, #0 - 8000d92: f8c7 30c4 str.w r3, [r7, #196] ; 0xc4 - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) - 8000d96: f107 03ac add.w r3, r7, #172 ; 0xac - 8000d9a: 4618 mov r0, r3 - 8000d9c: f001 faf2 bl 8002384 - 8000da0: 4603 mov r3, r0 - 8000da2: 2b00 cmp r3, #0 - 8000da4: bf14 ite ne - 8000da6: 2301 movne r3, #1 - 8000da8: 2300 moveq r3, #0 - 8000daa: b2db uxtb r3, r3 - 8000dac: 2b00 cmp r3, #0 - 8000dae: d001 beq.n 8000db4 <_Z18SystemClock_Configv+0x9c> - { + 8000c98: 2300 movs r3, #0 + 8000c9a: f8c7 30c4 str.w r3, [r7, #196] ; 0xc4 + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + 8000c9e: f107 03ac add.w r3, r7, #172 ; 0xac + 8000ca2: 4618 mov r0, r3 + 8000ca4: f001 fbb0 bl 8002408 + 8000ca8: 4603 mov r3, r0 + 8000caa: 2b00 cmp r3, #0 + 8000cac: bf14 ite ne + 8000cae: 2301 movne r3, #1 + 8000cb0: 2300 moveq r3, #0 + 8000cb2: b2db uxtb r3, r3 + 8000cb4: 2b00 cmp r3, #0 + 8000cb6: d001 beq.n 8000cbc <_Z18SystemClock_Configv+0x9c> Error_Handler(); - 8000db0: f000 fcc0 bl 8001734 + 8000cb8: f000 fd88 bl 80017cc } /** Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK - 8000db4: 230f movs r3, #15 - 8000db6: f8c7 3098 str.w r3, [r7, #152] ; 0x98 - |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK + 8000cbc: 230f movs r3, #15 + 8000cbe: f8c7 3098 str.w r3, [r7, #152] ; 0x98 + | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; - 8000dba: 2300 movs r3, #0 - 8000dbc: f8c7 309c str.w r3, [r7, #156] ; 0x9c + 8000cc2: 2300 movs r3, #0 + 8000cc4: f8c7 309c str.w r3, [r7, #156] ; 0x9c RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - 8000dc0: 2300 movs r3, #0 - 8000dc2: f8c7 30a0 str.w r3, [r7, #160] ; 0xa0 + 8000cc8: 2300 movs r3, #0 + 8000cca: f8c7 30a0 str.w r3, [r7, #160] ; 0xa0 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; - 8000dc6: 2300 movs r3, #0 - 8000dc8: f8c7 30a4 str.w r3, [r7, #164] ; 0xa4 + 8000cce: 2300 movs r3, #0 + 8000cd0: f8c7 30a4 str.w r3, [r7, #164] ; 0xa4 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - 8000dcc: 2300 movs r3, #0 - 8000dce: f8c7 30a8 str.w r3, [r7, #168] ; 0xa8 - - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) - 8000dd2: f107 0398 add.w r3, r7, #152 ; 0x98 - 8000dd6: 2100 movs r1, #0 - 8000dd8: 4618 mov r0, r3 - 8000dda: f001 fd45 bl 8002868 - 8000dde: 4603 mov r3, r0 - 8000de0: 2b00 cmp r3, #0 - 8000de2: bf14 ite ne - 8000de4: 2301 movne r3, #1 - 8000de6: 2300 moveq r3, #0 - 8000de8: b2db uxtb r3, r3 - 8000dea: 2b00 cmp r3, #0 - 8000dec: d001 beq.n 8000df2 <_Z18SystemClock_Configv+0xda> - { + 8000cd4: 2300 movs r3, #0 + 8000cd6: f8c7 30a8 str.w r3, [r7, #168] ; 0xa8 + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { + 8000cda: f107 0398 add.w r3, r7, #152 ; 0x98 + 8000cde: 2100 movs r1, #0 + 8000ce0: 4618 mov r0, r3 + 8000ce2: f001 fe03 bl 80028ec + 8000ce6: 4603 mov r3, r0 + 8000ce8: 2b00 cmp r3, #0 + 8000cea: bf14 ite ne + 8000cec: 2301 movne r3, #1 + 8000cee: 2300 moveq r3, #0 + 8000cf0: b2db uxtb r3, r3 + 8000cf2: 2b00 cmp r3, #0 + 8000cf4: d001 beq.n 8000cfa <_Z18SystemClock_Configv+0xda> Error_Handler(); - 8000dee: f000 fca1 bl 8001734 + 8000cf6: f000 fd69 bl 80017cc } PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART6; - 8000df2: f44f 6300 mov.w r3, #2048 ; 0x800 - 8000df6: 60bb str r3, [r7, #8] + 8000cfa: f44f 6300 mov.w r3, #2048 ; 0x800 + 8000cfe: 60bb str r3, [r7, #8] PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - 8000df8: 2300 movs r3, #0 - 8000dfa: 663b str r3, [r7, #96] ; 0x60 - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - 8000dfc: f107 0308 add.w r3, r7, #8 - 8000e00: 4618 mov r0, r3 - 8000e02: f001 feff bl 8002c04 - 8000e06: 4603 mov r3, r0 - 8000e08: 2b00 cmp r3, #0 - 8000e0a: bf14 ite ne - 8000e0c: 2301 movne r3, #1 - 8000e0e: 2300 moveq r3, #0 - 8000e10: b2db uxtb r3, r3 - 8000e12: 2b00 cmp r3, #0 - 8000e14: d001 beq.n 8000e1a <_Z18SystemClock_Configv+0x102> - { + 8000d00: 2300 movs r3, #0 + 8000d02: 663b str r3, [r7, #96] ; 0x60 + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + 8000d04: f107 0308 add.w r3, r7, #8 + 8000d08: 4618 mov r0, r3 + 8000d0a: f001 ffbd bl 8002c88 + 8000d0e: 4603 mov r3, r0 + 8000d10: 2b00 cmp r3, #0 + 8000d12: bf14 ite ne + 8000d14: 2301 movne r3, #1 + 8000d16: 2300 moveq r3, #0 + 8000d18: b2db uxtb r3, r3 + 8000d1a: 2b00 cmp r3, #0 + 8000d1c: d001 beq.n 8000d22 <_Z18SystemClock_Configv+0x102> Error_Handler(); - 8000e16: f000 fc8d bl 8001734 + 8000d1e: f000 fd55 bl 80017cc } } - 8000e1a: bf00 nop - 8000e1c: 37e0 adds r7, #224 ; 0xe0 - 8000e1e: 46bd mov sp, r7 - 8000e20: bd80 pop {r7, pc} - 8000e22: bf00 nop - 8000e24: 40023800 .word 0x40023800 - 8000e28: 40007000 .word 0x40007000 - -08000e2c <_ZL12MX_NVIC_Initv>: + 8000d22: bf00 nop + 8000d24: 37e0 adds r7, #224 ; 0xe0 + 8000d26: 46bd mov sp, r7 + 8000d28: bd80 pop {r7, pc} + 8000d2a: bf00 nop + 8000d2c: 40023800 .word 0x40023800 + 8000d30: 40007000 .word 0x40007000 + +08000d34 <_ZL12MX_NVIC_Initv>: + /** - * @brief NVIC Configuration. - * @retval None - */ -static void MX_NVIC_Init(void) -{ - 8000e2c: b580 push {r7, lr} - 8000e2e: af00 add r7, sp, #0 + * @brief NVIC Configuration. + * @retval None + */ +static void MX_NVIC_Init(void) { + 8000d34: b580 push {r7, lr} + 8000d36: af00 add r7, sp, #0 /* TIM3_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM3_IRQn, 2, 1); - 8000e30: 2201 movs r2, #1 - 8000e32: 2102 movs r1, #2 - 8000e34: 201d movs r0, #29 - 8000e36: f001 f870 bl 8001f1a + 8000d38: 2201 movs r2, #1 + 8000d3a: 2102 movs r1, #2 + 8000d3c: 201d movs r0, #29 + 8000d3e: f001 f92e bl 8001f9e HAL_NVIC_EnableIRQ(TIM3_IRQn); - 8000e3a: 201d movs r0, #29 - 8000e3c: f001 f889 bl 8001f52 + 8000d42: 201d movs r0, #29 + 8000d44: f001 f947 bl 8001fd6 /* TIM6_DAC_IRQn interrupt configuration */ HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 2, 2); - 8000e40: 2202 movs r2, #2 - 8000e42: 2102 movs r1, #2 - 8000e44: 2036 movs r0, #54 ; 0x36 - 8000e46: f001 f868 bl 8001f1a + 8000d48: 2202 movs r2, #2 + 8000d4a: 2102 movs r1, #2 + 8000d4c: 2036 movs r0, #54 ; 0x36 + 8000d4e: f001 f926 bl 8001f9e HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); - 8000e4a: 2036 movs r0, #54 ; 0x36 - 8000e4c: f001 f881 bl 8001f52 + 8000d52: 2036 movs r0, #54 ; 0x36 + 8000d54: f001 f93f bl 8001fd6 /* USART6_IRQn interrupt configuration */ HAL_NVIC_SetPriority(USART6_IRQn, 2, 0); - 8000e50: 2200 movs r2, #0 - 8000e52: 2102 movs r1, #2 - 8000e54: 2047 movs r0, #71 ; 0x47 - 8000e56: f001 f860 bl 8001f1a + 8000d58: 2200 movs r2, #0 + 8000d5a: 2102 movs r1, #2 + 8000d5c: 2047 movs r0, #71 ; 0x47 + 8000d5e: f001 f91e bl 8001f9e HAL_NVIC_EnableIRQ(USART6_IRQn); - 8000e5a: 2047 movs r0, #71 ; 0x47 - 8000e5c: f001 f879 bl 8001f52 + 8000d62: 2047 movs r0, #71 ; 0x47 + 8000d64: f001 f937 bl 8001fd6 } - 8000e60: bf00 nop - 8000e62: bd80 pop {r7, pc} + 8000d68: bf00 nop + 8000d6a: bd80 pop {r7, pc} -08000e64 <_ZL12MX_TIM2_Initv>: - * @brief TIM2 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM2_Init(void) -{ - 8000e64: b580 push {r7, lr} - 8000e66: b08c sub sp, #48 ; 0x30 - 8000e68: af00 add r7, sp, #0 +08000d6c <_ZL12MX_TIM2_Initv>: +/** + * @brief TIM2 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM2_Init(void) { + 8000d6c: b580 push {r7, lr} + 8000d6e: b08c sub sp, #48 ; 0x30 + 8000d70: af00 add r7, sp, #0 /* USER CODE BEGIN TIM2_Init 0 */ /* USER CODE END TIM2_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = {0}; - 8000e6a: f107 030c add.w r3, r7, #12 - 8000e6e: 2224 movs r2, #36 ; 0x24 - 8000e70: 2100 movs r1, #0 - 8000e72: 4618 mov r0, r3 - 8000e74: f004 fb5e bl 8005534 - TIM_MasterConfigTypeDef sMasterConfig = {0}; - 8000e78: 463b mov r3, r7 - 8000e7a: 2200 movs r2, #0 - 8000e7c: 601a str r2, [r3, #0] - 8000e7e: 605a str r2, [r3, #4] - 8000e80: 609a str r2, [r3, #8] + TIM_Encoder_InitTypeDef sConfig = { 0 }; + 8000d72: f107 030c add.w r3, r7, #12 + 8000d76: 2224 movs r2, #36 ; 0x24 + 8000d78: 2100 movs r1, #0 + 8000d7a: 4618 mov r0, r3 + 8000d7c: f004 fc1c bl 80055b8 + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000d80: 463b mov r3, r7 + 8000d82: 2200 movs r2, #0 + 8000d84: 601a str r2, [r3, #0] + 8000d86: 605a str r2, [r3, #4] + 8000d88: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM2_Init 1 */ /* USER CODE END TIM2_Init 1 */ htim2.Instance = TIM2; - 8000e82: 4b26 ldr r3, [pc, #152] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000e84: f04f 4280 mov.w r2, #1073741824 ; 0x40000000 - 8000e88: 601a str r2, [r3, #0] + 8000d8a: 4b26 ldr r3, [pc, #152] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000d8c: f04f 4280 mov.w r2, #1073741824 ; 0x40000000 + 8000d90: 601a str r2, [r3, #0] htim2.Init.Prescaler = 0; - 8000e8a: 4b24 ldr r3, [pc, #144] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000e8c: 2200 movs r2, #0 - 8000e8e: 605a str r2, [r3, #4] + 8000d92: 4b24 ldr r3, [pc, #144] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000d94: 2200 movs r2, #0 + 8000d96: 605a str r2, [r3, #4] htim2.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000e90: 4b22 ldr r3, [pc, #136] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000e92: 2200 movs r2, #0 - 8000e94: 609a str r2, [r3, #8] + 8000d98: 4b22 ldr r3, [pc, #136] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000d9a: 2200 movs r2, #0 + 8000d9c: 609a str r2, [r3, #8] htim2.Init.Period = 4294967295; - 8000e96: 4b21 ldr r3, [pc, #132] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000e98: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8000e9c: 60da str r2, [r3, #12] + 8000d9e: 4b21 ldr r3, [pc, #132] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000da0: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8000da4: 60da str r2, [r3, #12] htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000e9e: 4b1f ldr r3, [pc, #124] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000ea0: 2200 movs r2, #0 - 8000ea2: 611a str r2, [r3, #16] + 8000da6: 4b1f ldr r3, [pc, #124] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000da8: 2200 movs r2, #0 + 8000daa: 611a str r2, [r3, #16] htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000ea4: 4b1d ldr r3, [pc, #116] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000ea6: 2200 movs r2, #0 - 8000ea8: 619a str r2, [r3, #24] + 8000dac: 4b1d ldr r3, [pc, #116] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000dae: 2200 movs r2, #0 + 8000db0: 619a str r2, [r3, #24] sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - 8000eaa: 2303 movs r3, #3 - 8000eac: 60fb str r3, [r7, #12] + 8000db2: 2303 movs r3, #3 + 8000db4: 60fb str r3, [r7, #12] sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - 8000eae: 2300 movs r3, #0 - 8000eb0: 613b str r3, [r7, #16] + 8000db6: 2300 movs r3, #0 + 8000db8: 613b str r3, [r7, #16] sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - 8000eb2: 2301 movs r3, #1 - 8000eb4: 617b str r3, [r7, #20] + 8000dba: 2301 movs r3, #1 + 8000dbc: 617b str r3, [r7, #20] sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - 8000eb6: 2300 movs r3, #0 - 8000eb8: 61bb str r3, [r7, #24] + 8000dbe: 2300 movs r3, #0 + 8000dc0: 61bb str r3, [r7, #24] sConfig.IC1Filter = 0; - 8000eba: 2300 movs r3, #0 - 8000ebc: 61fb str r3, [r7, #28] + 8000dc2: 2300 movs r3, #0 + 8000dc4: 61fb str r3, [r7, #28] sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - 8000ebe: 2300 movs r3, #0 - 8000ec0: 623b str r3, [r7, #32] + 8000dc6: 2300 movs r3, #0 + 8000dc8: 623b str r3, [r7, #32] sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - 8000ec2: 2301 movs r3, #1 - 8000ec4: 627b str r3, [r7, #36] ; 0x24 + 8000dca: 2301 movs r3, #1 + 8000dcc: 627b str r3, [r7, #36] ; 0x24 sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - 8000ec6: 2300 movs r3, #0 - 8000ec8: 62bb str r3, [r7, #40] ; 0x28 + 8000dce: 2300 movs r3, #0 + 8000dd0: 62bb str r3, [r7, #40] ; 0x28 sConfig.IC2Filter = 0; - 8000eca: 2300 movs r3, #0 - 8000ecc: 62fb str r3, [r7, #44] ; 0x2c - if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) - 8000ece: f107 030c add.w r3, r7, #12 - 8000ed2: 4619 mov r1, r3 - 8000ed4: 4811 ldr r0, [pc, #68] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000ed6: f002 fb8b bl 80035f0 - 8000eda: 4603 mov r3, r0 - 8000edc: 2b00 cmp r3, #0 - 8000ede: bf14 ite ne - 8000ee0: 2301 movne r3, #1 - 8000ee2: 2300 moveq r3, #0 - 8000ee4: b2db uxtb r3, r3 - 8000ee6: 2b00 cmp r3, #0 - 8000ee8: d001 beq.n 8000eee <_ZL12MX_TIM2_Initv+0x8a> - { + 8000dd2: 2300 movs r3, #0 + 8000dd4: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK) { + 8000dd6: f107 030c add.w r3, r7, #12 + 8000dda: 4619 mov r1, r3 + 8000ddc: 4811 ldr r0, [pc, #68] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000dde: f002 fc49 bl 8003674 + 8000de2: 4603 mov r3, r0 + 8000de4: 2b00 cmp r3, #0 + 8000de6: bf14 ite ne + 8000de8: 2301 movne r3, #1 + 8000dea: 2300 moveq r3, #0 + 8000dec: b2db uxtb r3, r3 + 8000dee: 2b00 cmp r3, #0 + 8000df0: d001 beq.n 8000df6 <_ZL12MX_TIM2_Initv+0x8a> Error_Handler(); - 8000eea: f000 fc23 bl 8001734 + 8000df2: f000 fceb bl 80017cc } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8000eee: 2300 movs r3, #0 - 8000ef0: 603b str r3, [r7, #0] + 8000df6: 2300 movs r3, #0 + 8000df8: 603b str r3, [r7, #0] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8000ef2: 2300 movs r3, #0 - 8000ef4: 60bb str r3, [r7, #8] - if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) - 8000ef6: 463b mov r3, r7 - 8000ef8: 4619 mov r1, r3 - 8000efa: 4808 ldr r0, [pc, #32] ; (8000f1c <_ZL12MX_TIM2_Initv+0xb8>) - 8000efc: f003 fb18 bl 8004530 - 8000f00: 4603 mov r3, r0 - 8000f02: 2b00 cmp r3, #0 - 8000f04: bf14 ite ne - 8000f06: 2301 movne r3, #1 - 8000f08: 2300 moveq r3, #0 - 8000f0a: b2db uxtb r3, r3 - 8000f0c: 2b00 cmp r3, #0 - 8000f0e: d001 beq.n 8000f14 <_ZL12MX_TIM2_Initv+0xb0> - { + 8000dfa: 2300 movs r3, #0 + 8000dfc: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK) { + 8000dfe: 463b mov r3, r7 + 8000e00: 4619 mov r1, r3 + 8000e02: 4808 ldr r0, [pc, #32] ; (8000e24 <_ZL12MX_TIM2_Initv+0xb8>) + 8000e04: f003 fbd6 bl 80045b4 + 8000e08: 4603 mov r3, r0 + 8000e0a: 2b00 cmp r3, #0 + 8000e0c: bf14 ite ne + 8000e0e: 2301 movne r3, #1 + 8000e10: 2300 moveq r3, #0 + 8000e12: b2db uxtb r3, r3 + 8000e14: 2b00 cmp r3, #0 + 8000e16: d001 beq.n 8000e1c <_ZL12MX_TIM2_Initv+0xb0> Error_Handler(); - 8000f10: f000 fc10 bl 8001734 + 8000e18: f000 fcd8 bl 80017cc } /* USER CODE BEGIN TIM2_Init 2 */ /* USER CODE END TIM2_Init 2 */ } - 8000f14: bf00 nop - 8000f16: 3730 adds r7, #48 ; 0x30 - 8000f18: 46bd mov sp, r7 - 8000f1a: bd80 pop {r7, pc} - 8000f1c: 2000002c .word 0x2000002c - -08000f20 <_ZL12MX_TIM3_Initv>: - * @brief TIM3 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM3_Init(void) -{ - 8000f20: b580 push {r7, lr} - 8000f22: b088 sub sp, #32 - 8000f24: af00 add r7, sp, #0 + 8000e1c: bf00 nop + 8000e1e: 3730 adds r7, #48 ; 0x30 + 8000e20: 46bd mov sp, r7 + 8000e22: bd80 pop {r7, pc} + 8000e24: 2000002c .word 0x2000002c + +08000e28 <_ZL12MX_TIM3_Initv>: +/** + * @brief TIM3 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM3_Init(void) { + 8000e28: b580 push {r7, lr} + 8000e2a: b088 sub sp, #32 + 8000e2c: af00 add r7, sp, #0 /* USER CODE BEGIN TIM3_Init 0 */ /* USER CODE END TIM3_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = {0}; - 8000f26: f107 0310 add.w r3, r7, #16 - 8000f2a: 2200 movs r2, #0 - 8000f2c: 601a str r2, [r3, #0] - 8000f2e: 605a str r2, [r3, #4] - 8000f30: 609a str r2, [r3, #8] - 8000f32: 60da str r2, [r3, #12] - TIM_MasterConfigTypeDef sMasterConfig = {0}; - 8000f34: 1d3b adds r3, r7, #4 - 8000f36: 2200 movs r2, #0 - 8000f38: 601a str r2, [r3, #0] - 8000f3a: 605a str r2, [r3, #4] - 8000f3c: 609a str r2, [r3, #8] + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + 8000e2e: f107 0310 add.w r3, r7, #16 + 8000e32: 2200 movs r2, #0 + 8000e34: 601a str r2, [r3, #0] + 8000e36: 605a str r2, [r3, #4] + 8000e38: 609a str r2, [r3, #8] + 8000e3a: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000e3c: 1d3b adds r3, r7, #4 + 8000e3e: 2200 movs r2, #0 + 8000e40: 601a str r2, [r3, #0] + 8000e42: 605a str r2, [r3, #4] + 8000e44: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM3_Init 1 */ /* USER CODE END TIM3_Init 1 */ htim3.Instance = TIM3; - 8000f3e: 4b25 ldr r3, [pc, #148] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f40: 4a25 ldr r2, [pc, #148] ; (8000fd8 <_ZL12MX_TIM3_Initv+0xb8>) - 8000f42: 601a str r2, [r3, #0] + 8000e46: 4b25 ldr r3, [pc, #148] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e48: 4a25 ldr r2, [pc, #148] ; (8000ee0 <_ZL12MX_TIM3_Initv+0xb8>) + 8000e4a: 601a str r2, [r3, #0] htim3.Init.Prescaler = 999; - 8000f44: 4b23 ldr r3, [pc, #140] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f46: f240 32e7 movw r2, #999 ; 0x3e7 - 8000f4a: 605a str r2, [r3, #4] + 8000e4c: 4b23 ldr r3, [pc, #140] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e4e: f240 32e7 movw r2, #999 ; 0x3e7 + 8000e52: 605a str r2, [r3, #4] htim3.Init.CounterMode = TIM_COUNTERMODE_UP; - 8000f4c: 4b21 ldr r3, [pc, #132] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f4e: 2200 movs r2, #0 - 8000f50: 609a str r2, [r3, #8] + 8000e54: 4b21 ldr r3, [pc, #132] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e56: 2200 movs r2, #0 + 8000e58: 609a str r2, [r3, #8] htim3.Init.Period = 159; - 8000f52: 4b20 ldr r3, [pc, #128] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f54: 229f movs r2, #159 ; 0x9f - 8000f56: 60da str r2, [r3, #12] + 8000e5a: 4b20 ldr r3, [pc, #128] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e5c: 229f movs r2, #159 ; 0x9f + 8000e5e: 60da str r2, [r3, #12] htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8000f58: 4b1e ldr r3, [pc, #120] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f5a: 2200 movs r2, #0 - 8000f5c: 611a str r2, [r3, #16] + 8000e60: 4b1e ldr r3, [pc, #120] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e62: 2200 movs r2, #0 + 8000e64: 611a str r2, [r3, #16] htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8000f5e: 4b1d ldr r3, [pc, #116] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f60: 2200 movs r2, #0 - 8000f62: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim3) != HAL_OK) - 8000f64: 481b ldr r0, [pc, #108] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f66: f002 fa73 bl 8003450 - 8000f6a: 4603 mov r3, r0 - 8000f6c: 2b00 cmp r3, #0 - 8000f6e: bf14 ite ne - 8000f70: 2301 movne r3, #1 - 8000f72: 2300 moveq r3, #0 - 8000f74: b2db uxtb r3, r3 - 8000f76: 2b00 cmp r3, #0 - 8000f78: d001 beq.n 8000f7e <_ZL12MX_TIM3_Initv+0x5e> - { + 8000e66: 4b1d ldr r3, [pc, #116] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e68: 2200 movs r2, #0 + 8000e6a: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim3) != HAL_OK) { + 8000e6c: 481b ldr r0, [pc, #108] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e6e: f002 fb31 bl 80034d4 + 8000e72: 4603 mov r3, r0 + 8000e74: 2b00 cmp r3, #0 + 8000e76: bf14 ite ne + 8000e78: 2301 movne r3, #1 + 8000e7a: 2300 moveq r3, #0 + 8000e7c: b2db uxtb r3, r3 + 8000e7e: 2b00 cmp r3, #0 + 8000e80: d001 beq.n 8000e86 <_ZL12MX_TIM3_Initv+0x5e> Error_Handler(); - 8000f7a: f000 fbdb bl 8001734 + 8000e82: f000 fca3 bl 80017cc } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - 8000f7e: f44f 5380 mov.w r3, #4096 ; 0x1000 - 8000f82: 613b str r3, [r7, #16] - if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) - 8000f84: f107 0310 add.w r3, r7, #16 - 8000f88: 4619 mov r1, r3 - 8000f8a: 4812 ldr r0, [pc, #72] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000f8c: f002 fe30 bl 8003bf0 - 8000f90: 4603 mov r3, r0 - 8000f92: 2b00 cmp r3, #0 - 8000f94: bf14 ite ne - 8000f96: 2301 movne r3, #1 - 8000f98: 2300 moveq r3, #0 - 8000f9a: b2db uxtb r3, r3 - 8000f9c: 2b00 cmp r3, #0 - 8000f9e: d001 beq.n 8000fa4 <_ZL12MX_TIM3_Initv+0x84> - { + 8000e86: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8000e8a: 613b str r3, [r7, #16] + if (HAL_TIM_ConfigClockSource(&htim3, &sClockSourceConfig) != HAL_OK) { + 8000e8c: f107 0310 add.w r3, r7, #16 + 8000e90: 4619 mov r1, r3 + 8000e92: 4812 ldr r0, [pc, #72] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000e94: f002 feee bl 8003c74 + 8000e98: 4603 mov r3, r0 + 8000e9a: 2b00 cmp r3, #0 + 8000e9c: bf14 ite ne + 8000e9e: 2301 movne r3, #1 + 8000ea0: 2300 moveq r3, #0 + 8000ea2: b2db uxtb r3, r3 + 8000ea4: 2b00 cmp r3, #0 + 8000ea6: d001 beq.n 8000eac <_ZL12MX_TIM3_Initv+0x84> Error_Handler(); - 8000fa0: f000 fbc8 bl 8001734 + 8000ea8: f000 fc90 bl 80017cc } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8000fa4: 2300 movs r3, #0 - 8000fa6: 607b str r3, [r7, #4] + 8000eac: 2300 movs r3, #0 + 8000eae: 607b str r3, [r7, #4] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8000fa8: 2300 movs r3, #0 - 8000faa: 60fb str r3, [r7, #12] - if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) - 8000fac: 1d3b adds r3, r7, #4 - 8000fae: 4619 mov r1, r3 - 8000fb0: 4808 ldr r0, [pc, #32] ; (8000fd4 <_ZL12MX_TIM3_Initv+0xb4>) - 8000fb2: f003 fabd bl 8004530 - 8000fb6: 4603 mov r3, r0 - 8000fb8: 2b00 cmp r3, #0 - 8000fba: bf14 ite ne - 8000fbc: 2301 movne r3, #1 - 8000fbe: 2300 moveq r3, #0 - 8000fc0: b2db uxtb r3, r3 - 8000fc2: 2b00 cmp r3, #0 - 8000fc4: d001 beq.n 8000fca <_ZL12MX_TIM3_Initv+0xaa> - { + 8000eb0: 2300 movs r3, #0 + 8000eb2: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK) { + 8000eb4: 1d3b adds r3, r7, #4 + 8000eb6: 4619 mov r1, r3 + 8000eb8: 4808 ldr r0, [pc, #32] ; (8000edc <_ZL12MX_TIM3_Initv+0xb4>) + 8000eba: f003 fb7b bl 80045b4 + 8000ebe: 4603 mov r3, r0 + 8000ec0: 2b00 cmp r3, #0 + 8000ec2: bf14 ite ne + 8000ec4: 2301 movne r3, #1 + 8000ec6: 2300 moveq r3, #0 + 8000ec8: b2db uxtb r3, r3 + 8000eca: 2b00 cmp r3, #0 + 8000ecc: d001 beq.n 8000ed2 <_ZL12MX_TIM3_Initv+0xaa> Error_Handler(); - 8000fc6: f000 fbb5 bl 8001734 + 8000ece: f000 fc7d bl 80017cc } /* USER CODE BEGIN TIM3_Init 2 */ /* USER CODE END TIM3_Init 2 */ } - 8000fca: bf00 nop - 8000fcc: 3720 adds r7, #32 - 8000fce: 46bd mov sp, r7 - 8000fd0: bd80 pop {r7, pc} - 8000fd2: bf00 nop - 8000fd4: 2000006c .word 0x2000006c - 8000fd8: 40000400 .word 0x40000400 - -08000fdc <_ZL12MX_TIM4_Initv>: - * @brief TIM4 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM4_Init(void) -{ - 8000fdc: b580 push {r7, lr} - 8000fde: b08e sub sp, #56 ; 0x38 - 8000fe0: af00 add r7, sp, #0 + 8000ed2: bf00 nop + 8000ed4: 3720 adds r7, #32 + 8000ed6: 46bd mov sp, r7 + 8000ed8: bd80 pop {r7, pc} + 8000eda: bf00 nop + 8000edc: 2000006c .word 0x2000006c + 8000ee0: 40000400 .word 0x40000400 + +08000ee4 <_ZL12MX_TIM4_Initv>: +/** + * @brief TIM4 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM4_Init(void) { + 8000ee4: b580 push {r7, lr} + 8000ee6: b08e sub sp, #56 ; 0x38 + 8000ee8: af00 add r7, sp, #0 /* USER CODE BEGIN TIM4_Init 0 */ /* USER CODE END TIM4_Init 0 */ - TIM_ClockConfigTypeDef sClockSourceConfig = {0}; - 8000fe2: f107 0328 add.w r3, r7, #40 ; 0x28 - 8000fe6: 2200 movs r2, #0 - 8000fe8: 601a str r2, [r3, #0] - 8000fea: 605a str r2, [r3, #4] - 8000fec: 609a str r2, [r3, #8] - 8000fee: 60da str r2, [r3, #12] - TIM_MasterConfigTypeDef sMasterConfig = {0}; - 8000ff0: f107 031c add.w r3, r7, #28 - 8000ff4: 2200 movs r2, #0 - 8000ff6: 601a str r2, [r3, #0] - 8000ff8: 605a str r2, [r3, #4] - 8000ffa: 609a str r2, [r3, #8] - TIM_OC_InitTypeDef sConfigOC = {0}; - 8000ffc: 463b mov r3, r7 - 8000ffe: 2200 movs r2, #0 - 8001000: 601a str r2, [r3, #0] - 8001002: 605a str r2, [r3, #4] - 8001004: 609a str r2, [r3, #8] - 8001006: 60da str r2, [r3, #12] - 8001008: 611a str r2, [r3, #16] - 800100a: 615a str r2, [r3, #20] - 800100c: 619a str r2, [r3, #24] + TIM_ClockConfigTypeDef sClockSourceConfig = { 0 }; + 8000eea: f107 0328 add.w r3, r7, #40 ; 0x28 + 8000eee: 2200 movs r2, #0 + 8000ef0: 601a str r2, [r3, #0] + 8000ef2: 605a str r2, [r3, #4] + 8000ef4: 609a str r2, [r3, #8] + 8000ef6: 60da str r2, [r3, #12] + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8000ef8: f107 031c add.w r3, r7, #28 + 8000efc: 2200 movs r2, #0 + 8000efe: 601a str r2, [r3, #0] + 8000f00: 605a str r2, [r3, #4] + 8000f02: 609a str r2, [r3, #8] + TIM_OC_InitTypeDef sConfigOC = { 0 }; + 8000f04: 463b mov r3, r7 + 8000f06: 2200 movs r2, #0 + 8000f08: 601a str r2, [r3, #0] + 8000f0a: 605a str r2, [r3, #4] + 8000f0c: 609a str r2, [r3, #8] + 8000f0e: 60da str r2, [r3, #12] + 8000f10: 611a str r2, [r3, #16] + 8000f12: 615a str r2, [r3, #20] + 8000f14: 619a str r2, [r3, #24] /* USER CODE BEGIN TIM4_Init 1 */ /* USER CODE END TIM4_Init 1 */ htim4.Instance = TIM4; - 800100e: 4b41 ldr r3, [pc, #260] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001010: 4a41 ldr r2, [pc, #260] ; (8001118 <_ZL12MX_TIM4_Initv+0x13c>) - 8001012: 601a str r2, [r3, #0] + 8000f16: 4b41 ldr r3, [pc, #260] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f18: 4a41 ldr r2, [pc, #260] ; (8001020 <_ZL12MX_TIM4_Initv+0x13c>) + 8000f1a: 601a str r2, [r3, #0] htim4.Init.Prescaler = 0; - 8001014: 4b3f ldr r3, [pc, #252] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001016: 2200 movs r2, #0 - 8001018: 605a str r2, [r3, #4] + 8000f1c: 4b3f ldr r3, [pc, #252] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f1e: 2200 movs r2, #0 + 8000f20: 605a str r2, [r3, #4] htim4.Init.CounterMode = TIM_COUNTERMODE_UP; - 800101a: 4b3e ldr r3, [pc, #248] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 800101c: 2200 movs r2, #0 - 800101e: 609a str r2, [r3, #8] + 8000f22: 4b3e ldr r3, [pc, #248] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f24: 2200 movs r2, #0 + 8000f26: 609a str r2, [r3, #8] htim4.Init.Period = 799; - 8001020: 4b3c ldr r3, [pc, #240] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001022: f240 321f movw r2, #799 ; 0x31f - 8001026: 60da str r2, [r3, #12] + 8000f28: 4b3c ldr r3, [pc, #240] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f2a: f240 321f movw r2, #799 ; 0x31f + 8000f2e: 60da str r2, [r3, #12] htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8001028: 4b3a ldr r3, [pc, #232] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 800102a: 2200 movs r2, #0 - 800102c: 611a str r2, [r3, #16] + 8000f30: 4b3a ldr r3, [pc, #232] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f32: 2200 movs r2, #0 + 8000f34: 611a str r2, [r3, #16] htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 800102e: 4b39 ldr r3, [pc, #228] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001030: 2200 movs r2, #0 - 8001032: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim4) != HAL_OK) - 8001034: 4837 ldr r0, [pc, #220] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001036: f002 fa0b bl 8003450 - 800103a: 4603 mov r3, r0 - 800103c: 2b00 cmp r3, #0 - 800103e: bf14 ite ne - 8001040: 2301 movne r3, #1 - 8001042: 2300 moveq r3, #0 - 8001044: b2db uxtb r3, r3 - 8001046: 2b00 cmp r3, #0 - 8001048: d001 beq.n 800104e <_ZL12MX_TIM4_Initv+0x72> - { + 8000f36: 4b39 ldr r3, [pc, #228] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f38: 2200 movs r2, #0 + 8000f3a: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim4) != HAL_OK) { + 8000f3c: 4837 ldr r0, [pc, #220] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f3e: f002 fac9 bl 80034d4 + 8000f42: 4603 mov r3, r0 + 8000f44: 2b00 cmp r3, #0 + 8000f46: bf14 ite ne + 8000f48: 2301 movne r3, #1 + 8000f4a: 2300 moveq r3, #0 + 8000f4c: b2db uxtb r3, r3 + 8000f4e: 2b00 cmp r3, #0 + 8000f50: d001 beq.n 8000f56 <_ZL12MX_TIM4_Initv+0x72> Error_Handler(); - 800104a: f000 fb73 bl 8001734 + 8000f52: f000 fc3b bl 80017cc } sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; - 800104e: f44f 5380 mov.w r3, #4096 ; 0x1000 - 8001052: 62bb str r3, [r7, #40] ; 0x28 - if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) - 8001054: f107 0328 add.w r3, r7, #40 ; 0x28 - 8001058: 4619 mov r1, r3 - 800105a: 482e ldr r0, [pc, #184] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 800105c: f002 fdc8 bl 8003bf0 - 8001060: 4603 mov r3, r0 - 8001062: 2b00 cmp r3, #0 - 8001064: bf14 ite ne - 8001066: 2301 movne r3, #1 - 8001068: 2300 moveq r3, #0 - 800106a: b2db uxtb r3, r3 - 800106c: 2b00 cmp r3, #0 - 800106e: d001 beq.n 8001074 <_ZL12MX_TIM4_Initv+0x98> - { + 8000f56: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8000f5a: 62bb str r3, [r7, #40] ; 0x28 + if (HAL_TIM_ConfigClockSource(&htim4, &sClockSourceConfig) != HAL_OK) { + 8000f5c: f107 0328 add.w r3, r7, #40 ; 0x28 + 8000f60: 4619 mov r1, r3 + 8000f62: 482e ldr r0, [pc, #184] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f64: f002 fe86 bl 8003c74 + 8000f68: 4603 mov r3, r0 + 8000f6a: 2b00 cmp r3, #0 + 8000f6c: bf14 ite ne + 8000f6e: 2301 movne r3, #1 + 8000f70: 2300 moveq r3, #0 + 8000f72: b2db uxtb r3, r3 + 8000f74: 2b00 cmp r3, #0 + 8000f76: d001 beq.n 8000f7c <_ZL12MX_TIM4_Initv+0x98> Error_Handler(); - 8001070: f000 fb60 bl 8001734 - } - if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) - 8001074: 4827 ldr r0, [pc, #156] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001076: f002 fa41 bl 80034fc - 800107a: 4603 mov r3, r0 - 800107c: 2b00 cmp r3, #0 - 800107e: bf14 ite ne - 8001080: 2301 movne r3, #1 - 8001082: 2300 moveq r3, #0 - 8001084: b2db uxtb r3, r3 - 8001086: 2b00 cmp r3, #0 - 8001088: d001 beq.n 800108e <_ZL12MX_TIM4_Initv+0xb2> - { + 8000f78: f000 fc28 bl 80017cc + } + if (HAL_TIM_PWM_Init(&htim4) != HAL_OK) { + 8000f7c: 4827 ldr r0, [pc, #156] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000f7e: f002 faff bl 8003580 + 8000f82: 4603 mov r3, r0 + 8000f84: 2b00 cmp r3, #0 + 8000f86: bf14 ite ne + 8000f88: 2301 movne r3, #1 + 8000f8a: 2300 moveq r3, #0 + 8000f8c: b2db uxtb r3, r3 + 8000f8e: 2b00 cmp r3, #0 + 8000f90: d001 beq.n 8000f96 <_ZL12MX_TIM4_Initv+0xb2> Error_Handler(); - 800108a: f000 fb53 bl 8001734 + 8000f92: f000 fc1b bl 80017cc } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 800108e: 2300 movs r3, #0 - 8001090: 61fb str r3, [r7, #28] + 8000f96: 2300 movs r3, #0 + 8000f98: 61fb str r3, [r7, #28] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 8001092: 2300 movs r3, #0 - 8001094: 627b str r3, [r7, #36] ; 0x24 - if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) - 8001096: f107 031c add.w r3, r7, #28 - 800109a: 4619 mov r1, r3 - 800109c: 481d ldr r0, [pc, #116] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 800109e: f003 fa47 bl 8004530 - 80010a2: 4603 mov r3, r0 - 80010a4: 2b00 cmp r3, #0 - 80010a6: bf14 ite ne - 80010a8: 2301 movne r3, #1 - 80010aa: 2300 moveq r3, #0 - 80010ac: b2db uxtb r3, r3 - 80010ae: 2b00 cmp r3, #0 - 80010b0: d001 beq.n 80010b6 <_ZL12MX_TIM4_Initv+0xda> - { + 8000f9a: 2300 movs r3, #0 + 8000f9c: 627b str r3, [r7, #36] ; 0x24 + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) { + 8000f9e: f107 031c add.w r3, r7, #28 + 8000fa2: 4619 mov r1, r3 + 8000fa4: 481d ldr r0, [pc, #116] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000fa6: f003 fb05 bl 80045b4 + 8000faa: 4603 mov r3, r0 + 8000fac: 2b00 cmp r3, #0 + 8000fae: bf14 ite ne + 8000fb0: 2301 movne r3, #1 + 8000fb2: 2300 moveq r3, #0 + 8000fb4: b2db uxtb r3, r3 + 8000fb6: 2b00 cmp r3, #0 + 8000fb8: d001 beq.n 8000fbe <_ZL12MX_TIM4_Initv+0xda> Error_Handler(); - 80010b2: f000 fb3f bl 8001734 + 8000fba: f000 fc07 bl 80017cc } sConfigOC.OCMode = TIM_OCMODE_PWM1; - 80010b6: 2360 movs r3, #96 ; 0x60 - 80010b8: 603b str r3, [r7, #0] + 8000fbe: 2360 movs r3, #96 ; 0x60 + 8000fc0: 603b str r3, [r7, #0] sConfigOC.Pulse = 0; - 80010ba: 2300 movs r3, #0 - 80010bc: 607b str r3, [r7, #4] + 8000fc2: 2300 movs r3, #0 + 8000fc4: 607b str r3, [r7, #4] sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - 80010be: 2300 movs r3, #0 - 80010c0: 60bb str r3, [r7, #8] + 8000fc6: 2300 movs r3, #0 + 8000fc8: 60bb str r3, [r7, #8] sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - 80010c2: 2300 movs r3, #0 - 80010c4: 613b str r3, [r7, #16] - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) - 80010c6: 463b mov r3, r7 - 80010c8: 2208 movs r2, #8 - 80010ca: 4619 mov r1, r3 - 80010cc: 4811 ldr r0, [pc, #68] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 80010ce: f002 fc77 bl 80039c0 - 80010d2: 4603 mov r3, r0 - 80010d4: 2b00 cmp r3, #0 - 80010d6: bf14 ite ne - 80010d8: 2301 movne r3, #1 - 80010da: 2300 moveq r3, #0 - 80010dc: b2db uxtb r3, r3 - 80010de: 2b00 cmp r3, #0 - 80010e0: d001 beq.n 80010e6 <_ZL12MX_TIM4_Initv+0x10a> - { + 8000fca: 2300 movs r3, #0 + 8000fcc: 613b str r3, [r7, #16] + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) { + 8000fce: 463b mov r3, r7 + 8000fd0: 2208 movs r2, #8 + 8000fd2: 4619 mov r1, r3 + 8000fd4: 4811 ldr r0, [pc, #68] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000fd6: f002 fd35 bl 8003a44 + 8000fda: 4603 mov r3, r0 + 8000fdc: 2b00 cmp r3, #0 + 8000fde: bf14 ite ne + 8000fe0: 2301 movne r3, #1 + 8000fe2: 2300 moveq r3, #0 + 8000fe4: b2db uxtb r3, r3 + 8000fe6: 2b00 cmp r3, #0 + 8000fe8: d001 beq.n 8000fee <_ZL12MX_TIM4_Initv+0x10a> Error_Handler(); - 80010e2: f000 fb27 bl 8001734 - } - if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) - 80010e6: 463b mov r3, r7 - 80010e8: 220c movs r2, #12 - 80010ea: 4619 mov r1, r3 - 80010ec: 4809 ldr r0, [pc, #36] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 80010ee: f002 fc67 bl 80039c0 - 80010f2: 4603 mov r3, r0 - 80010f4: 2b00 cmp r3, #0 - 80010f6: bf14 ite ne - 80010f8: 2301 movne r3, #1 - 80010fa: 2300 moveq r3, #0 - 80010fc: b2db uxtb r3, r3 - 80010fe: 2b00 cmp r3, #0 - 8001100: d001 beq.n 8001106 <_ZL12MX_TIM4_Initv+0x12a> - { + 8000fea: f000 fbef bl 80017cc + } + if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK) { + 8000fee: 463b mov r3, r7 + 8000ff0: 220c movs r2, #12 + 8000ff2: 4619 mov r1, r3 + 8000ff4: 4809 ldr r0, [pc, #36] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8000ff6: f002 fd25 bl 8003a44 + 8000ffa: 4603 mov r3, r0 + 8000ffc: 2b00 cmp r3, #0 + 8000ffe: bf14 ite ne + 8001000: 2301 movne r3, #1 + 8001002: 2300 moveq r3, #0 + 8001004: b2db uxtb r3, r3 + 8001006: 2b00 cmp r3, #0 + 8001008: d001 beq.n 800100e <_ZL12MX_TIM4_Initv+0x12a> Error_Handler(); - 8001102: f000 fb17 bl 8001734 + 800100a: f000 fbdf bl 80017cc } /* USER CODE BEGIN TIM4_Init 2 */ /* USER CODE END TIM4_Init 2 */ HAL_TIM_MspPostInit(&htim4); - 8001106: 4803 ldr r0, [pc, #12] ; (8001114 <_ZL12MX_TIM4_Initv+0x138>) - 8001108: f000 fca0 bl 8001a4c + 800100e: 4803 ldr r0, [pc, #12] ; (800101c <_ZL12MX_TIM4_Initv+0x138>) + 8001010: f000 fd5e bl 8001ad0 } - 800110c: bf00 nop - 800110e: 3738 adds r7, #56 ; 0x38 - 8001110: 46bd mov sp, r7 - 8001112: bd80 pop {r7, pc} - 8001114: 200000ac .word 0x200000ac - 8001118: 40000800 .word 0x40000800 - -0800111c <_ZL12MX_TIM5_Initv>: - * @brief TIM5 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM5_Init(void) -{ - 800111c: b580 push {r7, lr} - 800111e: b08c sub sp, #48 ; 0x30 - 8001120: af00 add r7, sp, #0 + 8001014: bf00 nop + 8001016: 3738 adds r7, #56 ; 0x38 + 8001018: 46bd mov sp, r7 + 800101a: bd80 pop {r7, pc} + 800101c: 200000ac .word 0x200000ac + 8001020: 40000800 .word 0x40000800 + +08001024 <_ZL12MX_TIM5_Initv>: +/** + * @brief TIM5 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM5_Init(void) { + 8001024: b580 push {r7, lr} + 8001026: b08c sub sp, #48 ; 0x30 + 8001028: af00 add r7, sp, #0 /* USER CODE BEGIN TIM5_Init 0 */ /* USER CODE END TIM5_Init 0 */ - TIM_Encoder_InitTypeDef sConfig = {0}; - 8001122: f107 030c add.w r3, r7, #12 - 8001126: 2224 movs r2, #36 ; 0x24 - 8001128: 2100 movs r1, #0 - 800112a: 4618 mov r0, r3 - 800112c: f004 fa02 bl 8005534 - TIM_MasterConfigTypeDef sMasterConfig = {0}; - 8001130: 463b mov r3, r7 - 8001132: 2200 movs r2, #0 - 8001134: 601a str r2, [r3, #0] - 8001136: 605a str r2, [r3, #4] - 8001138: 609a str r2, [r3, #8] + TIM_Encoder_InitTypeDef sConfig = { 0 }; + 800102a: f107 030c add.w r3, r7, #12 + 800102e: 2224 movs r2, #36 ; 0x24 + 8001030: 2100 movs r1, #0 + 8001032: 4618 mov r0, r3 + 8001034: f004 fac0 bl 80055b8 + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 8001038: 463b mov r3, r7 + 800103a: 2200 movs r2, #0 + 800103c: 601a str r2, [r3, #0] + 800103e: 605a str r2, [r3, #4] + 8001040: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM5_Init 1 */ /* USER CODE END TIM5_Init 1 */ htim5.Instance = TIM5; - 800113a: 4b26 ldr r3, [pc, #152] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 800113c: 4a26 ldr r2, [pc, #152] ; (80011d8 <_ZL12MX_TIM5_Initv+0xbc>) - 800113e: 601a str r2, [r3, #0] + 8001042: 4b26 ldr r3, [pc, #152] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 8001044: 4a26 ldr r2, [pc, #152] ; (80010e0 <_ZL12MX_TIM5_Initv+0xbc>) + 8001046: 601a str r2, [r3, #0] htim5.Init.Prescaler = 0; - 8001140: 4b24 ldr r3, [pc, #144] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 8001142: 2200 movs r2, #0 - 8001144: 605a str r2, [r3, #4] + 8001048: 4b24 ldr r3, [pc, #144] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 800104a: 2200 movs r2, #0 + 800104c: 605a str r2, [r3, #4] htim5.Init.CounterMode = TIM_COUNTERMODE_UP; - 8001146: 4b23 ldr r3, [pc, #140] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 8001148: 2200 movs r2, #0 - 800114a: 609a str r2, [r3, #8] + 800104e: 4b23 ldr r3, [pc, #140] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 8001050: 2200 movs r2, #0 + 8001052: 609a str r2, [r3, #8] htim5.Init.Period = 4294967295; - 800114c: 4b21 ldr r3, [pc, #132] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 800114e: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8001152: 60da str r2, [r3, #12] + 8001054: 4b21 ldr r3, [pc, #132] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 8001056: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 800105a: 60da str r2, [r3, #12] htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - 8001154: 4b1f ldr r3, [pc, #124] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 8001156: 2200 movs r2, #0 - 8001158: 611a str r2, [r3, #16] + 800105c: 4b1f ldr r3, [pc, #124] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 800105e: 2200 movs r2, #0 + 8001060: 611a str r2, [r3, #16] htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 800115a: 4b1e ldr r3, [pc, #120] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 800115c: 2200 movs r2, #0 - 800115e: 619a str r2, [r3, #24] + 8001062: 4b1e ldr r3, [pc, #120] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 8001064: 2200 movs r2, #0 + 8001066: 619a str r2, [r3, #24] sConfig.EncoderMode = TIM_ENCODERMODE_TI12; - 8001160: 2303 movs r3, #3 - 8001162: 60fb str r3, [r7, #12] + 8001068: 2303 movs r3, #3 + 800106a: 60fb str r3, [r7, #12] sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; - 8001164: 2300 movs r3, #0 - 8001166: 613b str r3, [r7, #16] + 800106c: 2300 movs r3, #0 + 800106e: 613b str r3, [r7, #16] sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; - 8001168: 2301 movs r3, #1 - 800116a: 617b str r3, [r7, #20] + 8001070: 2301 movs r3, #1 + 8001072: 617b str r3, [r7, #20] sConfig.IC1Prescaler = TIM_ICPSC_DIV1; - 800116c: 2300 movs r3, #0 - 800116e: 61bb str r3, [r7, #24] + 8001074: 2300 movs r3, #0 + 8001076: 61bb str r3, [r7, #24] sConfig.IC1Filter = 0; - 8001170: 2300 movs r3, #0 - 8001172: 61fb str r3, [r7, #28] + 8001078: 2300 movs r3, #0 + 800107a: 61fb str r3, [r7, #28] sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; - 8001174: 2300 movs r3, #0 - 8001176: 623b str r3, [r7, #32] + 800107c: 2300 movs r3, #0 + 800107e: 623b str r3, [r7, #32] sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; - 8001178: 2301 movs r3, #1 - 800117a: 627b str r3, [r7, #36] ; 0x24 + 8001080: 2301 movs r3, #1 + 8001082: 627b str r3, [r7, #36] ; 0x24 sConfig.IC2Prescaler = TIM_ICPSC_DIV1; - 800117c: 2300 movs r3, #0 - 800117e: 62bb str r3, [r7, #40] ; 0x28 + 8001084: 2300 movs r3, #0 + 8001086: 62bb str r3, [r7, #40] ; 0x28 sConfig.IC2Filter = 0; - 8001180: 2300 movs r3, #0 - 8001182: 62fb str r3, [r7, #44] ; 0x2c - if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) - 8001184: f107 030c add.w r3, r7, #12 - 8001188: 4619 mov r1, r3 - 800118a: 4812 ldr r0, [pc, #72] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 800118c: f002 fa30 bl 80035f0 - 8001190: 4603 mov r3, r0 - 8001192: 2b00 cmp r3, #0 - 8001194: bf14 ite ne - 8001196: 2301 movne r3, #1 - 8001198: 2300 moveq r3, #0 - 800119a: b2db uxtb r3, r3 - 800119c: 2b00 cmp r3, #0 - 800119e: d001 beq.n 80011a4 <_ZL12MX_TIM5_Initv+0x88> - { + 8001088: 2300 movs r3, #0 + 800108a: 62fb str r3, [r7, #44] ; 0x2c + if (HAL_TIM_Encoder_Init(&htim5, &sConfig) != HAL_OK) { + 800108c: f107 030c add.w r3, r7, #12 + 8001090: 4619 mov r1, r3 + 8001092: 4812 ldr r0, [pc, #72] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 8001094: f002 faee bl 8003674 + 8001098: 4603 mov r3, r0 + 800109a: 2b00 cmp r3, #0 + 800109c: bf14 ite ne + 800109e: 2301 movne r3, #1 + 80010a0: 2300 moveq r3, #0 + 80010a2: b2db uxtb r3, r3 + 80010a4: 2b00 cmp r3, #0 + 80010a6: d001 beq.n 80010ac <_ZL12MX_TIM5_Initv+0x88> Error_Handler(); - 80011a0: f000 fac8 bl 8001734 + 80010a8: f000 fb90 bl 80017cc } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 80011a4: 2300 movs r3, #0 - 80011a6: 603b str r3, [r7, #0] + 80010ac: 2300 movs r3, #0 + 80010ae: 603b str r3, [r7, #0] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 80011a8: 2300 movs r3, #0 - 80011aa: 60bb str r3, [r7, #8] - if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) - 80011ac: 463b mov r3, r7 - 80011ae: 4619 mov r1, r3 - 80011b0: 4808 ldr r0, [pc, #32] ; (80011d4 <_ZL12MX_TIM5_Initv+0xb8>) - 80011b2: f003 f9bd bl 8004530 - 80011b6: 4603 mov r3, r0 - 80011b8: 2b00 cmp r3, #0 - 80011ba: bf14 ite ne - 80011bc: 2301 movne r3, #1 - 80011be: 2300 moveq r3, #0 - 80011c0: b2db uxtb r3, r3 - 80011c2: 2b00 cmp r3, #0 - 80011c4: d001 beq.n 80011ca <_ZL12MX_TIM5_Initv+0xae> - { + 80010b0: 2300 movs r3, #0 + 80010b2: 60bb str r3, [r7, #8] + if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK) { + 80010b4: 463b mov r3, r7 + 80010b6: 4619 mov r1, r3 + 80010b8: 4808 ldr r0, [pc, #32] ; (80010dc <_ZL12MX_TIM5_Initv+0xb8>) + 80010ba: f003 fa7b bl 80045b4 + 80010be: 4603 mov r3, r0 + 80010c0: 2b00 cmp r3, #0 + 80010c2: bf14 ite ne + 80010c4: 2301 movne r3, #1 + 80010c6: 2300 moveq r3, #0 + 80010c8: b2db uxtb r3, r3 + 80010ca: 2b00 cmp r3, #0 + 80010cc: d001 beq.n 80010d2 <_ZL12MX_TIM5_Initv+0xae> Error_Handler(); - 80011c6: f000 fab5 bl 8001734 + 80010ce: f000 fb7d bl 80017cc } /* USER CODE BEGIN TIM5_Init 2 */ /* USER CODE END TIM5_Init 2 */ } - 80011ca: bf00 nop - 80011cc: 3730 adds r7, #48 ; 0x30 - 80011ce: 46bd mov sp, r7 - 80011d0: bd80 pop {r7, pc} - 80011d2: bf00 nop - 80011d4: 200000ec .word 0x200000ec - 80011d8: 40000c00 .word 0x40000c00 - -080011dc <_ZL12MX_TIM6_Initv>: - * @brief TIM6 Initialization Function - * @param None - * @retval None - */ -static void MX_TIM6_Init(void) -{ - 80011dc: b580 push {r7, lr} - 80011de: b084 sub sp, #16 - 80011e0: af00 add r7, sp, #0 + 80010d2: bf00 nop + 80010d4: 3730 adds r7, #48 ; 0x30 + 80010d6: 46bd mov sp, r7 + 80010d8: bd80 pop {r7, pc} + 80010da: bf00 nop + 80010dc: 200000ec .word 0x200000ec + 80010e0: 40000c00 .word 0x40000c00 + +080010e4 <_ZL12MX_TIM6_Initv>: +/** + * @brief TIM6 Initialization Function + * @param None + * @retval None + */ +static void MX_TIM6_Init(void) { + 80010e4: b580 push {r7, lr} + 80010e6: b084 sub sp, #16 + 80010e8: af00 add r7, sp, #0 /* USER CODE BEGIN TIM6_Init 0 */ /* USER CODE END TIM6_Init 0 */ - TIM_MasterConfigTypeDef sMasterConfig = {0}; - 80011e2: 1d3b adds r3, r7, #4 - 80011e4: 2200 movs r2, #0 - 80011e6: 601a str r2, [r3, #0] - 80011e8: 605a str r2, [r3, #4] - 80011ea: 609a str r2, [r3, #8] + TIM_MasterConfigTypeDef sMasterConfig = { 0 }; + 80010ea: 1d3b adds r3, r7, #4 + 80010ec: 2200 movs r2, #0 + 80010ee: 601a str r2, [r3, #0] + 80010f0: 605a str r2, [r3, #4] + 80010f2: 609a str r2, [r3, #8] /* USER CODE BEGIN TIM6_Init 1 */ /* USER CODE END TIM6_Init 1 */ htim6.Instance = TIM6; - 80011ec: 4b1a ldr r3, [pc, #104] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 80011ee: 4a1b ldr r2, [pc, #108] ; (800125c <_ZL12MX_TIM6_Initv+0x80>) - 80011f0: 601a str r2, [r3, #0] + 80010f4: 4b1a ldr r3, [pc, #104] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 80010f6: 4a1b ldr r2, [pc, #108] ; (8001164 <_ZL12MX_TIM6_Initv+0x80>) + 80010f8: 601a str r2, [r3, #0] htim6.Init.Prescaler = 9999; - 80011f2: 4b19 ldr r3, [pc, #100] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 80011f4: f242 720f movw r2, #9999 ; 0x270f - 80011f8: 605a str r2, [r3, #4] + 80010fa: 4b19 ldr r3, [pc, #100] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 80010fc: f242 720f movw r2, #9999 ; 0x270f + 8001100: 605a str r2, [r3, #4] htim6.Init.CounterMode = TIM_COUNTERMODE_UP; - 80011fa: 4b17 ldr r3, [pc, #92] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 80011fc: 2200 movs r2, #0 - 80011fe: 609a str r2, [r3, #8] + 8001102: 4b17 ldr r3, [pc, #92] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 8001104: 2200 movs r2, #0 + 8001106: 609a str r2, [r3, #8] htim6.Init.Period = 799; - 8001200: 4b15 ldr r3, [pc, #84] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 8001202: f240 321f movw r2, #799 ; 0x31f - 8001206: 60da str r2, [r3, #12] + 8001108: 4b15 ldr r3, [pc, #84] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 800110a: f240 321f movw r2, #799 ; 0x31f + 800110e: 60da str r2, [r3, #12] htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - 8001208: 4b13 ldr r3, [pc, #76] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 800120a: 2200 movs r2, #0 - 800120c: 619a str r2, [r3, #24] - if (HAL_TIM_Base_Init(&htim6) != HAL_OK) - 800120e: 4812 ldr r0, [pc, #72] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 8001210: f002 f91e bl 8003450 - 8001214: 4603 mov r3, r0 - 8001216: 2b00 cmp r3, #0 - 8001218: bf14 ite ne - 800121a: 2301 movne r3, #1 - 800121c: 2300 moveq r3, #0 - 800121e: b2db uxtb r3, r3 - 8001220: 2b00 cmp r3, #0 - 8001222: d001 beq.n 8001228 <_ZL12MX_TIM6_Initv+0x4c> - { + 8001110: 4b13 ldr r3, [pc, #76] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 8001112: 2200 movs r2, #0 + 8001114: 619a str r2, [r3, #24] + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) { + 8001116: 4812 ldr r0, [pc, #72] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 8001118: f002 f9dc bl 80034d4 + 800111c: 4603 mov r3, r0 + 800111e: 2b00 cmp r3, #0 + 8001120: bf14 ite ne + 8001122: 2301 movne r3, #1 + 8001124: 2300 moveq r3, #0 + 8001126: b2db uxtb r3, r3 + 8001128: 2b00 cmp r3, #0 + 800112a: d001 beq.n 8001130 <_ZL12MX_TIM6_Initv+0x4c> Error_Handler(); - 8001224: f000 fa86 bl 8001734 + 800112c: f000 fb4e bl 80017cc } sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; - 8001228: 2300 movs r3, #0 - 800122a: 607b str r3, [r7, #4] + 8001130: 2300 movs r3, #0 + 8001132: 607b str r3, [r7, #4] sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - 800122c: 2300 movs r3, #0 - 800122e: 60fb str r3, [r7, #12] - if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) - 8001230: 1d3b adds r3, r7, #4 - 8001232: 4619 mov r1, r3 - 8001234: 4808 ldr r0, [pc, #32] ; (8001258 <_ZL12MX_TIM6_Initv+0x7c>) - 8001236: f003 f97b bl 8004530 - 800123a: 4603 mov r3, r0 - 800123c: 2b00 cmp r3, #0 - 800123e: bf14 ite ne - 8001240: 2301 movne r3, #1 - 8001242: 2300 moveq r3, #0 - 8001244: b2db uxtb r3, r3 - 8001246: 2b00 cmp r3, #0 - 8001248: d001 beq.n 800124e <_ZL12MX_TIM6_Initv+0x72> - { + 8001134: 2300 movs r3, #0 + 8001136: 60fb str r3, [r7, #12] + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) { + 8001138: 1d3b adds r3, r7, #4 + 800113a: 4619 mov r1, r3 + 800113c: 4808 ldr r0, [pc, #32] ; (8001160 <_ZL12MX_TIM6_Initv+0x7c>) + 800113e: f003 fa39 bl 80045b4 + 8001142: 4603 mov r3, r0 + 8001144: 2b00 cmp r3, #0 + 8001146: bf14 ite ne + 8001148: 2301 movne r3, #1 + 800114a: 2300 moveq r3, #0 + 800114c: b2db uxtb r3, r3 + 800114e: 2b00 cmp r3, #0 + 8001150: d001 beq.n 8001156 <_ZL12MX_TIM6_Initv+0x72> Error_Handler(); - 800124a: f000 fa73 bl 8001734 + 8001152: f000 fb3b bl 80017cc } /* USER CODE BEGIN TIM6_Init 2 */ /* USER CODE END TIM6_Init 2 */ } - 800124e: bf00 nop - 8001250: 3710 adds r7, #16 - 8001252: 46bd mov sp, r7 - 8001254: bd80 pop {r7, pc} - 8001256: bf00 nop - 8001258: 2000012c .word 0x2000012c - 800125c: 40001000 .word 0x40001000 - -08001260 <_ZL19MX_USART6_UART_Initv>: - * @brief USART6 Initialization Function - * @param None - * @retval None - */ -static void MX_USART6_UART_Init(void) -{ - 8001260: b580 push {r7, lr} - 8001262: af00 add r7, sp, #0 + 8001156: bf00 nop + 8001158: 3710 adds r7, #16 + 800115a: 46bd mov sp, r7 + 800115c: bd80 pop {r7, pc} + 800115e: bf00 nop + 8001160: 2000012c .word 0x2000012c + 8001164: 40001000 .word 0x40001000 + +08001168 <_ZL19MX_USART6_UART_Initv>: +/** + * @brief USART6 Initialization Function + * @param None + * @retval None + */ +static void MX_USART6_UART_Init(void) { + 8001168: b580 push {r7, lr} + 800116a: 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; - 8001264: 4b17 ldr r3, [pc, #92] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001266: 4a18 ldr r2, [pc, #96] ; (80012c8 <_ZL19MX_USART6_UART_Initv+0x68>) - 8001268: 601a str r2, [r3, #0] + 800116c: 4b17 ldr r3, [pc, #92] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 800116e: 4a18 ldr r2, [pc, #96] ; (80011d0 <_ZL19MX_USART6_UART_Initv+0x68>) + 8001170: 601a str r2, [r3, #0] huart6.Init.BaudRate = 115200; - 800126a: 4b16 ldr r3, [pc, #88] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 800126c: f44f 32e1 mov.w r2, #115200 ; 0x1c200 - 8001270: 605a str r2, [r3, #4] + 8001172: 4b16 ldr r3, [pc, #88] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 8001174: f44f 32e1 mov.w r2, #115200 ; 0x1c200 + 8001178: 605a str r2, [r3, #4] huart6.Init.WordLength = UART_WORDLENGTH_9B; - 8001272: 4b14 ldr r3, [pc, #80] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001274: f44f 5280 mov.w r2, #4096 ; 0x1000 - 8001278: 609a str r2, [r3, #8] + 800117a: 4b14 ldr r3, [pc, #80] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 800117c: f44f 5280 mov.w r2, #4096 ; 0x1000 + 8001180: 609a str r2, [r3, #8] huart6.Init.StopBits = UART_STOPBITS_1; - 800127a: 4b12 ldr r3, [pc, #72] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 800127c: 2200 movs r2, #0 - 800127e: 60da str r2, [r3, #12] + 8001182: 4b12 ldr r3, [pc, #72] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 8001184: 2200 movs r2, #0 + 8001186: 60da str r2, [r3, #12] huart6.Init.Parity = UART_PARITY_ODD; - 8001280: 4b10 ldr r3, [pc, #64] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001282: f44f 62c0 mov.w r2, #1536 ; 0x600 - 8001286: 611a str r2, [r3, #16] + 8001188: 4b10 ldr r3, [pc, #64] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 800118a: f44f 62c0 mov.w r2, #1536 ; 0x600 + 800118e: 611a str r2, [r3, #16] huart6.Init.Mode = UART_MODE_TX_RX; - 8001288: 4b0e ldr r3, [pc, #56] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 800128a: 220c movs r2, #12 - 800128c: 615a str r2, [r3, #20] + 8001190: 4b0e ldr r3, [pc, #56] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 8001192: 220c movs r2, #12 + 8001194: 615a str r2, [r3, #20] huart6.Init.HwFlowCtl = UART_HWCONTROL_NONE; - 800128e: 4b0d ldr r3, [pc, #52] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001290: 2200 movs r2, #0 - 8001292: 619a str r2, [r3, #24] + 8001196: 4b0d ldr r3, [pc, #52] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 8001198: 2200 movs r2, #0 + 800119a: 619a str r2, [r3, #24] huart6.Init.OverSampling = UART_OVERSAMPLING_16; - 8001294: 4b0b ldr r3, [pc, #44] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 8001296: 2200 movs r2, #0 - 8001298: 61da str r2, [r3, #28] + 800119c: 4b0b ldr r3, [pc, #44] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 800119e: 2200 movs r2, #0 + 80011a0: 61da str r2, [r3, #28] huart6.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; - 800129a: 4b0a ldr r3, [pc, #40] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 800129c: 2200 movs r2, #0 - 800129e: 621a str r2, [r3, #32] + 80011a2: 4b0a ldr r3, [pc, #40] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 80011a4: 2200 movs r2, #0 + 80011a6: 621a str r2, [r3, #32] huart6.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - 80012a0: 4b08 ldr r3, [pc, #32] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 80012a2: 2200 movs r2, #0 - 80012a4: 625a str r2, [r3, #36] ; 0x24 - if (HAL_UART_Init(&huart6) != HAL_OK) - 80012a6: 4807 ldr r0, [pc, #28] ; (80012c4 <_ZL19MX_USART6_UART_Initv+0x64>) - 80012a8: f003 f9bc bl 8004624 - 80012ac: 4603 mov r3, r0 - 80012ae: 2b00 cmp r3, #0 - 80012b0: bf14 ite ne - 80012b2: 2301 movne r3, #1 - 80012b4: 2300 moveq r3, #0 - 80012b6: b2db uxtb r3, r3 - 80012b8: 2b00 cmp r3, #0 - 80012ba: d001 beq.n 80012c0 <_ZL19MX_USART6_UART_Initv+0x60> - { + 80011a8: 4b08 ldr r3, [pc, #32] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 80011aa: 2200 movs r2, #0 + 80011ac: 625a str r2, [r3, #36] ; 0x24 + if (HAL_UART_Init(&huart6) != HAL_OK) { + 80011ae: 4807 ldr r0, [pc, #28] ; (80011cc <_ZL19MX_USART6_UART_Initv+0x64>) + 80011b0: f003 fa7a bl 80046a8 + 80011b4: 4603 mov r3, r0 + 80011b6: 2b00 cmp r3, #0 + 80011b8: bf14 ite ne + 80011ba: 2301 movne r3, #1 + 80011bc: 2300 moveq r3, #0 + 80011be: b2db uxtb r3, r3 + 80011c0: 2b00 cmp r3, #0 + 80011c2: d001 beq.n 80011c8 <_ZL19MX_USART6_UART_Initv+0x60> Error_Handler(); - 80012bc: f000 fa3a bl 8001734 + 80011c4: f000 fb02 bl 80017cc } /* USER CODE BEGIN USART6_Init 2 */ /* USER CODE END USART6_Init 2 */ } - 80012c0: bf00 nop - 80012c2: bd80 pop {r7, pc} - 80012c4: 2000016c .word 0x2000016c - 80012c8: 40011400 .word 0x40011400 - -080012cc <_ZL12MX_GPIO_Initv>: - * @brief GPIO Initialization Function - * @param None - * @retval None - */ -static void MX_GPIO_Init(void) -{ - 80012cc: b580 push {r7, lr} - 80012ce: b08c sub sp, #48 ; 0x30 - 80012d0: af00 add r7, sp, #0 - GPIO_InitTypeDef GPIO_InitStruct = {0}; - 80012d2: f107 031c add.w r3, r7, #28 - 80012d6: 2200 movs r2, #0 - 80012d8: 601a str r2, [r3, #0] - 80012da: 605a str r2, [r3, #4] - 80012dc: 609a str r2, [r3, #8] - 80012de: 60da str r2, [r3, #12] - 80012e0: 611a str r2, [r3, #16] + 80011c8: bf00 nop + 80011ca: bd80 pop {r7, pc} + 80011cc: 2000016c .word 0x2000016c + 80011d0: 40011400 .word 0x40011400 + +080011d4 <_ZL12MX_GPIO_Initv>: +/** + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +static void MX_GPIO_Init(void) { + 80011d4: b580 push {r7, lr} + 80011d6: b08c sub sp, #48 ; 0x30 + 80011d8: af00 add r7, sp, #0 + GPIO_InitTypeDef GPIO_InitStruct = { 0 }; + 80011da: f107 031c add.w r3, r7, #28 + 80011de: 2200 movs r2, #0 + 80011e0: 601a str r2, [r3, #0] + 80011e2: 605a str r2, [r3, #4] + 80011e4: 609a str r2, [r3, #8] + 80011e6: 60da str r2, [r3, #12] + 80011e8: 611a str r2, [r3, #16] /* GPIO Ports Clock Enable */ __HAL_RCC_GPIOC_CLK_ENABLE(); - 80012e2: 4b5e ldr r3, [pc, #376] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 80012e4: 6b1b ldr r3, [r3, #48] ; 0x30 - 80012e6: 4a5d ldr r2, [pc, #372] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 80012e8: f043 0304 orr.w r3, r3, #4 - 80012ec: 6313 str r3, [r2, #48] ; 0x30 - 80012ee: 4b5b ldr r3, [pc, #364] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 80012f0: 6b1b ldr r3, [r3, #48] ; 0x30 - 80012f2: f003 0304 and.w r3, r3, #4 - 80012f6: 61bb str r3, [r7, #24] - 80012f8: 69bb ldr r3, [r7, #24] + 80011ea: 4b5e ldr r3, [pc, #376] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 80011ec: 6b1b ldr r3, [r3, #48] ; 0x30 + 80011ee: 4a5d ldr r2, [pc, #372] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 80011f0: f043 0304 orr.w r3, r3, #4 + 80011f4: 6313 str r3, [r2, #48] ; 0x30 + 80011f6: 4b5b ldr r3, [pc, #364] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 80011f8: 6b1b ldr r3, [r3, #48] ; 0x30 + 80011fa: f003 0304 and.w r3, r3, #4 + 80011fe: 61bb str r3, [r7, #24] + 8001200: 69bb ldr r3, [r7, #24] __HAL_RCC_GPIOA_CLK_ENABLE(); - 80012fa: 4b58 ldr r3, [pc, #352] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 80012fc: 6b1b ldr r3, [r3, #48] ; 0x30 - 80012fe: 4a57 ldr r2, [pc, #348] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001300: f043 0301 orr.w r3, r3, #1 - 8001304: 6313 str r3, [r2, #48] ; 0x30 - 8001306: 4b55 ldr r3, [pc, #340] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001308: 6b1b ldr r3, [r3, #48] ; 0x30 - 800130a: f003 0301 and.w r3, r3, #1 - 800130e: 617b str r3, [r7, #20] - 8001310: 697b ldr r3, [r7, #20] + 8001202: 4b58 ldr r3, [pc, #352] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001204: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001206: 4a57 ldr r2, [pc, #348] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001208: f043 0301 orr.w r3, r3, #1 + 800120c: 6313 str r3, [r2, #48] ; 0x30 + 800120e: 4b55 ldr r3, [pc, #340] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001210: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001212: f003 0301 and.w r3, r3, #1 + 8001216: 617b str r3, [r7, #20] + 8001218: 697b ldr r3, [r7, #20] __HAL_RCC_GPIOF_CLK_ENABLE(); - 8001312: 4b52 ldr r3, [pc, #328] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001314: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001316: 4a51 ldr r2, [pc, #324] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001318: f043 0320 orr.w r3, r3, #32 - 800131c: 6313 str r3, [r2, #48] ; 0x30 - 800131e: 4b4f ldr r3, [pc, #316] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001320: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001322: f003 0320 and.w r3, r3, #32 - 8001326: 613b str r3, [r7, #16] - 8001328: 693b ldr r3, [r7, #16] + 800121a: 4b52 ldr r3, [pc, #328] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 800121c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800121e: 4a51 ldr r2, [pc, #324] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001220: f043 0320 orr.w r3, r3, #32 + 8001224: 6313 str r3, [r2, #48] ; 0x30 + 8001226: 4b4f ldr r3, [pc, #316] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001228: 6b1b ldr r3, [r3, #48] ; 0x30 + 800122a: f003 0320 and.w r3, r3, #32 + 800122e: 613b str r3, [r7, #16] + 8001230: 693b ldr r3, [r7, #16] __HAL_RCC_GPIOE_CLK_ENABLE(); - 800132a: 4b4c ldr r3, [pc, #304] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 800132c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800132e: 4a4b ldr r2, [pc, #300] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001330: f043 0310 orr.w r3, r3, #16 - 8001334: 6313 str r3, [r2, #48] ; 0x30 - 8001336: 4b49 ldr r3, [pc, #292] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001338: 6b1b ldr r3, [r3, #48] ; 0x30 - 800133a: f003 0310 and.w r3, r3, #16 - 800133e: 60fb str r3, [r7, #12] - 8001340: 68fb ldr r3, [r7, #12] + 8001232: 4b4c ldr r3, [pc, #304] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001234: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001236: 4a4b ldr r2, [pc, #300] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001238: f043 0310 orr.w r3, r3, #16 + 800123c: 6313 str r3, [r2, #48] ; 0x30 + 800123e: 4b49 ldr r3, [pc, #292] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001240: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001242: f003 0310 and.w r3, r3, #16 + 8001246: 60fb str r3, [r7, #12] + 8001248: 68fb ldr r3, [r7, #12] __HAL_RCC_GPIOD_CLK_ENABLE(); - 8001342: 4b46 ldr r3, [pc, #280] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001344: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001346: 4a45 ldr r2, [pc, #276] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001348: f043 0308 orr.w r3, r3, #8 - 800134c: 6313 str r3, [r2, #48] ; 0x30 - 800134e: 4b43 ldr r3, [pc, #268] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001350: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001352: f003 0308 and.w r3, r3, #8 - 8001356: 60bb str r3, [r7, #8] - 8001358: 68bb ldr r3, [r7, #8] + 800124a: 4b46 ldr r3, [pc, #280] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 800124c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800124e: 4a45 ldr r2, [pc, #276] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001250: f043 0308 orr.w r3, r3, #8 + 8001254: 6313 str r3, [r2, #48] ; 0x30 + 8001256: 4b43 ldr r3, [pc, #268] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001258: 6b1b ldr r3, [r3, #48] ; 0x30 + 800125a: f003 0308 and.w r3, r3, #8 + 800125e: 60bb str r3, [r7, #8] + 8001260: 68bb ldr r3, [r7, #8] __HAL_RCC_GPIOB_CLK_ENABLE(); - 800135a: 4b40 ldr r3, [pc, #256] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 800135c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800135e: 4a3f ldr r2, [pc, #252] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001360: f043 0302 orr.w r3, r3, #2 - 8001364: 6313 str r3, [r2, #48] ; 0x30 - 8001366: 4b3d ldr r3, [pc, #244] ; (800145c <_ZL12MX_GPIO_Initv+0x190>) - 8001368: 6b1b ldr r3, [r3, #48] ; 0x30 - 800136a: f003 0302 and.w r3, r3, #2 - 800136e: 607b str r3, [r7, #4] - 8001370: 687b ldr r3, [r7, #4] + 8001262: 4b40 ldr r3, [pc, #256] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001264: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001266: 4a3f ldr r2, [pc, #252] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001268: f043 0302 orr.w r3, r3, #2 + 800126c: 6313 str r3, [r2, #48] ; 0x30 + 800126e: 4b3d ldr r3, [pc, #244] ; (8001364 <_ZL12MX_GPIO_Initv+0x190>) + 8001270: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001272: f003 0302 and.w r3, r3, #2 + 8001276: 607b str r3, [r7, #4] + 8001278: 687b ldr r3, [r7, #4] /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, dir2_Pin|dir1_Pin, GPIO_PIN_RESET); - 8001372: 2200 movs r2, #0 - 8001374: f44f 5140 mov.w r1, #12288 ; 0x3000 - 8001378: 4839 ldr r0, [pc, #228] ; (8001460 <_ZL12MX_GPIO_Initv+0x194>) - 800137a: f000 ffd1 bl 8002320 + HAL_GPIO_WritePin(GPIOF, dir2_Pin | dir1_Pin, GPIO_PIN_RESET); + 800127a: 2200 movs r2, #0 + 800127c: f44f 5140 mov.w r1, #12288 ; 0x3000 + 8001280: 4839 ldr r0, [pc, #228] ; (8001368 <_ZL12MX_GPIO_Initv+0x194>) + 8001282: f001 f88f bl 80023a4 /*Configure GPIO pin Output Level */ - HAL_GPIO_WritePin(GPIOF, sleep2_Pin|sleep1_Pin, GPIO_PIN_SET); - 800137e: 2201 movs r2, #1 - 8001380: f44f 4140 mov.w r1, #49152 ; 0xc000 - 8001384: 4836 ldr r0, [pc, #216] ; (8001460 <_ZL12MX_GPIO_Initv+0x194>) - 8001386: f000 ffcb bl 8002320 + HAL_GPIO_WritePin(GPIOF, sleep2_Pin | sleep1_Pin, GPIO_PIN_SET); + 8001286: 2201 movs r2, #1 + 8001288: f44f 4140 mov.w r1, #49152 ; 0xc000 + 800128c: 4836 ldr r0, [pc, #216] ; (8001368 <_ZL12MX_GPIO_Initv+0x194>) + 800128e: f001 f889 bl 80023a4 /*Configure GPIO pin : user_button_Pin */ GPIO_InitStruct.Pin = user_button_Pin; - 800138a: f44f 5300 mov.w r3, #8192 ; 0x2000 - 800138e: 61fb str r3, [r7, #28] + 8001292: f44f 5300 mov.w r3, #8192 ; 0x2000 + 8001296: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; - 8001390: 4b34 ldr r3, [pc, #208] ; (8001464 <_ZL12MX_GPIO_Initv+0x198>) - 8001392: 623b str r3, [r7, #32] + 8001298: 4b34 ldr r3, [pc, #208] ; (800136c <_ZL12MX_GPIO_Initv+0x198>) + 800129a: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001394: 2300 movs r3, #0 - 8001396: 627b str r3, [r7, #36] ; 0x24 + 800129c: 2300 movs r3, #0 + 800129e: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(user_button_GPIO_Port, &GPIO_InitStruct); - 8001398: f107 031c add.w r3, r7, #28 - 800139c: 4619 mov r1, r3 - 800139e: 4832 ldr r0, [pc, #200] ; (8001468 <_ZL12MX_GPIO_Initv+0x19c>) - 80013a0: f000 fe14 bl 8001fcc + 80012a0: f107 031c add.w r3, r7, #28 + 80012a4: 4619 mov r1, r3 + 80012a6: 4832 ldr r0, [pc, #200] ; (8001370 <_ZL12MX_GPIO_Initv+0x19c>) + 80012a8: f000 fed2 bl 8002050 /*Configure GPIO pin : current2_Pin */ GPIO_InitStruct.Pin = current2_Pin; - 80013a4: 2301 movs r3, #1 - 80013a6: 61fb str r3, [r7, #28] + 80012ac: 2301 movs r3, #1 + 80012ae: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - 80013a8: 2303 movs r3, #3 - 80013aa: 623b str r3, [r7, #32] + 80012b0: 2303 movs r3, #3 + 80012b2: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80013ac: 2300 movs r3, #0 - 80013ae: 627b str r3, [r7, #36] ; 0x24 + 80012b4: 2300 movs r3, #0 + 80012b6: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(current2_GPIO_Port, &GPIO_InitStruct); - 80013b0: f107 031c add.w r3, r7, #28 - 80013b4: 4619 mov r1, r3 - 80013b6: 482c ldr r0, [pc, #176] ; (8001468 <_ZL12MX_GPIO_Initv+0x19c>) - 80013b8: f000 fe08 bl 8001fcc + 80012b8: f107 031c add.w r3, r7, #28 + 80012bc: 4619 mov r1, r3 + 80012be: 482c ldr r0, [pc, #176] ; (8001370 <_ZL12MX_GPIO_Initv+0x19c>) + 80012c0: f000 fec6 bl 8002050 /*Configure GPIO pin : current1_Pin */ GPIO_InitStruct.Pin = current1_Pin; - 80013bc: 2308 movs r3, #8 - 80013be: 61fb str r3, [r7, #28] + 80012c4: 2308 movs r3, #8 + 80012c6: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - 80013c0: 2303 movs r3, #3 - 80013c2: 623b str r3, [r7, #32] + 80012c8: 2303 movs r3, #3 + 80012ca: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80013c4: 2300 movs r3, #0 - 80013c6: 627b str r3, [r7, #36] ; 0x24 + 80012cc: 2300 movs r3, #0 + 80012ce: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(current1_GPIO_Port, &GPIO_InitStruct); - 80013c8: f107 031c add.w r3, r7, #28 - 80013cc: 4619 mov r1, r3 - 80013ce: 4827 ldr r0, [pc, #156] ; (800146c <_ZL12MX_GPIO_Initv+0x1a0>) - 80013d0: f000 fdfc bl 8001fcc + 80012d0: f107 031c add.w r3, r7, #28 + 80012d4: 4619 mov r1, r3 + 80012d6: 4827 ldr r0, [pc, #156] ; (8001374 <_ZL12MX_GPIO_Initv+0x1a0>) + 80012d8: f000 feba bl 8002050 /*Configure GPIO pin : fault2_Pin */ GPIO_InitStruct.Pin = fault2_Pin; - 80013d4: 2340 movs r3, #64 ; 0x40 - 80013d6: 61fb str r3, [r7, #28] + 80012dc: 2340 movs r3, #64 ; 0x40 + 80012de: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - 80013d8: 2300 movs r3, #0 - 80013da: 623b str r3, [r7, #32] + 80012e0: 2300 movs r3, #0 + 80012e2: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80013dc: 2300 movs r3, #0 - 80013de: 627b str r3, [r7, #36] ; 0x24 + 80012e4: 2300 movs r3, #0 + 80012e6: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(fault2_GPIO_Port, &GPIO_InitStruct); - 80013e0: f107 031c add.w r3, r7, #28 - 80013e4: 4619 mov r1, r3 - 80013e6: 4821 ldr r0, [pc, #132] ; (800146c <_ZL12MX_GPIO_Initv+0x1a0>) - 80013e8: f000 fdf0 bl 8001fcc + 80012e8: f107 031c add.w r3, r7, #28 + 80012ec: 4619 mov r1, r3 + 80012ee: 4821 ldr r0, [pc, #132] ; (8001374 <_ZL12MX_GPIO_Initv+0x1a0>) + 80012f0: f000 feae bl 8002050 /*Configure GPIO pins : dir2_Pin dir1_Pin */ - GPIO_InitStruct.Pin = dir2_Pin|dir1_Pin; - 80013ec: f44f 5340 mov.w r3, #12288 ; 0x3000 - 80013f0: 61fb str r3, [r7, #28] + GPIO_InitStruct.Pin = dir2_Pin | dir1_Pin; + 80012f4: f44f 5340 mov.w r3, #12288 ; 0x3000 + 80012f8: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - 80013f2: 2301 movs r3, #1 - 80013f4: 623b str r3, [r7, #32] + 80012fa: 2301 movs r3, #1 + 80012fc: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 80013f6: 2300 movs r3, #0 - 80013f8: 627b str r3, [r7, #36] ; 0x24 + 80012fe: 2300 movs r3, #0 + 8001300: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 80013fa: 2300 movs r3, #0 - 80013fc: 62bb str r3, [r7, #40] ; 0x28 + 8001302: 2300 movs r3, #0 + 8001304: 62bb str r3, [r7, #40] ; 0x28 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); - 80013fe: f107 031c add.w r3, r7, #28 - 8001402: 4619 mov r1, r3 - 8001404: 4816 ldr r0, [pc, #88] ; (8001460 <_ZL12MX_GPIO_Initv+0x194>) - 8001406: f000 fde1 bl 8001fcc + 8001306: f107 031c add.w r3, r7, #28 + 800130a: 4619 mov r1, r3 + 800130c: 4816 ldr r0, [pc, #88] ; (8001368 <_ZL12MX_GPIO_Initv+0x194>) + 800130e: f000 fe9f bl 8002050 /*Configure GPIO pins : sleep2_Pin sleep1_Pin */ - GPIO_InitStruct.Pin = sleep2_Pin|sleep1_Pin; - 800140a: f44f 4340 mov.w r3, #49152 ; 0xc000 - 800140e: 61fb str r3, [r7, #28] + GPIO_InitStruct.Pin = sleep2_Pin | sleep1_Pin; + 8001312: f44f 4340 mov.w r3, #49152 ; 0xc000 + 8001316: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - 8001410: 2301 movs r3, #1 - 8001412: 623b str r3, [r7, #32] + 8001318: 2301 movs r3, #1 + 800131a: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_PULLUP; - 8001414: 2301 movs r3, #1 - 8001416: 627b str r3, [r7, #36] ; 0x24 + 800131c: 2301 movs r3, #1 + 800131e: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001418: 2300 movs r3, #0 - 800141a: 62bb str r3, [r7, #40] ; 0x28 + 8001320: 2300 movs r3, #0 + 8001322: 62bb str r3, [r7, #40] ; 0x28 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); - 800141c: f107 031c add.w r3, r7, #28 - 8001420: 4619 mov r1, r3 - 8001422: 480f ldr r0, [pc, #60] ; (8001460 <_ZL12MX_GPIO_Initv+0x194>) - 8001424: f000 fdd2 bl 8001fcc + 8001324: f107 031c add.w r3, r7, #28 + 8001328: 4619 mov r1, r3 + 800132a: 480f ldr r0, [pc, #60] ; (8001368 <_ZL12MX_GPIO_Initv+0x194>) + 800132c: f000 fe90 bl 8002050 /*Configure GPIO pin : fault1_Pin */ GPIO_InitStruct.Pin = fault1_Pin; - 8001428: f44f 7300 mov.w r3, #512 ; 0x200 - 800142c: 61fb str r3, [r7, #28] + 8001330: f44f 7300 mov.w r3, #512 ; 0x200 + 8001334: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - 800142e: 2300 movs r3, #0 - 8001430: 623b str r3, [r7, #32] + 8001336: 2300 movs r3, #0 + 8001338: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001432: 2300 movs r3, #0 - 8001434: 627b str r3, [r7, #36] ; 0x24 + 800133a: 2300 movs r3, #0 + 800133c: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(fault1_GPIO_Port, &GPIO_InitStruct); - 8001436: f107 031c add.w r3, r7, #28 - 800143a: 4619 mov r1, r3 - 800143c: 480c ldr r0, [pc, #48] ; (8001470 <_ZL12MX_GPIO_Initv+0x1a4>) - 800143e: f000 fdc5 bl 8001fcc + 800133e: f107 031c add.w r3, r7, #28 + 8001342: 4619 mov r1, r3 + 8001344: 480c ldr r0, [pc, #48] ; (8001378 <_ZL12MX_GPIO_Initv+0x1a4>) + 8001346: f000 fe83 bl 8002050 /* EXTI interrupt init*/ HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0); - 8001442: 2200 movs r2, #0 - 8001444: 2100 movs r1, #0 - 8001446: 2028 movs r0, #40 ; 0x28 - 8001448: f000 fd67 bl 8001f1a + 800134a: 2200 movs r2, #0 + 800134c: 2100 movs r1, #0 + 800134e: 2028 movs r0, #40 ; 0x28 + 8001350: f000 fe25 bl 8001f9e HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); - 800144c: 2028 movs r0, #40 ; 0x28 - 800144e: f000 fd80 bl 8001f52 + 8001354: 2028 movs r0, #40 ; 0x28 + 8001356: f000 fe3e bl 8001fd6 } - 8001452: bf00 nop - 8001454: 3730 adds r7, #48 ; 0x30 - 8001456: 46bd mov sp, r7 - 8001458: bd80 pop {r7, pc} - 800145a: bf00 nop - 800145c: 40023800 .word 0x40023800 - 8001460: 40021400 .word 0x40021400 - 8001464: 10110000 .word 0x10110000 - 8001468: 40020800 .word 0x40020800 - 800146c: 40020000 .word 0x40020000 - 8001470: 40021000 .word 0x40021000 - -08001474 : + 800135a: bf00 nop + 800135c: 3730 adds r7, #48 ; 0x30 + 800135e: 46bd mov sp, r7 + 8001360: bd80 pop {r7, pc} + 8001362: bf00 nop + 8001364: 40023800 .word 0x40023800 + 8001368: 40021400 .word 0x40021400 + 800136c: 10110000 .word 0x10110000 + 8001370: 40020800 .word 0x40020800 + 8001374: 40020000 .word 0x40020000 + 8001378: 40021000 .word 0x40021000 + +0800137c : /* USER CODE BEGIN 4 */ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { - 8001474: b580 push {r7, lr} - 8001476: b082 sub sp, #8 - 8001478: af00 add r7, sp, #0 - 800147a: 6078 str r0, [r7, #4] + 800137c: b580 push {r7, lr} + 800137e: b084 sub sp, #16 + 8001380: af00 add r7, sp, #0 + 8001382: 6078 str r0, [r7, #4] //TIMER 100Hz PID control if (htim->Instance == TIM3) { - 800147c: 687b ldr r3, [r7, #4] - 800147e: 681b ldr r3, [r3, #0] - 8001480: 4a31 ldr r2, [pc, #196] ; (8001548 ) - 8001482: 4293 cmp r3, r2 - 8001484: d15b bne.n 800153e + 8001384: 687b ldr r3, [r7, #4] + 8001386: 681b ldr r3, [r3, #0] + 8001388: 4a62 ldr r2, [pc, #392] ; (8001514 ) + 800138a: 4293 cmp r3, r2 + 800138c: f040 80be bne.w 800150c if (mode == 1) { - 8001486: 4b31 ldr r3, [pc, #196] ; (800154c ) - 8001488: edd3 7a00 vldr s15, [r3] - 800148c: eeb7 7a00 vmov.f32 s14, #112 ; 0x3f800000 1.0 - 8001490: eef4 7a47 vcmp.f32 s15, s14 - 8001494: eef1 fa10 vmrs APSR_nzcv, fpscr - 8001498: d123 bne.n 80014e2 + 8001390: 4b61 ldr r3, [pc, #388] ; (8001518 ) + 8001392: edd3 7a00 vldr s15, [r3] + 8001396: eeb7 7a00 vmov.f32 s14, #112 ; 0x3f800000 1.0 + 800139a: eef4 7a47 vcmp.f32 s15, s14 + 800139e: eef1 fa10 vmrs APSR_nzcv, fpscr + 80013a2: d123 bne.n 80013ec left_velocity = left_encoder.GetLinearVelocity(); - 800149a: 482d ldr r0, [pc, #180] ; (8001550 ) - 800149c: f7ff f8c6 bl 800062c <_ZN7Encoder17GetLinearVelocityEv> - 80014a0: eef0 7a40 vmov.f32 s15, s0 - 80014a4: 4b2b ldr r3, [pc, #172] ; (8001554 ) - 80014a6: edc3 7a00 vstr s15, [r3] + 80013a4: 485d ldr r0, [pc, #372] ; (800151c ) + 80013a6: f7ff f935 bl 8000614 <_ZN7Encoder17GetLinearVelocityEv> + 80013aa: eef0 7a40 vmov.f32 s15, s0 + 80013ae: 4b5c ldr r3, [pc, #368] ; (8001520 ) + 80013b0: edc3 7a00 vstr s15, [r3] output_msg.velocity = left_velocity; - 80014aa: 4b2a ldr r3, [pc, #168] ; (8001554 ) - 80014ac: 681b ldr r3, [r3, #0] - 80014ae: 4a2a ldr r2, [pc, #168] ; (8001558 ) - 80014b0: 6013 str r3, [r2, #0] + 80013b4: 4b5a ldr r3, [pc, #360] ; (8001520 ) + 80013b6: 681b ldr r3, [r3, #0] + 80013b8: 4a5a ldr r2, [pc, #360] ; (8001524 ) + 80013ba: 6013 str r3, [r2, #0] left_dutycycle = left_pid.update(left_velocity); - 80014b2: 4b28 ldr r3, [pc, #160] ; (8001554 ) - 80014b4: edd3 7a00 vldr s15, [r3] - 80014b8: eeb0 0a67 vmov.f32 s0, s15 - 80014bc: 4827 ldr r0, [pc, #156] ; (800155c ) - 80014be: f7ff fb78 bl 8000bb2 <_ZN3Pid6updateEf> - 80014c2: 4602 mov r2, r0 - 80014c4: 4b26 ldr r3, [pc, #152] ; (8001560 ) - 80014c6: 601a str r2, [r3, #0] + 80013bc: 4b58 ldr r3, [pc, #352] ; (8001520 ) + 80013be: edd3 7a00 vldr s15, [r3] + 80013c2: eeb0 0a67 vmov.f32 s0, s15 + 80013c6: 4858 ldr r0, [pc, #352] ; (8001528 ) + 80013c8: f7ff fb8a bl 8000ae0 <_ZN3Pid6updateEf> + 80013cc: 4602 mov r2, r0 + 80013ce: 4b57 ldr r3, [pc, #348] ; (800152c ) + 80013d0: 601a str r2, [r3, #0] left_motor.set_speed(left_dutycycle); - 80014c8: 4b25 ldr r3, [pc, #148] ; (8001560 ) - 80014ca: 681b ldr r3, [r3, #0] - 80014cc: 4619 mov r1, r3 - 80014ce: 4825 ldr r0, [pc, #148] ; (8001564 ) - 80014d0: f7ff f978 bl 80007c4 <_ZN15MotorController9set_speedEi> + 80013d2: 4b56 ldr r3, [pc, #344] ; (800152c ) + 80013d4: 681b ldr r3, [r3, #0] + 80013d6: 4619 mov r1, r3 + 80013d8: 4855 ldr r0, [pc, #340] ; (8001530 ) + 80013da: f7ff f9df bl 800079c <_ZN15MotorController9set_speedEi> HAL_UART_Transmit(&huart6, tx_buffer, 4, 100); - 80014d4: 4b24 ldr r3, [pc, #144] ; (8001568 ) - 80014d6: 6819 ldr r1, [r3, #0] - 80014d8: 2364 movs r3, #100 ; 0x64 - 80014da: 2204 movs r2, #4 - 80014dc: 4823 ldr r0, [pc, #140] ; (800156c ) - 80014de: f003 f8ef bl 80046c0 + 80013de: 4b55 ldr r3, [pc, #340] ; (8001534 ) + 80013e0: 6819 ldr r1, [r3, #0] + 80013e2: 2364 movs r3, #100 ; 0x64 + 80013e4: 2204 movs r2, #4 + 80013e6: 4854 ldr r0, [pc, #336] ; (8001538 ) + 80013e8: f003 f9ac bl 8004744 } if (mode == 2) { - 80014e2: 4b1a ldr r3, [pc, #104] ; (800154c ) - 80014e4: edd3 7a00 vldr s15, [r3] - 80014e8: eeb0 7a00 vmov.f32 s14, #0 ; 0x40000000 2.0 - 80014ec: eef4 7a47 vcmp.f32 s15, s14 - 80014f0: eef1 fa10 vmrs APSR_nzcv, fpscr - 80014f4: d123 bne.n 800153e + 80013ec: 4b4a ldr r3, [pc, #296] ; (8001518 ) + 80013ee: edd3 7a00 vldr s15, [r3] + 80013f2: eeb0 7a00 vmov.f32 s14, #0 ; 0x40000000 2.0 + 80013f6: eef4 7a47 vcmp.f32 s15, s14 + 80013fa: eef1 fa10 vmrs APSR_nzcv, fpscr + 80013fe: d123 bne.n 8001448 right_velocity = right_encoder.GetLinearVelocity(); - 80014f6: 481e ldr r0, [pc, #120] ; (8001570 ) - 80014f8: f7ff f898 bl 800062c <_ZN7Encoder17GetLinearVelocityEv> - 80014fc: eef0 7a40 vmov.f32 s15, s0 - 8001500: 4b1c ldr r3, [pc, #112] ; (8001574 ) - 8001502: edc3 7a00 vstr s15, [r3] + 8001400: 484e ldr r0, [pc, #312] ; (800153c ) + 8001402: f7ff f907 bl 8000614 <_ZN7Encoder17GetLinearVelocityEv> + 8001406: eef0 7a40 vmov.f32 s15, s0 + 800140a: 4b4d ldr r3, [pc, #308] ; (8001540 ) + 800140c: edc3 7a00 vstr s15, [r3] output_msg.velocity = right_velocity; - 8001506: 4b1b ldr r3, [pc, #108] ; (8001574 ) - 8001508: 681b ldr r3, [r3, #0] - 800150a: 4a13 ldr r2, [pc, #76] ; (8001558 ) - 800150c: 6013 str r3, [r2, #0] + 8001410: 4b4b ldr r3, [pc, #300] ; (8001540 ) + 8001412: 681b ldr r3, [r3, #0] + 8001414: 4a43 ldr r2, [pc, #268] ; (8001524 ) + 8001416: 6013 str r3, [r2, #0] + right_dutycycle = right_pid.update(right_velocity); + 8001418: 4b49 ldr r3, [pc, #292] ; (8001540 ) + 800141a: edd3 7a00 vldr s15, [r3] + 800141e: eeb0 0a67 vmov.f32 s0, s15 + 8001422: 4848 ldr r0, [pc, #288] ; (8001544 ) + 8001424: f7ff fb5c bl 8000ae0 <_ZN3Pid6updateEf> + 8001428: 4602 mov r2, r0 + 800142a: 4b47 ldr r3, [pc, #284] ; (8001548 ) + 800142c: 601a str r2, [r3, #0] + right_motor.set_speed(right_dutycycle); + 800142e: 4b46 ldr r3, [pc, #280] ; (8001548 ) + 8001430: 681b ldr r3, [r3, #0] + 8001432: 4619 mov r1, r3 + 8001434: 4845 ldr r0, [pc, #276] ; (800154c ) + 8001436: f7ff f9b1 bl 800079c <_ZN15MotorController9set_speedEi> + HAL_UART_Transmit(&huart6, tx_buffer, 4, 100); + 800143a: 4b3e ldr r3, [pc, #248] ; (8001534 ) + 800143c: 6819 ldr r1, [r3, #0] + 800143e: 2364 movs r3, #100 ; 0x64 + 8001440: 2204 movs r2, #4 + 8001442: 483d ldr r0, [pc, #244] ; (8001538 ) + 8001444: f003 f97e bl 8004744 + } + if (mode == 3) { + 8001448: 4b33 ldr r3, [pc, #204] ; (8001518 ) + 800144a: edd3 7a00 vldr s15, [r3] + 800144e: eeb0 7a08 vmov.f32 s14, #8 ; 0x40400000 3.0 + 8001452: eef4 7a47 vcmp.f32 s15, s14 + 8001456: eef1 fa10 vmrs APSR_nzcv, fpscr + 800145a: d157 bne.n 800150c + + left_velocity = left_encoder.GetLinearVelocity(); + 800145c: 482f ldr r0, [pc, #188] ; (800151c ) + 800145e: f7ff f8d9 bl 8000614 <_ZN7Encoder17GetLinearVelocityEv> + 8001462: eef0 7a40 vmov.f32 s15, s0 + 8001466: 4b2e ldr r3, [pc, #184] ; (8001520 ) + 8001468: edc3 7a00 vstr s15, [r3] + left_dutycycle = left_pid.update(left_velocity); + 800146c: 4b2c ldr r3, [pc, #176] ; (8001520 ) + 800146e: edd3 7a00 vldr s15, [r3] + 8001472: eeb0 0a67 vmov.f32 s0, s15 + 8001476: 482c ldr r0, [pc, #176] ; (8001528 ) + 8001478: f7ff fb32 bl 8000ae0 <_ZN3Pid6updateEf> + 800147c: 4602 mov r2, r0 + 800147e: 4b2b ldr r3, [pc, #172] ; (800152c ) + 8001480: 601a str r2, [r3, #0] + left_motor.set_speed(left_dutycycle); + 8001482: 4b2a ldr r3, [pc, #168] ; (800152c ) + 8001484: 681b ldr r3, [r3, #0] + 8001486: 4619 mov r1, r3 + 8001488: 4829 ldr r0, [pc, #164] ; (8001530 ) + 800148a: f7ff f987 bl 800079c <_ZN15MotorController9set_speedEi> + + right_velocity = right_encoder.GetLinearVelocity(); + 800148e: 482b ldr r0, [pc, #172] ; (800153c ) + 8001490: f7ff f8c0 bl 8000614 <_ZN7Encoder17GetLinearVelocityEv> + 8001494: eef0 7a40 vmov.f32 s15, s0 + 8001498: 4b29 ldr r3, [pc, #164] ; (8001540 ) + 800149a: edc3 7a00 vstr s15, [r3] right_dutycycle = right_pid.update(right_velocity); - 800150e: 4b19 ldr r3, [pc, #100] ; (8001574 ) - 8001510: edd3 7a00 vldr s15, [r3] - 8001514: eeb0 0a67 vmov.f32 s0, s15 - 8001518: 4817 ldr r0, [pc, #92] ; (8001578 ) - 800151a: f7ff fb4a bl 8000bb2 <_ZN3Pid6updateEf> - 800151e: 4602 mov r2, r0 - 8001520: 4b16 ldr r3, [pc, #88] ; (800157c ) - 8001522: 601a str r2, [r3, #0] + 800149e: 4b28 ldr r3, [pc, #160] ; (8001540 ) + 80014a0: edd3 7a00 vldr s15, [r3] + 80014a4: eeb0 0a67 vmov.f32 s0, s15 + 80014a8: 4826 ldr r0, [pc, #152] ; (8001544 ) + 80014aa: f7ff fb19 bl 8000ae0 <_ZN3Pid6updateEf> + 80014ae: 4602 mov r2, r0 + 80014b0: 4b25 ldr r3, [pc, #148] ; (8001548 ) + 80014b2: 601a str r2, [r3, #0] right_motor.set_speed(right_dutycycle); - 8001524: 4b15 ldr r3, [pc, #84] ; (800157c ) - 8001526: 681b ldr r3, [r3, #0] - 8001528: 4619 mov r1, r3 - 800152a: 4815 ldr r0, [pc, #84] ; (8001580 ) - 800152c: f7ff f94a bl 80007c4 <_ZN15MotorController9set_speedEi> + 80014b4: 4b24 ldr r3, [pc, #144] ; (8001548 ) + 80014b6: 681b ldr r3, [r3, #0] + 80014b8: 4619 mov r1, r3 + 80014ba: 4824 ldr r0, [pc, #144] ; (800154c ) + 80014bc: f7ff f96e bl 800079c <_ZN15MotorController9set_speedEi> + + float difference = left_velocity - right_velocity; + 80014c0: 4b17 ldr r3, [pc, #92] ; (8001520 ) + 80014c2: ed93 7a00 vldr s14, [r3] + 80014c6: 4b1e ldr r3, [pc, #120] ; (8001540 ) + 80014c8: edd3 7a00 vldr s15, [r3] + 80014cc: ee77 7a67 vsub.f32 s15, s14, s15 + 80014d0: edc7 7a03 vstr s15, [r7, #12] + + int cross_dutycycle = cross_pid.update(difference); + 80014d4: ed97 0a03 vldr s0, [r7, #12] + 80014d8: 481d ldr r0, [pc, #116] ; (8001550 ) + 80014da: f7ff fb01 bl 8000ae0 <_ZN3Pid6updateEf> + 80014de: 60b8 str r0, [r7, #8] + + left_dutycycle += cross_dutycycle; + 80014e0: 4b12 ldr r3, [pc, #72] ; (800152c ) + 80014e2: 681a ldr r2, [r3, #0] + 80014e4: 68bb ldr r3, [r7, #8] + 80014e6: 4413 add r3, r2 + 80014e8: 4a10 ldr r2, [pc, #64] ; (800152c ) + 80014ea: 6013 str r3, [r2, #0] + right_dutycycle -= cross_dutycycle; + 80014ec: 4b16 ldr r3, [pc, #88] ; (8001548 ) + 80014ee: 681a ldr r2, [r3, #0] + 80014f0: 68bb ldr r3, [r7, #8] + 80014f2: 1ad3 subs r3, r2, r3 + 80014f4: 4a14 ldr r2, [pc, #80] ; (8001548 ) + 80014f6: 6013 str r3, [r2, #0] + + output_msg.velocity = difference; + 80014f8: 4a0a ldr r2, [pc, #40] ; (8001524 ) + 80014fa: 68fb ldr r3, [r7, #12] + 80014fc: 6013 str r3, [r2, #0] HAL_UART_Transmit(&huart6, tx_buffer, 4, 100); - 8001530: 4b0d ldr r3, [pc, #52] ; (8001568 ) - 8001532: 6819 ldr r1, [r3, #0] - 8001534: 2364 movs r3, #100 ; 0x64 - 8001536: 2204 movs r2, #4 - 8001538: 480c ldr r0, [pc, #48] ; (800156c ) - 800153a: f003 f8c1 bl 80046c0 + 80014fe: 4b0d ldr r3, [pc, #52] ; (8001534 ) + 8001500: 6819 ldr r1, [r3, #0] + 8001502: 2364 movs r3, #100 ; 0x64 + 8001504: 2204 movs r2, #4 + 8001506: 480c ldr r0, [pc, #48] ; (8001538 ) + 8001508: f003 f91c bl 8004744 } //TIMER 2Hz Transmit if (htim->Instance == TIM6) { } } - 800153e: bf00 nop - 8001540: 3708 adds r7, #8 - 8001542: 46bd mov sp, r7 - 8001544: bd80 pop {r7, pc} - 8001546: bf00 nop - 8001548: 40000400 .word 0x40000400 - 800154c: 20001ab0 .word 0x20001ab0 - 8001550: 20000208 .word 0x20000208 - 8001554: 2000026c .word 0x2000026c - 8001558: 20001aa4 .word 0x20001aa4 - 800155c: 20000274 .word 0x20000274 - 8001560: 20001a50 .word 0x20001a50 - 8001564: 20001a70 .word 0x20001a70 - 8001568: 20001a88 .word 0x20001a88 - 800156c: 2000016c .word 0x2000016c - 8001570: 200001ec .word 0x200001ec - 8001574: 20000270 .word 0x20000270 - 8001578: 20000a68 .word 0x20000a68 - 800157c: 20001a54 .word 0x20001a54 - 8001580: 20001a58 .word 0x20001a58 - -08001584 : + 800150c: bf00 nop + 800150e: 3710 adds r7, #16 + 8001510: 46bd mov sp, r7 + 8001512: bd80 pop {r7, pc} + 8001514: 40000400 .word 0x40000400 + 8001518: 20000304 .word 0x20000304 + 800151c: 20000200 .word 0x20000200 + 8001520: 2000021c .word 0x2000021c + 8001524: 200002f8 .word 0x200002f8 + 8001528: 20000224 .word 0x20000224 + 800152c: 2000029c .word 0x2000029c + 8001530: 200002bc .word 0x200002bc + 8001534: 200002d4 .word 0x200002d4 + 8001538: 2000016c .word 0x2000016c + 800153c: 200001ec .word 0x200001ec + 8001540: 20000220 .word 0x20000220 + 8001544: 20000248 .word 0x20000248 + 8001548: 200002a0 .word 0x200002a0 + 800154c: 200002a4 .word 0x200002a4 + 8001550: 2000026c .word 0x2000026c + 8001554: 00000000 .word 0x00000000 + +08001558 : void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) { - 8001584: b580 push {r7, lr} - 8001586: b082 sub sp, #8 - 8001588: af00 add r7, sp, #0 - 800158a: 6078 str r0, [r7, #4] + 8001558: b580 push {r7, lr} + 800155a: b082 sub sp, #8 + 800155c: af00 add r7, sp, #0 + 800155e: 6078 str r0, [r7, #4] if (input_msg.pid_select == 1) { - 800158c: 4b38 ldr r3, [pc, #224] ; (8001670 ) - 800158e: edd3 7a00 vldr s15, [r3] - 8001592: eeb7 7a00 vmov.f32 s14, #112 ; 0x3f800000 1.0 - 8001596: eef4 7a47 vcmp.f32 s15, s14 - 800159a: eef1 fa10 vmrs APSR_nzcv, fpscr - 800159e: d11a bne.n 80015d6 + 8001560: 4b6b ldr r3, [pc, #428] ; (8001710 ) + 8001562: edd3 7a00 vldr s15, [r3] + 8001566: eeb7 7a00 vmov.f32 s14, #112 ; 0x3f800000 1.0 + 800156a: eef4 7a47 vcmp.f32 s15, s14 + 800156e: eef1 fa10 vmrs APSR_nzcv, fpscr + 8001572: d11a bne.n 80015aa left_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - 80015a0: 4b33 ldr r3, [pc, #204] ; (8001670 ) - 80015a2: edd3 7a02 vldr s15, [r3, #8] - 80015a6: 4b32 ldr r3, [pc, #200] ; (8001670 ) - 80015a8: ed93 7a03 vldr s14, [r3, #12] - 80015ac: 4b30 ldr r3, [pc, #192] ; (8001670 ) - 80015ae: edd3 6a04 vldr s13, [r3, #16] - 80015b2: eeb0 1a66 vmov.f32 s2, s13 - 80015b6: eef0 0a47 vmov.f32 s1, s14 - 80015ba: eeb0 0a67 vmov.f32 s0, s15 - 80015be: 482d ldr r0, [pc, #180] ; (8001674 ) - 80015c0: f7ff faaa bl 8000b18 <_ZN3Pid6configEfff> - left_pid.set(input_msg.pid_setpoint); - 80015c4: 4b2a ldr r3, [pc, #168] ; (8001670 ) - 80015c6: edd3 7a01 vldr s15, [r3, #4] - 80015ca: eeb0 0a67 vmov.f32 s0, s15 - 80015ce: 4829 ldr r0, [pc, #164] ; (8001674 ) - 80015d0: f7ff fae0 bl 8000b94 <_ZN3Pid3setEf> - } else if (input_msg.pid_select == 3) { - cross_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - cross_pid.set(input_msg.pid_setpoint); + 8001574: 4b66 ldr r3, [pc, #408] ; (8001710 ) + 8001576: edd3 7a04 vldr s15, [r3, #16] + 800157a: 4b65 ldr r3, [pc, #404] ; (8001710 ) + 800157c: ed93 7a05 vldr s14, [r3, #20] + 8001580: 4b63 ldr r3, [pc, #396] ; (8001710 ) + 8001582: edd3 6a06 vldr s13, [r3, #24] + 8001586: eeb0 1a66 vmov.f32 s2, s13 + 800158a: eef0 0a47 vmov.f32 s1, s14 + 800158e: eeb0 0a67 vmov.f32 s0, s15 + 8001592: 4860 ldr r0, [pc, #384] ; (8001714 ) + 8001594: f7ff fa6c bl 8000a70 <_ZN3Pid6configEfff> + left_pid.set(input_msg.pid_setpoint_fixed); + 8001598: 4b5d ldr r3, [pc, #372] ; (8001710 ) + 800159a: edd3 7a01 vldr s15, [r3, #4] + 800159e: eeb0 0a67 vmov.f32 s0, s15 + 80015a2: 485c ldr r0, [pc, #368] ; (8001714 ) + 80015a4: f7ff fa8d bl 8000ac2 <_ZN3Pid3setEf> + + cross_setpoint = left_setpoint - right_setpoint; + cross_pid.set(cross_setpoint); } } - 80015d4: e048 b.n 8001668 + 80015a8: e0a8 b.n 80016fc } else if (input_msg.pid_select == 2) { - 80015d6: 4b26 ldr r3, [pc, #152] ; (8001670 ) - 80015d8: edd3 7a00 vldr s15, [r3] - 80015dc: eeb0 7a00 vmov.f32 s14, #0 ; 0x40000000 2.0 - 80015e0: eef4 7a47 vcmp.f32 s15, s14 - 80015e4: eef1 fa10 vmrs APSR_nzcv, fpscr - 80015e8: d11a bne.n 8001620 + 80015aa: 4b59 ldr r3, [pc, #356] ; (8001710 ) + 80015ac: edd3 7a00 vldr s15, [r3] + 80015b0: eeb0 7a00 vmov.f32 s14, #0 ; 0x40000000 2.0 + 80015b4: eef4 7a47 vcmp.f32 s15, s14 + 80015b8: eef1 fa10 vmrs APSR_nzcv, fpscr + 80015bc: d11a bne.n 80015f4 right_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - 80015ea: 4b21 ldr r3, [pc, #132] ; (8001670 ) - 80015ec: edd3 7a02 vldr s15, [r3, #8] - 80015f0: 4b1f ldr r3, [pc, #124] ; (8001670 ) - 80015f2: ed93 7a03 vldr s14, [r3, #12] - 80015f6: 4b1e ldr r3, [pc, #120] ; (8001670 ) - 80015f8: edd3 6a04 vldr s13, [r3, #16] - 80015fc: eeb0 1a66 vmov.f32 s2, s13 - 8001600: eef0 0a47 vmov.f32 s1, s14 - 8001604: eeb0 0a67 vmov.f32 s0, s15 - 8001608: 481b ldr r0, [pc, #108] ; (8001678 ) - 800160a: f7ff fa85 bl 8000b18 <_ZN3Pid6configEfff> - right_pid.set(input_msg.pid_setpoint); - 800160e: 4b18 ldr r3, [pc, #96] ; (8001670 ) - 8001610: edd3 7a01 vldr s15, [r3, #4] - 8001614: eeb0 0a67 vmov.f32 s0, s15 - 8001618: 4817 ldr r0, [pc, #92] ; (8001678 ) - 800161a: f7ff fabb bl 8000b94 <_ZN3Pid3setEf> + 80015be: 4b54 ldr r3, [pc, #336] ; (8001710 ) + 80015c0: edd3 7a04 vldr s15, [r3, #16] + 80015c4: 4b52 ldr r3, [pc, #328] ; (8001710 ) + 80015c6: ed93 7a05 vldr s14, [r3, #20] + 80015ca: 4b51 ldr r3, [pc, #324] ; (8001710 ) + 80015cc: edd3 6a06 vldr s13, [r3, #24] + 80015d0: eeb0 1a66 vmov.f32 s2, s13 + 80015d4: eef0 0a47 vmov.f32 s1, s14 + 80015d8: eeb0 0a67 vmov.f32 s0, s15 + 80015dc: 484e ldr r0, [pc, #312] ; (8001718 ) + 80015de: f7ff fa47 bl 8000a70 <_ZN3Pid6configEfff> + right_pid.set(input_msg.pid_setpoint_fixed); + 80015e2: 4b4b ldr r3, [pc, #300] ; (8001710 ) + 80015e4: edd3 7a01 vldr s15, [r3, #4] + 80015e8: eeb0 0a67 vmov.f32 s0, s15 + 80015ec: 484a ldr r0, [pc, #296] ; (8001718 ) + 80015ee: f7ff fa68 bl 8000ac2 <_ZN3Pid3setEf> } - 800161e: e023 b.n 8001668 + 80015f2: e083 b.n 80016fc } else if (input_msg.pid_select == 3) { - 8001620: 4b13 ldr r3, [pc, #76] ; (8001670 ) - 8001622: edd3 7a00 vldr s15, [r3] - 8001626: eeb0 7a08 vmov.f32 s14, #8 ; 0x40400000 3.0 - 800162a: eef4 7a47 vcmp.f32 s15, s14 - 800162e: eef1 fa10 vmrs APSR_nzcv, fpscr - 8001632: d119 bne.n 8001668 + 80015f4: 4b46 ldr r3, [pc, #280] ; (8001710 ) + 80015f6: edd3 7a00 vldr s15, [r3] + 80015fa: eeb0 7a08 vmov.f32 s14, #8 ; 0x40400000 3.0 + 80015fe: eef4 7a47 vcmp.f32 s15, s14 + 8001602: eef1 fa10 vmrs APSR_nzcv, fpscr + 8001606: d179 bne.n 80016fc + left_pid.config(180, 200, 0); + 8001608: ed9f 1a44 vldr s2, [pc, #272] ; 800171c + 800160c: eddf 0a44 vldr s1, [pc, #272] ; 8001720 + 8001610: ed9f 0a44 vldr s0, [pc, #272] ; 8001724 + 8001614: 483f ldr r0, [pc, #252] ; (8001714 ) + 8001616: f7ff fa2b bl 8000a70 <_ZN3Pid6configEfff> + right_pid.config(185, 195, 0); + 800161a: ed9f 1a40 vldr s2, [pc, #256] ; 800171c + 800161e: eddf 0a42 vldr s1, [pc, #264] ; 8001728 + 8001622: ed9f 0a42 vldr s0, [pc, #264] ; 800172c + 8001626: 483c ldr r0, [pc, #240] ; (8001718 ) + 8001628: f7ff fa22 bl 8000a70 <_ZN3Pid6configEfff> cross_pid.config(input_msg.pid_kp, input_msg.pid_ki, input_msg.pid_kd); - 8001634: 4b0e ldr r3, [pc, #56] ; (8001670 ) - 8001636: edd3 7a02 vldr s15, [r3, #8] - 800163a: 4b0d ldr r3, [pc, #52] ; (8001670 ) - 800163c: ed93 7a03 vldr s14, [r3, #12] - 8001640: 4b0b ldr r3, [pc, #44] ; (8001670 ) - 8001642: edd3 6a04 vldr s13, [r3, #16] - 8001646: eeb0 1a66 vmov.f32 s2, s13 - 800164a: eef0 0a47 vmov.f32 s1, s14 - 800164e: eeb0 0a67 vmov.f32 s0, s15 - 8001652: 480a ldr r0, [pc, #40] ; (800167c ) - 8001654: f7ff fa60 bl 8000b18 <_ZN3Pid6configEfff> - cross_pid.set(input_msg.pid_setpoint); - 8001658: 4b05 ldr r3, [pc, #20] ; (8001670 ) - 800165a: edd3 7a01 vldr s15, [r3, #4] - 800165e: eeb0 0a67 vmov.f32 s0, s15 - 8001662: 4806 ldr r0, [pc, #24] ; (800167c ) - 8001664: f7ff fa96 bl 8000b94 <_ZN3Pid3setEf> + 800162c: 4b38 ldr r3, [pc, #224] ; (8001710 ) + 800162e: edd3 7a04 vldr s15, [r3, #16] + 8001632: 4b37 ldr r3, [pc, #220] ; (8001710 ) + 8001634: ed93 7a05 vldr s14, [r3, #20] + 8001638: 4b35 ldr r3, [pc, #212] ; (8001710 ) + 800163a: edd3 6a06 vldr s13, [r3, #24] + 800163e: eeb0 1a66 vmov.f32 s2, s13 + 8001642: eef0 0a47 vmov.f32 s1, s14 + 8001646: eeb0 0a67 vmov.f32 s0, s15 + 800164a: 4839 ldr r0, [pc, #228] ; (8001730 ) + 800164c: f7ff fa10 bl 8000a70 <_ZN3Pid6configEfff> + odom.UpdateValues(input_msg.pid_setpoint_lin, input_msg.pid_setpoint_ang); + 8001650: 4b2f ldr r3, [pc, #188] ; (8001710 ) + 8001652: edd3 7a02 vldr s15, [r3, #8] + 8001656: 4b2e ldr r3, [pc, #184] ; (8001710 ) + 8001658: ed93 7a03 vldr s14, [r3, #12] + 800165c: eef0 0a47 vmov.f32 s1, s14 + 8001660: eeb0 0a67 vmov.f32 s0, s15 + 8001664: 4833 ldr r0, [pc, #204] ; (8001734 ) + 8001666: f7ff f82f bl 80006c8 <_ZN8Odometry12UpdateValuesEff> + left_setpoint = input_msg.pid_setpoint_lin + 800166a: 4b29 ldr r3, [pc, #164] ; (8001710 ) + 800166c: edd3 7a02 vldr s15, [r3, #8] + 8001670: eeb7 6ae7 vcvt.f64.f32 d6, s15 + - (BASELINE * input_msg.pid_setpoint_ang) / 2; + 8001674: 4b26 ldr r3, [pc, #152] ; (8001710 ) + 8001676: edd3 7a03 vldr s15, [r3, #12] + 800167a: eeb7 7ae7 vcvt.f64.f32 d7, s15 + 800167e: ed9f 5b22 vldr d5, [pc, #136] ; 8001708 + 8001682: ee27 5b05 vmul.f64 d5, d7, d5 + 8001686: eeb0 4b00 vmov.f64 d4, #0 ; 0x40000000 2.0 + 800168a: ee85 7b04 vdiv.f64 d7, d5, d4 + 800168e: ee36 7b47 vsub.f64 d7, d6, d7 + 8001692: eef7 7bc7 vcvt.f32.f64 s15, d7 + left_setpoint = input_msg.pid_setpoint_lin + 8001696: 4b28 ldr r3, [pc, #160] ; (8001738 ) + 8001698: edc3 7a00 vstr s15, [r3] + right_setpoint = 2 * input_msg.pid_setpoint_lin - left_setpoint; + 800169c: 4b1c ldr r3, [pc, #112] ; (8001710 ) + 800169e: edd3 7a02 vldr s15, [r3, #8] + 80016a2: ee37 7aa7 vadd.f32 s14, s15, s15 + 80016a6: 4b24 ldr r3, [pc, #144] ; (8001738 ) + 80016a8: edd3 7a00 vldr s15, [r3] + 80016ac: ee77 7a67 vsub.f32 s15, s14, s15 + 80016b0: 4b22 ldr r3, [pc, #136] ; (800173c ) + 80016b2: edc3 7a00 vstr s15, [r3] + left_pid.set(left_setpoint); + 80016b6: 4b20 ldr r3, [pc, #128] ; (8001738 ) + 80016b8: edd3 7a00 vldr s15, [r3] + 80016bc: eeb0 0a67 vmov.f32 s0, s15 + 80016c0: 4814 ldr r0, [pc, #80] ; (8001714 ) + 80016c2: f7ff f9fe bl 8000ac2 <_ZN3Pid3setEf> + right_pid.set(right_setpoint); + 80016c6: 4b1d ldr r3, [pc, #116] ; (800173c ) + 80016c8: edd3 7a00 vldr s15, [r3] + 80016cc: eeb0 0a67 vmov.f32 s0, s15 + 80016d0: 4811 ldr r0, [pc, #68] ; (8001718 ) + 80016d2: f7ff f9f6 bl 8000ac2 <_ZN3Pid3setEf> + cross_setpoint = left_setpoint - right_setpoint; + 80016d6: 4b18 ldr r3, [pc, #96] ; (8001738 ) + 80016d8: ed93 7a00 vldr s14, [r3] + 80016dc: 4b17 ldr r3, [pc, #92] ; (800173c ) + 80016de: edd3 7a00 vldr s15, [r3] + 80016e2: ee77 7a67 vsub.f32 s15, s14, s15 + 80016e6: 4b16 ldr r3, [pc, #88] ; (8001740 ) + 80016e8: edc3 7a00 vstr s15, [r3] + cross_pid.set(cross_setpoint); + 80016ec: 4b14 ldr r3, [pc, #80] ; (8001740 ) + 80016ee: edd3 7a00 vldr s15, [r3] + 80016f2: eeb0 0a67 vmov.f32 s0, s15 + 80016f6: 480e ldr r0, [pc, #56] ; (8001730 ) + 80016f8: f7ff f9e3 bl 8000ac2 <_ZN3Pid3setEf> } - 8001668: bf00 nop - 800166a: 3708 adds r7, #8 - 800166c: 46bd mov sp, r7 - 800166e: bd80 pop {r7, pc} - 8001670: 20001a90 .word 0x20001a90 - 8001674: 20000274 .word 0x20000274 - 8001678: 20000a68 .word 0x20000a68 - 800167c: 2000125c .word 0x2000125c - -08001680 : + 80016fc: bf00 nop + 80016fe: 3708 adds r7, #8 + 8001700: 46bd mov sp, r7 + 8001702: bd80 pop {r7, pc} + 8001704: f3af 8000 nop.w + 8001708: 33333333 .word 0x33333333 + 800170c: 3fd33333 .word 0x3fd33333 + 8001710: 200002dc .word 0x200002dc + 8001714: 20000224 .word 0x20000224 + 8001718: 20000248 .word 0x20000248 + 800171c: 00000000 .word 0x00000000 + 8001720: 43480000 .word 0x43480000 + 8001724: 43340000 .word 0x43340000 + 8001728: 43430000 .word 0x43430000 + 800172c: 43390000 .word 0x43390000 + 8001730: 2000026c .word 0x2000026c + 8001734: 20000214 .word 0x20000214 + 8001738: 20000290 .word 0x20000290 + 800173c: 20000294 .word 0x20000294 + 8001740: 20000298 .word 0x20000298 + +08001744 : void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { - 8001680: b580 push {r7, lr} - 8001682: b082 sub sp, #8 - 8001684: af00 add r7, sp, #0 - 8001686: 4603 mov r3, r0 - 8001688: 80fb strh r3, [r7, #6] + 8001744: b580 push {r7, lr} + 8001746: b082 sub sp, #8 + 8001748: af00 add r7, sp, #0 + 800174a: 4603 mov r3, r0 + 800174c: 80fb strh r3, [r7, #6] //Blue user button if (GPIO_Pin == GPIO_PIN_13) { - 800168a: 88fb ldrh r3, [r7, #6] - 800168c: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 8001690: d139 bne.n 8001706 + 800174e: 88fb ldrh r3, [r7, #6] + 8001750: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8001754: d12a bne.n 80017ac previous_millis = current_millis; - 8001692: 4b1f ldr r3, [pc, #124] ; (8001710 ) - 8001694: 681b ldr r3, [r3, #0] - 8001696: 4a1f ldr r2, [pc, #124] ; (8001714 ) - 8001698: 6013 str r3, [r2, #0] + 8001756: 4b17 ldr r3, [pc, #92] ; (80017b4 ) + 8001758: 681b ldr r3, [r3, #0] + 800175a: 4a17 ldr r2, [pc, #92] ; (80017b8 ) + 800175c: 6013 str r3, [r2, #0] current_millis = HAL_GetTick(); - 800169a: f000 fb57 bl 8001d4c - 800169e: 4603 mov r3, r0 - 80016a0: 461a mov r2, r3 - 80016a2: 4b1b ldr r3, [pc, #108] ; (8001710 ) - 80016a4: 601a str r2, [r3, #0] + 800175e: f000 fb37 bl 8001dd0 + 8001762: 4603 mov r3, r0 + 8001764: 461a mov r2, r3 + 8001766: 4b13 ldr r3, [pc, #76] ; (80017b4 ) + 8001768: 601a str r2, [r3, #0] if (current_millis - previous_millis < 200) - 80016a6: 4b1a ldr r3, [pc, #104] ; (8001710 ) - 80016a8: 681a ldr r2, [r3, #0] - 80016aa: 4b1a ldr r3, [pc, #104] ; (8001714 ) - 80016ac: 681b ldr r3, [r3, #0] - 80016ae: 1ad3 subs r3, r2, r3 - 80016b0: 2bc7 cmp r3, #199 ; 0xc7 - 80016b2: dc03 bgt.n 80016bc + 800176a: 4b12 ldr r3, [pc, #72] ; (80017b4 ) + 800176c: 681a ldr r2, [r3, #0] + 800176e: 4b12 ldr r3, [pc, #72] ; (80017b8 ) + 8001770: 681b ldr r3, [r3, #0] + 8001772: 1ad3 subs r3, r2, r3 + 8001774: 2bc7 cmp r3, #199 ; 0xc7 + 8001776: dc03 bgt.n 8001780 debounce = false; - 80016b4: 4b18 ldr r3, [pc, #96] ; (8001718 ) - 80016b6: 2200 movs r2, #0 - 80016b8: 701a strb r2, [r3, #0] - 80016ba: e002 b.n 80016c2 + 8001778: 4b10 ldr r3, [pc, #64] ; (80017bc ) + 800177a: 2200 movs r2, #0 + 800177c: 701a strb r2, [r3, #0] + 800177e: e002 b.n 8001786 else debounce = true; - 80016bc: 4b16 ldr r3, [pc, #88] ; (8001718 ) - 80016be: 2201 movs r2, #1 - 80016c0: 701a strb r2, [r3, #0] + 8001780: 4b0e ldr r3, [pc, #56] ; (80017bc ) + 8001782: 2201 movs r2, #1 + 8001784: 701a strb r2, [r3, #0] if (mode == 0 && debounce) { - 80016c2: 4b16 ldr r3, [pc, #88] ; (800171c ) - 80016c4: edd3 7a00 vldr s15, [r3] - 80016c8: eef5 7a40 vcmp.f32 s15, #0.0 - 80016cc: eef1 fa10 vmrs APSR_nzcv, fpscr - 80016d0: d10e bne.n 80016f0 - 80016d2: 4b11 ldr r3, [pc, #68] ; (8001718 ) - 80016d4: 781b ldrb r3, [r3, #0] - 80016d6: 2b00 cmp r3, #0 - 80016d8: d00a beq.n 80016f0 + 8001786: 4b0e ldr r3, [pc, #56] ; (80017c0 ) + 8001788: edd3 7a00 vldr s15, [r3] + 800178c: eef5 7a40 vcmp.f32 s15, #0.0 + 8001790: eef1 fa10 vmrs APSR_nzcv, fpscr + 8001794: d10a bne.n 80017ac + 8001796: 4b09 ldr r3, [pc, #36] ; (80017bc ) + 8001798: 781b ldrb r3, [r3, #0] + 800179a: 2b00 cmp r3, #0 + 800179c: d006 beq.n 80017ac mode = input_msg.pid_select; - 80016da: 4b11 ldr r3, [pc, #68] ; (8001720 ) - 80016dc: 681b ldr r3, [r3, #0] - 80016de: 4a0f ldr r2, [pc, #60] ; (800171c ) - 80016e0: 6013 str r3, [r2, #0] + 800179e: 4b09 ldr r3, [pc, #36] ; (80017c4 ) + 80017a0: 681b ldr r3, [r3, #0] + 80017a2: 4a07 ldr r2, [pc, #28] ; (80017c0 ) + 80017a4: 6013 str r3, [r2, #0] //Enables TIM3 interrupt (used for PID control) HAL_TIM_Base_Start_IT(&htim3); - 80016e2: 4810 ldr r0, [pc, #64] ; (8001724 ) - 80016e4: f001 fee0 bl 80034a8 - - //Enables TIM6 interrupt (used for periodic transmission) - HAL_TIM_Base_Start_IT(&htim6); - 80016e8: 480f ldr r0, [pc, #60] ; (8001728 ) - 80016ea: f001 fedd bl 80034a8 - - } + 80017a6: 4808 ldr r0, [pc, #32] ; (80017c8 ) + 80017a8: f001 fec0 bl 800352c } - } } - 80016ee: e00a b.n 8001706 - } else if (debounce){ - 80016f0: 4b09 ldr r3, [pc, #36] ; (8001718 ) - 80016f2: 781b ldrb r3, [r3, #0] - 80016f4: 2b00 cmp r3, #0 - 80016f6: d006 beq.n 8001706 - left_motor.brake(); - 80016f8: 480c ldr r0, [pc, #48] ; (800172c ) - 80016fa: f7ff f981 bl 8000a00 <_ZN15MotorController5brakeEv> - right_motor.brake(); - 80016fe: 480c ldr r0, [pc, #48] ; (8001730 ) - 8001700: f7ff f97e bl 8000a00 <_ZN15MotorController5brakeEv> - while (1) { - 8001704: e7fe b.n 8001704 -} - 8001706: bf00 nop - 8001708: 3708 adds r7, #8 - 800170a: 46bd mov sp, r7 - 800170c: bd80 pop {r7, pc} - 800170e: bf00 nop - 8001710: 20001aac .word 0x20001aac - 8001714: 20001aa8 .word 0x20001aa8 - 8001718: 20000000 .word 0x20000000 - 800171c: 20001ab0 .word 0x20001ab0 - 8001720: 20001a90 .word 0x20001a90 - 8001724: 2000006c .word 0x2000006c - 8001728: 2000012c .word 0x2000012c - 800172c: 20001a70 .word 0x20001a70 - 8001730: 20001a58 .word 0x20001a58 - -08001734 : + 80017ac: bf00 nop + 80017ae: 3708 adds r7, #8 + 80017b0: 46bd mov sp, r7 + 80017b2: bd80 pop {r7, pc} + 80017b4: 20000300 .word 0x20000300 + 80017b8: 200002fc .word 0x200002fc + 80017bc: 20000000 .word 0x20000000 + 80017c0: 20000304 .word 0x20000304 + 80017c4: 200002dc .word 0x200002dc + 80017c8: 2000006c .word 0x2000006c + +080017cc : + /** - * @brief This function is executed in case of error occurrence. - * @retval None - */ -void Error_Handler(void) -{ - 8001734: b480 push {r7} - 8001736: af00 add r7, sp, #0 + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) { + 80017cc: b480 push {r7} + 80017ce: 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 */ } - 8001738: bf00 nop - 800173a: 46bd mov sp, r7 - 800173c: f85d 7b04 ldr.w r7, [sp], #4 - 8001740: 4770 bx lr + 80017d0: bf00 nop + 80017d2: 46bd mov sp, r7 + 80017d4: f85d 7b04 ldr.w r7, [sp], #4 + 80017d8: 4770 bx lr ... -08001744 <_Z41__static_initialization_and_destruction_0ii>: - 8001744: b5f0 push {r4, r5, r6, r7, lr} - 8001746: b08f sub sp, #60 ; 0x3c - 8001748: af0c add r7, sp, #48 ; 0x30 - 800174a: 6078 str r0, [r7, #4] - 800174c: 6039 str r1, [r7, #0] - 800174e: 687b ldr r3, [r7, #4] - 8001750: 2b01 cmp r3, #1 - 8001752: d158 bne.n 8001806 <_Z41__static_initialization_and_destruction_0ii+0xc2> - 8001754: 683b ldr r3, [r7, #0] - 8001756: f64f 72ff movw r2, #65535 ; 0xffff - 800175a: 4293 cmp r3, r2 - 800175c: d153 bne.n 8001806 <_Z41__static_initialization_and_destruction_0ii+0xc2> -Encoder right_encoder = Encoder(&htim5); - 800175e: 492c ldr r1, [pc, #176] ; (8001810 <_Z41__static_initialization_and_destruction_0ii+0xcc>) - 8001760: 482c ldr r0, [pc, #176] ; (8001814 <_Z41__static_initialization_and_destruction_0ii+0xd0>) - 8001762: f7fe ff11 bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> -Encoder left_encoder = Encoder(&htim2); - 8001766: 492c ldr r1, [pc, #176] ; (8001818 <_Z41__static_initialization_and_destruction_0ii+0xd4>) - 8001768: 482c ldr r0, [pc, #176] ; (800181c <_Z41__static_initialization_and_destruction_0ii+0xd8>) - 800176a: f7fe ff0d bl 8000588 <_ZN7EncoderC1EP17TIM_HandleTypeDef> -Odometry odom = Odometry(left_encoder, right_encoder); - 800176e: 4e2b ldr r6, [pc, #172] ; (800181c <_Z41__static_initialization_and_destruction_0ii+0xd8>) - 8001770: 4b28 ldr r3, [pc, #160] ; (8001814 <_Z41__static_initialization_and_destruction_0ii+0xd0>) - 8001772: ac04 add r4, sp, #16 - 8001774: 461d mov r5, r3 - 8001776: cd0f ldmia r5!, {r0, r1, r2, r3} - 8001778: c40f stmia r4!, {r0, r1, r2, r3} - 800177a: e895 0007 ldmia.w r5, {r0, r1, r2} - 800177e: e884 0007 stmia.w r4, {r0, r1, r2} - 8001782: 466c mov r4, sp - 8001784: f106 030c add.w r3, r6, #12 - 8001788: cb0f ldmia r3, {r0, r1, r2, r3} - 800178a: e884 000f stmia.w r4, {r0, r1, r2, r3} - 800178e: e896 000e ldmia.w r6, {r1, r2, r3} - 8001792: 4823 ldr r0, [pc, #140] ; (8001820 <_Z41__static_initialization_and_destruction_0ii+0xdc>) - 8001794: f7fe ffb0 bl 80006f8 <_ZN8OdometryC1E7EncoderS0_> +080017dc <_Z41__static_initialization_and_destruction_0ii>: + 80017dc: b580 push {r7, lr} + 80017de: b086 sub sp, #24 + 80017e0: af04 add r7, sp, #16 + 80017e2: 6078 str r0, [r7, #4] + 80017e4: 6039 str r1, [r7, #0] + 80017e6: 687b ldr r3, [r7, #4] + 80017e8: 2b01 cmp r3, #1 + 80017ea: d14a bne.n 8001882 <_Z41__static_initialization_and_destruction_0ii+0xa6> + 80017ec: 683b ldr r3, [r7, #0] + 80017ee: f64f 72ff movw r2, #65535 ; 0xffff + 80017f2: 4293 cmp r3, r2 + 80017f4: d145 bne.n 8001882 <_Z41__static_initialization_and_destruction_0ii+0xa6> +Encoder right_encoder = Encoder(&htim5, RIGHT_WHEEL_CIRCUMFERENCE); + 80017f6: ed9f 0a25 vldr s0, [pc, #148] ; 800188c <_Z41__static_initialization_and_destruction_0ii+0xb0> + 80017fa: 4925 ldr r1, [pc, #148] ; (8001890 <_Z41__static_initialization_and_destruction_0ii+0xb4>) + 80017fc: 4825 ldr r0, [pc, #148] ; (8001894 <_Z41__static_initialization_and_destruction_0ii+0xb8>) + 80017fe: f7fe fec2 bl 8000586 <_ZN7EncoderC1EP17TIM_HandleTypeDeff> +Encoder left_encoder = Encoder(&htim2, LEFT_WHEEL_CIRCUMFERENCE); + 8001802: ed9f 0a25 vldr s0, [pc, #148] ; 8001898 <_Z41__static_initialization_and_destruction_0ii+0xbc> + 8001806: 4925 ldr r1, [pc, #148] ; (800189c <_Z41__static_initialization_and_destruction_0ii+0xc0>) + 8001808: 4825 ldr r0, [pc, #148] ; (80018a0 <_Z41__static_initialization_and_destruction_0ii+0xc4>) + 800180a: f7fe febc bl 8000586 <_ZN7EncoderC1EP17TIM_HandleTypeDeff> +Odometry odom = Odometry(); + 800180e: 4825 ldr r0, [pc, #148] ; (80018a4 <_Z41__static_initialization_and_destruction_0ii+0xc8>) + 8001810: f7fe ff46 bl 80006a0 <_ZN8OdometryC1Ev> Pid left_pid(0, 0, 0); - 8001798: ed9f 1a22 vldr s2, [pc, #136] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 800179c: eddf 0a21 vldr s1, [pc, #132] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017a0: ed9f 0a20 vldr s0, [pc, #128] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017a4: 4820 ldr r0, [pc, #128] ; (8001828 <_Z41__static_initialization_and_destruction_0ii+0xe4>) - 80017a6: f7ff f96d bl 8000a84 <_ZN3PidC1Efff> + 8001814: ed9f 1a24 vldr s2, [pc, #144] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 8001818: eddf 0a23 vldr s1, [pc, #140] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 800181c: ed9f 0a22 vldr s0, [pc, #136] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 8001820: 4822 ldr r0, [pc, #136] ; (80018ac <_Z41__static_initialization_and_destruction_0ii+0xd0>) + 8001822: f7ff f8f1 bl 8000a08 <_ZN3PidC1Efff> Pid right_pid(0, 0, 0); - 80017aa: ed9f 1a1e vldr s2, [pc, #120] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017ae: eddf 0a1d vldr s1, [pc, #116] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017b2: ed9f 0a1c vldr s0, [pc, #112] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017b6: 481d ldr r0, [pc, #116] ; (800182c <_Z41__static_initialization_and_destruction_0ii+0xe8>) - 80017b8: f7ff f964 bl 8000a84 <_ZN3PidC1Efff> + 8001826: ed9f 1a20 vldr s2, [pc, #128] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 800182a: eddf 0a1f vldr s1, [pc, #124] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 800182e: ed9f 0a1e vldr s0, [pc, #120] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 8001832: 481f ldr r0, [pc, #124] ; (80018b0 <_Z41__static_initialization_and_destruction_0ii+0xd4>) + 8001834: f7ff f8e8 bl 8000a08 <_ZN3PidC1Efff> Pid cross_pid(0, 0, 0); - 80017bc: ed9f 1a19 vldr s2, [pc, #100] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017c0: eddf 0a18 vldr s1, [pc, #96] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017c4: ed9f 0a17 vldr s0, [pc, #92] ; 8001824 <_Z41__static_initialization_and_destruction_0ii+0xe0> - 80017c8: 4819 ldr r0, [pc, #100] ; (8001830 <_Z41__static_initialization_and_destruction_0ii+0xec>) - 80017ca: f7ff f95b bl 8000a84 <_ZN3PidC1Efff> + 8001838: ed9f 1a1b vldr s2, [pc, #108] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 800183c: eddf 0a1a vldr s1, [pc, #104] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 8001840: ed9f 0a19 vldr s0, [pc, #100] ; 80018a8 <_Z41__static_initialization_and_destruction_0ii+0xcc> + 8001844: 481b ldr r0, [pc, #108] ; (80018b4 <_Z41__static_initialization_and_destruction_0ii+0xd8>) + 8001846: f7ff f8df bl 8000a08 <_ZN3PidC1Efff> TIM_CHANNEL_4); - 80017ce: 230c movs r3, #12 - 80017d0: 9302 str r3, [sp, #8] - 80017d2: 4b18 ldr r3, [pc, #96] ; (8001834 <_Z41__static_initialization_and_destruction_0ii+0xf0>) - 80017d4: 9301 str r3, [sp, #4] - 80017d6: f44f 5300 mov.w r3, #8192 ; 0x2000 - 80017da: 9300 str r3, [sp, #0] - 80017dc: 4b16 ldr r3, [pc, #88] ; (8001838 <_Z41__static_initialization_and_destruction_0ii+0xf4>) - 80017de: f44f 4200 mov.w r2, #32768 ; 0x8000 - 80017e2: 4915 ldr r1, [pc, #84] ; (8001838 <_Z41__static_initialization_and_destruction_0ii+0xf4>) - 80017e4: 4815 ldr r0, [pc, #84] ; (800183c <_Z41__static_initialization_and_destruction_0ii+0xf8>) - 80017e6: f7fe ffbb bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> + 800184a: 230c movs r3, #12 + 800184c: 9302 str r3, [sp, #8] + 800184e: 4b1a ldr r3, [pc, #104] ; (80018b8 <_Z41__static_initialization_and_destruction_0ii+0xdc>) + 8001850: 9301 str r3, [sp, #4] + 8001852: f44f 5300 mov.w r3, #8192 ; 0x2000 + 8001856: 9300 str r3, [sp, #0] + 8001858: 4b18 ldr r3, [pc, #96] ; (80018bc <_Z41__static_initialization_and_destruction_0ii+0xe0>) + 800185a: f44f 4200 mov.w r2, #32768 ; 0x8000 + 800185e: 4917 ldr r1, [pc, #92] ; (80018bc <_Z41__static_initialization_and_destruction_0ii+0xe0>) + 8001860: 4817 ldr r0, [pc, #92] ; (80018c0 <_Z41__static_initialization_and_destruction_0ii+0xe4>) + 8001862: f7fe ff69 bl 8000738 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> TIM_CHANNEL_3); - 80017ea: 2308 movs r3, #8 - 80017ec: 9302 str r3, [sp, #8] - 80017ee: 4b11 ldr r3, [pc, #68] ; (8001834 <_Z41__static_initialization_and_destruction_0ii+0xf0>) - 80017f0: 9301 str r3, [sp, #4] - 80017f2: f44f 5380 mov.w r3, #4096 ; 0x1000 - 80017f6: 9300 str r3, [sp, #0] - 80017f8: 4b0f ldr r3, [pc, #60] ; (8001838 <_Z41__static_initialization_and_destruction_0ii+0xf4>) - 80017fa: f44f 4280 mov.w r2, #16384 ; 0x4000 - 80017fe: 490e ldr r1, [pc, #56] ; (8001838 <_Z41__static_initialization_and_destruction_0ii+0xf4>) - 8001800: 480f ldr r0, [pc, #60] ; (8001840 <_Z41__static_initialization_and_destruction_0ii+0xfc>) - 8001802: f7fe ffad bl 8000760 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> + 8001866: 2308 movs r3, #8 + 8001868: 9302 str r3, [sp, #8] + 800186a: 4b13 ldr r3, [pc, #76] ; (80018b8 <_Z41__static_initialization_and_destruction_0ii+0xdc>) + 800186c: 9301 str r3, [sp, #4] + 800186e: f44f 5380 mov.w r3, #4096 ; 0x1000 + 8001872: 9300 str r3, [sp, #0] + 8001874: 4b11 ldr r3, [pc, #68] ; (80018bc <_Z41__static_initialization_and_destruction_0ii+0xe0>) + 8001876: f44f 4280 mov.w r2, #16384 ; 0x4000 + 800187a: 4910 ldr r1, [pc, #64] ; (80018bc <_Z41__static_initialization_and_destruction_0ii+0xe0>) + 800187c: 4811 ldr r0, [pc, #68] ; (80018c4 <_Z41__static_initialization_and_destruction_0ii+0xe8>) + 800187e: f7fe ff5b bl 8000738 <_ZN15MotorControllerC1EP12GPIO_TypeDeftS1_tP17TIM_HandleTypeDefm> } - 8001806: bf00 nop - 8001808: 370c adds r7, #12 - 800180a: 46bd mov sp, r7 - 800180c: bdf0 pop {r4, r5, r6, r7, pc} - 800180e: bf00 nop - 8001810: 200000ec .word 0x200000ec - 8001814: 200001ec .word 0x200001ec - 8001818: 2000002c .word 0x2000002c - 800181c: 20000208 .word 0x20000208 - 8001820: 20000224 .word 0x20000224 - 8001824: 00000000 .word 0x00000000 - 8001828: 20000274 .word 0x20000274 - 800182c: 20000a68 .word 0x20000a68 - 8001830: 2000125c .word 0x2000125c - 8001834: 200000ac .word 0x200000ac - 8001838: 40021400 .word 0x40021400 - 800183c: 20001a58 .word 0x20001a58 - 8001840: 20001a70 .word 0x20001a70 - -08001844 <_GLOBAL__sub_I_htim2>: - 8001844: b580 push {r7, lr} - 8001846: af00 add r7, sp, #0 - 8001848: f64f 71ff movw r1, #65535 ; 0xffff - 800184c: 2001 movs r0, #1 - 800184e: f7ff ff79 bl 8001744 <_Z41__static_initialization_and_destruction_0ii> - 8001852: bd80 pop {r7, pc} - -08001854 : + 8001882: bf00 nop + 8001884: 3708 adds r7, #8 + 8001886: 46bd mov sp, r7 + 8001888: bd80 pop {r7, pc} + 800188a: bf00 nop + 800188c: 3f4ccccd .word 0x3f4ccccd + 8001890: 200000ec .word 0x200000ec + 8001894: 200001ec .word 0x200001ec + 8001898: 3f47ae14 .word 0x3f47ae14 + 800189c: 2000002c .word 0x2000002c + 80018a0: 20000200 .word 0x20000200 + 80018a4: 20000214 .word 0x20000214 + 80018a8: 00000000 .word 0x00000000 + 80018ac: 20000224 .word 0x20000224 + 80018b0: 20000248 .word 0x20000248 + 80018b4: 2000026c .word 0x2000026c + 80018b8: 200000ac .word 0x200000ac + 80018bc: 40021400 .word 0x40021400 + 80018c0: 200002a4 .word 0x200002a4 + 80018c4: 200002bc .word 0x200002bc + +080018c8 <_GLOBAL__sub_I_htim2>: + 80018c8: b580 push {r7, lr} + 80018ca: af00 add r7, sp, #0 + 80018cc: f64f 71ff movw r1, #65535 ; 0xffff + 80018d0: 2001 movs r0, #1 + 80018d2: f7ff ff83 bl 80017dc <_Z41__static_initialization_and_destruction_0ii> + 80018d6: bd80 pop {r7, pc} + +080018d8 : void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); /** * Initializes the Global MSP. */ void HAL_MspInit(void) { - 8001854: b480 push {r7} - 8001856: b083 sub sp, #12 - 8001858: af00 add r7, sp, #0 + 80018d8: b480 push {r7} + 80018da: b083 sub sp, #12 + 80018dc: af00 add r7, sp, #0 /* USER CODE BEGIN MspInit 0 */ /* USER CODE END MspInit 0 */ __HAL_RCC_PWR_CLK_ENABLE(); - 800185a: 4b0f ldr r3, [pc, #60] ; (8001898 ) - 800185c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800185e: 4a0e ldr r2, [pc, #56] ; (8001898 ) - 8001860: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8001864: 6413 str r3, [r2, #64] ; 0x40 - 8001866: 4b0c ldr r3, [pc, #48] ; (8001898 ) - 8001868: 6c1b ldr r3, [r3, #64] ; 0x40 - 800186a: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 800186e: 607b str r3, [r7, #4] - 8001870: 687b ldr r3, [r7, #4] + 80018de: 4b0f ldr r3, [pc, #60] ; (800191c ) + 80018e0: 6c1b ldr r3, [r3, #64] ; 0x40 + 80018e2: 4a0e ldr r2, [pc, #56] ; (800191c ) + 80018e4: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 80018e8: 6413 str r3, [r2, #64] ; 0x40 + 80018ea: 4b0c ldr r3, [pc, #48] ; (800191c ) + 80018ec: 6c1b ldr r3, [r3, #64] ; 0x40 + 80018ee: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 80018f2: 607b str r3, [r7, #4] + 80018f4: 687b ldr r3, [r7, #4] __HAL_RCC_SYSCFG_CLK_ENABLE(); - 8001872: 4b09 ldr r3, [pc, #36] ; (8001898 ) - 8001874: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001876: 4a08 ldr r2, [pc, #32] ; (8001898 ) - 8001878: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 800187c: 6453 str r3, [r2, #68] ; 0x44 - 800187e: 4b06 ldr r3, [pc, #24] ; (8001898 ) - 8001880: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001882: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 8001886: 603b str r3, [r7, #0] - 8001888: 683b ldr r3, [r7, #0] + 80018f6: 4b09 ldr r3, [pc, #36] ; (800191c ) + 80018f8: 6c5b ldr r3, [r3, #68] ; 0x44 + 80018fa: 4a08 ldr r2, [pc, #32] ; (800191c ) + 80018fc: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 8001900: 6453 str r3, [r2, #68] ; 0x44 + 8001902: 4b06 ldr r3, [pc, #24] ; (800191c ) + 8001904: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001906: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 800190a: 603b str r3, [r7, #0] + 800190c: 683b ldr r3, [r7, #0] /* System interrupt init*/ /* USER CODE BEGIN MspInit 1 */ /* USER CODE END MspInit 1 */ } - 800188a: bf00 nop - 800188c: 370c adds r7, #12 - 800188e: 46bd mov sp, r7 - 8001890: f85d 7b04 ldr.w r7, [sp], #4 - 8001894: 4770 bx lr - 8001896: bf00 nop - 8001898: 40023800 .word 0x40023800 - -0800189c : + 800190e: bf00 nop + 8001910: 370c adds r7, #12 + 8001912: 46bd mov sp, r7 + 8001914: f85d 7b04 ldr.w r7, [sp], #4 + 8001918: 4770 bx lr + 800191a: bf00 nop + 800191c: 40023800 .word 0x40023800 + +08001920 : * 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) { - 800189c: b580 push {r7, lr} - 800189e: b08c sub sp, #48 ; 0x30 - 80018a0: af00 add r7, sp, #0 - 80018a2: 6078 str r0, [r7, #4] + 8001920: b580 push {r7, lr} + 8001922: b08c sub sp, #48 ; 0x30 + 8001924: af00 add r7, sp, #0 + 8001926: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 80018a4: f107 031c add.w r3, r7, #28 - 80018a8: 2200 movs r2, #0 - 80018aa: 601a str r2, [r3, #0] - 80018ac: 605a str r2, [r3, #4] - 80018ae: 609a str r2, [r3, #8] - 80018b0: 60da str r2, [r3, #12] - 80018b2: 611a str r2, [r3, #16] + 8001928: f107 031c add.w r3, r7, #28 + 800192c: 2200 movs r2, #0 + 800192e: 601a str r2, [r3, #0] + 8001930: 605a str r2, [r3, #4] + 8001932: 609a str r2, [r3, #8] + 8001934: 60da str r2, [r3, #12] + 8001936: 611a str r2, [r3, #16] if(htim_encoder->Instance==TIM2) - 80018b4: 687b ldr r3, [r7, #4] - 80018b6: 681b ldr r3, [r3, #0] - 80018b8: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 80018bc: d144 bne.n 8001948 + 8001938: 687b ldr r3, [r7, #4] + 800193a: 681b ldr r3, [r3, #0] + 800193c: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8001940: d144 bne.n 80019cc { /* USER CODE BEGIN TIM2_MspInit 0 */ /* USER CODE END TIM2_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_TIM2_CLK_ENABLE(); - 80018be: 4b3b ldr r3, [pc, #236] ; (80019ac ) - 80018c0: 6c1b ldr r3, [r3, #64] ; 0x40 - 80018c2: 4a3a ldr r2, [pc, #232] ; (80019ac ) - 80018c4: f043 0301 orr.w r3, r3, #1 - 80018c8: 6413 str r3, [r2, #64] ; 0x40 - 80018ca: 4b38 ldr r3, [pc, #224] ; (80019ac ) - 80018cc: 6c1b ldr r3, [r3, #64] ; 0x40 - 80018ce: f003 0301 and.w r3, r3, #1 - 80018d2: 61bb str r3, [r7, #24] - 80018d4: 69bb ldr r3, [r7, #24] + 8001942: 4b3b ldr r3, [pc, #236] ; (8001a30 ) + 8001944: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001946: 4a3a ldr r2, [pc, #232] ; (8001a30 ) + 8001948: f043 0301 orr.w r3, r3, #1 + 800194c: 6413 str r3, [r2, #64] ; 0x40 + 800194e: 4b38 ldr r3, [pc, #224] ; (8001a30 ) + 8001950: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001952: f003 0301 and.w r3, r3, #1 + 8001956: 61bb str r3, [r7, #24] + 8001958: 69bb ldr r3, [r7, #24] __HAL_RCC_GPIOA_CLK_ENABLE(); - 80018d6: 4b35 ldr r3, [pc, #212] ; (80019ac ) - 80018d8: 6b1b ldr r3, [r3, #48] ; 0x30 - 80018da: 4a34 ldr r2, [pc, #208] ; (80019ac ) - 80018dc: f043 0301 orr.w r3, r3, #1 - 80018e0: 6313 str r3, [r2, #48] ; 0x30 - 80018e2: 4b32 ldr r3, [pc, #200] ; (80019ac ) - 80018e4: 6b1b ldr r3, [r3, #48] ; 0x30 - 80018e6: f003 0301 and.w r3, r3, #1 - 80018ea: 617b str r3, [r7, #20] - 80018ec: 697b ldr r3, [r7, #20] + 800195a: 4b35 ldr r3, [pc, #212] ; (8001a30 ) + 800195c: 6b1b ldr r3, [r3, #48] ; 0x30 + 800195e: 4a34 ldr r2, [pc, #208] ; (8001a30 ) + 8001960: f043 0301 orr.w r3, r3, #1 + 8001964: 6313 str r3, [r2, #48] ; 0x30 + 8001966: 4b32 ldr r3, [pc, #200] ; (8001a30 ) + 8001968: 6b1b ldr r3, [r3, #48] ; 0x30 + 800196a: f003 0301 and.w r3, r3, #1 + 800196e: 617b str r3, [r7, #20] + 8001970: 697b ldr r3, [r7, #20] __HAL_RCC_GPIOB_CLK_ENABLE(); - 80018ee: 4b2f ldr r3, [pc, #188] ; (80019ac ) - 80018f0: 6b1b ldr r3, [r3, #48] ; 0x30 - 80018f2: 4a2e ldr r2, [pc, #184] ; (80019ac ) - 80018f4: f043 0302 orr.w r3, r3, #2 - 80018f8: 6313 str r3, [r2, #48] ; 0x30 - 80018fa: 4b2c ldr r3, [pc, #176] ; (80019ac ) - 80018fc: 6b1b ldr r3, [r3, #48] ; 0x30 - 80018fe: f003 0302 and.w r3, r3, #2 - 8001902: 613b str r3, [r7, #16] - 8001904: 693b ldr r3, [r7, #16] + 8001972: 4b2f ldr r3, [pc, #188] ; (8001a30 ) + 8001974: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001976: 4a2e ldr r2, [pc, #184] ; (8001a30 ) + 8001978: f043 0302 orr.w r3, r3, #2 + 800197c: 6313 str r3, [r2, #48] ; 0x30 + 800197e: 4b2c ldr r3, [pc, #176] ; (8001a30 ) + 8001980: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001982: f003 0302 and.w r3, r3, #2 + 8001986: 613b str r3, [r7, #16] + 8001988: 693b ldr r3, [r7, #16] /**TIM2 GPIO Configuration PA5 ------> TIM2_CH1 PB3 ------> TIM2_CH2 */ GPIO_InitStruct.Pin = encoder_sx1_Pin; - 8001906: 2320 movs r3, #32 - 8001908: 61fb str r3, [r7, #28] + 800198a: 2320 movs r3, #32 + 800198c: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 800190a: 2302 movs r3, #2 - 800190c: 623b str r3, [r7, #32] + 800198e: 2302 movs r3, #2 + 8001990: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800190e: 2300 movs r3, #0 - 8001910: 627b str r3, [r7, #36] ; 0x24 + 8001992: 2300 movs r3, #0 + 8001994: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001912: 2300 movs r3, #0 - 8001914: 62bb str r3, [r7, #40] ; 0x28 + 8001996: 2300 movs r3, #0 + 8001998: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - 8001916: 2301 movs r3, #1 - 8001918: 62fb str r3, [r7, #44] ; 0x2c + 800199a: 2301 movs r3, #1 + 800199c: 62fb str r3, [r7, #44] ; 0x2c HAL_GPIO_Init(encoder_sx1_GPIO_Port, &GPIO_InitStruct); - 800191a: f107 031c add.w r3, r7, #28 - 800191e: 4619 mov r1, r3 - 8001920: 4823 ldr r0, [pc, #140] ; (80019b0 ) - 8001922: f000 fb53 bl 8001fcc + 800199e: f107 031c add.w r3, r7, #28 + 80019a2: 4619 mov r1, r3 + 80019a4: 4823 ldr r0, [pc, #140] ; (8001a34 ) + 80019a6: f000 fb53 bl 8002050 GPIO_InitStruct.Pin = encoder_sx2_Pin; - 8001926: 2308 movs r3, #8 - 8001928: 61fb str r3, [r7, #28] + 80019aa: 2308 movs r3, #8 + 80019ac: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 800192a: 2302 movs r3, #2 - 800192c: 623b str r3, [r7, #32] + 80019ae: 2302 movs r3, #2 + 80019b0: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800192e: 2300 movs r3, #0 - 8001930: 627b str r3, [r7, #36] ; 0x24 + 80019b2: 2300 movs r3, #0 + 80019b4: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001932: 2300 movs r3, #0 - 8001934: 62bb str r3, [r7, #40] ; 0x28 + 80019b6: 2300 movs r3, #0 + 80019b8: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF1_TIM2; - 8001936: 2301 movs r3, #1 - 8001938: 62fb str r3, [r7, #44] ; 0x2c + 80019ba: 2301 movs r3, #1 + 80019bc: 62fb str r3, [r7, #44] ; 0x2c HAL_GPIO_Init(encoder_sx2_GPIO_Port, &GPIO_InitStruct); - 800193a: f107 031c add.w r3, r7, #28 - 800193e: 4619 mov r1, r3 - 8001940: 481c ldr r0, [pc, #112] ; (80019b4 ) - 8001942: f000 fb43 bl 8001fcc + 80019be: f107 031c add.w r3, r7, #28 + 80019c2: 4619 mov r1, r3 + 80019c4: 481c ldr r0, [pc, #112] ; (8001a38 ) + 80019c6: f000 fb43 bl 8002050 /* USER CODE BEGIN TIM5_MspInit 1 */ /* USER CODE END TIM5_MspInit 1 */ } } - 8001946: e02c b.n 80019a2 + 80019ca: e02c b.n 8001a26 else if(htim_encoder->Instance==TIM5) - 8001948: 687b ldr r3, [r7, #4] - 800194a: 681b ldr r3, [r3, #0] - 800194c: 4a1a ldr r2, [pc, #104] ; (80019b8 ) - 800194e: 4293 cmp r3, r2 - 8001950: d127 bne.n 80019a2 + 80019cc: 687b ldr r3, [r7, #4] + 80019ce: 681b ldr r3, [r3, #0] + 80019d0: 4a1a ldr r2, [pc, #104] ; (8001a3c ) + 80019d2: 4293 cmp r3, r2 + 80019d4: d127 bne.n 8001a26 __HAL_RCC_TIM5_CLK_ENABLE(); - 8001952: 4b16 ldr r3, [pc, #88] ; (80019ac ) - 8001954: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001956: 4a15 ldr r2, [pc, #84] ; (80019ac ) - 8001958: f043 0308 orr.w r3, r3, #8 - 800195c: 6413 str r3, [r2, #64] ; 0x40 - 800195e: 4b13 ldr r3, [pc, #76] ; (80019ac ) - 8001960: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001962: f003 0308 and.w r3, r3, #8 - 8001966: 60fb str r3, [r7, #12] - 8001968: 68fb ldr r3, [r7, #12] + 80019d6: 4b16 ldr r3, [pc, #88] ; (8001a30 ) + 80019d8: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019da: 4a15 ldr r2, [pc, #84] ; (8001a30 ) + 80019dc: f043 0308 orr.w r3, r3, #8 + 80019e0: 6413 str r3, [r2, #64] ; 0x40 + 80019e2: 4b13 ldr r3, [pc, #76] ; (8001a30 ) + 80019e4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80019e6: f003 0308 and.w r3, r3, #8 + 80019ea: 60fb str r3, [r7, #12] + 80019ec: 68fb ldr r3, [r7, #12] __HAL_RCC_GPIOA_CLK_ENABLE(); - 800196a: 4b10 ldr r3, [pc, #64] ; (80019ac ) - 800196c: 6b1b ldr r3, [r3, #48] ; 0x30 - 800196e: 4a0f ldr r2, [pc, #60] ; (80019ac ) - 8001970: f043 0301 orr.w r3, r3, #1 - 8001974: 6313 str r3, [r2, #48] ; 0x30 - 8001976: 4b0d ldr r3, [pc, #52] ; (80019ac ) - 8001978: 6b1b ldr r3, [r3, #48] ; 0x30 - 800197a: f003 0301 and.w r3, r3, #1 - 800197e: 60bb str r3, [r7, #8] - 8001980: 68bb ldr r3, [r7, #8] + 80019ee: 4b10 ldr r3, [pc, #64] ; (8001a30 ) + 80019f0: 6b1b ldr r3, [r3, #48] ; 0x30 + 80019f2: 4a0f ldr r2, [pc, #60] ; (8001a30 ) + 80019f4: f043 0301 orr.w r3, r3, #1 + 80019f8: 6313 str r3, [r2, #48] ; 0x30 + 80019fa: 4b0d ldr r3, [pc, #52] ; (8001a30 ) + 80019fc: 6b1b ldr r3, [r3, #48] ; 0x30 + 80019fe: f003 0301 and.w r3, r3, #1 + 8001a02: 60bb str r3, [r7, #8] + 8001a04: 68bb ldr r3, [r7, #8] GPIO_InitStruct.Pin = encoder_dx1_Pin|encoder_dx2_Pin; - 8001982: 2303 movs r3, #3 - 8001984: 61fb str r3, [r7, #28] + 8001a06: 2303 movs r3, #3 + 8001a08: 61fb str r3, [r7, #28] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 8001986: 2302 movs r3, #2 - 8001988: 623b str r3, [r7, #32] + 8001a0a: 2302 movs r3, #2 + 8001a0c: 623b str r3, [r7, #32] GPIO_InitStruct.Pull = GPIO_NOPULL; - 800198a: 2300 movs r3, #0 - 800198c: 627b str r3, [r7, #36] ; 0x24 + 8001a0e: 2300 movs r3, #0 + 8001a10: 627b str r3, [r7, #36] ; 0x24 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 800198e: 2300 movs r3, #0 - 8001990: 62bb str r3, [r7, #40] ; 0x28 + 8001a12: 2300 movs r3, #0 + 8001a14: 62bb str r3, [r7, #40] ; 0x28 GPIO_InitStruct.Alternate = GPIO_AF2_TIM5; - 8001992: 2302 movs r3, #2 - 8001994: 62fb str r3, [r7, #44] ; 0x2c + 8001a16: 2302 movs r3, #2 + 8001a18: 62fb str r3, [r7, #44] ; 0x2c HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - 8001996: f107 031c add.w r3, r7, #28 - 800199a: 4619 mov r1, r3 - 800199c: 4804 ldr r0, [pc, #16] ; (80019b0 ) - 800199e: f000 fb15 bl 8001fcc + 8001a1a: f107 031c add.w r3, r7, #28 + 8001a1e: 4619 mov r1, r3 + 8001a20: 4804 ldr r0, [pc, #16] ; (8001a34 ) + 8001a22: f000 fb15 bl 8002050 } - 80019a2: bf00 nop - 80019a4: 3730 adds r7, #48 ; 0x30 - 80019a6: 46bd mov sp, r7 - 80019a8: bd80 pop {r7, pc} - 80019aa: bf00 nop - 80019ac: 40023800 .word 0x40023800 - 80019b0: 40020000 .word 0x40020000 - 80019b4: 40020400 .word 0x40020400 - 80019b8: 40000c00 .word 0x40000c00 - -080019bc : + 8001a26: bf00 nop + 8001a28: 3730 adds r7, #48 ; 0x30 + 8001a2a: 46bd mov sp, r7 + 8001a2c: bd80 pop {r7, pc} + 8001a2e: bf00 nop + 8001a30: 40023800 .word 0x40023800 + 8001a34: 40020000 .word 0x40020000 + 8001a38: 40020400 .word 0x40020400 + 8001a3c: 40000c00 .word 0x40000c00 + +08001a40 : * 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) { - 80019bc: b480 push {r7} - 80019be: b087 sub sp, #28 - 80019c0: af00 add r7, sp, #0 - 80019c2: 6078 str r0, [r7, #4] + 8001a40: b480 push {r7} + 8001a42: b087 sub sp, #28 + 8001a44: af00 add r7, sp, #0 + 8001a46: 6078 str r0, [r7, #4] if(htim_base->Instance==TIM3) - 80019c4: 687b ldr r3, [r7, #4] - 80019c6: 681b ldr r3, [r3, #0] - 80019c8: 4a1c ldr r2, [pc, #112] ; (8001a3c ) - 80019ca: 4293 cmp r3, r2 - 80019cc: d10c bne.n 80019e8 + 8001a48: 687b ldr r3, [r7, #4] + 8001a4a: 681b ldr r3, [r3, #0] + 8001a4c: 4a1c ldr r2, [pc, #112] ; (8001ac0 ) + 8001a4e: 4293 cmp r3, r2 + 8001a50: d10c bne.n 8001a6c { /* USER CODE BEGIN TIM3_MspInit 0 */ /* USER CODE END TIM3_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_TIM3_CLK_ENABLE(); - 80019ce: 4b1c ldr r3, [pc, #112] ; (8001a40 ) - 80019d0: 6c1b ldr r3, [r3, #64] ; 0x40 - 80019d2: 4a1b ldr r2, [pc, #108] ; (8001a40 ) - 80019d4: f043 0302 orr.w r3, r3, #2 - 80019d8: 6413 str r3, [r2, #64] ; 0x40 - 80019da: 4b19 ldr r3, [pc, #100] ; (8001a40 ) - 80019dc: 6c1b ldr r3, [r3, #64] ; 0x40 - 80019de: f003 0302 and.w r3, r3, #2 - 80019e2: 617b str r3, [r7, #20] - 80019e4: 697b ldr r3, [r7, #20] + 8001a52: 4b1c ldr r3, [pc, #112] ; (8001ac4 ) + 8001a54: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a56: 4a1b ldr r2, [pc, #108] ; (8001ac4 ) + 8001a58: f043 0302 orr.w r3, r3, #2 + 8001a5c: 6413 str r3, [r2, #64] ; 0x40 + 8001a5e: 4b19 ldr r3, [pc, #100] ; (8001ac4 ) + 8001a60: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a62: f003 0302 and.w r3, r3, #2 + 8001a66: 617b str r3, [r7, #20] + 8001a68: 697b ldr r3, [r7, #20] /* USER CODE BEGIN TIM6_MspInit 1 */ /* USER CODE END TIM6_MspInit 1 */ } } - 80019e6: e022 b.n 8001a2e + 8001a6a: e022 b.n 8001ab2 else if(htim_base->Instance==TIM4) - 80019e8: 687b ldr r3, [r7, #4] - 80019ea: 681b ldr r3, [r3, #0] - 80019ec: 4a15 ldr r2, [pc, #84] ; (8001a44 ) - 80019ee: 4293 cmp r3, r2 - 80019f0: d10c bne.n 8001a0c + 8001a6c: 687b ldr r3, [r7, #4] + 8001a6e: 681b ldr r3, [r3, #0] + 8001a70: 4a15 ldr r2, [pc, #84] ; (8001ac8 ) + 8001a72: 4293 cmp r3, r2 + 8001a74: d10c bne.n 8001a90 __HAL_RCC_TIM4_CLK_ENABLE(); - 80019f2: 4b13 ldr r3, [pc, #76] ; (8001a40 ) - 80019f4: 6c1b ldr r3, [r3, #64] ; 0x40 - 80019f6: 4a12 ldr r2, [pc, #72] ; (8001a40 ) - 80019f8: f043 0304 orr.w r3, r3, #4 - 80019fc: 6413 str r3, [r2, #64] ; 0x40 - 80019fe: 4b10 ldr r3, [pc, #64] ; (8001a40 ) - 8001a00: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001a02: f003 0304 and.w r3, r3, #4 - 8001a06: 613b str r3, [r7, #16] - 8001a08: 693b ldr r3, [r7, #16] + 8001a76: 4b13 ldr r3, [pc, #76] ; (8001ac4 ) + 8001a78: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a7a: 4a12 ldr r2, [pc, #72] ; (8001ac4 ) + 8001a7c: f043 0304 orr.w r3, r3, #4 + 8001a80: 6413 str r3, [r2, #64] ; 0x40 + 8001a82: 4b10 ldr r3, [pc, #64] ; (8001ac4 ) + 8001a84: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a86: f003 0304 and.w r3, r3, #4 + 8001a8a: 613b str r3, [r7, #16] + 8001a8c: 693b ldr r3, [r7, #16] } - 8001a0a: e010 b.n 8001a2e + 8001a8e: e010 b.n 8001ab2 else if(htim_base->Instance==TIM6) - 8001a0c: 687b ldr r3, [r7, #4] - 8001a0e: 681b ldr r3, [r3, #0] - 8001a10: 4a0d ldr r2, [pc, #52] ; (8001a48 ) - 8001a12: 4293 cmp r3, r2 - 8001a14: d10b bne.n 8001a2e + 8001a90: 687b ldr r3, [r7, #4] + 8001a92: 681b ldr r3, [r3, #0] + 8001a94: 4a0d ldr r2, [pc, #52] ; (8001acc ) + 8001a96: 4293 cmp r3, r2 + 8001a98: d10b bne.n 8001ab2 __HAL_RCC_TIM6_CLK_ENABLE(); - 8001a16: 4b0a ldr r3, [pc, #40] ; (8001a40 ) - 8001a18: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001a1a: 4a09 ldr r2, [pc, #36] ; (8001a40 ) - 8001a1c: f043 0310 orr.w r3, r3, #16 - 8001a20: 6413 str r3, [r2, #64] ; 0x40 - 8001a22: 4b07 ldr r3, [pc, #28] ; (8001a40 ) - 8001a24: 6c1b ldr r3, [r3, #64] ; 0x40 - 8001a26: f003 0310 and.w r3, r3, #16 - 8001a2a: 60fb str r3, [r7, #12] - 8001a2c: 68fb ldr r3, [r7, #12] + 8001a9a: 4b0a ldr r3, [pc, #40] ; (8001ac4 ) + 8001a9c: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001a9e: 4a09 ldr r2, [pc, #36] ; (8001ac4 ) + 8001aa0: f043 0310 orr.w r3, r3, #16 + 8001aa4: 6413 str r3, [r2, #64] ; 0x40 + 8001aa6: 4b07 ldr r3, [pc, #28] ; (8001ac4 ) + 8001aa8: 6c1b ldr r3, [r3, #64] ; 0x40 + 8001aaa: f003 0310 and.w r3, r3, #16 + 8001aae: 60fb str r3, [r7, #12] + 8001ab0: 68fb ldr r3, [r7, #12] } - 8001a2e: bf00 nop - 8001a30: 371c adds r7, #28 - 8001a32: 46bd mov sp, r7 - 8001a34: f85d 7b04 ldr.w r7, [sp], #4 - 8001a38: 4770 bx lr - 8001a3a: bf00 nop - 8001a3c: 40000400 .word 0x40000400 - 8001a40: 40023800 .word 0x40023800 - 8001a44: 40000800 .word 0x40000800 - 8001a48: 40001000 .word 0x40001000 - -08001a4c : + 8001ab2: bf00 nop + 8001ab4: 371c adds r7, #28 + 8001ab6: 46bd mov sp, r7 + 8001ab8: f85d 7b04 ldr.w r7, [sp], #4 + 8001abc: 4770 bx lr + 8001abe: bf00 nop + 8001ac0: 40000400 .word 0x40000400 + 8001ac4: 40023800 .word 0x40023800 + 8001ac8: 40000800 .word 0x40000800 + 8001acc: 40001000 .word 0x40001000 + +08001ad0 : void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) { - 8001a4c: b580 push {r7, lr} - 8001a4e: b088 sub sp, #32 - 8001a50: af00 add r7, sp, #0 - 8001a52: 6078 str r0, [r7, #4] + 8001ad0: b580 push {r7, lr} + 8001ad2: b088 sub sp, #32 + 8001ad4: af00 add r7, sp, #0 + 8001ad6: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 8001a54: f107 030c add.w r3, r7, #12 - 8001a58: 2200 movs r2, #0 - 8001a5a: 601a str r2, [r3, #0] - 8001a5c: 605a str r2, [r3, #4] - 8001a5e: 609a str r2, [r3, #8] - 8001a60: 60da str r2, [r3, #12] - 8001a62: 611a str r2, [r3, #16] + 8001ad8: f107 030c add.w r3, r7, #12 + 8001adc: 2200 movs r2, #0 + 8001ade: 601a str r2, [r3, #0] + 8001ae0: 605a str r2, [r3, #4] + 8001ae2: 609a str r2, [r3, #8] + 8001ae4: 60da str r2, [r3, #12] + 8001ae6: 611a str r2, [r3, #16] if(htim->Instance==TIM4) - 8001a64: 687b ldr r3, [r7, #4] - 8001a66: 681b ldr r3, [r3, #0] - 8001a68: 4a11 ldr r2, [pc, #68] ; (8001ab0 ) - 8001a6a: 4293 cmp r3, r2 - 8001a6c: d11c bne.n 8001aa8 + 8001ae8: 687b ldr r3, [r7, #4] + 8001aea: 681b ldr r3, [r3, #0] + 8001aec: 4a11 ldr r2, [pc, #68] ; (8001b34 ) + 8001aee: 4293 cmp r3, r2 + 8001af0: d11c bne.n 8001b2c { /* USER CODE BEGIN TIM4_MspPostInit 0 */ /* USER CODE END TIM4_MspPostInit 0 */ __HAL_RCC_GPIOD_CLK_ENABLE(); - 8001a6e: 4b11 ldr r3, [pc, #68] ; (8001ab4 ) - 8001a70: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001a72: 4a10 ldr r2, [pc, #64] ; (8001ab4 ) - 8001a74: f043 0308 orr.w r3, r3, #8 - 8001a78: 6313 str r3, [r2, #48] ; 0x30 - 8001a7a: 4b0e ldr r3, [pc, #56] ; (8001ab4 ) - 8001a7c: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001a7e: f003 0308 and.w r3, r3, #8 - 8001a82: 60bb str r3, [r7, #8] - 8001a84: 68bb ldr r3, [r7, #8] + 8001af2: 4b11 ldr r3, [pc, #68] ; (8001b38 ) + 8001af4: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001af6: 4a10 ldr r2, [pc, #64] ; (8001b38 ) + 8001af8: f043 0308 orr.w r3, r3, #8 + 8001afc: 6313 str r3, [r2, #48] ; 0x30 + 8001afe: 4b0e ldr r3, [pc, #56] ; (8001b38 ) + 8001b00: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001b02: f003 0308 and.w r3, r3, #8 + 8001b06: 60bb str r3, [r7, #8] + 8001b08: 68bb ldr r3, [r7, #8] /**TIM4 GPIO Configuration PD14 ------> TIM4_CH3 PD15 ------> TIM4_CH4 */ GPIO_InitStruct.Pin = pwm2_Pin|pwm1_Pin; - 8001a86: f44f 4340 mov.w r3, #49152 ; 0xc000 - 8001a8a: 60fb str r3, [r7, #12] + 8001b0a: f44f 4340 mov.w r3, #49152 ; 0xc000 + 8001b0e: 60fb str r3, [r7, #12] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 8001a8c: 2302 movs r3, #2 - 8001a8e: 613b str r3, [r7, #16] + 8001b10: 2302 movs r3, #2 + 8001b12: 613b str r3, [r7, #16] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001a90: 2300 movs r3, #0 - 8001a92: 617b str r3, [r7, #20] + 8001b14: 2300 movs r3, #0 + 8001b16: 617b str r3, [r7, #20] GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - 8001a94: 2300 movs r3, #0 - 8001a96: 61bb str r3, [r7, #24] + 8001b18: 2300 movs r3, #0 + 8001b1a: 61bb str r3, [r7, #24] GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; - 8001a98: 2302 movs r3, #2 - 8001a9a: 61fb str r3, [r7, #28] + 8001b1c: 2302 movs r3, #2 + 8001b1e: 61fb str r3, [r7, #28] HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - 8001a9c: f107 030c add.w r3, r7, #12 - 8001aa0: 4619 mov r1, r3 - 8001aa2: 4805 ldr r0, [pc, #20] ; (8001ab8 ) - 8001aa4: f000 fa92 bl 8001fcc + 8001b20: f107 030c add.w r3, r7, #12 + 8001b24: 4619 mov r1, r3 + 8001b26: 4805 ldr r0, [pc, #20] ; (8001b3c ) + 8001b28: f000 fa92 bl 8002050 /* USER CODE BEGIN TIM4_MspPostInit 1 */ /* USER CODE END TIM4_MspPostInit 1 */ } } - 8001aa8: bf00 nop - 8001aaa: 3720 adds r7, #32 - 8001aac: 46bd mov sp, r7 - 8001aae: bd80 pop {r7, pc} - 8001ab0: 40000800 .word 0x40000800 - 8001ab4: 40023800 .word 0x40023800 - 8001ab8: 40020c00 .word 0x40020c00 - -08001abc : + 8001b2c: bf00 nop + 8001b2e: 3720 adds r7, #32 + 8001b30: 46bd mov sp, r7 + 8001b32: bd80 pop {r7, pc} + 8001b34: 40000800 .word 0x40000800 + 8001b38: 40023800 .word 0x40023800 + 8001b3c: 40020c00 .word 0x40020c00 + +08001b40 : * This function configures the hardware resources used in this example * @param huart: UART handle pointer * @retval None */ void HAL_UART_MspInit(UART_HandleTypeDef* huart) { - 8001abc: b580 push {r7, lr} - 8001abe: b08a sub sp, #40 ; 0x28 - 8001ac0: af00 add r7, sp, #0 - 8001ac2: 6078 str r0, [r7, #4] + 8001b40: b580 push {r7, lr} + 8001b42: b08a sub sp, #40 ; 0x28 + 8001b44: af00 add r7, sp, #0 + 8001b46: 6078 str r0, [r7, #4] GPIO_InitTypeDef GPIO_InitStruct = {0}; - 8001ac4: f107 0314 add.w r3, r7, #20 - 8001ac8: 2200 movs r2, #0 - 8001aca: 601a str r2, [r3, #0] - 8001acc: 605a str r2, [r3, #4] - 8001ace: 609a str r2, [r3, #8] - 8001ad0: 60da str r2, [r3, #12] - 8001ad2: 611a str r2, [r3, #16] + 8001b48: f107 0314 add.w r3, r7, #20 + 8001b4c: 2200 movs r2, #0 + 8001b4e: 601a str r2, [r3, #0] + 8001b50: 605a str r2, [r3, #4] + 8001b52: 609a str r2, [r3, #8] + 8001b54: 60da str r2, [r3, #12] + 8001b56: 611a str r2, [r3, #16] if(huart->Instance==USART6) - 8001ad4: 687b ldr r3, [r7, #4] - 8001ad6: 681b ldr r3, [r3, #0] - 8001ad8: 4a17 ldr r2, [pc, #92] ; (8001b38 ) - 8001ada: 4293 cmp r3, r2 - 8001adc: d127 bne.n 8001b2e + 8001b58: 687b ldr r3, [r7, #4] + 8001b5a: 681b ldr r3, [r3, #0] + 8001b5c: 4a17 ldr r2, [pc, #92] ; (8001bbc ) + 8001b5e: 4293 cmp r3, r2 + 8001b60: d127 bne.n 8001bb2 { /* USER CODE BEGIN USART6_MspInit 0 */ /* USER CODE END USART6_MspInit 0 */ /* Peripheral clock enable */ __HAL_RCC_USART6_CLK_ENABLE(); - 8001ade: 4b17 ldr r3, [pc, #92] ; (8001b3c ) - 8001ae0: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001ae2: 4a16 ldr r2, [pc, #88] ; (8001b3c ) - 8001ae4: f043 0320 orr.w r3, r3, #32 - 8001ae8: 6453 str r3, [r2, #68] ; 0x44 - 8001aea: 4b14 ldr r3, [pc, #80] ; (8001b3c ) - 8001aec: 6c5b ldr r3, [r3, #68] ; 0x44 - 8001aee: f003 0320 and.w r3, r3, #32 - 8001af2: 613b str r3, [r7, #16] - 8001af4: 693b ldr r3, [r7, #16] + 8001b62: 4b17 ldr r3, [pc, #92] ; (8001bc0 ) + 8001b64: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001b66: 4a16 ldr r2, [pc, #88] ; (8001bc0 ) + 8001b68: f043 0320 orr.w r3, r3, #32 + 8001b6c: 6453 str r3, [r2, #68] ; 0x44 + 8001b6e: 4b14 ldr r3, [pc, #80] ; (8001bc0 ) + 8001b70: 6c5b ldr r3, [r3, #68] ; 0x44 + 8001b72: f003 0320 and.w r3, r3, #32 + 8001b76: 613b str r3, [r7, #16] + 8001b78: 693b ldr r3, [r7, #16] __HAL_RCC_GPIOC_CLK_ENABLE(); - 8001af6: 4b11 ldr r3, [pc, #68] ; (8001b3c ) - 8001af8: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001afa: 4a10 ldr r2, [pc, #64] ; (8001b3c ) - 8001afc: f043 0304 orr.w r3, r3, #4 - 8001b00: 6313 str r3, [r2, #48] ; 0x30 - 8001b02: 4b0e ldr r3, [pc, #56] ; (8001b3c ) - 8001b04: 6b1b ldr r3, [r3, #48] ; 0x30 - 8001b06: f003 0304 and.w r3, r3, #4 - 8001b0a: 60fb str r3, [r7, #12] - 8001b0c: 68fb ldr r3, [r7, #12] + 8001b7a: 4b11 ldr r3, [pc, #68] ; (8001bc0 ) + 8001b7c: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001b7e: 4a10 ldr r2, [pc, #64] ; (8001bc0 ) + 8001b80: f043 0304 orr.w r3, r3, #4 + 8001b84: 6313 str r3, [r2, #48] ; 0x30 + 8001b86: 4b0e ldr r3, [pc, #56] ; (8001bc0 ) + 8001b88: 6b1b ldr r3, [r3, #48] ; 0x30 + 8001b8a: f003 0304 and.w r3, r3, #4 + 8001b8e: 60fb str r3, [r7, #12] + 8001b90: 68fb ldr r3, [r7, #12] /**USART6 GPIO Configuration PC6 ------> USART6_TX PC7 ------> USART6_RX */ GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; - 8001b0e: 23c0 movs r3, #192 ; 0xc0 - 8001b10: 617b str r3, [r7, #20] + 8001b92: 23c0 movs r3, #192 ; 0xc0 + 8001b94: 617b str r3, [r7, #20] GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - 8001b12: 2302 movs r3, #2 - 8001b14: 61bb str r3, [r7, #24] + 8001b96: 2302 movs r3, #2 + 8001b98: 61bb str r3, [r7, #24] GPIO_InitStruct.Pull = GPIO_NOPULL; - 8001b16: 2300 movs r3, #0 - 8001b18: 61fb str r3, [r7, #28] + 8001b9a: 2300 movs r3, #0 + 8001b9c: 61fb str r3, [r7, #28] GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - 8001b1a: 2303 movs r3, #3 - 8001b1c: 623b str r3, [r7, #32] + 8001b9e: 2303 movs r3, #3 + 8001ba0: 623b str r3, [r7, #32] GPIO_InitStruct.Alternate = GPIO_AF8_USART6; - 8001b1e: 2308 movs r3, #8 - 8001b20: 627b str r3, [r7, #36] ; 0x24 + 8001ba2: 2308 movs r3, #8 + 8001ba4: 627b str r3, [r7, #36] ; 0x24 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - 8001b22: f107 0314 add.w r3, r7, #20 - 8001b26: 4619 mov r1, r3 - 8001b28: 4805 ldr r0, [pc, #20] ; (8001b40 ) - 8001b2a: f000 fa4f bl 8001fcc + 8001ba6: f107 0314 add.w r3, r7, #20 + 8001baa: 4619 mov r1, r3 + 8001bac: 4805 ldr r0, [pc, #20] ; (8001bc4 ) + 8001bae: f000 fa4f bl 8002050 /* USER CODE BEGIN USART6_MspInit 1 */ /* USER CODE END USART6_MspInit 1 */ } } - 8001b2e: bf00 nop - 8001b30: 3728 adds r7, #40 ; 0x28 - 8001b32: 46bd mov sp, r7 - 8001b34: bd80 pop {r7, pc} - 8001b36: bf00 nop - 8001b38: 40011400 .word 0x40011400 - 8001b3c: 40023800 .word 0x40023800 - 8001b40: 40020800 .word 0x40020800 - -08001b44 : + 8001bb2: bf00 nop + 8001bb4: 3728 adds r7, #40 ; 0x28 + 8001bb6: 46bd mov sp, r7 + 8001bb8: bd80 pop {r7, pc} + 8001bba: bf00 nop + 8001bbc: 40011400 .word 0x40011400 + 8001bc0: 40023800 .word 0x40023800 + 8001bc4: 40020800 .word 0x40020800 + +08001bc8 : /******************************************************************************/ /** * @brief This function handles Non maskable interrupt. */ void NMI_Handler(void) { - 8001b44: b480 push {r7} - 8001b46: af00 add r7, sp, #0 + 8001bc8: b480 push {r7} + 8001bca: af00 add r7, sp, #0 /* USER CODE END NonMaskableInt_IRQn 0 */ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ /* USER CODE END NonMaskableInt_IRQn 1 */ } - 8001b48: bf00 nop - 8001b4a: 46bd mov sp, r7 - 8001b4c: f85d 7b04 ldr.w r7, [sp], #4 - 8001b50: 4770 bx lr + 8001bcc: bf00 nop + 8001bce: 46bd mov sp, r7 + 8001bd0: f85d 7b04 ldr.w r7, [sp], #4 + 8001bd4: 4770 bx lr -08001b52 : +08001bd6 : /** * @brief This function handles Hard fault interrupt. */ void HardFault_Handler(void) { - 8001b52: b480 push {r7} - 8001b54: af00 add r7, sp, #0 + 8001bd6: b480 push {r7} + 8001bd8: af00 add r7, sp, #0 /* USER CODE BEGIN HardFault_IRQn 0 */ /* USER CODE END HardFault_IRQn 0 */ while (1) - 8001b56: e7fe b.n 8001b56 + 8001bda: e7fe b.n 8001bda -08001b58 : +08001bdc : /** * @brief This function handles Memory management fault. */ void MemManage_Handler(void) { - 8001b58: b480 push {r7} - 8001b5a: af00 add r7, sp, #0 + 8001bdc: b480 push {r7} + 8001bde: af00 add r7, sp, #0 /* USER CODE BEGIN MemoryManagement_IRQn 0 */ /* USER CODE END MemoryManagement_IRQn 0 */ while (1) - 8001b5c: e7fe b.n 8001b5c + 8001be0: e7fe b.n 8001be0 -08001b5e : +08001be2 : /** * @brief This function handles Pre-fetch fault, memory access fault. */ void BusFault_Handler(void) { - 8001b5e: b480 push {r7} - 8001b60: af00 add r7, sp, #0 + 8001be2: b480 push {r7} + 8001be4: af00 add r7, sp, #0 /* USER CODE BEGIN BusFault_IRQn 0 */ /* USER CODE END BusFault_IRQn 0 */ while (1) - 8001b62: e7fe b.n 8001b62 + 8001be6: e7fe b.n 8001be6 -08001b64 : +08001be8 : /** * @brief This function handles Undefined instruction or illegal state. */ void UsageFault_Handler(void) { - 8001b64: b480 push {r7} - 8001b66: af00 add r7, sp, #0 + 8001be8: b480 push {r7} + 8001bea: af00 add r7, sp, #0 /* USER CODE BEGIN UsageFault_IRQn 0 */ /* USER CODE END UsageFault_IRQn 0 */ while (1) - 8001b68: e7fe b.n 8001b68 + 8001bec: e7fe b.n 8001bec -08001b6a : +08001bee : /** * @brief This function handles System service call via SWI instruction. */ void SVC_Handler(void) { - 8001b6a: b480 push {r7} - 8001b6c: af00 add r7, sp, #0 + 8001bee: b480 push {r7} + 8001bf0: af00 add r7, sp, #0 /* USER CODE END SVCall_IRQn 0 */ /* USER CODE BEGIN SVCall_IRQn 1 */ /* USER CODE END SVCall_IRQn 1 */ } - 8001b6e: bf00 nop - 8001b70: 46bd mov sp, r7 - 8001b72: f85d 7b04 ldr.w r7, [sp], #4 - 8001b76: 4770 bx lr + 8001bf2: bf00 nop + 8001bf4: 46bd mov sp, r7 + 8001bf6: f85d 7b04 ldr.w r7, [sp], #4 + 8001bfa: 4770 bx lr -08001b78 : +08001bfc : /** * @brief This function handles Debug monitor. */ void DebugMon_Handler(void) { - 8001b78: b480 push {r7} - 8001b7a: af00 add r7, sp, #0 + 8001bfc: b480 push {r7} + 8001bfe: af00 add r7, sp, #0 /* USER CODE END DebugMonitor_IRQn 0 */ /* USER CODE BEGIN DebugMonitor_IRQn 1 */ /* USER CODE END DebugMonitor_IRQn 1 */ } - 8001b7c: bf00 nop - 8001b7e: 46bd mov sp, r7 - 8001b80: f85d 7b04 ldr.w r7, [sp], #4 - 8001b84: 4770 bx lr + 8001c00: bf00 nop + 8001c02: 46bd mov sp, r7 + 8001c04: f85d 7b04 ldr.w r7, [sp], #4 + 8001c08: 4770 bx lr -08001b86 : +08001c0a : /** * @brief This function handles Pendable request for system service. */ void PendSV_Handler(void) { - 8001b86: b480 push {r7} - 8001b88: af00 add r7, sp, #0 + 8001c0a: b480 push {r7} + 8001c0c: af00 add r7, sp, #0 /* USER CODE END PendSV_IRQn 0 */ /* USER CODE BEGIN PendSV_IRQn 1 */ /* USER CODE END PendSV_IRQn 1 */ } - 8001b8a: bf00 nop - 8001b8c: 46bd mov sp, r7 - 8001b8e: f85d 7b04 ldr.w r7, [sp], #4 - 8001b92: 4770 bx lr + 8001c0e: bf00 nop + 8001c10: 46bd mov sp, r7 + 8001c12: f85d 7b04 ldr.w r7, [sp], #4 + 8001c16: 4770 bx lr -08001b94 : +08001c18 : /** * @brief This function handles System tick timer. */ void SysTick_Handler(void) { - 8001b94: b580 push {r7, lr} - 8001b96: af00 add r7, sp, #0 + 8001c18: b580 push {r7, lr} + 8001c1a: af00 add r7, sp, #0 /* USER CODE BEGIN SysTick_IRQn 0 */ /* USER CODE END SysTick_IRQn 0 */ HAL_IncTick(); - 8001b98: f000 f8c4 bl 8001d24 + 8001c1c: f000 f8c4 bl 8001da8 /* USER CODE BEGIN SysTick_IRQn 1 */ /* USER CODE END SysTick_IRQn 1 */ } - 8001b9c: bf00 nop - 8001b9e: bd80 pop {r7, pc} + 8001c20: bf00 nop + 8001c22: bd80 pop {r7, pc} -08001ba0 : +08001c24 : /** * @brief This function handles TIM3 global interrupt. */ void TIM3_IRQHandler(void) { - 8001ba0: b580 push {r7, lr} - 8001ba2: af00 add r7, sp, #0 + 8001c24: b580 push {r7, lr} + 8001c26: af00 add r7, sp, #0 /* USER CODE BEGIN TIM3_IRQn 0 */ /* USER CODE END TIM3_IRQn 0 */ HAL_TIM_IRQHandler(&htim3); - 8001ba4: 4802 ldr r0, [pc, #8] ; (8001bb0 ) - 8001ba6: f001 fdec bl 8003782 + 8001c28: 4802 ldr r0, [pc, #8] ; (8001c34 ) + 8001c2a: f001 fdec bl 8003806 /* USER CODE BEGIN TIM3_IRQn 1 */ /* USER CODE END TIM3_IRQn 1 */ } - 8001baa: bf00 nop - 8001bac: bd80 pop {r7, pc} - 8001bae: bf00 nop - 8001bb0: 2000006c .word 0x2000006c + 8001c2e: bf00 nop + 8001c30: bd80 pop {r7, pc} + 8001c32: bf00 nop + 8001c34: 2000006c .word 0x2000006c -08001bb4 : +08001c38 : /** * @brief This function handles EXTI line[15:10] interrupts. */ void EXTI15_10_IRQHandler(void) { - 8001bb4: b580 push {r7, lr} - 8001bb6: af00 add r7, sp, #0 + 8001c38: b580 push {r7, lr} + 8001c3a: af00 add r7, sp, #0 /* USER CODE BEGIN EXTI15_10_IRQn 0 */ /* USER CODE END EXTI15_10_IRQn 0 */ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_13); - 8001bb8: f44f 5000 mov.w r0, #8192 ; 0x2000 - 8001bbc: f000 fbca bl 8002354 + 8001c3c: f44f 5000 mov.w r0, #8192 ; 0x2000 + 8001c40: f000 fbca bl 80023d8 /* USER CODE BEGIN EXTI15_10_IRQn 1 */ /* USER CODE END EXTI15_10_IRQn 1 */ } - 8001bc0: bf00 nop - 8001bc2: bd80 pop {r7, pc} + 8001c44: bf00 nop + 8001c46: bd80 pop {r7, pc} -08001bc4 : +08001c48 : /** * @brief This function handles TIM6 global interrupt, DAC1 and DAC2 underrun error interrupts. */ void TIM6_DAC_IRQHandler(void) { - 8001bc4: b580 push {r7, lr} - 8001bc6: af00 add r7, sp, #0 + 8001c48: b580 push {r7, lr} + 8001c4a: af00 add r7, sp, #0 /* USER CODE BEGIN TIM6_DAC_IRQn 0 */ /* USER CODE END TIM6_DAC_IRQn 0 */ HAL_TIM_IRQHandler(&htim6); - 8001bc8: 4802 ldr r0, [pc, #8] ; (8001bd4 ) - 8001bca: f001 fdda bl 8003782 + 8001c4c: 4802 ldr r0, [pc, #8] ; (8001c58 ) + 8001c4e: f001 fdda bl 8003806 /* USER CODE BEGIN TIM6_DAC_IRQn 1 */ /* USER CODE END TIM6_DAC_IRQn 1 */ } - 8001bce: bf00 nop - 8001bd0: bd80 pop {r7, pc} - 8001bd2: bf00 nop - 8001bd4: 2000012c .word 0x2000012c + 8001c52: bf00 nop + 8001c54: bd80 pop {r7, pc} + 8001c56: bf00 nop + 8001c58: 2000012c .word 0x2000012c -08001bd8 : +08001c5c : /** * @brief This function handles USART6 global interrupt. */ void USART6_IRQHandler(void) { - 8001bd8: b580 push {r7, lr} - 8001bda: af00 add r7, sp, #0 + 8001c5c: b580 push {r7, lr} + 8001c5e: af00 add r7, sp, #0 /* USER CODE BEGIN USART6_IRQn 0 */ /* USER CODE END USART6_IRQn 0 */ HAL_UART_IRQHandler(&huart6); - 8001bdc: 4802 ldr r0, [pc, #8] ; (8001be8 ) - 8001bde: f002 fea3 bl 8004928 + 8001c60: 4802 ldr r0, [pc, #8] ; (8001c6c ) + 8001c62: f002 fea3 bl 80049ac /* USER CODE BEGIN USART6_IRQn 1 */ /* USER CODE END USART6_IRQn 1 */ } - 8001be2: bf00 nop - 8001be4: bd80 pop {r7, pc} - 8001be6: bf00 nop - 8001be8: 2000016c .word 0x2000016c + 8001c66: bf00 nop + 8001c68: bd80 pop {r7, pc} + 8001c6a: bf00 nop + 8001c6c: 2000016c .word 0x2000016c -08001bec : +08001c70 : * SystemFrequency variable. * @param None * @retval None */ void SystemInit(void) { - 8001bec: b480 push {r7} - 8001bee: af00 add r7, sp, #0 + 8001c70: b480 push {r7} + 8001c72: 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 */ - 8001bf0: 4b15 ldr r3, [pc, #84] ; (8001c48 ) - 8001bf2: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8001bf6: 4a14 ldr r2, [pc, #80] ; (8001c48 ) - 8001bf8: f443 0370 orr.w r3, r3, #15728640 ; 0xf00000 - 8001bfc: f8c2 3088 str.w r3, [r2, #136] ; 0x88 + 8001c74: 4b15 ldr r3, [pc, #84] ; (8001ccc ) + 8001c76: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8001c7a: 4a14 ldr r2, [pc, #80] ; (8001ccc ) + 8001c7c: f443 0370 orr.w r3, r3, #15728640 ; 0xf00000 + 8001c80: 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; - 8001c00: 4b12 ldr r3, [pc, #72] ; (8001c4c ) - 8001c02: 681b ldr r3, [r3, #0] - 8001c04: 4a11 ldr r2, [pc, #68] ; (8001c4c ) - 8001c06: f043 0301 orr.w r3, r3, #1 - 8001c0a: 6013 str r3, [r2, #0] + 8001c84: 4b12 ldr r3, [pc, #72] ; (8001cd0 ) + 8001c86: 681b ldr r3, [r3, #0] + 8001c88: 4a11 ldr r2, [pc, #68] ; (8001cd0 ) + 8001c8a: f043 0301 orr.w r3, r3, #1 + 8001c8e: 6013 str r3, [r2, #0] /* Reset CFGR register */ RCC->CFGR = 0x00000000; - 8001c0c: 4b0f ldr r3, [pc, #60] ; (8001c4c ) - 8001c0e: 2200 movs r2, #0 - 8001c10: 609a str r2, [r3, #8] + 8001c90: 4b0f ldr r3, [pc, #60] ; (8001cd0 ) + 8001c92: 2200 movs r2, #0 + 8001c94: 609a str r2, [r3, #8] /* Reset HSEON, CSSON and PLLON bits */ RCC->CR &= (uint32_t)0xFEF6FFFF; - 8001c12: 4b0e ldr r3, [pc, #56] ; (8001c4c ) - 8001c14: 681a ldr r2, [r3, #0] - 8001c16: 490d ldr r1, [pc, #52] ; (8001c4c ) - 8001c18: 4b0d ldr r3, [pc, #52] ; (8001c50 ) - 8001c1a: 4013 ands r3, r2 - 8001c1c: 600b str r3, [r1, #0] + 8001c96: 4b0e ldr r3, [pc, #56] ; (8001cd0 ) + 8001c98: 681a ldr r2, [r3, #0] + 8001c9a: 490d ldr r1, [pc, #52] ; (8001cd0 ) + 8001c9c: 4b0d ldr r3, [pc, #52] ; (8001cd4 ) + 8001c9e: 4013 ands r3, r2 + 8001ca0: 600b str r3, [r1, #0] /* Reset PLLCFGR register */ RCC->PLLCFGR = 0x24003010; - 8001c1e: 4b0b ldr r3, [pc, #44] ; (8001c4c ) - 8001c20: 4a0c ldr r2, [pc, #48] ; (8001c54 ) - 8001c22: 605a str r2, [r3, #4] + 8001ca2: 4b0b ldr r3, [pc, #44] ; (8001cd0 ) + 8001ca4: 4a0c ldr r2, [pc, #48] ; (8001cd8 ) + 8001ca6: 605a str r2, [r3, #4] /* Reset HSEBYP bit */ RCC->CR &= (uint32_t)0xFFFBFFFF; - 8001c24: 4b09 ldr r3, [pc, #36] ; (8001c4c ) - 8001c26: 681b ldr r3, [r3, #0] - 8001c28: 4a08 ldr r2, [pc, #32] ; (8001c4c ) - 8001c2a: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 8001c2e: 6013 str r3, [r2, #0] + 8001ca8: 4b09 ldr r3, [pc, #36] ; (8001cd0 ) + 8001caa: 681b ldr r3, [r3, #0] + 8001cac: 4a08 ldr r2, [pc, #32] ; (8001cd0 ) + 8001cae: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 8001cb2: 6013 str r3, [r2, #0] /* Disable all interrupts */ RCC->CIR = 0x00000000; - 8001c30: 4b06 ldr r3, [pc, #24] ; (8001c4c ) - 8001c32: 2200 movs r2, #0 - 8001c34: 60da str r2, [r3, #12] + 8001cb4: 4b06 ldr r3, [pc, #24] ; (8001cd0 ) + 8001cb6: 2200 movs r2, #0 + 8001cb8: 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 */ - 8001c36: 4b04 ldr r3, [pc, #16] ; (8001c48 ) - 8001c38: f04f 6200 mov.w r2, #134217728 ; 0x8000000 - 8001c3c: 609a str r2, [r3, #8] + 8001cba: 4b04 ldr r3, [pc, #16] ; (8001ccc ) + 8001cbc: f04f 6200 mov.w r2, #134217728 ; 0x8000000 + 8001cc0: 609a str r2, [r3, #8] #endif } - 8001c3e: bf00 nop - 8001c40: 46bd mov sp, r7 - 8001c42: f85d 7b04 ldr.w r7, [sp], #4 - 8001c46: 4770 bx lr - 8001c48: e000ed00 .word 0xe000ed00 - 8001c4c: 40023800 .word 0x40023800 - 8001c50: fef6ffff .word 0xfef6ffff - 8001c54: 24003010 .word 0x24003010 + 8001cc2: bf00 nop + 8001cc4: 46bd mov sp, r7 + 8001cc6: f85d 7b04 ldr.w r7, [sp], #4 + 8001cca: 4770 bx lr + 8001ccc: e000ed00 .word 0xe000ed00 + 8001cd0: 40023800 .word 0x40023800 + 8001cd4: fef6ffff .word 0xfef6ffff + 8001cd8: 24003010 .word 0x24003010 -08001c58 : +08001cdc : .section .text.Reset_Handler .weak Reset_Handler .type Reset_Handler, %function Reset_Handler: ldr sp, =_estack /* set stack pointer */ - 8001c58: f8df d034 ldr.w sp, [pc, #52] ; 8001c90 + 8001cdc: f8df d034 ldr.w sp, [pc, #52] ; 8001d14 /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 - 8001c5c: 2100 movs r1, #0 + 8001ce0: 2100 movs r1, #0 b LoopCopyDataInit - 8001c5e: e003 b.n 8001c68 + 8001ce2: e003 b.n 8001cec -08001c60 : +08001ce4 : CopyDataInit: ldr r3, =_sidata - 8001c60: 4b0c ldr r3, [pc, #48] ; (8001c94 ) + 8001ce4: 4b0c ldr r3, [pc, #48] ; (8001d18 ) ldr r3, [r3, r1] - 8001c62: 585b ldr r3, [r3, r1] + 8001ce6: 585b ldr r3, [r3, r1] str r3, [r0, r1] - 8001c64: 5043 str r3, [r0, r1] + 8001ce8: 5043 str r3, [r0, r1] adds r1, r1, #4 - 8001c66: 3104 adds r1, #4 + 8001cea: 3104 adds r1, #4 -08001c68 : +08001cec : LoopCopyDataInit: ldr r0, =_sdata - 8001c68: 480b ldr r0, [pc, #44] ; (8001c98 ) + 8001cec: 480b ldr r0, [pc, #44] ; (8001d1c ) ldr r3, =_edata - 8001c6a: 4b0c ldr r3, [pc, #48] ; (8001c9c ) + 8001cee: 4b0c ldr r3, [pc, #48] ; (8001d20 ) adds r2, r0, r1 - 8001c6c: 1842 adds r2, r0, r1 + 8001cf0: 1842 adds r2, r0, r1 cmp r2, r3 - 8001c6e: 429a cmp r2, r3 + 8001cf2: 429a cmp r2, r3 bcc CopyDataInit - 8001c70: d3f6 bcc.n 8001c60 + 8001cf4: d3f6 bcc.n 8001ce4 ldr r2, =_sbss - 8001c72: 4a0b ldr r2, [pc, #44] ; (8001ca0 ) + 8001cf6: 4a0b ldr r2, [pc, #44] ; (8001d24 ) b LoopFillZerobss - 8001c74: e002 b.n 8001c7c + 8001cf8: e002 b.n 8001d00 -08001c76 : +08001cfa : /* Zero fill the bss segment. */ FillZerobss: movs r3, #0 - 8001c76: 2300 movs r3, #0 + 8001cfa: 2300 movs r3, #0 str r3, [r2], #4 - 8001c78: f842 3b04 str.w r3, [r2], #4 + 8001cfc: f842 3b04 str.w r3, [r2], #4 -08001c7c : +08001d00 : LoopFillZerobss: ldr r3, = _ebss - 8001c7c: 4b09 ldr r3, [pc, #36] ; (8001ca4 ) + 8001d00: 4b09 ldr r3, [pc, #36] ; (8001d28 ) cmp r2, r3 - 8001c7e: 429a cmp r2, r3 + 8001d02: 429a cmp r2, r3 bcc FillZerobss - 8001c80: d3f9 bcc.n 8001c76 + 8001d04: d3f9 bcc.n 8001cfa /* Call the clock system initialization function.*/ bl SystemInit - 8001c82: f7ff ffb3 bl 8001bec + 8001d06: f7ff ffb3 bl 8001c70 /* Call static constructors */ bl __libc_init_array - 8001c86: f003 fc31 bl 80054ec <__libc_init_array> + 8001d0a: f003 fc31 bl 8005570 <__libc_init_array> /* Call the application's entry point.*/ bl main - 8001c8a: f7ff f803 bl 8000c94
+ 8001d0e: f7fe ff3f bl 8000b90
bx lr - 8001c8e: 4770 bx lr + 8001d12: 4770 bx lr ldr sp, =_estack /* set stack pointer */ - 8001c90: 20080000 .word 0x20080000 + 8001d14: 20080000 .word 0x20080000 ldr r3, =_sidata - 8001c94: 08005588 .word 0x08005588 + 8001d18: 0800560c .word 0x0800560c ldr r0, =_sdata - 8001c98: 20000000 .word 0x20000000 + 8001d1c: 20000000 .word 0x20000000 ldr r3, =_edata - 8001c9c: 20000010 .word 0x20000010 + 8001d20: 20000010 .word 0x20000010 ldr r2, =_sbss - 8001ca0: 20000010 .word 0x20000010 + 8001d24: 20000010 .word 0x20000010 ldr r3, = _ebss - 8001ca4: 20001ab8 .word 0x20001ab8 + 8001d28: 2000030c .word 0x2000030c -08001ca8 : +08001d2c : * @retval None */ .section .text.Default_Handler,"ax",%progbits Default_Handler: Infinite_Loop: b Infinite_Loop - 8001ca8: e7fe b.n 8001ca8 + 8001d2c: e7fe b.n 8001d2c -08001caa : +08001d2e : * 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) { - 8001caa: b580 push {r7, lr} - 8001cac: af00 add r7, sp, #0 + 8001d2e: b580 push {r7, lr} + 8001d30: 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); - 8001cae: 2003 movs r0, #3 - 8001cb0: f000 f928 bl 8001f04 + 8001d32: 2003 movs r0, #3 + 8001d34: f000 f928 bl 8001f88 /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ HAL_InitTick(TICK_INT_PRIORITY); - 8001cb4: 2000 movs r0, #0 - 8001cb6: f000 f805 bl 8001cc4 + 8001d38: 2000 movs r0, #0 + 8001d3a: f000 f805 bl 8001d48 /* Init the low level hardware */ HAL_MspInit(); - 8001cba: f7ff fdcb bl 8001854 + 8001d3e: f7ff fdcb bl 80018d8 /* Return function status */ return HAL_OK; - 8001cbe: 2300 movs r3, #0 + 8001d42: 2300 movs r3, #0 } - 8001cc0: 4618 mov r0, r3 - 8001cc2: bd80 pop {r7, pc} + 8001d44: 4618 mov r0, r3 + 8001d46: bd80 pop {r7, pc} -08001cc4 : +08001d48 : * implementation in user file. * @param TickPriority Tick interrupt priority. * @retval HAL status */ __weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) { - 8001cc4: b580 push {r7, lr} - 8001cc6: b082 sub sp, #8 - 8001cc8: af00 add r7, sp, #0 - 8001cca: 6078 str r0, [r7, #4] + 8001d48: b580 push {r7, lr} + 8001d4a: b082 sub sp, #8 + 8001d4c: af00 add r7, sp, #0 + 8001d4e: 6078 str r0, [r7, #4] /* Configure the SysTick to have interrupt in 1ms time basis*/ if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) - 8001ccc: 4b12 ldr r3, [pc, #72] ; (8001d18 ) - 8001cce: 681a ldr r2, [r3, #0] - 8001cd0: 4b12 ldr r3, [pc, #72] ; (8001d1c ) - 8001cd2: 781b ldrb r3, [r3, #0] - 8001cd4: 4619 mov r1, r3 - 8001cd6: f44f 737a mov.w r3, #1000 ; 0x3e8 - 8001cda: fbb3 f3f1 udiv r3, r3, r1 - 8001cde: fbb2 f3f3 udiv r3, r2, r3 - 8001ce2: 4618 mov r0, r3 - 8001ce4: f000 f943 bl 8001f6e - 8001ce8: 4603 mov r3, r0 - 8001cea: 2b00 cmp r3, #0 - 8001cec: d001 beq.n 8001cf2 + 8001d50: 4b12 ldr r3, [pc, #72] ; (8001d9c ) + 8001d52: 681a ldr r2, [r3, #0] + 8001d54: 4b12 ldr r3, [pc, #72] ; (8001da0 ) + 8001d56: 781b ldrb r3, [r3, #0] + 8001d58: 4619 mov r1, r3 + 8001d5a: f44f 737a mov.w r3, #1000 ; 0x3e8 + 8001d5e: fbb3 f3f1 udiv r3, r3, r1 + 8001d62: fbb2 f3f3 udiv r3, r2, r3 + 8001d66: 4618 mov r0, r3 + 8001d68: f000 f943 bl 8001ff2 + 8001d6c: 4603 mov r3, r0 + 8001d6e: 2b00 cmp r3, #0 + 8001d70: d001 beq.n 8001d76 { return HAL_ERROR; - 8001cee: 2301 movs r3, #1 - 8001cf0: e00e b.n 8001d10 + 8001d72: 2301 movs r3, #1 + 8001d74: e00e b.n 8001d94 } /* Configure the SysTick IRQ priority */ if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - 8001cf2: 687b ldr r3, [r7, #4] - 8001cf4: 2b0f cmp r3, #15 - 8001cf6: d80a bhi.n 8001d0e + 8001d76: 687b ldr r3, [r7, #4] + 8001d78: 2b0f cmp r3, #15 + 8001d7a: d80a bhi.n 8001d92 { HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); - 8001cf8: 2200 movs r2, #0 - 8001cfa: 6879 ldr r1, [r7, #4] - 8001cfc: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff - 8001d00: f000 f90b bl 8001f1a + 8001d7c: 2200 movs r2, #0 + 8001d7e: 6879 ldr r1, [r7, #4] + 8001d80: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001d84: f000 f90b bl 8001f9e uwTickPrio = TickPriority; - 8001d04: 4a06 ldr r2, [pc, #24] ; (8001d20 ) - 8001d06: 687b ldr r3, [r7, #4] - 8001d08: 6013 str r3, [r2, #0] + 8001d88: 4a06 ldr r2, [pc, #24] ; (8001da4 ) + 8001d8a: 687b ldr r3, [r7, #4] + 8001d8c: 6013 str r3, [r2, #0] { return HAL_ERROR; } /* Return function status */ return HAL_OK; - 8001d0a: 2300 movs r3, #0 - 8001d0c: e000 b.n 8001d10 + 8001d8e: 2300 movs r3, #0 + 8001d90: e000 b.n 8001d94 return HAL_ERROR; - 8001d0e: 2301 movs r3, #1 + 8001d92: 2301 movs r3, #1 } - 8001d10: 4618 mov r0, r3 - 8001d12: 3708 adds r7, #8 - 8001d14: 46bd mov sp, r7 - 8001d16: bd80 pop {r7, pc} - 8001d18: 20000004 .word 0x20000004 - 8001d1c: 2000000c .word 0x2000000c - 8001d20: 20000008 .word 0x20000008 - -08001d24 : + 8001d94: 4618 mov r0, r3 + 8001d96: 3708 adds r7, #8 + 8001d98: 46bd mov sp, r7 + 8001d9a: bd80 pop {r7, pc} + 8001d9c: 20000004 .word 0x20000004 + 8001da0: 2000000c .word 0x2000000c + 8001da4: 20000008 .word 0x20000008 + +08001da8 : * @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) { - 8001d24: b480 push {r7} - 8001d26: af00 add r7, sp, #0 + 8001da8: b480 push {r7} + 8001daa: af00 add r7, sp, #0 uwTick += uwTickFreq; - 8001d28: 4b06 ldr r3, [pc, #24] ; (8001d44 ) - 8001d2a: 781b ldrb r3, [r3, #0] - 8001d2c: 461a mov r2, r3 - 8001d2e: 4b06 ldr r3, [pc, #24] ; (8001d48 ) - 8001d30: 681b ldr r3, [r3, #0] - 8001d32: 4413 add r3, r2 - 8001d34: 4a04 ldr r2, [pc, #16] ; (8001d48 ) - 8001d36: 6013 str r3, [r2, #0] + 8001dac: 4b06 ldr r3, [pc, #24] ; (8001dc8 ) + 8001dae: 781b ldrb r3, [r3, #0] + 8001db0: 461a mov r2, r3 + 8001db2: 4b06 ldr r3, [pc, #24] ; (8001dcc ) + 8001db4: 681b ldr r3, [r3, #0] + 8001db6: 4413 add r3, r2 + 8001db8: 4a04 ldr r2, [pc, #16] ; (8001dcc ) + 8001dba: 6013 str r3, [r2, #0] } - 8001d38: bf00 nop - 8001d3a: 46bd mov sp, r7 - 8001d3c: f85d 7b04 ldr.w r7, [sp], #4 - 8001d40: 4770 bx lr - 8001d42: bf00 nop - 8001d44: 2000000c .word 0x2000000c - 8001d48: 20001ab4 .word 0x20001ab4 - -08001d4c : + 8001dbc: bf00 nop + 8001dbe: 46bd mov sp, r7 + 8001dc0: f85d 7b04 ldr.w r7, [sp], #4 + 8001dc4: 4770 bx lr + 8001dc6: bf00 nop + 8001dc8: 2000000c .word 0x2000000c + 8001dcc: 20000308 .word 0x20000308 + +08001dd0 : * @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) { - 8001d4c: b480 push {r7} - 8001d4e: af00 add r7, sp, #0 + 8001dd0: b480 push {r7} + 8001dd2: af00 add r7, sp, #0 return uwTick; - 8001d50: 4b03 ldr r3, [pc, #12] ; (8001d60 ) - 8001d52: 681b ldr r3, [r3, #0] + 8001dd4: 4b03 ldr r3, [pc, #12] ; (8001de4 ) + 8001dd6: 681b ldr r3, [r3, #0] } - 8001d54: 4618 mov r0, r3 - 8001d56: 46bd mov sp, r7 - 8001d58: f85d 7b04 ldr.w r7, [sp], #4 - 8001d5c: 4770 bx lr - 8001d5e: bf00 nop - 8001d60: 20001ab4 .word 0x20001ab4 - -08001d64 <__NVIC_SetPriorityGrouping>: + 8001dd8: 4618 mov r0, r3 + 8001dda: 46bd mov sp, r7 + 8001ddc: f85d 7b04 ldr.w r7, [sp], #4 + 8001de0: 4770 bx lr + 8001de2: bf00 nop + 8001de4: 20000308 .word 0x20000308 + +08001de8 <__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) { - 8001d64: b480 push {r7} - 8001d66: b085 sub sp, #20 - 8001d68: af00 add r7, sp, #0 - 8001d6a: 6078 str r0, [r7, #4] + 8001de8: b480 push {r7} + 8001dea: b085 sub sp, #20 + 8001dec: af00 add r7, sp, #0 + 8001dee: 6078 str r0, [r7, #4] uint32_t reg_value; uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - 8001d6c: 687b ldr r3, [r7, #4] - 8001d6e: f003 0307 and.w r3, r3, #7 - 8001d72: 60fb str r3, [r7, #12] + 8001df0: 687b ldr r3, [r7, #4] + 8001df2: f003 0307 and.w r3, r3, #7 + 8001df6: 60fb str r3, [r7, #12] reg_value = SCB->AIRCR; /* read old register configuration */ - 8001d74: 4b0b ldr r3, [pc, #44] ; (8001da4 <__NVIC_SetPriorityGrouping+0x40>) - 8001d76: 68db ldr r3, [r3, #12] - 8001d78: 60bb str r3, [r7, #8] + 8001df8: 4b0b ldr r3, [pc, #44] ; (8001e28 <__NVIC_SetPriorityGrouping+0x40>) + 8001dfa: 68db ldr r3, [r3, #12] + 8001dfc: 60bb str r3, [r7, #8] reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - 8001d7a: 68ba ldr r2, [r7, #8] - 8001d7c: f64f 03ff movw r3, #63743 ; 0xf8ff - 8001d80: 4013 ands r3, r2 - 8001d82: 60bb str r3, [r7, #8] + 8001dfe: 68ba ldr r2, [r7, #8] + 8001e00: f64f 03ff movw r3, #63743 ; 0xf8ff + 8001e04: 4013 ands r3, r2 + 8001e06: 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 */ - 8001d84: 68fb ldr r3, [r7, #12] - 8001d86: 021a lsls r2, r3, #8 + 8001e08: 68fb ldr r3, [r7, #12] + 8001e0a: 021a lsls r2, r3, #8 ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - 8001d88: 68bb ldr r3, [r7, #8] - 8001d8a: 431a orrs r2, r3 + 8001e0c: 68bb ldr r3, [r7, #8] + 8001e0e: 431a orrs r2, r3 reg_value = (reg_value | - 8001d8c: 4b06 ldr r3, [pc, #24] ; (8001da8 <__NVIC_SetPriorityGrouping+0x44>) - 8001d8e: 4313 orrs r3, r2 - 8001d90: 60bb str r3, [r7, #8] + 8001e10: 4b06 ldr r3, [pc, #24] ; (8001e2c <__NVIC_SetPriorityGrouping+0x44>) + 8001e12: 4313 orrs r3, r2 + 8001e14: 60bb str r3, [r7, #8] SCB->AIRCR = reg_value; - 8001d92: 4a04 ldr r2, [pc, #16] ; (8001da4 <__NVIC_SetPriorityGrouping+0x40>) - 8001d94: 68bb ldr r3, [r7, #8] - 8001d96: 60d3 str r3, [r2, #12] + 8001e16: 4a04 ldr r2, [pc, #16] ; (8001e28 <__NVIC_SetPriorityGrouping+0x40>) + 8001e18: 68bb ldr r3, [r7, #8] + 8001e1a: 60d3 str r3, [r2, #12] } - 8001d98: bf00 nop - 8001d9a: 3714 adds r7, #20 - 8001d9c: 46bd mov sp, r7 - 8001d9e: f85d 7b04 ldr.w r7, [sp], #4 - 8001da2: 4770 bx lr - 8001da4: e000ed00 .word 0xe000ed00 - 8001da8: 05fa0000 .word 0x05fa0000 - -08001dac <__NVIC_GetPriorityGrouping>: + 8001e1c: bf00 nop + 8001e1e: 3714 adds r7, #20 + 8001e20: 46bd mov sp, r7 + 8001e22: f85d 7b04 ldr.w r7, [sp], #4 + 8001e26: 4770 bx lr + 8001e28: e000ed00 .word 0xe000ed00 + 8001e2c: 05fa0000 .word 0x05fa0000 + +08001e30 <__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) { - 8001dac: b480 push {r7} - 8001dae: af00 add r7, sp, #0 + 8001e30: b480 push {r7} + 8001e32: af00 add r7, sp, #0 return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); - 8001db0: 4b04 ldr r3, [pc, #16] ; (8001dc4 <__NVIC_GetPriorityGrouping+0x18>) - 8001db2: 68db ldr r3, [r3, #12] - 8001db4: 0a1b lsrs r3, r3, #8 - 8001db6: f003 0307 and.w r3, r3, #7 + 8001e34: 4b04 ldr r3, [pc, #16] ; (8001e48 <__NVIC_GetPriorityGrouping+0x18>) + 8001e36: 68db ldr r3, [r3, #12] + 8001e38: 0a1b lsrs r3, r3, #8 + 8001e3a: f003 0307 and.w r3, r3, #7 } - 8001dba: 4618 mov r0, r3 - 8001dbc: 46bd mov sp, r7 - 8001dbe: f85d 7b04 ldr.w r7, [sp], #4 - 8001dc2: 4770 bx lr - 8001dc4: e000ed00 .word 0xe000ed00 + 8001e3e: 4618 mov r0, r3 + 8001e40: 46bd mov sp, r7 + 8001e42: f85d 7b04 ldr.w r7, [sp], #4 + 8001e46: 4770 bx lr + 8001e48: e000ed00 .word 0xe000ed00 -08001dc8 <__NVIC_EnableIRQ>: +08001e4c <__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) { - 8001dc8: b480 push {r7} - 8001dca: b083 sub sp, #12 - 8001dcc: af00 add r7, sp, #0 - 8001dce: 4603 mov r3, r0 - 8001dd0: 71fb strb r3, [r7, #7] + 8001e4c: b480 push {r7} + 8001e4e: b083 sub sp, #12 + 8001e50: af00 add r7, sp, #0 + 8001e52: 4603 mov r3, r0 + 8001e54: 71fb strb r3, [r7, #7] if ((int32_t)(IRQn) >= 0) - 8001dd2: f997 3007 ldrsb.w r3, [r7, #7] - 8001dd6: 2b00 cmp r3, #0 - 8001dd8: db0b blt.n 8001df2 <__NVIC_EnableIRQ+0x2a> + 8001e56: f997 3007 ldrsb.w r3, [r7, #7] + 8001e5a: 2b00 cmp r3, #0 + 8001e5c: db0b blt.n 8001e76 <__NVIC_EnableIRQ+0x2a> { NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - 8001dda: 79fb ldrb r3, [r7, #7] - 8001ddc: f003 021f and.w r2, r3, #31 - 8001de0: 4907 ldr r1, [pc, #28] ; (8001e00 <__NVIC_EnableIRQ+0x38>) - 8001de2: f997 3007 ldrsb.w r3, [r7, #7] - 8001de6: 095b lsrs r3, r3, #5 - 8001de8: 2001 movs r0, #1 - 8001dea: fa00 f202 lsl.w r2, r0, r2 - 8001dee: f841 2023 str.w r2, [r1, r3, lsl #2] + 8001e5e: 79fb ldrb r3, [r7, #7] + 8001e60: f003 021f and.w r2, r3, #31 + 8001e64: 4907 ldr r1, [pc, #28] ; (8001e84 <__NVIC_EnableIRQ+0x38>) + 8001e66: f997 3007 ldrsb.w r3, [r7, #7] + 8001e6a: 095b lsrs r3, r3, #5 + 8001e6c: 2001 movs r0, #1 + 8001e6e: fa00 f202 lsl.w r2, r0, r2 + 8001e72: f841 2023 str.w r2, [r1, r3, lsl #2] } } - 8001df2: bf00 nop - 8001df4: 370c adds r7, #12 - 8001df6: 46bd mov sp, r7 - 8001df8: f85d 7b04 ldr.w r7, [sp], #4 - 8001dfc: 4770 bx lr - 8001dfe: bf00 nop - 8001e00: e000e100 .word 0xe000e100 - -08001e04 <__NVIC_SetPriority>: + 8001e76: bf00 nop + 8001e78: 370c adds r7, #12 + 8001e7a: 46bd mov sp, r7 + 8001e7c: f85d 7b04 ldr.w r7, [sp], #4 + 8001e80: 4770 bx lr + 8001e82: bf00 nop + 8001e84: e000e100 .word 0xe000e100 + +08001e88 <__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) { - 8001e04: b480 push {r7} - 8001e06: b083 sub sp, #12 - 8001e08: af00 add r7, sp, #0 - 8001e0a: 4603 mov r3, r0 - 8001e0c: 6039 str r1, [r7, #0] - 8001e0e: 71fb strb r3, [r7, #7] + 8001e88: b480 push {r7} + 8001e8a: b083 sub sp, #12 + 8001e8c: af00 add r7, sp, #0 + 8001e8e: 4603 mov r3, r0 + 8001e90: 6039 str r1, [r7, #0] + 8001e92: 71fb strb r3, [r7, #7] if ((int32_t)(IRQn) >= 0) - 8001e10: f997 3007 ldrsb.w r3, [r7, #7] - 8001e14: 2b00 cmp r3, #0 - 8001e16: db0a blt.n 8001e2e <__NVIC_SetPriority+0x2a> + 8001e94: f997 3007 ldrsb.w r3, [r7, #7] + 8001e98: 2b00 cmp r3, #0 + 8001e9a: db0a blt.n 8001eb2 <__NVIC_SetPriority+0x2a> { NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - 8001e18: 683b ldr r3, [r7, #0] - 8001e1a: b2da uxtb r2, r3 - 8001e1c: 490c ldr r1, [pc, #48] ; (8001e50 <__NVIC_SetPriority+0x4c>) - 8001e1e: f997 3007 ldrsb.w r3, [r7, #7] - 8001e22: 0112 lsls r2, r2, #4 - 8001e24: b2d2 uxtb r2, r2 - 8001e26: 440b add r3, r1 - 8001e28: f883 2300 strb.w r2, [r3, #768] ; 0x300 + 8001e9c: 683b ldr r3, [r7, #0] + 8001e9e: b2da uxtb r2, r3 + 8001ea0: 490c ldr r1, [pc, #48] ; (8001ed4 <__NVIC_SetPriority+0x4c>) + 8001ea2: f997 3007 ldrsb.w r3, [r7, #7] + 8001ea6: 0112 lsls r2, r2, #4 + 8001ea8: b2d2 uxtb r2, r2 + 8001eaa: 440b add r3, r1 + 8001eac: 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); } } - 8001e2c: e00a b.n 8001e44 <__NVIC_SetPriority+0x40> + 8001eb0: e00a b.n 8001ec8 <__NVIC_SetPriority+0x40> SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - 8001e2e: 683b ldr r3, [r7, #0] - 8001e30: b2da uxtb r2, r3 - 8001e32: 4908 ldr r1, [pc, #32] ; (8001e54 <__NVIC_SetPriority+0x50>) - 8001e34: 79fb ldrb r3, [r7, #7] - 8001e36: f003 030f and.w r3, r3, #15 - 8001e3a: 3b04 subs r3, #4 - 8001e3c: 0112 lsls r2, r2, #4 - 8001e3e: b2d2 uxtb r2, r2 - 8001e40: 440b add r3, r1 - 8001e42: 761a strb r2, [r3, #24] + 8001eb2: 683b ldr r3, [r7, #0] + 8001eb4: b2da uxtb r2, r3 + 8001eb6: 4908 ldr r1, [pc, #32] ; (8001ed8 <__NVIC_SetPriority+0x50>) + 8001eb8: 79fb ldrb r3, [r7, #7] + 8001eba: f003 030f and.w r3, r3, #15 + 8001ebe: 3b04 subs r3, #4 + 8001ec0: 0112 lsls r2, r2, #4 + 8001ec2: b2d2 uxtb r2, r2 + 8001ec4: 440b add r3, r1 + 8001ec6: 761a strb r2, [r3, #24] } - 8001e44: bf00 nop - 8001e46: 370c adds r7, #12 - 8001e48: 46bd mov sp, r7 - 8001e4a: f85d 7b04 ldr.w r7, [sp], #4 - 8001e4e: 4770 bx lr - 8001e50: e000e100 .word 0xe000e100 - 8001e54: e000ed00 .word 0xe000ed00 - -08001e58 : + 8001ec8: bf00 nop + 8001eca: 370c adds r7, #12 + 8001ecc: 46bd mov sp, r7 + 8001ece: f85d 7b04 ldr.w r7, [sp], #4 + 8001ed2: 4770 bx lr + 8001ed4: e000e100 .word 0xe000e100 + 8001ed8: e000ed00 .word 0xe000ed00 + +08001edc : \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) { - 8001e58: b480 push {r7} - 8001e5a: b089 sub sp, #36 ; 0x24 - 8001e5c: af00 add r7, sp, #0 - 8001e5e: 60f8 str r0, [r7, #12] - 8001e60: 60b9 str r1, [r7, #8] - 8001e62: 607a str r2, [r7, #4] + 8001edc: b480 push {r7} + 8001ede: b089 sub sp, #36 ; 0x24 + 8001ee0: af00 add r7, sp, #0 + 8001ee2: 60f8 str r0, [r7, #12] + 8001ee4: 60b9 str r1, [r7, #8] + 8001ee6: 607a str r2, [r7, #4] uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - 8001e64: 68fb ldr r3, [r7, #12] - 8001e66: f003 0307 and.w r3, r3, #7 - 8001e6a: 61fb str r3, [r7, #28] + 8001ee8: 68fb ldr r3, [r7, #12] + 8001eea: f003 0307 and.w r3, r3, #7 + 8001eee: 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); - 8001e6c: 69fb ldr r3, [r7, #28] - 8001e6e: f1c3 0307 rsb r3, r3, #7 - 8001e72: 2b04 cmp r3, #4 - 8001e74: bf28 it cs - 8001e76: 2304 movcs r3, #4 - 8001e78: 61bb str r3, [r7, #24] + 8001ef0: 69fb ldr r3, [r7, #28] + 8001ef2: f1c3 0307 rsb r3, r3, #7 + 8001ef6: 2b04 cmp r3, #4 + 8001ef8: bf28 it cs + 8001efa: 2304 movcs r3, #4 + 8001efc: 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)); - 8001e7a: 69fb ldr r3, [r7, #28] - 8001e7c: 3304 adds r3, #4 - 8001e7e: 2b06 cmp r3, #6 - 8001e80: d902 bls.n 8001e88 - 8001e82: 69fb ldr r3, [r7, #28] - 8001e84: 3b03 subs r3, #3 - 8001e86: e000 b.n 8001e8a - 8001e88: 2300 movs r3, #0 - 8001e8a: 617b str r3, [r7, #20] + 8001efe: 69fb ldr r3, [r7, #28] + 8001f00: 3304 adds r3, #4 + 8001f02: 2b06 cmp r3, #6 + 8001f04: d902 bls.n 8001f0c + 8001f06: 69fb ldr r3, [r7, #28] + 8001f08: 3b03 subs r3, #3 + 8001f0a: e000 b.n 8001f0e + 8001f0c: 2300 movs r3, #0 + 8001f0e: 617b str r3, [r7, #20] return ( ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - 8001e8c: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff - 8001e90: 69bb ldr r3, [r7, #24] - 8001e92: fa02 f303 lsl.w r3, r2, r3 - 8001e96: 43da mvns r2, r3 - 8001e98: 68bb ldr r3, [r7, #8] - 8001e9a: 401a ands r2, r3 - 8001e9c: 697b ldr r3, [r7, #20] - 8001e9e: 409a lsls r2, r3 + 8001f10: f04f 32ff mov.w r2, #4294967295 ; 0xffffffff + 8001f14: 69bb ldr r3, [r7, #24] + 8001f16: fa02 f303 lsl.w r3, r2, r3 + 8001f1a: 43da mvns r2, r3 + 8001f1c: 68bb ldr r3, [r7, #8] + 8001f1e: 401a ands r2, r3 + 8001f20: 697b ldr r3, [r7, #20] + 8001f22: 409a lsls r2, r3 ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - 8001ea0: f04f 31ff mov.w r1, #4294967295 ; 0xffffffff - 8001ea4: 697b ldr r3, [r7, #20] - 8001ea6: fa01 f303 lsl.w r3, r1, r3 - 8001eaa: 43d9 mvns r1, r3 - 8001eac: 687b ldr r3, [r7, #4] - 8001eae: 400b ands r3, r1 + 8001f24: f04f 31ff mov.w r1, #4294967295 ; 0xffffffff + 8001f28: 697b ldr r3, [r7, #20] + 8001f2a: fa01 f303 lsl.w r3, r1, r3 + 8001f2e: 43d9 mvns r1, r3 + 8001f30: 687b ldr r3, [r7, #4] + 8001f32: 400b ands r3, r1 ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - 8001eb0: 4313 orrs r3, r2 + 8001f34: 4313 orrs r3, r2 ); } - 8001eb2: 4618 mov r0, r3 - 8001eb4: 3724 adds r7, #36 ; 0x24 - 8001eb6: 46bd mov sp, r7 - 8001eb8: f85d 7b04 ldr.w r7, [sp], #4 - 8001ebc: 4770 bx lr + 8001f36: 4618 mov r0, r3 + 8001f38: 3724 adds r7, #36 ; 0x24 + 8001f3a: 46bd mov sp, r7 + 8001f3c: f85d 7b04 ldr.w r7, [sp], #4 + 8001f40: 4770 bx lr ... -08001ec0 : +08001f44 : \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) { - 8001ec0: b580 push {r7, lr} - 8001ec2: b082 sub sp, #8 - 8001ec4: af00 add r7, sp, #0 - 8001ec6: 6078 str r0, [r7, #4] + 8001f44: b580 push {r7, lr} + 8001f46: b082 sub sp, #8 + 8001f48: af00 add r7, sp, #0 + 8001f4a: 6078 str r0, [r7, #4] if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - 8001ec8: 687b ldr r3, [r7, #4] - 8001eca: 3b01 subs r3, #1 - 8001ecc: f1b3 7f80 cmp.w r3, #16777216 ; 0x1000000 - 8001ed0: d301 bcc.n 8001ed6 + 8001f4c: 687b ldr r3, [r7, #4] + 8001f4e: 3b01 subs r3, #1 + 8001f50: f1b3 7f80 cmp.w r3, #16777216 ; 0x1000000 + 8001f54: d301 bcc.n 8001f5a { return (1UL); /* Reload value impossible */ - 8001ed2: 2301 movs r3, #1 - 8001ed4: e00f b.n 8001ef6 + 8001f56: 2301 movs r3, #1 + 8001f58: e00f b.n 8001f7a } SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - 8001ed6: 4a0a ldr r2, [pc, #40] ; (8001f00 ) - 8001ed8: 687b ldr r3, [r7, #4] - 8001eda: 3b01 subs r3, #1 - 8001edc: 6053 str r3, [r2, #4] + 8001f5a: 4a0a ldr r2, [pc, #40] ; (8001f84 ) + 8001f5c: 687b ldr r3, [r7, #4] + 8001f5e: 3b01 subs r3, #1 + 8001f60: 6053 str r3, [r2, #4] NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - 8001ede: 210f movs r1, #15 - 8001ee0: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff - 8001ee4: f7ff ff8e bl 8001e04 <__NVIC_SetPriority> + 8001f62: 210f movs r1, #15 + 8001f64: f04f 30ff mov.w r0, #4294967295 ; 0xffffffff + 8001f68: f7ff ff8e bl 8001e88 <__NVIC_SetPriority> SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - 8001ee8: 4b05 ldr r3, [pc, #20] ; (8001f00 ) - 8001eea: 2200 movs r2, #0 - 8001eec: 609a str r2, [r3, #8] + 8001f6c: 4b05 ldr r3, [pc, #20] ; (8001f84 ) + 8001f6e: 2200 movs r2, #0 + 8001f70: 609a str r2, [r3, #8] SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - 8001eee: 4b04 ldr r3, [pc, #16] ; (8001f00 ) - 8001ef0: 2207 movs r2, #7 - 8001ef2: 601a str r2, [r3, #0] + 8001f72: 4b04 ldr r3, [pc, #16] ; (8001f84 ) + 8001f74: 2207 movs r2, #7 + 8001f76: 601a str r2, [r3, #0] SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ return (0UL); /* Function successful */ - 8001ef4: 2300 movs r3, #0 + 8001f78: 2300 movs r3, #0 } - 8001ef6: 4618 mov r0, r3 - 8001ef8: 3708 adds r7, #8 - 8001efa: 46bd mov sp, r7 - 8001efc: bd80 pop {r7, pc} - 8001efe: bf00 nop - 8001f00: e000e010 .word 0xe000e010 - -08001f04 : + 8001f7a: 4618 mov r0, r3 + 8001f7c: 3708 adds r7, #8 + 8001f7e: 46bd mov sp, r7 + 8001f80: bd80 pop {r7, pc} + 8001f82: bf00 nop + 8001f84: e000e010 .word 0xe000e010 + +08001f88 : * @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) { - 8001f04: b580 push {r7, lr} - 8001f06: b082 sub sp, #8 - 8001f08: af00 add r7, sp, #0 - 8001f0a: 6078 str r0, [r7, #4] + 8001f88: b580 push {r7, lr} + 8001f8a: b082 sub sp, #8 + 8001f8c: af00 add r7, sp, #0 + 8001f8e: 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); - 8001f0c: 6878 ldr r0, [r7, #4] - 8001f0e: f7ff ff29 bl 8001d64 <__NVIC_SetPriorityGrouping> + 8001f90: 6878 ldr r0, [r7, #4] + 8001f92: f7ff ff29 bl 8001de8 <__NVIC_SetPriorityGrouping> } - 8001f12: bf00 nop - 8001f14: 3708 adds r7, #8 - 8001f16: 46bd mov sp, r7 - 8001f18: bd80 pop {r7, pc} + 8001f96: bf00 nop + 8001f98: 3708 adds r7, #8 + 8001f9a: 46bd mov sp, r7 + 8001f9c: bd80 pop {r7, pc} -08001f1a : +08001f9e : * 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) { - 8001f1a: b580 push {r7, lr} - 8001f1c: b086 sub sp, #24 - 8001f1e: af00 add r7, sp, #0 - 8001f20: 4603 mov r3, r0 - 8001f22: 60b9 str r1, [r7, #8] - 8001f24: 607a str r2, [r7, #4] - 8001f26: 73fb strb r3, [r7, #15] + 8001f9e: b580 push {r7, lr} + 8001fa0: b086 sub sp, #24 + 8001fa2: af00 add r7, sp, #0 + 8001fa4: 4603 mov r3, r0 + 8001fa6: 60b9 str r1, [r7, #8] + 8001fa8: 607a str r2, [r7, #4] + 8001faa: 73fb strb r3, [r7, #15] uint32_t prioritygroup = 0x00; - 8001f28: 2300 movs r3, #0 - 8001f2a: 617b str r3, [r7, #20] + 8001fac: 2300 movs r3, #0 + 8001fae: 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(); - 8001f2c: f7ff ff3e bl 8001dac <__NVIC_GetPriorityGrouping> - 8001f30: 6178 str r0, [r7, #20] + 8001fb0: f7ff ff3e bl 8001e30 <__NVIC_GetPriorityGrouping> + 8001fb4: 6178 str r0, [r7, #20] NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); - 8001f32: 687a ldr r2, [r7, #4] - 8001f34: 68b9 ldr r1, [r7, #8] - 8001f36: 6978 ldr r0, [r7, #20] - 8001f38: f7ff ff8e bl 8001e58 - 8001f3c: 4602 mov r2, r0 - 8001f3e: f997 300f ldrsb.w r3, [r7, #15] - 8001f42: 4611 mov r1, r2 - 8001f44: 4618 mov r0, r3 - 8001f46: f7ff ff5d bl 8001e04 <__NVIC_SetPriority> + 8001fb6: 687a ldr r2, [r7, #4] + 8001fb8: 68b9 ldr r1, [r7, #8] + 8001fba: 6978 ldr r0, [r7, #20] + 8001fbc: f7ff ff8e bl 8001edc + 8001fc0: 4602 mov r2, r0 + 8001fc2: f997 300f ldrsb.w r3, [r7, #15] + 8001fc6: 4611 mov r1, r2 + 8001fc8: 4618 mov r0, r3 + 8001fca: f7ff ff5d bl 8001e88 <__NVIC_SetPriority> } - 8001f4a: bf00 nop - 8001f4c: 3718 adds r7, #24 - 8001f4e: 46bd mov sp, r7 - 8001f50: bd80 pop {r7, pc} + 8001fce: bf00 nop + 8001fd0: 3718 adds r7, #24 + 8001fd2: 46bd mov sp, r7 + 8001fd4: bd80 pop {r7, pc} -08001f52 : +08001fd6 : * 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) { - 8001f52: b580 push {r7, lr} - 8001f54: b082 sub sp, #8 - 8001f56: af00 add r7, sp, #0 - 8001f58: 4603 mov r3, r0 - 8001f5a: 71fb strb r3, [r7, #7] + 8001fd6: b580 push {r7, lr} + 8001fd8: b082 sub sp, #8 + 8001fda: af00 add r7, sp, #0 + 8001fdc: 4603 mov r3, r0 + 8001fde: 71fb strb r3, [r7, #7] /* Check the parameters */ assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); /* Enable interrupt */ NVIC_EnableIRQ(IRQn); - 8001f5c: f997 3007 ldrsb.w r3, [r7, #7] - 8001f60: 4618 mov r0, r3 - 8001f62: f7ff ff31 bl 8001dc8 <__NVIC_EnableIRQ> + 8001fe0: f997 3007 ldrsb.w r3, [r7, #7] + 8001fe4: 4618 mov r0, r3 + 8001fe6: f7ff ff31 bl 8001e4c <__NVIC_EnableIRQ> } - 8001f66: bf00 nop - 8001f68: 3708 adds r7, #8 - 8001f6a: 46bd mov sp, r7 - 8001f6c: bd80 pop {r7, pc} + 8001fea: bf00 nop + 8001fec: 3708 adds r7, #8 + 8001fee: 46bd mov sp, r7 + 8001ff0: bd80 pop {r7, pc} -08001f6e : +08001ff2 : * @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) { - 8001f6e: b580 push {r7, lr} - 8001f70: b082 sub sp, #8 - 8001f72: af00 add r7, sp, #0 - 8001f74: 6078 str r0, [r7, #4] + 8001ff2: b580 push {r7, lr} + 8001ff4: b082 sub sp, #8 + 8001ff6: af00 add r7, sp, #0 + 8001ff8: 6078 str r0, [r7, #4] return SysTick_Config(TicksNumb); - 8001f76: 6878 ldr r0, [r7, #4] - 8001f78: f7ff ffa2 bl 8001ec0 - 8001f7c: 4603 mov r3, r0 + 8001ffa: 6878 ldr r0, [r7, #4] + 8001ffc: f7ff ffa2 bl 8001f44 + 8002000: 4603 mov r3, r0 } - 8001f7e: 4618 mov r0, r3 - 8001f80: 3708 adds r7, #8 - 8001f82: 46bd mov sp, r7 - 8001f84: bd80 pop {r7, pc} + 8002002: 4618 mov r0, r3 + 8002004: 3708 adds r7, #8 + 8002006: 46bd mov sp, r7 + 8002008: bd80 pop {r7, pc} -08001f86 : +0800200a : * @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) { - 8001f86: b480 push {r7} - 8001f88: b083 sub sp, #12 - 8001f8a: af00 add r7, sp, #0 - 8001f8c: 6078 str r0, [r7, #4] + 800200a: b480 push {r7} + 800200c: b083 sub sp, #12 + 800200e: af00 add r7, sp, #0 + 8002010: 6078 str r0, [r7, #4] if(hdma->State != HAL_DMA_STATE_BUSY) - 8001f8e: 687b ldr r3, [r7, #4] - 8001f90: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 - 8001f94: b2db uxtb r3, r3 - 8001f96: 2b02 cmp r3, #2 - 8001f98: d004 beq.n 8001fa4 + 8002012: 687b ldr r3, [r7, #4] + 8002014: f893 3035 ldrb.w r3, [r3, #53] ; 0x35 + 8002018: b2db uxtb r3, r3 + 800201a: 2b02 cmp r3, #2 + 800201c: d004 beq.n 8002028 { hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - 8001f9a: 687b ldr r3, [r7, #4] - 8001f9c: 2280 movs r2, #128 ; 0x80 - 8001f9e: 655a str r2, [r3, #84] ; 0x54 + 800201e: 687b ldr r3, [r7, #4] + 8002020: 2280 movs r2, #128 ; 0x80 + 8002022: 655a str r2, [r3, #84] ; 0x54 return HAL_ERROR; - 8001fa0: 2301 movs r3, #1 - 8001fa2: e00c b.n 8001fbe + 8002024: 2301 movs r3, #1 + 8002026: e00c b.n 8002042 } else { /* Set Abort State */ hdma->State = HAL_DMA_STATE_ABORT; - 8001fa4: 687b ldr r3, [r7, #4] - 8001fa6: 2205 movs r2, #5 - 8001fa8: f883 2035 strb.w r2, [r3, #53] ; 0x35 + 8002028: 687b ldr r3, [r7, #4] + 800202a: 2205 movs r2, #5 + 800202c: f883 2035 strb.w r2, [r3, #53] ; 0x35 /* Disable the stream */ __HAL_DMA_DISABLE(hdma); - 8001fac: 687b ldr r3, [r7, #4] - 8001fae: 681b ldr r3, [r3, #0] - 8001fb0: 681a ldr r2, [r3, #0] - 8001fb2: 687b ldr r3, [r7, #4] - 8001fb4: 681b ldr r3, [r3, #0] - 8001fb6: f022 0201 bic.w r2, r2, #1 - 8001fba: 601a str r2, [r3, #0] + 8002030: 687b ldr r3, [r7, #4] + 8002032: 681b ldr r3, [r3, #0] + 8002034: 681a ldr r2, [r3, #0] + 8002036: 687b ldr r3, [r7, #4] + 8002038: 681b ldr r3, [r3, #0] + 800203a: f022 0201 bic.w r2, r2, #1 + 800203e: 601a str r2, [r3, #0] } return HAL_OK; - 8001fbc: 2300 movs r3, #0 + 8002040: 2300 movs r3, #0 } - 8001fbe: 4618 mov r0, r3 - 8001fc0: 370c adds r7, #12 - 8001fc2: 46bd mov sp, r7 - 8001fc4: f85d 7b04 ldr.w r7, [sp], #4 - 8001fc8: 4770 bx lr + 8002042: 4618 mov r0, r3 + 8002044: 370c adds r7, #12 + 8002046: 46bd mov sp, r7 + 8002048: f85d 7b04 ldr.w r7, [sp], #4 + 800204c: 4770 bx lr ... -08001fcc : +08002050 : * @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) { - 8001fcc: b480 push {r7} - 8001fce: b089 sub sp, #36 ; 0x24 - 8001fd0: af00 add r7, sp, #0 - 8001fd2: 6078 str r0, [r7, #4] - 8001fd4: 6039 str r1, [r7, #0] + 8002050: b480 push {r7} + 8002052: b089 sub sp, #36 ; 0x24 + 8002054: af00 add r7, sp, #0 + 8002056: 6078 str r0, [r7, #4] + 8002058: 6039 str r1, [r7, #0] uint32_t position = 0x00; - 8001fd6: 2300 movs r3, #0 - 8001fd8: 61fb str r3, [r7, #28] + 800205a: 2300 movs r3, #0 + 800205c: 61fb str r3, [r7, #28] uint32_t ioposition = 0x00; - 8001fda: 2300 movs r3, #0 - 8001fdc: 617b str r3, [r7, #20] + 800205e: 2300 movs r3, #0 + 8002060: 617b str r3, [r7, #20] uint32_t iocurrent = 0x00; - 8001fde: 2300 movs r3, #0 - 8001fe0: 613b str r3, [r7, #16] + 8002062: 2300 movs r3, #0 + 8002064: 613b str r3, [r7, #16] uint32_t temp = 0x00; - 8001fe2: 2300 movs r3, #0 - 8001fe4: 61bb str r3, [r7, #24] + 8002066: 2300 movs r3, #0 + 8002068: 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++) - 8001fe6: 2300 movs r3, #0 - 8001fe8: 61fb str r3, [r7, #28] - 8001fea: e175 b.n 80022d8 + 800206a: 2300 movs r3, #0 + 800206c: 61fb str r3, [r7, #28] + 800206e: e175 b.n 800235c { /* Get the IO position */ ioposition = ((uint32_t)0x01) << position; - 8001fec: 2201 movs r2, #1 - 8001fee: 69fb ldr r3, [r7, #28] - 8001ff0: fa02 f303 lsl.w r3, r2, r3 - 8001ff4: 617b str r3, [r7, #20] + 8002070: 2201 movs r2, #1 + 8002072: 69fb ldr r3, [r7, #28] + 8002074: fa02 f303 lsl.w r3, r2, r3 + 8002078: 617b str r3, [r7, #20] /* Get the current IO position */ iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; - 8001ff6: 683b ldr r3, [r7, #0] - 8001ff8: 681b ldr r3, [r3, #0] - 8001ffa: 697a ldr r2, [r7, #20] - 8001ffc: 4013 ands r3, r2 - 8001ffe: 613b str r3, [r7, #16] + 800207a: 683b ldr r3, [r7, #0] + 800207c: 681b ldr r3, [r3, #0] + 800207e: 697a ldr r2, [r7, #20] + 8002080: 4013 ands r3, r2 + 8002082: 613b str r3, [r7, #16] if(iocurrent == ioposition) - 8002000: 693a ldr r2, [r7, #16] - 8002002: 697b ldr r3, [r7, #20] - 8002004: 429a cmp r2, r3 - 8002006: f040 8164 bne.w 80022d2 + 8002084: 693a ldr r2, [r7, #16] + 8002086: 697b ldr r3, [r7, #20] + 8002088: 429a cmp r2, r3 + 800208a: f040 8164 bne.w 8002356 { /*--------------------- 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)) - 800200a: 683b ldr r3, [r7, #0] - 800200c: 685b ldr r3, [r3, #4] - 800200e: 2b02 cmp r3, #2 - 8002010: d003 beq.n 800201a - 8002012: 683b ldr r3, [r7, #0] - 8002014: 685b ldr r3, [r3, #4] - 8002016: 2b12 cmp r3, #18 - 8002018: d123 bne.n 8002062 + 800208e: 683b ldr r3, [r7, #0] + 8002090: 685b ldr r3, [r3, #4] + 8002092: 2b02 cmp r3, #2 + 8002094: d003 beq.n 800209e + 8002096: 683b ldr r3, [r7, #0] + 8002098: 685b ldr r3, [r3, #4] + 800209a: 2b12 cmp r3, #18 + 800209c: d123 bne.n 80020e6 { /* 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]; - 800201a: 69fb ldr r3, [r7, #28] - 800201c: 08da lsrs r2, r3, #3 - 800201e: 687b ldr r3, [r7, #4] - 8002020: 3208 adds r2, #8 - 8002022: f853 3022 ldr.w r3, [r3, r2, lsl #2] - 8002026: 61bb str r3, [r7, #24] + 800209e: 69fb ldr r3, [r7, #28] + 80020a0: 08da lsrs r2, r3, #3 + 80020a2: 687b ldr r3, [r7, #4] + 80020a4: 3208 adds r2, #8 + 80020a6: f853 3022 ldr.w r3, [r3, r2, lsl #2] + 80020aa: 61bb str r3, [r7, #24] temp &= ~((uint32_t)0xF << ((uint32_t)(position & (uint32_t)0x07) * 4)) ; - 8002028: 69fb ldr r3, [r7, #28] - 800202a: f003 0307 and.w r3, r3, #7 - 800202e: 009b lsls r3, r3, #2 - 8002030: 220f movs r2, #15 - 8002032: fa02 f303 lsl.w r3, r2, r3 - 8002036: 43db mvns r3, r3 - 8002038: 69ba ldr r2, [r7, #24] - 800203a: 4013 ands r3, r2 - 800203c: 61bb str r3, [r7, #24] + 80020ac: 69fb ldr r3, [r7, #28] + 80020ae: f003 0307 and.w r3, r3, #7 + 80020b2: 009b lsls r3, r3, #2 + 80020b4: 220f movs r2, #15 + 80020b6: fa02 f303 lsl.w r3, r2, r3 + 80020ba: 43db mvns r3, r3 + 80020bc: 69ba ldr r2, [r7, #24] + 80020be: 4013 ands r3, r2 + 80020c0: 61bb str r3, [r7, #24] temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & (uint32_t)0x07) * 4)); - 800203e: 683b ldr r3, [r7, #0] - 8002040: 691a ldr r2, [r3, #16] - 8002042: 69fb ldr r3, [r7, #28] - 8002044: f003 0307 and.w r3, r3, #7 - 8002048: 009b lsls r3, r3, #2 - 800204a: fa02 f303 lsl.w r3, r2, r3 - 800204e: 69ba ldr r2, [r7, #24] - 8002050: 4313 orrs r3, r2 - 8002052: 61bb str r3, [r7, #24] + 80020c2: 683b ldr r3, [r7, #0] + 80020c4: 691a ldr r2, [r3, #16] + 80020c6: 69fb ldr r3, [r7, #28] + 80020c8: f003 0307 and.w r3, r3, #7 + 80020cc: 009b lsls r3, r3, #2 + 80020ce: fa02 f303 lsl.w r3, r2, r3 + 80020d2: 69ba ldr r2, [r7, #24] + 80020d4: 4313 orrs r3, r2 + 80020d6: 61bb str r3, [r7, #24] GPIOx->AFR[position >> 3] = temp; - 8002054: 69fb ldr r3, [r7, #28] - 8002056: 08da lsrs r2, r3, #3 - 8002058: 687b ldr r3, [r7, #4] - 800205a: 3208 adds r2, #8 - 800205c: 69b9 ldr r1, [r7, #24] - 800205e: f843 1022 str.w r1, [r3, r2, lsl #2] + 80020d8: 69fb ldr r3, [r7, #28] + 80020da: 08da lsrs r2, r3, #3 + 80020dc: 687b ldr r3, [r7, #4] + 80020de: 3208 adds r2, #8 + 80020e0: 69b9 ldr r1, [r7, #24] + 80020e2: f843 1022 str.w r1, [r3, r2, lsl #2] } /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ temp = GPIOx->MODER; - 8002062: 687b ldr r3, [r7, #4] - 8002064: 681b ldr r3, [r3, #0] - 8002066: 61bb str r3, [r7, #24] + 80020e6: 687b ldr r3, [r7, #4] + 80020e8: 681b ldr r3, [r3, #0] + 80020ea: 61bb str r3, [r7, #24] temp &= ~(GPIO_MODER_MODER0 << (position * 2)); - 8002068: 69fb ldr r3, [r7, #28] - 800206a: 005b lsls r3, r3, #1 - 800206c: 2203 movs r2, #3 - 800206e: fa02 f303 lsl.w r3, r2, r3 - 8002072: 43db mvns r3, r3 - 8002074: 69ba ldr r2, [r7, #24] - 8002076: 4013 ands r3, r2 - 8002078: 61bb str r3, [r7, #24] + 80020ec: 69fb ldr r3, [r7, #28] + 80020ee: 005b lsls r3, r3, #1 + 80020f0: 2203 movs r2, #3 + 80020f2: fa02 f303 lsl.w r3, r2, r3 + 80020f6: 43db mvns r3, r3 + 80020f8: 69ba ldr r2, [r7, #24] + 80020fa: 4013 ands r3, r2 + 80020fc: 61bb str r3, [r7, #24] temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2)); - 800207a: 683b ldr r3, [r7, #0] - 800207c: 685b ldr r3, [r3, #4] - 800207e: f003 0203 and.w r2, r3, #3 - 8002082: 69fb ldr r3, [r7, #28] - 8002084: 005b lsls r3, r3, #1 - 8002086: fa02 f303 lsl.w r3, r2, r3 - 800208a: 69ba ldr r2, [r7, #24] - 800208c: 4313 orrs r3, r2 - 800208e: 61bb str r3, [r7, #24] + 80020fe: 683b ldr r3, [r7, #0] + 8002100: 685b ldr r3, [r3, #4] + 8002102: f003 0203 and.w r2, r3, #3 + 8002106: 69fb ldr r3, [r7, #28] + 8002108: 005b lsls r3, r3, #1 + 800210a: fa02 f303 lsl.w r3, r2, r3 + 800210e: 69ba ldr r2, [r7, #24] + 8002110: 4313 orrs r3, r2 + 8002112: 61bb str r3, [r7, #24] GPIOx->MODER = temp; - 8002090: 687b ldr r3, [r7, #4] - 8002092: 69ba ldr r2, [r7, #24] - 8002094: 601a str r2, [r3, #0] + 8002114: 687b ldr r3, [r7, #4] + 8002116: 69ba ldr r2, [r7, #24] + 8002118: 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) || - 8002096: 683b ldr r3, [r7, #0] - 8002098: 685b ldr r3, [r3, #4] - 800209a: 2b01 cmp r3, #1 - 800209c: d00b beq.n 80020b6 - 800209e: 683b ldr r3, [r7, #0] - 80020a0: 685b ldr r3, [r3, #4] - 80020a2: 2b02 cmp r3, #2 - 80020a4: d007 beq.n 80020b6 + 800211a: 683b ldr r3, [r7, #0] + 800211c: 685b ldr r3, [r3, #4] + 800211e: 2b01 cmp r3, #1 + 8002120: d00b beq.n 800213a + 8002122: 683b ldr r3, [r7, #0] + 8002124: 685b ldr r3, [r3, #4] + 8002126: 2b02 cmp r3, #2 + 8002128: d007 beq.n 800213a (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) - 80020a6: 683b ldr r3, [r7, #0] - 80020a8: 685b ldr r3, [r3, #4] + 800212a: 683b ldr r3, [r7, #0] + 800212c: 685b ldr r3, [r3, #4] if((GPIO_Init->Mode == GPIO_MODE_OUTPUT_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_PP) || - 80020aa: 2b11 cmp r3, #17 - 80020ac: d003 beq.n 80020b6 + 800212e: 2b11 cmp r3, #17 + 8002130: d003 beq.n 800213a (GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD)) - 80020ae: 683b ldr r3, [r7, #0] - 80020b0: 685b ldr r3, [r3, #4] - 80020b2: 2b12 cmp r3, #18 - 80020b4: d130 bne.n 8002118 + 8002132: 683b ldr r3, [r7, #0] + 8002134: 685b ldr r3, [r3, #4] + 8002136: 2b12 cmp r3, #18 + 8002138: d130 bne.n 800219c { /* Check the Speed parameter */ assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); /* Configure the IO Speed */ temp = GPIOx->OSPEEDR; - 80020b6: 687b ldr r3, [r7, #4] - 80020b8: 689b ldr r3, [r3, #8] - 80020ba: 61bb str r3, [r7, #24] + 800213a: 687b ldr r3, [r7, #4] + 800213c: 689b ldr r3, [r3, #8] + 800213e: 61bb str r3, [r7, #24] temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2)); - 80020bc: 69fb ldr r3, [r7, #28] - 80020be: 005b lsls r3, r3, #1 - 80020c0: 2203 movs r2, #3 - 80020c2: fa02 f303 lsl.w r3, r2, r3 - 80020c6: 43db mvns r3, r3 - 80020c8: 69ba ldr r2, [r7, #24] - 80020ca: 4013 ands r3, r2 - 80020cc: 61bb str r3, [r7, #24] + 8002140: 69fb ldr r3, [r7, #28] + 8002142: 005b lsls r3, r3, #1 + 8002144: 2203 movs r2, #3 + 8002146: fa02 f303 lsl.w r3, r2, r3 + 800214a: 43db mvns r3, r3 + 800214c: 69ba ldr r2, [r7, #24] + 800214e: 4013 ands r3, r2 + 8002150: 61bb str r3, [r7, #24] temp |= (GPIO_Init->Speed << (position * 2)); - 80020ce: 683b ldr r3, [r7, #0] - 80020d0: 68da ldr r2, [r3, #12] - 80020d2: 69fb ldr r3, [r7, #28] - 80020d4: 005b lsls r3, r3, #1 - 80020d6: fa02 f303 lsl.w r3, r2, r3 - 80020da: 69ba ldr r2, [r7, #24] - 80020dc: 4313 orrs r3, r2 - 80020de: 61bb str r3, [r7, #24] + 8002152: 683b ldr r3, [r7, #0] + 8002154: 68da ldr r2, [r3, #12] + 8002156: 69fb ldr r3, [r7, #28] + 8002158: 005b lsls r3, r3, #1 + 800215a: fa02 f303 lsl.w r3, r2, r3 + 800215e: 69ba ldr r2, [r7, #24] + 8002160: 4313 orrs r3, r2 + 8002162: 61bb str r3, [r7, #24] GPIOx->OSPEEDR = temp; - 80020e0: 687b ldr r3, [r7, #4] - 80020e2: 69ba ldr r2, [r7, #24] - 80020e4: 609a str r2, [r3, #8] + 8002164: 687b ldr r3, [r7, #4] + 8002166: 69ba ldr r2, [r7, #24] + 8002168: 609a str r2, [r3, #8] /* Configure the IO Output Type */ temp = GPIOx->OTYPER; - 80020e6: 687b ldr r3, [r7, #4] - 80020e8: 685b ldr r3, [r3, #4] - 80020ea: 61bb str r3, [r7, #24] + 800216a: 687b ldr r3, [r7, #4] + 800216c: 685b ldr r3, [r3, #4] + 800216e: 61bb str r3, [r7, #24] temp &= ~(GPIO_OTYPER_OT_0 << position) ; - 80020ec: 2201 movs r2, #1 - 80020ee: 69fb ldr r3, [r7, #28] - 80020f0: fa02 f303 lsl.w r3, r2, r3 - 80020f4: 43db mvns r3, r3 - 80020f6: 69ba ldr r2, [r7, #24] - 80020f8: 4013 ands r3, r2 - 80020fa: 61bb str r3, [r7, #24] + 8002170: 2201 movs r2, #1 + 8002172: 69fb ldr r3, [r7, #28] + 8002174: fa02 f303 lsl.w r3, r2, r3 + 8002178: 43db mvns r3, r3 + 800217a: 69ba ldr r2, [r7, #24] + 800217c: 4013 ands r3, r2 + 800217e: 61bb str r3, [r7, #24] temp |= (((GPIO_Init->Mode & GPIO_OUTPUT_TYPE) >> 4) << position); - 80020fc: 683b ldr r3, [r7, #0] - 80020fe: 685b ldr r3, [r3, #4] - 8002100: 091b lsrs r3, r3, #4 - 8002102: f003 0201 and.w r2, r3, #1 - 8002106: 69fb ldr r3, [r7, #28] - 8002108: fa02 f303 lsl.w r3, r2, r3 - 800210c: 69ba ldr r2, [r7, #24] - 800210e: 4313 orrs r3, r2 - 8002110: 61bb str r3, [r7, #24] + 8002180: 683b ldr r3, [r7, #0] + 8002182: 685b ldr r3, [r3, #4] + 8002184: 091b lsrs r3, r3, #4 + 8002186: f003 0201 and.w r2, r3, #1 + 800218a: 69fb ldr r3, [r7, #28] + 800218c: fa02 f303 lsl.w r3, r2, r3 + 8002190: 69ba ldr r2, [r7, #24] + 8002192: 4313 orrs r3, r2 + 8002194: 61bb str r3, [r7, #24] GPIOx->OTYPER = temp; - 8002112: 687b ldr r3, [r7, #4] - 8002114: 69ba ldr r2, [r7, #24] - 8002116: 605a str r2, [r3, #4] + 8002196: 687b ldr r3, [r7, #4] + 8002198: 69ba ldr r2, [r7, #24] + 800219a: 605a str r2, [r3, #4] } /* Activate the Pull-up or Pull down resistor for the current IO */ temp = GPIOx->PUPDR; - 8002118: 687b ldr r3, [r7, #4] - 800211a: 68db ldr r3, [r3, #12] - 800211c: 61bb str r3, [r7, #24] + 800219c: 687b ldr r3, [r7, #4] + 800219e: 68db ldr r3, [r3, #12] + 80021a0: 61bb str r3, [r7, #24] temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2)); - 800211e: 69fb ldr r3, [r7, #28] - 8002120: 005b lsls r3, r3, #1 - 8002122: 2203 movs r2, #3 - 8002124: fa02 f303 lsl.w r3, r2, r3 - 8002128: 43db mvns r3, r3 - 800212a: 69ba ldr r2, [r7, #24] - 800212c: 4013 ands r3, r2 - 800212e: 61bb str r3, [r7, #24] + 80021a2: 69fb ldr r3, [r7, #28] + 80021a4: 005b lsls r3, r3, #1 + 80021a6: 2203 movs r2, #3 + 80021a8: fa02 f303 lsl.w r3, r2, r3 + 80021ac: 43db mvns r3, r3 + 80021ae: 69ba ldr r2, [r7, #24] + 80021b0: 4013 ands r3, r2 + 80021b2: 61bb str r3, [r7, #24] temp |= ((GPIO_Init->Pull) << (position * 2)); - 8002130: 683b ldr r3, [r7, #0] - 8002132: 689a ldr r2, [r3, #8] - 8002134: 69fb ldr r3, [r7, #28] - 8002136: 005b lsls r3, r3, #1 - 8002138: fa02 f303 lsl.w r3, r2, r3 - 800213c: 69ba ldr r2, [r7, #24] - 800213e: 4313 orrs r3, r2 - 8002140: 61bb str r3, [r7, #24] + 80021b4: 683b ldr r3, [r7, #0] + 80021b6: 689a ldr r2, [r3, #8] + 80021b8: 69fb ldr r3, [r7, #28] + 80021ba: 005b lsls r3, r3, #1 + 80021bc: fa02 f303 lsl.w r3, r2, r3 + 80021c0: 69ba ldr r2, [r7, #24] + 80021c2: 4313 orrs r3, r2 + 80021c4: 61bb str r3, [r7, #24] GPIOx->PUPDR = temp; - 8002142: 687b ldr r3, [r7, #4] - 8002144: 69ba ldr r2, [r7, #24] - 8002146: 60da str r2, [r3, #12] + 80021c6: 687b ldr r3, [r7, #4] + 80021c8: 69ba ldr r2, [r7, #24] + 80021ca: 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) - 8002148: 683b ldr r3, [r7, #0] - 800214a: 685b ldr r3, [r3, #4] - 800214c: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002150: 2b00 cmp r3, #0 - 8002152: f000 80be beq.w 80022d2 + 80021cc: 683b ldr r3, [r7, #0] + 80021ce: 685b ldr r3, [r3, #4] + 80021d0: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 80021d4: 2b00 cmp r3, #0 + 80021d6: f000 80be beq.w 8002356 { /* Enable SYSCFG Clock */ __HAL_RCC_SYSCFG_CLK_ENABLE(); - 8002156: 4b65 ldr r3, [pc, #404] ; (80022ec ) - 8002158: 6c5b ldr r3, [r3, #68] ; 0x44 - 800215a: 4a64 ldr r2, [pc, #400] ; (80022ec ) - 800215c: f443 4380 orr.w r3, r3, #16384 ; 0x4000 - 8002160: 6453 str r3, [r2, #68] ; 0x44 - 8002162: 4b62 ldr r3, [pc, #392] ; (80022ec ) - 8002164: 6c5b ldr r3, [r3, #68] ; 0x44 - 8002166: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 800216a: 60fb str r3, [r7, #12] - 800216c: 68fb ldr r3, [r7, #12] + 80021da: 4b65 ldr r3, [pc, #404] ; (8002370 ) + 80021dc: 6c5b ldr r3, [r3, #68] ; 0x44 + 80021de: 4a64 ldr r2, [pc, #400] ; (8002370 ) + 80021e0: f443 4380 orr.w r3, r3, #16384 ; 0x4000 + 80021e4: 6453 str r3, [r2, #68] ; 0x44 + 80021e6: 4b62 ldr r3, [pc, #392] ; (8002370 ) + 80021e8: 6c5b ldr r3, [r3, #68] ; 0x44 + 80021ea: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 80021ee: 60fb str r3, [r7, #12] + 80021f0: 68fb ldr r3, [r7, #12] temp = SYSCFG->EXTICR[position >> 2]; - 800216e: 4a60 ldr r2, [pc, #384] ; (80022f0 ) - 8002170: 69fb ldr r3, [r7, #28] - 8002172: 089b lsrs r3, r3, #2 - 8002174: 3302 adds r3, #2 - 8002176: f852 3023 ldr.w r3, [r2, r3, lsl #2] - 800217a: 61bb str r3, [r7, #24] + 80021f2: 4a60 ldr r2, [pc, #384] ; (8002374 ) + 80021f4: 69fb ldr r3, [r7, #28] + 80021f6: 089b lsrs r3, r3, #2 + 80021f8: 3302 adds r3, #2 + 80021fa: f852 3023 ldr.w r3, [r2, r3, lsl #2] + 80021fe: 61bb str r3, [r7, #24] temp &= ~(((uint32_t)0x0F) << (4 * (position & 0x03))); - 800217c: 69fb ldr r3, [r7, #28] - 800217e: f003 0303 and.w r3, r3, #3 - 8002182: 009b lsls r3, r3, #2 - 8002184: 220f movs r2, #15 - 8002186: fa02 f303 lsl.w r3, r2, r3 - 800218a: 43db mvns r3, r3 - 800218c: 69ba ldr r2, [r7, #24] - 800218e: 4013 ands r3, r2 - 8002190: 61bb str r3, [r7, #24] + 8002200: 69fb ldr r3, [r7, #28] + 8002202: f003 0303 and.w r3, r3, #3 + 8002206: 009b lsls r3, r3, #2 + 8002208: 220f movs r2, #15 + 800220a: fa02 f303 lsl.w r3, r2, r3 + 800220e: 43db mvns r3, r3 + 8002210: 69ba ldr r2, [r7, #24] + 8002212: 4013 ands r3, r2 + 8002214: 61bb str r3, [r7, #24] temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4 * (position & 0x03))); - 8002192: 687b ldr r3, [r7, #4] - 8002194: 4a57 ldr r2, [pc, #348] ; (80022f4 ) - 8002196: 4293 cmp r3, r2 - 8002198: d037 beq.n 800220a - 800219a: 687b ldr r3, [r7, #4] - 800219c: 4a56 ldr r2, [pc, #344] ; (80022f8 ) - 800219e: 4293 cmp r3, r2 - 80021a0: d031 beq.n 8002206 - 80021a2: 687b ldr r3, [r7, #4] - 80021a4: 4a55 ldr r2, [pc, #340] ; (80022fc ) - 80021a6: 4293 cmp r3, r2 - 80021a8: d02b beq.n 8002202 - 80021aa: 687b ldr r3, [r7, #4] - 80021ac: 4a54 ldr r2, [pc, #336] ; (8002300 ) - 80021ae: 4293 cmp r3, r2 - 80021b0: d025 beq.n 80021fe - 80021b2: 687b ldr r3, [r7, #4] - 80021b4: 4a53 ldr r2, [pc, #332] ; (8002304 ) - 80021b6: 4293 cmp r3, r2 - 80021b8: d01f beq.n 80021fa - 80021ba: 687b ldr r3, [r7, #4] - 80021bc: 4a52 ldr r2, [pc, #328] ; (8002308 ) - 80021be: 4293 cmp r3, r2 - 80021c0: d019 beq.n 80021f6 - 80021c2: 687b ldr r3, [r7, #4] - 80021c4: 4a51 ldr r2, [pc, #324] ; (800230c ) - 80021c6: 4293 cmp r3, r2 - 80021c8: d013 beq.n 80021f2 - 80021ca: 687b ldr r3, [r7, #4] - 80021cc: 4a50 ldr r2, [pc, #320] ; (8002310 ) - 80021ce: 4293 cmp r3, r2 - 80021d0: d00d beq.n 80021ee - 80021d2: 687b ldr r3, [r7, #4] - 80021d4: 4a4f ldr r2, [pc, #316] ; (8002314 ) - 80021d6: 4293 cmp r3, r2 - 80021d8: d007 beq.n 80021ea - 80021da: 687b ldr r3, [r7, #4] - 80021dc: 4a4e ldr r2, [pc, #312] ; (8002318 ) - 80021de: 4293 cmp r3, r2 - 80021e0: d101 bne.n 80021e6 - 80021e2: 2309 movs r3, #9 - 80021e4: e012 b.n 800220c - 80021e6: 230a movs r3, #10 - 80021e8: e010 b.n 800220c - 80021ea: 2308 movs r3, #8 - 80021ec: e00e b.n 800220c - 80021ee: 2307 movs r3, #7 - 80021f0: e00c b.n 800220c - 80021f2: 2306 movs r3, #6 - 80021f4: e00a b.n 800220c - 80021f6: 2305 movs r3, #5 - 80021f8: e008 b.n 800220c - 80021fa: 2304 movs r3, #4 - 80021fc: e006 b.n 800220c - 80021fe: 2303 movs r3, #3 - 8002200: e004 b.n 800220c - 8002202: 2302 movs r3, #2 - 8002204: e002 b.n 800220c - 8002206: 2301 movs r3, #1 - 8002208: e000 b.n 800220c - 800220a: 2300 movs r3, #0 - 800220c: 69fa ldr r2, [r7, #28] - 800220e: f002 0203 and.w r2, r2, #3 - 8002212: 0092 lsls r2, r2, #2 - 8002214: 4093 lsls r3, r2 - 8002216: 69ba ldr r2, [r7, #24] - 8002218: 4313 orrs r3, r2 - 800221a: 61bb str r3, [r7, #24] + 8002216: 687b ldr r3, [r7, #4] + 8002218: 4a57 ldr r2, [pc, #348] ; (8002378 ) + 800221a: 4293 cmp r3, r2 + 800221c: d037 beq.n 800228e + 800221e: 687b ldr r3, [r7, #4] + 8002220: 4a56 ldr r2, [pc, #344] ; (800237c ) + 8002222: 4293 cmp r3, r2 + 8002224: d031 beq.n 800228a + 8002226: 687b ldr r3, [r7, #4] + 8002228: 4a55 ldr r2, [pc, #340] ; (8002380 ) + 800222a: 4293 cmp r3, r2 + 800222c: d02b beq.n 8002286 + 800222e: 687b ldr r3, [r7, #4] + 8002230: 4a54 ldr r2, [pc, #336] ; (8002384 ) + 8002232: 4293 cmp r3, r2 + 8002234: d025 beq.n 8002282 + 8002236: 687b ldr r3, [r7, #4] + 8002238: 4a53 ldr r2, [pc, #332] ; (8002388 ) + 800223a: 4293 cmp r3, r2 + 800223c: d01f beq.n 800227e + 800223e: 687b ldr r3, [r7, #4] + 8002240: 4a52 ldr r2, [pc, #328] ; (800238c ) + 8002242: 4293 cmp r3, r2 + 8002244: d019 beq.n 800227a + 8002246: 687b ldr r3, [r7, #4] + 8002248: 4a51 ldr r2, [pc, #324] ; (8002390 ) + 800224a: 4293 cmp r3, r2 + 800224c: d013 beq.n 8002276 + 800224e: 687b ldr r3, [r7, #4] + 8002250: 4a50 ldr r2, [pc, #320] ; (8002394 ) + 8002252: 4293 cmp r3, r2 + 8002254: d00d beq.n 8002272 + 8002256: 687b ldr r3, [r7, #4] + 8002258: 4a4f ldr r2, [pc, #316] ; (8002398 ) + 800225a: 4293 cmp r3, r2 + 800225c: d007 beq.n 800226e + 800225e: 687b ldr r3, [r7, #4] + 8002260: 4a4e ldr r2, [pc, #312] ; (800239c ) + 8002262: 4293 cmp r3, r2 + 8002264: d101 bne.n 800226a + 8002266: 2309 movs r3, #9 + 8002268: e012 b.n 8002290 + 800226a: 230a movs r3, #10 + 800226c: e010 b.n 8002290 + 800226e: 2308 movs r3, #8 + 8002270: e00e b.n 8002290 + 8002272: 2307 movs r3, #7 + 8002274: e00c b.n 8002290 + 8002276: 2306 movs r3, #6 + 8002278: e00a b.n 8002290 + 800227a: 2305 movs r3, #5 + 800227c: e008 b.n 8002290 + 800227e: 2304 movs r3, #4 + 8002280: e006 b.n 8002290 + 8002282: 2303 movs r3, #3 + 8002284: e004 b.n 8002290 + 8002286: 2302 movs r3, #2 + 8002288: e002 b.n 8002290 + 800228a: 2301 movs r3, #1 + 800228c: e000 b.n 8002290 + 800228e: 2300 movs r3, #0 + 8002290: 69fa ldr r2, [r7, #28] + 8002292: f002 0203 and.w r2, r2, #3 + 8002296: 0092 lsls r2, r2, #2 + 8002298: 4093 lsls r3, r2 + 800229a: 69ba ldr r2, [r7, #24] + 800229c: 4313 orrs r3, r2 + 800229e: 61bb str r3, [r7, #24] SYSCFG->EXTICR[position >> 2] = temp; - 800221c: 4934 ldr r1, [pc, #208] ; (80022f0 ) - 800221e: 69fb ldr r3, [r7, #28] - 8002220: 089b lsrs r3, r3, #2 - 8002222: 3302 adds r3, #2 - 8002224: 69ba ldr r2, [r7, #24] - 8002226: f841 2023 str.w r2, [r1, r3, lsl #2] + 80022a0: 4934 ldr r1, [pc, #208] ; (8002374 ) + 80022a2: 69fb ldr r3, [r7, #28] + 80022a4: 089b lsrs r3, r3, #2 + 80022a6: 3302 adds r3, #2 + 80022a8: 69ba ldr r2, [r7, #24] + 80022aa: f841 2023 str.w r2, [r1, r3, lsl #2] /* Clear EXTI line configuration */ temp = EXTI->IMR; - 800222a: 4b3c ldr r3, [pc, #240] ; (800231c ) - 800222c: 681b ldr r3, [r3, #0] - 800222e: 61bb str r3, [r7, #24] + 80022ae: 4b3c ldr r3, [pc, #240] ; (80023a0 ) + 80022b0: 681b ldr r3, [r3, #0] + 80022b2: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 8002230: 693b ldr r3, [r7, #16] - 8002232: 43db mvns r3, r3 - 8002234: 69ba ldr r2, [r7, #24] - 8002236: 4013 ands r3, r2 - 8002238: 61bb str r3, [r7, #24] + 80022b4: 693b ldr r3, [r7, #16] + 80022b6: 43db mvns r3, r3 + 80022b8: 69ba ldr r2, [r7, #24] + 80022ba: 4013 ands r3, r2 + 80022bc: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & GPIO_MODE_IT) == GPIO_MODE_IT) - 800223a: 683b ldr r3, [r7, #0] - 800223c: 685b ldr r3, [r3, #4] - 800223e: f403 3380 and.w r3, r3, #65536 ; 0x10000 - 8002242: 2b00 cmp r3, #0 - 8002244: d003 beq.n 800224e + 80022be: 683b ldr r3, [r7, #0] + 80022c0: 685b ldr r3, [r3, #4] + 80022c2: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 80022c6: 2b00 cmp r3, #0 + 80022c8: d003 beq.n 80022d2 { temp |= iocurrent; - 8002246: 69ba ldr r2, [r7, #24] - 8002248: 693b ldr r3, [r7, #16] - 800224a: 4313 orrs r3, r2 - 800224c: 61bb str r3, [r7, #24] + 80022ca: 69ba ldr r2, [r7, #24] + 80022cc: 693b ldr r3, [r7, #16] + 80022ce: 4313 orrs r3, r2 + 80022d0: 61bb str r3, [r7, #24] } EXTI->IMR = temp; - 800224e: 4a33 ldr r2, [pc, #204] ; (800231c ) - 8002250: 69bb ldr r3, [r7, #24] - 8002252: 6013 str r3, [r2, #0] + 80022d2: 4a33 ldr r2, [pc, #204] ; (80023a0 ) + 80022d4: 69bb ldr r3, [r7, #24] + 80022d6: 6013 str r3, [r2, #0] temp = EXTI->EMR; - 8002254: 4b31 ldr r3, [pc, #196] ; (800231c ) - 8002256: 685b ldr r3, [r3, #4] - 8002258: 61bb str r3, [r7, #24] + 80022d8: 4b31 ldr r3, [pc, #196] ; (80023a0 ) + 80022da: 685b ldr r3, [r3, #4] + 80022dc: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 800225a: 693b ldr r3, [r7, #16] - 800225c: 43db mvns r3, r3 - 800225e: 69ba ldr r2, [r7, #24] - 8002260: 4013 ands r3, r2 - 8002262: 61bb str r3, [r7, #24] + 80022de: 693b ldr r3, [r7, #16] + 80022e0: 43db mvns r3, r3 + 80022e2: 69ba ldr r2, [r7, #24] + 80022e4: 4013 ands r3, r2 + 80022e6: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & GPIO_MODE_EVT) == GPIO_MODE_EVT) - 8002264: 683b ldr r3, [r7, #0] - 8002266: 685b ldr r3, [r3, #4] - 8002268: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 800226c: 2b00 cmp r3, #0 - 800226e: d003 beq.n 8002278 + 80022e8: 683b ldr r3, [r7, #0] + 80022ea: 685b ldr r3, [r3, #4] + 80022ec: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 80022f0: 2b00 cmp r3, #0 + 80022f2: d003 beq.n 80022fc { temp |= iocurrent; - 8002270: 69ba ldr r2, [r7, #24] - 8002272: 693b ldr r3, [r7, #16] - 8002274: 4313 orrs r3, r2 - 8002276: 61bb str r3, [r7, #24] + 80022f4: 69ba ldr r2, [r7, #24] + 80022f6: 693b ldr r3, [r7, #16] + 80022f8: 4313 orrs r3, r2 + 80022fa: 61bb str r3, [r7, #24] } EXTI->EMR = temp; - 8002278: 4a28 ldr r2, [pc, #160] ; (800231c ) - 800227a: 69bb ldr r3, [r7, #24] - 800227c: 6053 str r3, [r2, #4] + 80022fc: 4a28 ldr r2, [pc, #160] ; (80023a0 ) + 80022fe: 69bb ldr r3, [r7, #24] + 8002300: 6053 str r3, [r2, #4] /* Clear Rising Falling edge configuration */ temp = EXTI->RTSR; - 800227e: 4b27 ldr r3, [pc, #156] ; (800231c ) - 8002280: 689b ldr r3, [r3, #8] - 8002282: 61bb str r3, [r7, #24] + 8002302: 4b27 ldr r3, [pc, #156] ; (80023a0 ) + 8002304: 689b ldr r3, [r3, #8] + 8002306: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 8002284: 693b ldr r3, [r7, #16] - 8002286: 43db mvns r3, r3 - 8002288: 69ba ldr r2, [r7, #24] - 800228a: 4013 ands r3, r2 - 800228c: 61bb str r3, [r7, #24] + 8002308: 693b ldr r3, [r7, #16] + 800230a: 43db mvns r3, r3 + 800230c: 69ba ldr r2, [r7, #24] + 800230e: 4013 ands r3, r2 + 8002310: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & RISING_EDGE) == RISING_EDGE) - 800228e: 683b ldr r3, [r7, #0] - 8002290: 685b ldr r3, [r3, #4] - 8002292: f403 1380 and.w r3, r3, #1048576 ; 0x100000 - 8002296: 2b00 cmp r3, #0 - 8002298: d003 beq.n 80022a2 + 8002312: 683b ldr r3, [r7, #0] + 8002314: 685b ldr r3, [r3, #4] + 8002316: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 800231a: 2b00 cmp r3, #0 + 800231c: d003 beq.n 8002326 { temp |= iocurrent; - 800229a: 69ba ldr r2, [r7, #24] - 800229c: 693b ldr r3, [r7, #16] - 800229e: 4313 orrs r3, r2 - 80022a0: 61bb str r3, [r7, #24] + 800231e: 69ba ldr r2, [r7, #24] + 8002320: 693b ldr r3, [r7, #16] + 8002322: 4313 orrs r3, r2 + 8002324: 61bb str r3, [r7, #24] } EXTI->RTSR = temp; - 80022a2: 4a1e ldr r2, [pc, #120] ; (800231c ) - 80022a4: 69bb ldr r3, [r7, #24] - 80022a6: 6093 str r3, [r2, #8] + 8002326: 4a1e ldr r2, [pc, #120] ; (80023a0 ) + 8002328: 69bb ldr r3, [r7, #24] + 800232a: 6093 str r3, [r2, #8] temp = EXTI->FTSR; - 80022a8: 4b1c ldr r3, [pc, #112] ; (800231c ) - 80022aa: 68db ldr r3, [r3, #12] - 80022ac: 61bb str r3, [r7, #24] + 800232c: 4b1c ldr r3, [pc, #112] ; (80023a0 ) + 800232e: 68db ldr r3, [r3, #12] + 8002330: 61bb str r3, [r7, #24] temp &= ~((uint32_t)iocurrent); - 80022ae: 693b ldr r3, [r7, #16] - 80022b0: 43db mvns r3, r3 - 80022b2: 69ba ldr r2, [r7, #24] - 80022b4: 4013 ands r3, r2 - 80022b6: 61bb str r3, [r7, #24] + 8002332: 693b ldr r3, [r7, #16] + 8002334: 43db mvns r3, r3 + 8002336: 69ba ldr r2, [r7, #24] + 8002338: 4013 ands r3, r2 + 800233a: 61bb str r3, [r7, #24] if((GPIO_Init->Mode & FALLING_EDGE) == FALLING_EDGE) - 80022b8: 683b ldr r3, [r7, #0] - 80022ba: 685b ldr r3, [r3, #4] - 80022bc: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 80022c0: 2b00 cmp r3, #0 - 80022c2: d003 beq.n 80022cc + 800233c: 683b ldr r3, [r7, #0] + 800233e: 685b ldr r3, [r3, #4] + 8002340: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8002344: 2b00 cmp r3, #0 + 8002346: d003 beq.n 8002350 { temp |= iocurrent; - 80022c4: 69ba ldr r2, [r7, #24] - 80022c6: 693b ldr r3, [r7, #16] - 80022c8: 4313 orrs r3, r2 - 80022ca: 61bb str r3, [r7, #24] + 8002348: 69ba ldr r2, [r7, #24] + 800234a: 693b ldr r3, [r7, #16] + 800234c: 4313 orrs r3, r2 + 800234e: 61bb str r3, [r7, #24] } EXTI->FTSR = temp; - 80022cc: 4a13 ldr r2, [pc, #76] ; (800231c ) - 80022ce: 69bb ldr r3, [r7, #24] - 80022d0: 60d3 str r3, [r2, #12] + 8002350: 4a13 ldr r2, [pc, #76] ; (80023a0 ) + 8002352: 69bb ldr r3, [r7, #24] + 8002354: 60d3 str r3, [r2, #12] for(position = 0; position < GPIO_NUMBER; position++) - 80022d2: 69fb ldr r3, [r7, #28] - 80022d4: 3301 adds r3, #1 - 80022d6: 61fb str r3, [r7, #28] - 80022d8: 69fb ldr r3, [r7, #28] - 80022da: 2b0f cmp r3, #15 - 80022dc: f67f ae86 bls.w 8001fec + 8002356: 69fb ldr r3, [r7, #28] + 8002358: 3301 adds r3, #1 + 800235a: 61fb str r3, [r7, #28] + 800235c: 69fb ldr r3, [r7, #28] + 800235e: 2b0f cmp r3, #15 + 8002360: f67f ae86 bls.w 8002070 } } } } - 80022e0: bf00 nop - 80022e2: 3724 adds r7, #36 ; 0x24 - 80022e4: 46bd mov sp, r7 - 80022e6: f85d 7b04 ldr.w r7, [sp], #4 - 80022ea: 4770 bx lr - 80022ec: 40023800 .word 0x40023800 - 80022f0: 40013800 .word 0x40013800 - 80022f4: 40020000 .word 0x40020000 - 80022f8: 40020400 .word 0x40020400 - 80022fc: 40020800 .word 0x40020800 - 8002300: 40020c00 .word 0x40020c00 - 8002304: 40021000 .word 0x40021000 - 8002308: 40021400 .word 0x40021400 - 800230c: 40021800 .word 0x40021800 - 8002310: 40021c00 .word 0x40021c00 - 8002314: 40022000 .word 0x40022000 - 8002318: 40022400 .word 0x40022400 - 800231c: 40013c00 .word 0x40013c00 - -08002320 : + 8002364: bf00 nop + 8002366: 3724 adds r7, #36 ; 0x24 + 8002368: 46bd mov sp, r7 + 800236a: f85d 7b04 ldr.w r7, [sp], #4 + 800236e: 4770 bx lr + 8002370: 40023800 .word 0x40023800 + 8002374: 40013800 .word 0x40013800 + 8002378: 40020000 .word 0x40020000 + 800237c: 40020400 .word 0x40020400 + 8002380: 40020800 .word 0x40020800 + 8002384: 40020c00 .word 0x40020c00 + 8002388: 40021000 .word 0x40021000 + 800238c: 40021400 .word 0x40021400 + 8002390: 40021800 .word 0x40021800 + 8002394: 40021c00 .word 0x40021c00 + 8002398: 40022000 .word 0x40022000 + 800239c: 40022400 .word 0x40022400 + 80023a0: 40013c00 .word 0x40013c00 + +080023a4 : * @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) { - 8002320: b480 push {r7} - 8002322: b083 sub sp, #12 - 8002324: af00 add r7, sp, #0 - 8002326: 6078 str r0, [r7, #4] - 8002328: 460b mov r3, r1 - 800232a: 807b strh r3, [r7, #2] - 800232c: 4613 mov r3, r2 - 800232e: 707b strb r3, [r7, #1] + 80023a4: b480 push {r7} + 80023a6: b083 sub sp, #12 + 80023a8: af00 add r7, sp, #0 + 80023aa: 6078 str r0, [r7, #4] + 80023ac: 460b mov r3, r1 + 80023ae: 807b strh r3, [r7, #2] + 80023b0: 4613 mov r3, r2 + 80023b2: 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) - 8002330: 787b ldrb r3, [r7, #1] - 8002332: 2b00 cmp r3, #0 - 8002334: d003 beq.n 800233e + 80023b4: 787b ldrb r3, [r7, #1] + 80023b6: 2b00 cmp r3, #0 + 80023b8: d003 beq.n 80023c2 { GPIOx->BSRR = GPIO_Pin; - 8002336: 887a ldrh r2, [r7, #2] - 8002338: 687b ldr r3, [r7, #4] - 800233a: 619a str r2, [r3, #24] + 80023ba: 887a ldrh r2, [r7, #2] + 80023bc: 687b ldr r3, [r7, #4] + 80023be: 619a str r2, [r3, #24] } else { GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; } } - 800233c: e003 b.n 8002346 + 80023c0: e003 b.n 80023ca GPIOx->BSRR = (uint32_t)GPIO_Pin << 16; - 800233e: 887b ldrh r3, [r7, #2] - 8002340: 041a lsls r2, r3, #16 - 8002342: 687b ldr r3, [r7, #4] - 8002344: 619a str r2, [r3, #24] + 80023c2: 887b ldrh r3, [r7, #2] + 80023c4: 041a lsls r2, r3, #16 + 80023c6: 687b ldr r3, [r7, #4] + 80023c8: 619a str r2, [r3, #24] } - 8002346: bf00 nop - 8002348: 370c adds r7, #12 - 800234a: 46bd mov sp, r7 - 800234c: f85d 7b04 ldr.w r7, [sp], #4 - 8002350: 4770 bx lr + 80023ca: bf00 nop + 80023cc: 370c adds r7, #12 + 80023ce: 46bd mov sp, r7 + 80023d0: f85d 7b04 ldr.w r7, [sp], #4 + 80023d4: 4770 bx lr ... -08002354 : +080023d8 : * @brief This function handles EXTI interrupt request. * @param GPIO_Pin Specifies the pins connected EXTI line * @retval None */ void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) { - 8002354: b580 push {r7, lr} - 8002356: b082 sub sp, #8 - 8002358: af00 add r7, sp, #0 - 800235a: 4603 mov r3, r0 - 800235c: 80fb strh r3, [r7, #6] + 80023d8: b580 push {r7, lr} + 80023da: b082 sub sp, #8 + 80023dc: af00 add r7, sp, #0 + 80023de: 4603 mov r3, r0 + 80023e0: 80fb strh r3, [r7, #6] /* EXTI line interrupt detected */ if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) - 800235e: 4b08 ldr r3, [pc, #32] ; (8002380 ) - 8002360: 695a ldr r2, [r3, #20] - 8002362: 88fb ldrh r3, [r7, #6] - 8002364: 4013 ands r3, r2 - 8002366: 2b00 cmp r3, #0 - 8002368: d006 beq.n 8002378 + 80023e2: 4b08 ldr r3, [pc, #32] ; (8002404 ) + 80023e4: 695a ldr r2, [r3, #20] + 80023e6: 88fb ldrh r3, [r7, #6] + 80023e8: 4013 ands r3, r2 + 80023ea: 2b00 cmp r3, #0 + 80023ec: d006 beq.n 80023fc { __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); - 800236a: 4a05 ldr r2, [pc, #20] ; (8002380 ) - 800236c: 88fb ldrh r3, [r7, #6] - 800236e: 6153 str r3, [r2, #20] + 80023ee: 4a05 ldr r2, [pc, #20] ; (8002404 ) + 80023f0: 88fb ldrh r3, [r7, #6] + 80023f2: 6153 str r3, [r2, #20] HAL_GPIO_EXTI_Callback(GPIO_Pin); - 8002370: 88fb ldrh r3, [r7, #6] - 8002372: 4618 mov r0, r3 - 8002374: f7ff f984 bl 8001680 + 80023f4: 88fb ldrh r3, [r7, #6] + 80023f6: 4618 mov r0, r3 + 80023f8: f7ff f9a4 bl 8001744 } } - 8002378: bf00 nop - 800237a: 3708 adds r7, #8 - 800237c: 46bd mov sp, r7 - 800237e: bd80 pop {r7, pc} - 8002380: 40013c00 .word 0x40013c00 + 80023fc: bf00 nop + 80023fe: 3708 adds r7, #8 + 8002400: 46bd mov sp, r7 + 8002402: bd80 pop {r7, pc} + 8002404: 40013c00 .word 0x40013c00 -08002384 : +08002408 : * 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) { - 8002384: b580 push {r7, lr} - 8002386: b086 sub sp, #24 - 8002388: af00 add r7, sp, #0 - 800238a: 6078 str r0, [r7, #4] + 8002408: b580 push {r7, lr} + 800240a: b086 sub sp, #24 + 800240c: af00 add r7, sp, #0 + 800240e: 6078 str r0, [r7, #4] uint32_t tickstart; FlagStatus pwrclkchanged = RESET; - 800238c: 2300 movs r3, #0 - 800238e: 75fb strb r3, [r7, #23] + 8002410: 2300 movs r3, #0 + 8002412: 75fb strb r3, [r7, #23] /* Check Null pointer */ if(RCC_OscInitStruct == NULL) - 8002390: 687b ldr r3, [r7, #4] - 8002392: 2b00 cmp r3, #0 - 8002394: d101 bne.n 800239a + 8002414: 687b ldr r3, [r7, #4] + 8002416: 2b00 cmp r3, #0 + 8002418: d101 bne.n 800241e { return HAL_ERROR; - 8002396: 2301 movs r3, #1 - 8002398: e25e b.n 8002858 + 800241a: 2301 movs r3, #1 + 800241c: e25e b.n 80028dc /* Check the parameters */ assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); /*------------------------------- HSE Configuration ------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - 800239a: 687b ldr r3, [r7, #4] - 800239c: 681b ldr r3, [r3, #0] - 800239e: f003 0301 and.w r3, r3, #1 - 80023a2: 2b00 cmp r3, #0 - 80023a4: f000 8087 beq.w 80024b6 + 800241e: 687b ldr r3, [r7, #4] + 8002420: 681b ldr r3, [r3, #0] + 8002422: f003 0301 and.w r3, r3, #1 + 8002426: 2b00 cmp r3, #0 + 8002428: f000 8087 beq.w 800253a { /* 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) - 80023a8: 4b96 ldr r3, [pc, #600] ; (8002604 ) - 80023aa: 689b ldr r3, [r3, #8] - 80023ac: f003 030c and.w r3, r3, #12 - 80023b0: 2b04 cmp r3, #4 - 80023b2: d00c beq.n 80023ce + 800242c: 4b96 ldr r3, [pc, #600] ; (8002688 ) + 800242e: 689b ldr r3, [r3, #8] + 8002430: f003 030c and.w r3, r3, #12 + 8002434: 2b04 cmp r3, #4 + 8002436: d00c beq.n 8002452 || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) - 80023b4: 4b93 ldr r3, [pc, #588] ; (8002604 ) - 80023b6: 689b ldr r3, [r3, #8] - 80023b8: f003 030c and.w r3, r3, #12 - 80023bc: 2b08 cmp r3, #8 - 80023be: d112 bne.n 80023e6 - 80023c0: 4b90 ldr r3, [pc, #576] ; (8002604 ) - 80023c2: 685b ldr r3, [r3, #4] - 80023c4: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 80023c8: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 80023cc: d10b bne.n 80023e6 + 8002438: 4b93 ldr r3, [pc, #588] ; (8002688 ) + 800243a: 689b ldr r3, [r3, #8] + 800243c: f003 030c and.w r3, r3, #12 + 8002440: 2b08 cmp r3, #8 + 8002442: d112 bne.n 800246a + 8002444: 4b90 ldr r3, [pc, #576] ; (8002688 ) + 8002446: 685b ldr r3, [r3, #4] + 8002448: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 800244c: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002450: d10b bne.n 800246a { if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - 80023ce: 4b8d ldr r3, [pc, #564] ; (8002604 ) - 80023d0: 681b ldr r3, [r3, #0] - 80023d2: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 80023d6: 2b00 cmp r3, #0 - 80023d8: d06c beq.n 80024b4 - 80023da: 687b ldr r3, [r7, #4] - 80023dc: 685b ldr r3, [r3, #4] - 80023de: 2b00 cmp r3, #0 - 80023e0: d168 bne.n 80024b4 + 8002452: 4b8d ldr r3, [pc, #564] ; (8002688 ) + 8002454: 681b ldr r3, [r3, #0] + 8002456: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800245a: 2b00 cmp r3, #0 + 800245c: d06c beq.n 8002538 + 800245e: 687b ldr r3, [r7, #4] + 8002460: 685b ldr r3, [r3, #4] + 8002462: 2b00 cmp r3, #0 + 8002464: d168 bne.n 8002538 { return HAL_ERROR; - 80023e2: 2301 movs r3, #1 - 80023e4: e238 b.n 8002858 + 8002466: 2301 movs r3, #1 + 8002468: e238 b.n 80028dc } } else { /* Set the new HSE configuration ---------------------------------------*/ __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - 80023e6: 687b ldr r3, [r7, #4] - 80023e8: 685b ldr r3, [r3, #4] - 80023ea: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 80023ee: d106 bne.n 80023fe - 80023f0: 4b84 ldr r3, [pc, #528] ; (8002604 ) - 80023f2: 681b ldr r3, [r3, #0] - 80023f4: 4a83 ldr r2, [pc, #524] ; (8002604 ) - 80023f6: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 80023fa: 6013 str r3, [r2, #0] - 80023fc: e02e b.n 800245c - 80023fe: 687b ldr r3, [r7, #4] - 8002400: 685b ldr r3, [r3, #4] - 8002402: 2b00 cmp r3, #0 - 8002404: d10c bne.n 8002420 - 8002406: 4b7f ldr r3, [pc, #508] ; (8002604 ) - 8002408: 681b ldr r3, [r3, #0] - 800240a: 4a7e ldr r2, [pc, #504] ; (8002604 ) - 800240c: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 8002410: 6013 str r3, [r2, #0] - 8002412: 4b7c ldr r3, [pc, #496] ; (8002604 ) - 8002414: 681b ldr r3, [r3, #0] - 8002416: 4a7b ldr r2, [pc, #492] ; (8002604 ) - 8002418: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 800241c: 6013 str r3, [r2, #0] - 800241e: e01d b.n 800245c - 8002420: 687b ldr r3, [r7, #4] - 8002422: 685b ldr r3, [r3, #4] - 8002424: f5b3 2fa0 cmp.w r3, #327680 ; 0x50000 - 8002428: d10c bne.n 8002444 - 800242a: 4b76 ldr r3, [pc, #472] ; (8002604 ) - 800242c: 681b ldr r3, [r3, #0] - 800242e: 4a75 ldr r2, [pc, #468] ; (8002604 ) - 8002430: f443 2380 orr.w r3, r3, #262144 ; 0x40000 - 8002434: 6013 str r3, [r2, #0] - 8002436: 4b73 ldr r3, [pc, #460] ; (8002604 ) - 8002438: 681b ldr r3, [r3, #0] - 800243a: 4a72 ldr r2, [pc, #456] ; (8002604 ) - 800243c: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 8002440: 6013 str r3, [r2, #0] - 8002442: e00b b.n 800245c - 8002444: 4b6f ldr r3, [pc, #444] ; (8002604 ) - 8002446: 681b ldr r3, [r3, #0] - 8002448: 4a6e ldr r2, [pc, #440] ; (8002604 ) - 800244a: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 800244e: 6013 str r3, [r2, #0] - 8002450: 4b6c ldr r3, [pc, #432] ; (8002604 ) - 8002452: 681b ldr r3, [r3, #0] - 8002454: 4a6b ldr r2, [pc, #428] ; (8002604 ) - 8002456: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 800245a: 6013 str r3, [r2, #0] + 800246a: 687b ldr r3, [r7, #4] + 800246c: 685b ldr r3, [r3, #4] + 800246e: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8002472: d106 bne.n 8002482 + 8002474: 4b84 ldr r3, [pc, #528] ; (8002688 ) + 8002476: 681b ldr r3, [r3, #0] + 8002478: 4a83 ldr r2, [pc, #524] ; (8002688 ) + 800247a: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 800247e: 6013 str r3, [r2, #0] + 8002480: e02e b.n 80024e0 + 8002482: 687b ldr r3, [r7, #4] + 8002484: 685b ldr r3, [r3, #4] + 8002486: 2b00 cmp r3, #0 + 8002488: d10c bne.n 80024a4 + 800248a: 4b7f ldr r3, [pc, #508] ; (8002688 ) + 800248c: 681b ldr r3, [r3, #0] + 800248e: 4a7e ldr r2, [pc, #504] ; (8002688 ) + 8002490: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002494: 6013 str r3, [r2, #0] + 8002496: 4b7c ldr r3, [pc, #496] ; (8002688 ) + 8002498: 681b ldr r3, [r3, #0] + 800249a: 4a7b ldr r2, [pc, #492] ; (8002688 ) + 800249c: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 80024a0: 6013 str r3, [r2, #0] + 80024a2: e01d b.n 80024e0 + 80024a4: 687b ldr r3, [r7, #4] + 80024a6: 685b ldr r3, [r3, #4] + 80024a8: f5b3 2fa0 cmp.w r3, #327680 ; 0x50000 + 80024ac: d10c bne.n 80024c8 + 80024ae: 4b76 ldr r3, [pc, #472] ; (8002688 ) + 80024b0: 681b ldr r3, [r3, #0] + 80024b2: 4a75 ldr r2, [pc, #468] ; (8002688 ) + 80024b4: f443 2380 orr.w r3, r3, #262144 ; 0x40000 + 80024b8: 6013 str r3, [r2, #0] + 80024ba: 4b73 ldr r3, [pc, #460] ; (8002688 ) + 80024bc: 681b ldr r3, [r3, #0] + 80024be: 4a72 ldr r2, [pc, #456] ; (8002688 ) + 80024c0: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 80024c4: 6013 str r3, [r2, #0] + 80024c6: e00b b.n 80024e0 + 80024c8: 4b6f ldr r3, [pc, #444] ; (8002688 ) + 80024ca: 681b ldr r3, [r3, #0] + 80024cc: 4a6e ldr r2, [pc, #440] ; (8002688 ) + 80024ce: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 80024d2: 6013 str r3, [r2, #0] + 80024d4: 4b6c ldr r3, [pc, #432] ; (8002688 ) + 80024d6: 681b ldr r3, [r3, #0] + 80024d8: 4a6b ldr r2, [pc, #428] ; (8002688 ) + 80024da: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 80024de: 6013 str r3, [r2, #0] /* Check the HSE State */ if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF) - 800245c: 687b ldr r3, [r7, #4] - 800245e: 685b ldr r3, [r3, #4] - 8002460: 2b00 cmp r3, #0 - 8002462: d013 beq.n 800248c + 80024e0: 687b ldr r3, [r7, #4] + 80024e2: 685b ldr r3, [r3, #4] + 80024e4: 2b00 cmp r3, #0 + 80024e6: d013 beq.n 8002510 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002464: f7ff fc72 bl 8001d4c - 8002468: 6138 str r0, [r7, #16] + 80024e8: f7ff fc72 bl 8001dd0 + 80024ec: 6138 str r0, [r7, #16] /* Wait till HSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 800246a: e008 b.n 800247e + 80024ee: e008 b.n 8002502 { if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - 800246c: f7ff fc6e bl 8001d4c - 8002470: 4602 mov r2, r0 - 8002472: 693b ldr r3, [r7, #16] - 8002474: 1ad3 subs r3, r2, r3 - 8002476: 2b64 cmp r3, #100 ; 0x64 - 8002478: d901 bls.n 800247e + 80024f0: f7ff fc6e bl 8001dd0 + 80024f4: 4602 mov r2, r0 + 80024f6: 693b ldr r3, [r7, #16] + 80024f8: 1ad3 subs r3, r2, r3 + 80024fa: 2b64 cmp r3, #100 ; 0x64 + 80024fc: d901 bls.n 8002502 { return HAL_TIMEOUT; - 800247a: 2303 movs r3, #3 - 800247c: e1ec b.n 8002858 + 80024fe: 2303 movs r3, #3 + 8002500: e1ec b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 800247e: 4b61 ldr r3, [pc, #388] ; (8002604 ) - 8002480: 681b ldr r3, [r3, #0] - 8002482: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8002486: 2b00 cmp r3, #0 - 8002488: d0f0 beq.n 800246c - 800248a: e014 b.n 80024b6 + 8002502: 4b61 ldr r3, [pc, #388] ; (8002688 ) + 8002504: 681b ldr r3, [r3, #0] + 8002506: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800250a: 2b00 cmp r3, #0 + 800250c: d0f0 beq.n 80024f0 + 800250e: e014 b.n 800253a } } else { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800248c: f7ff fc5e bl 8001d4c - 8002490: 6138 str r0, [r7, #16] + 8002510: f7ff fc5e bl 8001dd0 + 8002514: 6138 str r0, [r7, #16] /* Wait till HSE is bypassed or disabled */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - 8002492: e008 b.n 80024a6 + 8002516: e008 b.n 800252a { if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - 8002494: f7ff fc5a bl 8001d4c - 8002498: 4602 mov r2, r0 - 800249a: 693b ldr r3, [r7, #16] - 800249c: 1ad3 subs r3, r2, r3 - 800249e: 2b64 cmp r3, #100 ; 0x64 - 80024a0: d901 bls.n 80024a6 + 8002518: f7ff fc5a bl 8001dd0 + 800251c: 4602 mov r2, r0 + 800251e: 693b ldr r3, [r7, #16] + 8002520: 1ad3 subs r3, r2, r3 + 8002522: 2b64 cmp r3, #100 ; 0x64 + 8002524: d901 bls.n 800252a { return HAL_TIMEOUT; - 80024a2: 2303 movs r3, #3 - 80024a4: e1d8 b.n 8002858 + 8002526: 2303 movs r3, #3 + 8002528: e1d8 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - 80024a6: 4b57 ldr r3, [pc, #348] ; (8002604 ) - 80024a8: 681b ldr r3, [r3, #0] - 80024aa: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 80024ae: 2b00 cmp r3, #0 - 80024b0: d1f0 bne.n 8002494 - 80024b2: e000 b.n 80024b6 + 800252a: 4b57 ldr r3, [pc, #348] ; (8002688 ) + 800252c: 681b ldr r3, [r3, #0] + 800252e: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 8002532: 2b00 cmp r3, #0 + 8002534: d1f0 bne.n 8002518 + 8002536: e000 b.n 800253a if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - 80024b4: bf00 nop + 8002538: bf00 nop } } } } /*----------------------------- HSI Configuration --------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - 80024b6: 687b ldr r3, [r7, #4] - 80024b8: 681b ldr r3, [r3, #0] - 80024ba: f003 0302 and.w r3, r3, #2 - 80024be: 2b00 cmp r3, #0 - 80024c0: d069 beq.n 8002596 + 800253a: 687b ldr r3, [r7, #4] + 800253c: 681b ldr r3, [r3, #0] + 800253e: f003 0302 and.w r3, r3, #2 + 8002542: 2b00 cmp r3, #0 + 8002544: d069 beq.n 800261a /* 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) - 80024c2: 4b50 ldr r3, [pc, #320] ; (8002604 ) - 80024c4: 689b ldr r3, [r3, #8] - 80024c6: f003 030c and.w r3, r3, #12 - 80024ca: 2b00 cmp r3, #0 - 80024cc: d00b beq.n 80024e6 + 8002546: 4b50 ldr r3, [pc, #320] ; (8002688 ) + 8002548: 689b ldr r3, [r3, #8] + 800254a: f003 030c and.w r3, r3, #12 + 800254e: 2b00 cmp r3, #0 + 8002550: d00b beq.n 800256a || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) - 80024ce: 4b4d ldr r3, [pc, #308] ; (8002604 ) - 80024d0: 689b ldr r3, [r3, #8] - 80024d2: f003 030c and.w r3, r3, #12 - 80024d6: 2b08 cmp r3, #8 - 80024d8: d11c bne.n 8002514 - 80024da: 4b4a ldr r3, [pc, #296] ; (8002604 ) - 80024dc: 685b ldr r3, [r3, #4] - 80024de: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 80024e2: 2b00 cmp r3, #0 - 80024e4: d116 bne.n 8002514 + 8002552: 4b4d ldr r3, [pc, #308] ; (8002688 ) + 8002554: 689b ldr r3, [r3, #8] + 8002556: f003 030c and.w r3, r3, #12 + 800255a: 2b08 cmp r3, #8 + 800255c: d11c bne.n 8002598 + 800255e: 4b4a ldr r3, [pc, #296] ; (8002688 ) + 8002560: 685b ldr r3, [r3, #4] + 8002562: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002566: 2b00 cmp r3, #0 + 8002568: d116 bne.n 8002598 { /* 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)) - 80024e6: 4b47 ldr r3, [pc, #284] ; (8002604 ) - 80024e8: 681b ldr r3, [r3, #0] - 80024ea: f003 0302 and.w r3, r3, #2 - 80024ee: 2b00 cmp r3, #0 - 80024f0: d005 beq.n 80024fe - 80024f2: 687b ldr r3, [r7, #4] - 80024f4: 68db ldr r3, [r3, #12] - 80024f6: 2b01 cmp r3, #1 - 80024f8: d001 beq.n 80024fe + 800256a: 4b47 ldr r3, [pc, #284] ; (8002688 ) + 800256c: 681b ldr r3, [r3, #0] + 800256e: f003 0302 and.w r3, r3, #2 + 8002572: 2b00 cmp r3, #0 + 8002574: d005 beq.n 8002582 + 8002576: 687b ldr r3, [r7, #4] + 8002578: 68db ldr r3, [r3, #12] + 800257a: 2b01 cmp r3, #1 + 800257c: d001 beq.n 8002582 { return HAL_ERROR; - 80024fa: 2301 movs r3, #1 - 80024fc: e1ac b.n 8002858 + 800257e: 2301 movs r3, #1 + 8002580: e1ac b.n 80028dc } /* Otherwise, just the calibration is allowed */ else { /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - 80024fe: 4b41 ldr r3, [pc, #260] ; (8002604 ) - 8002500: 681b ldr r3, [r3, #0] - 8002502: f023 02f8 bic.w r2, r3, #248 ; 0xf8 - 8002506: 687b ldr r3, [r7, #4] - 8002508: 691b ldr r3, [r3, #16] - 800250a: 00db lsls r3, r3, #3 - 800250c: 493d ldr r1, [pc, #244] ; (8002604 ) - 800250e: 4313 orrs r3, r2 - 8002510: 600b str r3, [r1, #0] + 8002582: 4b41 ldr r3, [pc, #260] ; (8002688 ) + 8002584: 681b ldr r3, [r3, #0] + 8002586: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 800258a: 687b ldr r3, [r7, #4] + 800258c: 691b ldr r3, [r3, #16] + 800258e: 00db lsls r3, r3, #3 + 8002590: 493d ldr r1, [pc, #244] ; (8002688 ) + 8002592: 4313 orrs r3, r2 + 8002594: 600b str r3, [r1, #0] if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - 8002512: e040 b.n 8002596 + 8002596: e040 b.n 800261a } } else { /* Check the HSI State */ if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - 8002514: 687b ldr r3, [r7, #4] - 8002516: 68db ldr r3, [r3, #12] - 8002518: 2b00 cmp r3, #0 - 800251a: d023 beq.n 8002564 + 8002598: 687b ldr r3, [r7, #4] + 800259a: 68db ldr r3, [r3, #12] + 800259c: 2b00 cmp r3, #0 + 800259e: d023 beq.n 80025e8 { /* Enable the Internal High Speed oscillator (HSI). */ __HAL_RCC_HSI_ENABLE(); - 800251c: 4b39 ldr r3, [pc, #228] ; (8002604 ) - 800251e: 681b ldr r3, [r3, #0] - 8002520: 4a38 ldr r2, [pc, #224] ; (8002604 ) - 8002522: f043 0301 orr.w r3, r3, #1 - 8002526: 6013 str r3, [r2, #0] + 80025a0: 4b39 ldr r3, [pc, #228] ; (8002688 ) + 80025a2: 681b ldr r3, [r3, #0] + 80025a4: 4a38 ldr r2, [pc, #224] ; (8002688 ) + 80025a6: f043 0301 orr.w r3, r3, #1 + 80025aa: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002528: f7ff fc10 bl 8001d4c - 800252c: 6138 str r0, [r7, #16] + 80025ac: f7ff fc10 bl 8001dd0 + 80025b0: 6138 str r0, [r7, #16] /* Wait till HSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 800252e: e008 b.n 8002542 + 80025b2: e008 b.n 80025c6 { if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - 8002530: f7ff fc0c bl 8001d4c - 8002534: 4602 mov r2, r0 - 8002536: 693b ldr r3, [r7, #16] - 8002538: 1ad3 subs r3, r2, r3 - 800253a: 2b02 cmp r3, #2 - 800253c: d901 bls.n 8002542 + 80025b4: f7ff fc0c bl 8001dd0 + 80025b8: 4602 mov r2, r0 + 80025ba: 693b ldr r3, [r7, #16] + 80025bc: 1ad3 subs r3, r2, r3 + 80025be: 2b02 cmp r3, #2 + 80025c0: d901 bls.n 80025c6 { return HAL_TIMEOUT; - 800253e: 2303 movs r3, #3 - 8002540: e18a b.n 8002858 + 80025c2: 2303 movs r3, #3 + 80025c4: e18a b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 8002542: 4b30 ldr r3, [pc, #192] ; (8002604 ) - 8002544: 681b ldr r3, [r3, #0] - 8002546: f003 0302 and.w r3, r3, #2 - 800254a: 2b00 cmp r3, #0 - 800254c: d0f0 beq.n 8002530 + 80025c6: 4b30 ldr r3, [pc, #192] ; (8002688 ) + 80025c8: 681b ldr r3, [r3, #0] + 80025ca: f003 0302 and.w r3, r3, #2 + 80025ce: 2b00 cmp r3, #0 + 80025d0: d0f0 beq.n 80025b4 } } /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - 800254e: 4b2d ldr r3, [pc, #180] ; (8002604 ) - 8002550: 681b ldr r3, [r3, #0] - 8002552: f023 02f8 bic.w r2, r3, #248 ; 0xf8 - 8002556: 687b ldr r3, [r7, #4] - 8002558: 691b ldr r3, [r3, #16] - 800255a: 00db lsls r3, r3, #3 - 800255c: 4929 ldr r1, [pc, #164] ; (8002604 ) - 800255e: 4313 orrs r3, r2 - 8002560: 600b str r3, [r1, #0] - 8002562: e018 b.n 8002596 + 80025d2: 4b2d ldr r3, [pc, #180] ; (8002688 ) + 80025d4: 681b ldr r3, [r3, #0] + 80025d6: f023 02f8 bic.w r2, r3, #248 ; 0xf8 + 80025da: 687b ldr r3, [r7, #4] + 80025dc: 691b ldr r3, [r3, #16] + 80025de: 00db lsls r3, r3, #3 + 80025e0: 4929 ldr r1, [pc, #164] ; (8002688 ) + 80025e2: 4313 orrs r3, r2 + 80025e4: 600b str r3, [r1, #0] + 80025e6: e018 b.n 800261a } else { /* Disable the Internal High Speed oscillator (HSI). */ __HAL_RCC_HSI_DISABLE(); - 8002564: 4b27 ldr r3, [pc, #156] ; (8002604 ) - 8002566: 681b ldr r3, [r3, #0] - 8002568: 4a26 ldr r2, [pc, #152] ; (8002604 ) - 800256a: f023 0301 bic.w r3, r3, #1 - 800256e: 6013 str r3, [r2, #0] + 80025e8: 4b27 ldr r3, [pc, #156] ; (8002688 ) + 80025ea: 681b ldr r3, [r3, #0] + 80025ec: 4a26 ldr r2, [pc, #152] ; (8002688 ) + 80025ee: f023 0301 bic.w r3, r3, #1 + 80025f2: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002570: f7ff fbec bl 8001d4c - 8002574: 6138 str r0, [r7, #16] + 80025f4: f7ff fbec bl 8001dd0 + 80025f8: 6138 str r0, [r7, #16] /* Wait till HSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - 8002576: e008 b.n 800258a + 80025fa: e008 b.n 800260e { if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - 8002578: f7ff fbe8 bl 8001d4c - 800257c: 4602 mov r2, r0 - 800257e: 693b ldr r3, [r7, #16] - 8002580: 1ad3 subs r3, r2, r3 - 8002582: 2b02 cmp r3, #2 - 8002584: d901 bls.n 800258a + 80025fc: f7ff fbe8 bl 8001dd0 + 8002600: 4602 mov r2, r0 + 8002602: 693b ldr r3, [r7, #16] + 8002604: 1ad3 subs r3, r2, r3 + 8002606: 2b02 cmp r3, #2 + 8002608: d901 bls.n 800260e { return HAL_TIMEOUT; - 8002586: 2303 movs r3, #3 - 8002588: e166 b.n 8002858 + 800260a: 2303 movs r3, #3 + 800260c: e166 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - 800258a: 4b1e ldr r3, [pc, #120] ; (8002604 ) - 800258c: 681b ldr r3, [r3, #0] - 800258e: f003 0302 and.w r3, r3, #2 - 8002592: 2b00 cmp r3, #0 - 8002594: d1f0 bne.n 8002578 + 800260e: 4b1e ldr r3, [pc, #120] ; (8002688 ) + 8002610: 681b ldr r3, [r3, #0] + 8002612: f003 0302 and.w r3, r3, #2 + 8002616: 2b00 cmp r3, #0 + 8002618: d1f0 bne.n 80025fc } } } } /*------------------------------ LSI Configuration -------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - 8002596: 687b ldr r3, [r7, #4] - 8002598: 681b ldr r3, [r3, #0] - 800259a: f003 0308 and.w r3, r3, #8 - 800259e: 2b00 cmp r3, #0 - 80025a0: d038 beq.n 8002614 + 800261a: 687b ldr r3, [r7, #4] + 800261c: 681b ldr r3, [r3, #0] + 800261e: f003 0308 and.w r3, r3, #8 + 8002622: 2b00 cmp r3, #0 + 8002624: d038 beq.n 8002698 { /* Check the parameters */ assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); /* Check the LSI State */ if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - 80025a2: 687b ldr r3, [r7, #4] - 80025a4: 695b ldr r3, [r3, #20] - 80025a6: 2b00 cmp r3, #0 - 80025a8: d019 beq.n 80025de + 8002626: 687b ldr r3, [r7, #4] + 8002628: 695b ldr r3, [r3, #20] + 800262a: 2b00 cmp r3, #0 + 800262c: d019 beq.n 8002662 { /* Enable the Internal Low Speed oscillator (LSI). */ __HAL_RCC_LSI_ENABLE(); - 80025aa: 4b16 ldr r3, [pc, #88] ; (8002604 ) - 80025ac: 6f5b ldr r3, [r3, #116] ; 0x74 - 80025ae: 4a15 ldr r2, [pc, #84] ; (8002604 ) - 80025b0: f043 0301 orr.w r3, r3, #1 - 80025b4: 6753 str r3, [r2, #116] ; 0x74 + 800262e: 4b16 ldr r3, [pc, #88] ; (8002688 ) + 8002630: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002632: 4a15 ldr r2, [pc, #84] ; (8002688 ) + 8002634: f043 0301 orr.w r3, r3, #1 + 8002638: 6753 str r3, [r2, #116] ; 0x74 /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80025b6: f7ff fbc9 bl 8001d4c - 80025ba: 6138 str r0, [r7, #16] + 800263a: f7ff fbc9 bl 8001dd0 + 800263e: 6138 str r0, [r7, #16] /* Wait till LSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - 80025bc: e008 b.n 80025d0 + 8002640: e008 b.n 8002654 { if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - 80025be: f7ff fbc5 bl 8001d4c - 80025c2: 4602 mov r2, r0 - 80025c4: 693b ldr r3, [r7, #16] - 80025c6: 1ad3 subs r3, r2, r3 - 80025c8: 2b02 cmp r3, #2 - 80025ca: d901 bls.n 80025d0 + 8002642: f7ff fbc5 bl 8001dd0 + 8002646: 4602 mov r2, r0 + 8002648: 693b ldr r3, [r7, #16] + 800264a: 1ad3 subs r3, r2, r3 + 800264c: 2b02 cmp r3, #2 + 800264e: d901 bls.n 8002654 { return HAL_TIMEOUT; - 80025cc: 2303 movs r3, #3 - 80025ce: e143 b.n 8002858 + 8002650: 2303 movs r3, #3 + 8002652: e143 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - 80025d0: 4b0c ldr r3, [pc, #48] ; (8002604 ) - 80025d2: 6f5b ldr r3, [r3, #116] ; 0x74 - 80025d4: f003 0302 and.w r3, r3, #2 - 80025d8: 2b00 cmp r3, #0 - 80025da: d0f0 beq.n 80025be - 80025dc: e01a b.n 8002614 + 8002654: 4b0c ldr r3, [pc, #48] ; (8002688 ) + 8002656: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002658: f003 0302 and.w r3, r3, #2 + 800265c: 2b00 cmp r3, #0 + 800265e: d0f0 beq.n 8002642 + 8002660: e01a b.n 8002698 } } else { /* Disable the Internal Low Speed oscillator (LSI). */ __HAL_RCC_LSI_DISABLE(); - 80025de: 4b09 ldr r3, [pc, #36] ; (8002604 ) - 80025e0: 6f5b ldr r3, [r3, #116] ; 0x74 - 80025e2: 4a08 ldr r2, [pc, #32] ; (8002604 ) - 80025e4: f023 0301 bic.w r3, r3, #1 - 80025e8: 6753 str r3, [r2, #116] ; 0x74 + 8002662: 4b09 ldr r3, [pc, #36] ; (8002688 ) + 8002664: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002666: 4a08 ldr r2, [pc, #32] ; (8002688 ) + 8002668: f023 0301 bic.w r3, r3, #1 + 800266c: 6753 str r3, [r2, #116] ; 0x74 /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80025ea: f7ff fbaf bl 8001d4c - 80025ee: 6138 str r0, [r7, #16] + 800266e: f7ff fbaf bl 8001dd0 + 8002672: 6138 str r0, [r7, #16] /* Wait till LSI is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - 80025f0: e00a b.n 8002608 + 8002674: e00a b.n 800268c { if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - 80025f2: f7ff fbab bl 8001d4c - 80025f6: 4602 mov r2, r0 - 80025f8: 693b ldr r3, [r7, #16] - 80025fa: 1ad3 subs r3, r2, r3 - 80025fc: 2b02 cmp r3, #2 - 80025fe: d903 bls.n 8002608 + 8002676: f7ff fbab bl 8001dd0 + 800267a: 4602 mov r2, r0 + 800267c: 693b ldr r3, [r7, #16] + 800267e: 1ad3 subs r3, r2, r3 + 8002680: 2b02 cmp r3, #2 + 8002682: d903 bls.n 800268c { return HAL_TIMEOUT; - 8002600: 2303 movs r3, #3 - 8002602: e129 b.n 8002858 - 8002604: 40023800 .word 0x40023800 + 8002684: 2303 movs r3, #3 + 8002686: e129 b.n 80028dc + 8002688: 40023800 .word 0x40023800 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - 8002608: 4b95 ldr r3, [pc, #596] ; (8002860 ) - 800260a: 6f5b ldr r3, [r3, #116] ; 0x74 - 800260c: f003 0302 and.w r3, r3, #2 - 8002610: 2b00 cmp r3, #0 - 8002612: d1ee bne.n 80025f2 + 800268c: 4b95 ldr r3, [pc, #596] ; (80028e4 ) + 800268e: 6f5b ldr r3, [r3, #116] ; 0x74 + 8002690: f003 0302 and.w r3, r3, #2 + 8002694: 2b00 cmp r3, #0 + 8002696: d1ee bne.n 8002676 } } } } /*------------------------------ LSE Configuration -------------------------*/ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - 8002614: 687b ldr r3, [r7, #4] - 8002616: 681b ldr r3, [r3, #0] - 8002618: f003 0304 and.w r3, r3, #4 - 800261c: 2b00 cmp r3, #0 - 800261e: f000 80a4 beq.w 800276a + 8002698: 687b ldr r3, [r7, #4] + 800269a: 681b ldr r3, [r3, #0] + 800269c: f003 0304 and.w r3, r3, #4 + 80026a0: 2b00 cmp r3, #0 + 80026a2: f000 80a4 beq.w 80027ee /* 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()) - 8002622: 4b8f ldr r3, [pc, #572] ; (8002860 ) - 8002624: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002626: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 800262a: 2b00 cmp r3, #0 - 800262c: d10d bne.n 800264a + 80026a6: 4b8f ldr r3, [pc, #572] ; (80028e4 ) + 80026a8: 6c1b ldr r3, [r3, #64] ; 0x40 + 80026aa: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 80026ae: 2b00 cmp r3, #0 + 80026b0: d10d bne.n 80026ce { /* Enable Power Clock*/ __HAL_RCC_PWR_CLK_ENABLE(); - 800262e: 4b8c ldr r3, [pc, #560] ; (8002860 ) - 8002630: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002632: 4a8b ldr r2, [pc, #556] ; (8002860 ) - 8002634: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8002638: 6413 str r3, [r2, #64] ; 0x40 - 800263a: 4b89 ldr r3, [pc, #548] ; (8002860 ) - 800263c: 6c1b ldr r3, [r3, #64] ; 0x40 - 800263e: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002642: 60fb str r3, [r7, #12] - 8002644: 68fb ldr r3, [r7, #12] + 80026b2: 4b8c ldr r3, [pc, #560] ; (80028e4 ) + 80026b4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80026b6: 4a8b ldr r2, [pc, #556] ; (80028e4 ) + 80026b8: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 80026bc: 6413 str r3, [r2, #64] ; 0x40 + 80026be: 4b89 ldr r3, [pc, #548] ; (80028e4 ) + 80026c0: 6c1b ldr r3, [r3, #64] ; 0x40 + 80026c2: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 80026c6: 60fb str r3, [r7, #12] + 80026c8: 68fb ldr r3, [r7, #12] pwrclkchanged = SET; - 8002646: 2301 movs r3, #1 - 8002648: 75fb strb r3, [r7, #23] + 80026ca: 2301 movs r3, #1 + 80026cc: 75fb strb r3, [r7, #23] } if(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 800264a: 4b86 ldr r3, [pc, #536] ; (8002864 ) - 800264c: 681b ldr r3, [r3, #0] - 800264e: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002652: 2b00 cmp r3, #0 - 8002654: d118 bne.n 8002688 + 80026ce: 4b86 ldr r3, [pc, #536] ; (80028e8 ) + 80026d0: 681b ldr r3, [r3, #0] + 80026d2: f403 7380 and.w r3, r3, #256 ; 0x100 + 80026d6: 2b00 cmp r3, #0 + 80026d8: d118 bne.n 800270c { /* Enable write access to Backup domain */ PWR->CR1 |= PWR_CR1_DBP; - 8002656: 4b83 ldr r3, [pc, #524] ; (8002864 ) - 8002658: 681b ldr r3, [r3, #0] - 800265a: 4a82 ldr r2, [pc, #520] ; (8002864 ) - 800265c: f443 7380 orr.w r3, r3, #256 ; 0x100 - 8002660: 6013 str r3, [r2, #0] + 80026da: 4b83 ldr r3, [pc, #524] ; (80028e8 ) + 80026dc: 681b ldr r3, [r3, #0] + 80026de: 4a82 ldr r2, [pc, #520] ; (80028e8 ) + 80026e0: f443 7380 orr.w r3, r3, #256 ; 0x100 + 80026e4: 6013 str r3, [r2, #0] /* Wait for Backup domain Write protection disable */ tickstart = HAL_GetTick(); - 8002662: f7ff fb73 bl 8001d4c - 8002666: 6138 str r0, [r7, #16] + 80026e6: f7ff fb73 bl 8001dd0 + 80026ea: 6138 str r0, [r7, #16] while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 8002668: e008 b.n 800267c + 80026ec: e008 b.n 8002700 { if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - 800266a: f7ff fb6f bl 8001d4c - 800266e: 4602 mov r2, r0 - 8002670: 693b ldr r3, [r7, #16] - 8002672: 1ad3 subs r3, r2, r3 - 8002674: 2b64 cmp r3, #100 ; 0x64 - 8002676: d901 bls.n 800267c + 80026ee: f7ff fb6f bl 8001dd0 + 80026f2: 4602 mov r2, r0 + 80026f4: 693b ldr r3, [r7, #16] + 80026f6: 1ad3 subs r3, r2, r3 + 80026f8: 2b64 cmp r3, #100 ; 0x64 + 80026fa: d901 bls.n 8002700 { return HAL_TIMEOUT; - 8002678: 2303 movs r3, #3 - 800267a: e0ed b.n 8002858 + 80026fc: 2303 movs r3, #3 + 80026fe: e0ed b.n 80028dc while(HAL_IS_BIT_CLR(PWR->CR1, PWR_CR1_DBP)) - 800267c: 4b79 ldr r3, [pc, #484] ; (8002864 ) - 800267e: 681b ldr r3, [r3, #0] - 8002680: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002684: 2b00 cmp r3, #0 - 8002686: d0f0 beq.n 800266a + 8002700: 4b79 ldr r3, [pc, #484] ; (80028e8 ) + 8002702: 681b ldr r3, [r3, #0] + 8002704: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002708: 2b00 cmp r3, #0 + 800270a: d0f0 beq.n 80026ee } } } /* Set the new LSE configuration -----------------------------------------*/ __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - 8002688: 687b ldr r3, [r7, #4] - 800268a: 689b ldr r3, [r3, #8] - 800268c: 2b01 cmp r3, #1 - 800268e: d106 bne.n 800269e - 8002690: 4b73 ldr r3, [pc, #460] ; (8002860 ) - 8002692: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002694: 4a72 ldr r2, [pc, #456] ; (8002860 ) - 8002696: f043 0301 orr.w r3, r3, #1 - 800269a: 6713 str r3, [r2, #112] ; 0x70 - 800269c: e02d b.n 80026fa - 800269e: 687b ldr r3, [r7, #4] - 80026a0: 689b ldr r3, [r3, #8] - 80026a2: 2b00 cmp r3, #0 - 80026a4: d10c bne.n 80026c0 - 80026a6: 4b6e ldr r3, [pc, #440] ; (8002860 ) - 80026a8: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026aa: 4a6d ldr r2, [pc, #436] ; (8002860 ) - 80026ac: f023 0301 bic.w r3, r3, #1 - 80026b0: 6713 str r3, [r2, #112] ; 0x70 - 80026b2: 4b6b ldr r3, [pc, #428] ; (8002860 ) - 80026b4: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026b6: 4a6a ldr r2, [pc, #424] ; (8002860 ) - 80026b8: f023 0304 bic.w r3, r3, #4 - 80026bc: 6713 str r3, [r2, #112] ; 0x70 - 80026be: e01c b.n 80026fa - 80026c0: 687b ldr r3, [r7, #4] - 80026c2: 689b ldr r3, [r3, #8] - 80026c4: 2b05 cmp r3, #5 - 80026c6: d10c bne.n 80026e2 - 80026c8: 4b65 ldr r3, [pc, #404] ; (8002860 ) - 80026ca: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026cc: 4a64 ldr r2, [pc, #400] ; (8002860 ) - 80026ce: f043 0304 orr.w r3, r3, #4 - 80026d2: 6713 str r3, [r2, #112] ; 0x70 - 80026d4: 4b62 ldr r3, [pc, #392] ; (8002860 ) - 80026d6: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026d8: 4a61 ldr r2, [pc, #388] ; (8002860 ) - 80026da: f043 0301 orr.w r3, r3, #1 - 80026de: 6713 str r3, [r2, #112] ; 0x70 - 80026e0: e00b b.n 80026fa - 80026e2: 4b5f ldr r3, [pc, #380] ; (8002860 ) - 80026e4: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026e6: 4a5e ldr r2, [pc, #376] ; (8002860 ) - 80026e8: f023 0301 bic.w r3, r3, #1 - 80026ec: 6713 str r3, [r2, #112] ; 0x70 - 80026ee: 4b5c ldr r3, [pc, #368] ; (8002860 ) - 80026f0: 6f1b ldr r3, [r3, #112] ; 0x70 - 80026f2: 4a5b ldr r2, [pc, #364] ; (8002860 ) - 80026f4: f023 0304 bic.w r3, r3, #4 - 80026f8: 6713 str r3, [r2, #112] ; 0x70 + 800270c: 687b ldr r3, [r7, #4] + 800270e: 689b ldr r3, [r3, #8] + 8002710: 2b01 cmp r3, #1 + 8002712: d106 bne.n 8002722 + 8002714: 4b73 ldr r3, [pc, #460] ; (80028e4 ) + 8002716: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002718: 4a72 ldr r2, [pc, #456] ; (80028e4 ) + 800271a: f043 0301 orr.w r3, r3, #1 + 800271e: 6713 str r3, [r2, #112] ; 0x70 + 8002720: e02d b.n 800277e + 8002722: 687b ldr r3, [r7, #4] + 8002724: 689b ldr r3, [r3, #8] + 8002726: 2b00 cmp r3, #0 + 8002728: d10c bne.n 8002744 + 800272a: 4b6e ldr r3, [pc, #440] ; (80028e4 ) + 800272c: 6f1b ldr r3, [r3, #112] ; 0x70 + 800272e: 4a6d ldr r2, [pc, #436] ; (80028e4 ) + 8002730: f023 0301 bic.w r3, r3, #1 + 8002734: 6713 str r3, [r2, #112] ; 0x70 + 8002736: 4b6b ldr r3, [pc, #428] ; (80028e4 ) + 8002738: 6f1b ldr r3, [r3, #112] ; 0x70 + 800273a: 4a6a ldr r2, [pc, #424] ; (80028e4 ) + 800273c: f023 0304 bic.w r3, r3, #4 + 8002740: 6713 str r3, [r2, #112] ; 0x70 + 8002742: e01c b.n 800277e + 8002744: 687b ldr r3, [r7, #4] + 8002746: 689b ldr r3, [r3, #8] + 8002748: 2b05 cmp r3, #5 + 800274a: d10c bne.n 8002766 + 800274c: 4b65 ldr r3, [pc, #404] ; (80028e4 ) + 800274e: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002750: 4a64 ldr r2, [pc, #400] ; (80028e4 ) + 8002752: f043 0304 orr.w r3, r3, #4 + 8002756: 6713 str r3, [r2, #112] ; 0x70 + 8002758: 4b62 ldr r3, [pc, #392] ; (80028e4 ) + 800275a: 6f1b ldr r3, [r3, #112] ; 0x70 + 800275c: 4a61 ldr r2, [pc, #388] ; (80028e4 ) + 800275e: f043 0301 orr.w r3, r3, #1 + 8002762: 6713 str r3, [r2, #112] ; 0x70 + 8002764: e00b b.n 800277e + 8002766: 4b5f ldr r3, [pc, #380] ; (80028e4 ) + 8002768: 6f1b ldr r3, [r3, #112] ; 0x70 + 800276a: 4a5e ldr r2, [pc, #376] ; (80028e4 ) + 800276c: f023 0301 bic.w r3, r3, #1 + 8002770: 6713 str r3, [r2, #112] ; 0x70 + 8002772: 4b5c ldr r3, [pc, #368] ; (80028e4 ) + 8002774: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002776: 4a5b ldr r2, [pc, #364] ; (80028e4 ) + 8002778: f023 0304 bic.w r3, r3, #4 + 800277c: 6713 str r3, [r2, #112] ; 0x70 /* Check the LSE State */ if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - 80026fa: 687b ldr r3, [r7, #4] - 80026fc: 689b ldr r3, [r3, #8] - 80026fe: 2b00 cmp r3, #0 - 8002700: d015 beq.n 800272e + 800277e: 687b ldr r3, [r7, #4] + 8002780: 689b ldr r3, [r3, #8] + 8002782: 2b00 cmp r3, #0 + 8002784: d015 beq.n 80027b2 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002702: f7ff fb23 bl 8001d4c - 8002706: 6138 str r0, [r7, #16] + 8002786: f7ff fb23 bl 8001dd0 + 800278a: 6138 str r0, [r7, #16] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002708: e00a b.n 8002720 + 800278c: e00a b.n 80027a4 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 800270a: f7ff fb1f bl 8001d4c - 800270e: 4602 mov r2, r0 - 8002710: 693b ldr r3, [r7, #16] - 8002712: 1ad3 subs r3, r2, r3 - 8002714: f241 3288 movw r2, #5000 ; 0x1388 - 8002718: 4293 cmp r3, r2 - 800271a: d901 bls.n 8002720 + 800278e: f7ff fb1f bl 8001dd0 + 8002792: 4602 mov r2, r0 + 8002794: 693b ldr r3, [r7, #16] + 8002796: 1ad3 subs r3, r2, r3 + 8002798: f241 3288 movw r2, #5000 ; 0x1388 + 800279c: 4293 cmp r3, r2 + 800279e: d901 bls.n 80027a4 { return HAL_TIMEOUT; - 800271c: 2303 movs r3, #3 - 800271e: e09b b.n 8002858 + 80027a0: 2303 movs r3, #3 + 80027a2: e09b b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002720: 4b4f ldr r3, [pc, #316] ; (8002860 ) - 8002722: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002724: f003 0302 and.w r3, r3, #2 - 8002728: 2b00 cmp r3, #0 - 800272a: d0ee beq.n 800270a - 800272c: e014 b.n 8002758 + 80027a4: 4b4f ldr r3, [pc, #316] ; (80028e4 ) + 80027a6: 6f1b ldr r3, [r3, #112] ; 0x70 + 80027a8: f003 0302 and.w r3, r3, #2 + 80027ac: 2b00 cmp r3, #0 + 80027ae: d0ee beq.n 800278e + 80027b0: e014 b.n 80027dc } } else { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800272e: f7ff fb0d bl 8001d4c - 8002732: 6138 str r0, [r7, #16] + 80027b2: f7ff fb0d bl 8001dd0 + 80027b6: 6138 str r0, [r7, #16] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - 8002734: e00a b.n 800274c + 80027b8: e00a b.n 80027d0 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 8002736: f7ff fb09 bl 8001d4c - 800273a: 4602 mov r2, r0 - 800273c: 693b ldr r3, [r7, #16] - 800273e: 1ad3 subs r3, r2, r3 - 8002740: f241 3288 movw r2, #5000 ; 0x1388 - 8002744: 4293 cmp r3, r2 - 8002746: d901 bls.n 800274c + 80027ba: f7ff fb09 bl 8001dd0 + 80027be: 4602 mov r2, r0 + 80027c0: 693b ldr r3, [r7, #16] + 80027c2: 1ad3 subs r3, r2, r3 + 80027c4: f241 3288 movw r2, #5000 ; 0x1388 + 80027c8: 4293 cmp r3, r2 + 80027ca: d901 bls.n 80027d0 { return HAL_TIMEOUT; - 8002748: 2303 movs r3, #3 - 800274a: e085 b.n 8002858 + 80027cc: 2303 movs r3, #3 + 80027ce: e085 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - 800274c: 4b44 ldr r3, [pc, #272] ; (8002860 ) - 800274e: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002750: f003 0302 and.w r3, r3, #2 - 8002754: 2b00 cmp r3, #0 - 8002756: d1ee bne.n 8002736 + 80027d0: 4b44 ldr r3, [pc, #272] ; (80028e4 ) + 80027d2: 6f1b ldr r3, [r3, #112] ; 0x70 + 80027d4: f003 0302 and.w r3, r3, #2 + 80027d8: 2b00 cmp r3, #0 + 80027da: d1ee bne.n 80027ba } } } /* Restore clock configuration if changed */ if(pwrclkchanged == SET) - 8002758: 7dfb ldrb r3, [r7, #23] - 800275a: 2b01 cmp r3, #1 - 800275c: d105 bne.n 800276a + 80027dc: 7dfb ldrb r3, [r7, #23] + 80027de: 2b01 cmp r3, #1 + 80027e0: d105 bne.n 80027ee { __HAL_RCC_PWR_CLK_DISABLE(); - 800275e: 4b40 ldr r3, [pc, #256] ; (8002860 ) - 8002760: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002762: 4a3f ldr r2, [pc, #252] ; (8002860 ) - 8002764: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 - 8002768: 6413 str r3, [r2, #64] ; 0x40 + 80027e2: 4b40 ldr r3, [pc, #256] ; (80028e4 ) + 80027e4: 6c1b ldr r3, [r3, #64] ; 0x40 + 80027e6: 4a3f ldr r2, [pc, #252] ; (80028e4 ) + 80027e8: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 80027ec: 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) - 800276a: 687b ldr r3, [r7, #4] - 800276c: 699b ldr r3, [r3, #24] - 800276e: 2b00 cmp r3, #0 - 8002770: d071 beq.n 8002856 + 80027ee: 687b ldr r3, [r7, #4] + 80027f0: 699b ldr r3, [r3, #24] + 80027f2: 2b00 cmp r3, #0 + 80027f4: d071 beq.n 80028da { /* Check if the PLL is used as system clock or not */ if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK) - 8002772: 4b3b ldr r3, [pc, #236] ; (8002860 ) - 8002774: 689b ldr r3, [r3, #8] - 8002776: f003 030c and.w r3, r3, #12 - 800277a: 2b08 cmp r3, #8 - 800277c: d069 beq.n 8002852 + 80027f6: 4b3b ldr r3, [pc, #236] ; (80028e4 ) + 80027f8: 689b ldr r3, [r3, #8] + 80027fa: f003 030c and.w r3, r3, #12 + 80027fe: 2b08 cmp r3, #8 + 8002800: d069 beq.n 80028d6 { if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - 800277e: 687b ldr r3, [r7, #4] - 8002780: 699b ldr r3, [r3, #24] - 8002782: 2b02 cmp r3, #2 - 8002784: d14b bne.n 800281e + 8002802: 687b ldr r3, [r7, #4] + 8002804: 699b ldr r3, [r3, #24] + 8002806: 2b02 cmp r3, #2 + 8002808: d14b bne.n 80028a2 #if defined (RCC_PLLCFGR_PLLR) assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); #endif /* Disable the main PLL. */ __HAL_RCC_PLL_DISABLE(); - 8002786: 4b36 ldr r3, [pc, #216] ; (8002860 ) - 8002788: 681b ldr r3, [r3, #0] - 800278a: 4a35 ldr r2, [pc, #212] ; (8002860 ) - 800278c: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 8002790: 6013 str r3, [r2, #0] + 800280a: 4b36 ldr r3, [pc, #216] ; (80028e4 ) + 800280c: 681b ldr r3, [r3, #0] + 800280e: 4a35 ldr r2, [pc, #212] ; (80028e4 ) + 8002810: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 8002814: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002792: f7ff fadb bl 8001d4c - 8002796: 6138 str r0, [r7, #16] + 8002816: f7ff fadb bl 8001dd0 + 800281a: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 8002798: e008 b.n 80027ac + 800281c: e008 b.n 8002830 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 800279a: f7ff fad7 bl 8001d4c - 800279e: 4602 mov r2, r0 - 80027a0: 693b ldr r3, [r7, #16] - 80027a2: 1ad3 subs r3, r2, r3 - 80027a4: 2b02 cmp r3, #2 - 80027a6: d901 bls.n 80027ac + 800281e: f7ff fad7 bl 8001dd0 + 8002822: 4602 mov r2, r0 + 8002824: 693b ldr r3, [r7, #16] + 8002826: 1ad3 subs r3, r2, r3 + 8002828: 2b02 cmp r3, #2 + 800282a: d901 bls.n 8002830 { return HAL_TIMEOUT; - 80027a8: 2303 movs r3, #3 - 80027aa: e055 b.n 8002858 + 800282c: 2303 movs r3, #3 + 800282e: e055 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 80027ac: 4b2c ldr r3, [pc, #176] ; (8002860 ) - 80027ae: 681b ldr r3, [r3, #0] - 80027b0: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 80027b4: 2b00 cmp r3, #0 - 80027b6: d1f0 bne.n 800279a + 8002830: 4b2c ldr r3, [pc, #176] ; (80028e4 ) + 8002832: 681b ldr r3, [r3, #0] + 8002834: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 8002838: 2b00 cmp r3, #0 + 800283a: d1f0 bne.n 800281e } } /* Configure the main PLL clock source, multiplication and division factors. */ #if defined (RCC_PLLCFGR_PLLR) __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource, - 80027b8: 687b ldr r3, [r7, #4] - 80027ba: 69da ldr r2, [r3, #28] - 80027bc: 687b ldr r3, [r7, #4] - 80027be: 6a1b ldr r3, [r3, #32] - 80027c0: 431a orrs r2, r3 - 80027c2: 687b ldr r3, [r7, #4] - 80027c4: 6a5b ldr r3, [r3, #36] ; 0x24 - 80027c6: 019b lsls r3, r3, #6 - 80027c8: 431a orrs r2, r3 - 80027ca: 687b ldr r3, [r7, #4] - 80027cc: 6a9b ldr r3, [r3, #40] ; 0x28 - 80027ce: 085b lsrs r3, r3, #1 - 80027d0: 3b01 subs r3, #1 - 80027d2: 041b lsls r3, r3, #16 - 80027d4: 431a orrs r2, r3 - 80027d6: 687b ldr r3, [r7, #4] - 80027d8: 6adb ldr r3, [r3, #44] ; 0x2c - 80027da: 061b lsls r3, r3, #24 - 80027dc: 431a orrs r2, r3 - 80027de: 687b ldr r3, [r7, #4] - 80027e0: 6b1b ldr r3, [r3, #48] ; 0x30 - 80027e2: 071b lsls r3, r3, #28 - 80027e4: 491e ldr r1, [pc, #120] ; (8002860 ) - 80027e6: 4313 orrs r3, r2 - 80027e8: 604b str r3, [r1, #4] + 800283c: 687b ldr r3, [r7, #4] + 800283e: 69da ldr r2, [r3, #28] + 8002840: 687b ldr r3, [r7, #4] + 8002842: 6a1b ldr r3, [r3, #32] + 8002844: 431a orrs r2, r3 + 8002846: 687b ldr r3, [r7, #4] + 8002848: 6a5b ldr r3, [r3, #36] ; 0x24 + 800284a: 019b lsls r3, r3, #6 + 800284c: 431a orrs r2, r3 + 800284e: 687b ldr r3, [r7, #4] + 8002850: 6a9b ldr r3, [r3, #40] ; 0x28 + 8002852: 085b lsrs r3, r3, #1 + 8002854: 3b01 subs r3, #1 + 8002856: 041b lsls r3, r3, #16 + 8002858: 431a orrs r2, r3 + 800285a: 687b ldr r3, [r7, #4] + 800285c: 6adb ldr r3, [r3, #44] ; 0x2c + 800285e: 061b lsls r3, r3, #24 + 8002860: 431a orrs r2, r3 + 8002862: 687b ldr r3, [r7, #4] + 8002864: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002866: 071b lsls r3, r3, #28 + 8002868: 491e ldr r1, [pc, #120] ; (80028e4 ) + 800286a: 4313 orrs r3, r2 + 800286c: 604b str r3, [r1, #4] RCC_OscInitStruct->PLL.PLLP, RCC_OscInitStruct->PLL.PLLQ); #endif /* Enable the main PLL. */ __HAL_RCC_PLL_ENABLE(); - 80027ea: 4b1d ldr r3, [pc, #116] ; (8002860 ) - 80027ec: 681b ldr r3, [r3, #0] - 80027ee: 4a1c ldr r2, [pc, #112] ; (8002860 ) - 80027f0: f043 7380 orr.w r3, r3, #16777216 ; 0x1000000 - 80027f4: 6013 str r3, [r2, #0] + 800286e: 4b1d ldr r3, [pc, #116] ; (80028e4 ) + 8002870: 681b ldr r3, [r3, #0] + 8002872: 4a1c ldr r2, [pc, #112] ; (80028e4 ) + 8002874: f043 7380 orr.w r3, r3, #16777216 ; 0x1000000 + 8002878: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80027f6: f7ff faa9 bl 8001d4c - 80027fa: 6138 str r0, [r7, #16] + 800287a: f7ff faa9 bl 8001dd0 + 800287e: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 80027fc: e008 b.n 8002810 + 8002880: e008 b.n 8002894 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 80027fe: f7ff faa5 bl 8001d4c - 8002802: 4602 mov r2, r0 - 8002804: 693b ldr r3, [r7, #16] - 8002806: 1ad3 subs r3, r2, r3 - 8002808: 2b02 cmp r3, #2 - 800280a: d901 bls.n 8002810 + 8002882: f7ff faa5 bl 8001dd0 + 8002886: 4602 mov r2, r0 + 8002888: 693b ldr r3, [r7, #16] + 800288a: 1ad3 subs r3, r2, r3 + 800288c: 2b02 cmp r3, #2 + 800288e: d901 bls.n 8002894 { return HAL_TIMEOUT; - 800280c: 2303 movs r3, #3 - 800280e: e023 b.n 8002858 + 8002890: 2303 movs r3, #3 + 8002892: e023 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 8002810: 4b13 ldr r3, [pc, #76] ; (8002860 ) - 8002812: 681b ldr r3, [r3, #0] - 8002814: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8002818: 2b00 cmp r3, #0 - 800281a: d0f0 beq.n 80027fe - 800281c: e01b b.n 8002856 + 8002894: 4b13 ldr r3, [pc, #76] ; (80028e4 ) + 8002896: 681b ldr r3, [r3, #0] + 8002898: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 800289c: 2b00 cmp r3, #0 + 800289e: d0f0 beq.n 8002882 + 80028a0: e01b b.n 80028da } } else { /* Disable the main PLL. */ __HAL_RCC_PLL_DISABLE(); - 800281e: 4b10 ldr r3, [pc, #64] ; (8002860 ) - 8002820: 681b ldr r3, [r3, #0] - 8002822: 4a0f ldr r2, [pc, #60] ; (8002860 ) - 8002824: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 8002828: 6013 str r3, [r2, #0] + 80028a2: 4b10 ldr r3, [pc, #64] ; (80028e4 ) + 80028a4: 681b ldr r3, [r3, #0] + 80028a6: 4a0f ldr r2, [pc, #60] ; (80028e4 ) + 80028a8: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 80028ac: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800282a: f7ff fa8f bl 8001d4c - 800282e: 6138 str r0, [r7, #16] + 80028ae: f7ff fa8f bl 8001dd0 + 80028b2: 6138 str r0, [r7, #16] /* Wait till PLL is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 8002830: e008 b.n 8002844 + 80028b4: e008 b.n 80028c8 { if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - 8002832: f7ff fa8b bl 8001d4c - 8002836: 4602 mov r2, r0 - 8002838: 693b ldr r3, [r7, #16] - 800283a: 1ad3 subs r3, r2, r3 - 800283c: 2b02 cmp r3, #2 - 800283e: d901 bls.n 8002844 + 80028b6: f7ff fa8b bl 8001dd0 + 80028ba: 4602 mov r2, r0 + 80028bc: 693b ldr r3, [r7, #16] + 80028be: 1ad3 subs r3, r2, r3 + 80028c0: 2b02 cmp r3, #2 + 80028c2: d901 bls.n 80028c8 { return HAL_TIMEOUT; - 8002840: 2303 movs r3, #3 - 8002842: e009 b.n 8002858 + 80028c4: 2303 movs r3, #3 + 80028c6: e009 b.n 80028dc while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - 8002844: 4b06 ldr r3, [pc, #24] ; (8002860 ) - 8002846: 681b ldr r3, [r3, #0] - 8002848: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 800284c: 2b00 cmp r3, #0 - 800284e: d1f0 bne.n 8002832 - 8002850: e001 b.n 8002856 + 80028c8: 4b06 ldr r3, [pc, #24] ; (80028e4 ) + 80028ca: 681b ldr r3, [r3, #0] + 80028cc: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 80028d0: 2b00 cmp r3, #0 + 80028d2: d1f0 bne.n 80028b6 + 80028d4: e001 b.n 80028da } } } else { return HAL_ERROR; - 8002852: 2301 movs r3, #1 - 8002854: e000 b.n 8002858 + 80028d6: 2301 movs r3, #1 + 80028d8: e000 b.n 80028dc } } return HAL_OK; - 8002856: 2300 movs r3, #0 + 80028da: 2300 movs r3, #0 } - 8002858: 4618 mov r0, r3 - 800285a: 3718 adds r7, #24 - 800285c: 46bd mov sp, r7 - 800285e: bd80 pop {r7, pc} - 8002860: 40023800 .word 0x40023800 - 8002864: 40007000 .word 0x40007000 - -08002868 : + 80028dc: 4618 mov r0, r3 + 80028de: 3718 adds r7, #24 + 80028e0: 46bd mov sp, r7 + 80028e2: bd80 pop {r7, pc} + 80028e4: 40023800 .word 0x40023800 + 80028e8: 40007000 .word 0x40007000 + +080028ec : * 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) { - 8002868: b580 push {r7, lr} - 800286a: b084 sub sp, #16 - 800286c: af00 add r7, sp, #0 - 800286e: 6078 str r0, [r7, #4] - 8002870: 6039 str r1, [r7, #0] + 80028ec: b580 push {r7, lr} + 80028ee: b084 sub sp, #16 + 80028f0: af00 add r7, sp, #0 + 80028f2: 6078 str r0, [r7, #4] + 80028f4: 6039 str r1, [r7, #0] uint32_t tickstart = 0; - 8002872: 2300 movs r3, #0 - 8002874: 60fb str r3, [r7, #12] + 80028f6: 2300 movs r3, #0 + 80028f8: 60fb str r3, [r7, #12] /* Check Null pointer */ if(RCC_ClkInitStruct == NULL) - 8002876: 687b ldr r3, [r7, #4] - 8002878: 2b00 cmp r3, #0 - 800287a: d101 bne.n 8002880 + 80028fa: 687b ldr r3, [r7, #4] + 80028fc: 2b00 cmp r3, #0 + 80028fe: d101 bne.n 8002904 { return HAL_ERROR; - 800287c: 2301 movs r3, #1 - 800287e: e0ce b.n 8002a1e + 8002900: 2301 movs r3, #1 + 8002902: e0ce b.n 8002aa2 /* 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()) - 8002880: 4b69 ldr r3, [pc, #420] ; (8002a28 ) - 8002882: 681b ldr r3, [r3, #0] - 8002884: f003 030f and.w r3, r3, #15 - 8002888: 683a ldr r2, [r7, #0] - 800288a: 429a cmp r2, r3 - 800288c: d910 bls.n 80028b0 + 8002904: 4b69 ldr r3, [pc, #420] ; (8002aac ) + 8002906: 681b ldr r3, [r3, #0] + 8002908: f003 030f and.w r3, r3, #15 + 800290c: 683a ldr r2, [r7, #0] + 800290e: 429a cmp r2, r3 + 8002910: d910 bls.n 8002934 { /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ __HAL_FLASH_SET_LATENCY(FLatency); - 800288e: 4b66 ldr r3, [pc, #408] ; (8002a28 ) - 8002890: 681b ldr r3, [r3, #0] - 8002892: f023 020f bic.w r2, r3, #15 - 8002896: 4964 ldr r1, [pc, #400] ; (8002a28 ) - 8002898: 683b ldr r3, [r7, #0] - 800289a: 4313 orrs r3, r2 - 800289c: 600b str r3, [r1, #0] + 8002912: 4b66 ldr r3, [pc, #408] ; (8002aac ) + 8002914: 681b ldr r3, [r3, #0] + 8002916: f023 020f bic.w r2, r3, #15 + 800291a: 4964 ldr r1, [pc, #400] ; (8002aac ) + 800291c: 683b ldr r3, [r7, #0] + 800291e: 4313 orrs r3, r2 + 8002920: 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) - 800289e: 4b62 ldr r3, [pc, #392] ; (8002a28 ) - 80028a0: 681b ldr r3, [r3, #0] - 80028a2: f003 030f and.w r3, r3, #15 - 80028a6: 683a ldr r2, [r7, #0] - 80028a8: 429a cmp r2, r3 - 80028aa: d001 beq.n 80028b0 + 8002922: 4b62 ldr r3, [pc, #392] ; (8002aac ) + 8002924: 681b ldr r3, [r3, #0] + 8002926: f003 030f and.w r3, r3, #15 + 800292a: 683a ldr r2, [r7, #0] + 800292c: 429a cmp r2, r3 + 800292e: d001 beq.n 8002934 { return HAL_ERROR; - 80028ac: 2301 movs r3, #1 - 80028ae: e0b6 b.n 8002a1e + 8002930: 2301 movs r3, #1 + 8002932: e0b6 b.n 8002aa2 } } /*-------------------------- HCLK Configuration --------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) - 80028b0: 687b ldr r3, [r7, #4] - 80028b2: 681b ldr r3, [r3, #0] - 80028b4: f003 0302 and.w r3, r3, #2 - 80028b8: 2b00 cmp r3, #0 - 80028ba: d020 beq.n 80028fe + 8002934: 687b ldr r3, [r7, #4] + 8002936: 681b ldr r3, [r3, #0] + 8002938: f003 0302 and.w r3, r3, #2 + 800293c: 2b00 cmp r3, #0 + 800293e: d020 beq.n 8002982 { /* 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) - 80028bc: 687b ldr r3, [r7, #4] - 80028be: 681b ldr r3, [r3, #0] - 80028c0: f003 0304 and.w r3, r3, #4 - 80028c4: 2b00 cmp r3, #0 - 80028c6: d005 beq.n 80028d4 + 8002940: 687b ldr r3, [r7, #4] + 8002942: 681b ldr r3, [r3, #0] + 8002944: f003 0304 and.w r3, r3, #4 + 8002948: 2b00 cmp r3, #0 + 800294a: d005 beq.n 8002958 { MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); - 80028c8: 4b58 ldr r3, [pc, #352] ; (8002a2c ) - 80028ca: 689b ldr r3, [r3, #8] - 80028cc: 4a57 ldr r2, [pc, #348] ; (8002a2c ) - 80028ce: f443 53e0 orr.w r3, r3, #7168 ; 0x1c00 - 80028d2: 6093 str r3, [r2, #8] + 800294c: 4b58 ldr r3, [pc, #352] ; (8002ab0 ) + 800294e: 689b ldr r3, [r3, #8] + 8002950: 4a57 ldr r2, [pc, #348] ; (8002ab0 ) + 8002952: f443 53e0 orr.w r3, r3, #7168 ; 0x1c00 + 8002956: 6093 str r3, [r2, #8] } if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - 80028d4: 687b ldr r3, [r7, #4] - 80028d6: 681b ldr r3, [r3, #0] - 80028d8: f003 0308 and.w r3, r3, #8 - 80028dc: 2b00 cmp r3, #0 - 80028de: d005 beq.n 80028ec + 8002958: 687b ldr r3, [r7, #4] + 800295a: 681b ldr r3, [r3, #0] + 800295c: f003 0308 and.w r3, r3, #8 + 8002960: 2b00 cmp r3, #0 + 8002962: d005 beq.n 8002970 { MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); - 80028e0: 4b52 ldr r3, [pc, #328] ; (8002a2c ) - 80028e2: 689b ldr r3, [r3, #8] - 80028e4: 4a51 ldr r2, [pc, #324] ; (8002a2c ) - 80028e6: f443 4360 orr.w r3, r3, #57344 ; 0xe000 - 80028ea: 6093 str r3, [r2, #8] + 8002964: 4b52 ldr r3, [pc, #328] ; (8002ab0 ) + 8002966: 689b ldr r3, [r3, #8] + 8002968: 4a51 ldr r2, [pc, #324] ; (8002ab0 ) + 800296a: f443 4360 orr.w r3, r3, #57344 ; 0xe000 + 800296e: 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); - 80028ec: 4b4f ldr r3, [pc, #316] ; (8002a2c ) - 80028ee: 689b ldr r3, [r3, #8] - 80028f0: f023 02f0 bic.w r2, r3, #240 ; 0xf0 - 80028f4: 687b ldr r3, [r7, #4] - 80028f6: 689b ldr r3, [r3, #8] - 80028f8: 494c ldr r1, [pc, #304] ; (8002a2c ) - 80028fa: 4313 orrs r3, r2 - 80028fc: 608b str r3, [r1, #8] + 8002970: 4b4f ldr r3, [pc, #316] ; (8002ab0 ) + 8002972: 689b ldr r3, [r3, #8] + 8002974: f023 02f0 bic.w r2, r3, #240 ; 0xf0 + 8002978: 687b ldr r3, [r7, #4] + 800297a: 689b ldr r3, [r3, #8] + 800297c: 494c ldr r1, [pc, #304] ; (8002ab0 ) + 800297e: 4313 orrs r3, r2 + 8002980: 608b str r3, [r1, #8] } /*------------------------- SYSCLK Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) - 80028fe: 687b ldr r3, [r7, #4] - 8002900: 681b ldr r3, [r3, #0] - 8002902: f003 0301 and.w r3, r3, #1 - 8002906: 2b00 cmp r3, #0 - 8002908: d040 beq.n 800298c + 8002982: 687b ldr r3, [r7, #4] + 8002984: 681b ldr r3, [r3, #0] + 8002986: f003 0301 and.w r3, r3, #1 + 800298a: 2b00 cmp r3, #0 + 800298c: d040 beq.n 8002a10 { assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); /* HSE is selected as System Clock Source */ if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) - 800290a: 687b ldr r3, [r7, #4] - 800290c: 685b ldr r3, [r3, #4] - 800290e: 2b01 cmp r3, #1 - 8002910: d107 bne.n 8002922 + 800298e: 687b ldr r3, [r7, #4] + 8002990: 685b ldr r3, [r3, #4] + 8002992: 2b01 cmp r3, #1 + 8002994: d107 bne.n 80029a6 { /* Check the HSE ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - 8002912: 4b46 ldr r3, [pc, #280] ; (8002a2c ) - 8002914: 681b ldr r3, [r3, #0] - 8002916: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 800291a: 2b00 cmp r3, #0 - 800291c: d115 bne.n 800294a + 8002996: 4b46 ldr r3, [pc, #280] ; (8002ab0 ) + 8002998: 681b ldr r3, [r3, #0] + 800299a: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 800299e: 2b00 cmp r3, #0 + 80029a0: d115 bne.n 80029ce { return HAL_ERROR; - 800291e: 2301 movs r3, #1 - 8002920: e07d b.n 8002a1e + 80029a2: 2301 movs r3, #1 + 80029a4: e07d b.n 8002aa2 } } /* PLL is selected as System Clock Source */ else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) - 8002922: 687b ldr r3, [r7, #4] - 8002924: 685b ldr r3, [r3, #4] - 8002926: 2b02 cmp r3, #2 - 8002928: d107 bne.n 800293a + 80029a6: 687b ldr r3, [r7, #4] + 80029a8: 685b ldr r3, [r3, #4] + 80029aa: 2b02 cmp r3, #2 + 80029ac: d107 bne.n 80029be { /* Check the PLL ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - 800292a: 4b40 ldr r3, [pc, #256] ; (8002a2c ) - 800292c: 681b ldr r3, [r3, #0] - 800292e: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8002932: 2b00 cmp r3, #0 - 8002934: d109 bne.n 800294a + 80029ae: 4b40 ldr r3, [pc, #256] ; (8002ab0 ) + 80029b0: 681b ldr r3, [r3, #0] + 80029b2: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 80029b6: 2b00 cmp r3, #0 + 80029b8: d109 bne.n 80029ce { return HAL_ERROR; - 8002936: 2301 movs r3, #1 - 8002938: e071 b.n 8002a1e + 80029ba: 2301 movs r3, #1 + 80029bc: e071 b.n 8002aa2 } /* HSI is selected as System Clock Source */ else { /* Check the HSI ready flag */ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - 800293a: 4b3c ldr r3, [pc, #240] ; (8002a2c ) - 800293c: 681b ldr r3, [r3, #0] - 800293e: f003 0302 and.w r3, r3, #2 - 8002942: 2b00 cmp r3, #0 - 8002944: d101 bne.n 800294a + 80029be: 4b3c ldr r3, [pc, #240] ; (8002ab0 ) + 80029c0: 681b ldr r3, [r3, #0] + 80029c2: f003 0302 and.w r3, r3, #2 + 80029c6: 2b00 cmp r3, #0 + 80029c8: d101 bne.n 80029ce { return HAL_ERROR; - 8002946: 2301 movs r3, #1 - 8002948: e069 b.n 8002a1e + 80029ca: 2301 movs r3, #1 + 80029cc: e069 b.n 8002aa2 } } __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); - 800294a: 4b38 ldr r3, [pc, #224] ; (8002a2c ) - 800294c: 689b ldr r3, [r3, #8] - 800294e: f023 0203 bic.w r2, r3, #3 - 8002952: 687b ldr r3, [r7, #4] - 8002954: 685b ldr r3, [r3, #4] - 8002956: 4935 ldr r1, [pc, #212] ; (8002a2c ) - 8002958: 4313 orrs r3, r2 - 800295a: 608b str r3, [r1, #8] + 80029ce: 4b38 ldr r3, [pc, #224] ; (8002ab0 ) + 80029d0: 689b ldr r3, [r3, #8] + 80029d2: f023 0203 bic.w r2, r3, #3 + 80029d6: 687b ldr r3, [r7, #4] + 80029d8: 685b ldr r3, [r3, #4] + 80029da: 4935 ldr r1, [pc, #212] ; (8002ab0 ) + 80029dc: 4313 orrs r3, r2 + 80029de: 608b str r3, [r1, #8] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 800295c: f7ff f9f6 bl 8001d4c - 8002960: 60f8 str r0, [r7, #12] + 80029e0: f7ff f9f6 bl 8001dd0 + 80029e4: 60f8 str r0, [r7, #12] while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - 8002962: e00a b.n 800297a + 80029e6: e00a b.n 80029fe { if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - 8002964: f7ff f9f2 bl 8001d4c - 8002968: 4602 mov r2, r0 - 800296a: 68fb ldr r3, [r7, #12] - 800296c: 1ad3 subs r3, r2, r3 - 800296e: f241 3288 movw r2, #5000 ; 0x1388 - 8002972: 4293 cmp r3, r2 - 8002974: d901 bls.n 800297a + 80029e8: f7ff f9f2 bl 8001dd0 + 80029ec: 4602 mov r2, r0 + 80029ee: 68fb ldr r3, [r7, #12] + 80029f0: 1ad3 subs r3, r2, r3 + 80029f2: f241 3288 movw r2, #5000 ; 0x1388 + 80029f6: 4293 cmp r3, r2 + 80029f8: d901 bls.n 80029fe { return HAL_TIMEOUT; - 8002976: 2303 movs r3, #3 - 8002978: e051 b.n 8002a1e + 80029fa: 2303 movs r3, #3 + 80029fc: e051 b.n 8002aa2 while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - 800297a: 4b2c ldr r3, [pc, #176] ; (8002a2c ) - 800297c: 689b ldr r3, [r3, #8] - 800297e: f003 020c and.w r2, r3, #12 - 8002982: 687b ldr r3, [r7, #4] - 8002984: 685b ldr r3, [r3, #4] - 8002986: 009b lsls r3, r3, #2 - 8002988: 429a cmp r2, r3 - 800298a: d1eb bne.n 8002964 + 80029fe: 4b2c ldr r3, [pc, #176] ; (8002ab0 ) + 8002a00: 689b ldr r3, [r3, #8] + 8002a02: f003 020c and.w r2, r3, #12 + 8002a06: 687b ldr r3, [r7, #4] + 8002a08: 685b ldr r3, [r3, #4] + 8002a0a: 009b lsls r3, r3, #2 + 8002a0c: 429a cmp r2, r3 + 8002a0e: d1eb bne.n 80029e8 } } } /* Decreasing the number of wait states because of lower CPU frequency */ if(FLatency < __HAL_FLASH_GET_LATENCY()) - 800298c: 4b26 ldr r3, [pc, #152] ; (8002a28 ) - 800298e: 681b ldr r3, [r3, #0] - 8002990: f003 030f and.w r3, r3, #15 - 8002994: 683a ldr r2, [r7, #0] - 8002996: 429a cmp r2, r3 - 8002998: d210 bcs.n 80029bc + 8002a10: 4b26 ldr r3, [pc, #152] ; (8002aac ) + 8002a12: 681b ldr r3, [r3, #0] + 8002a14: f003 030f and.w r3, r3, #15 + 8002a18: 683a ldr r2, [r7, #0] + 8002a1a: 429a cmp r2, r3 + 8002a1c: d210 bcs.n 8002a40 { /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ __HAL_FLASH_SET_LATENCY(FLatency); - 800299a: 4b23 ldr r3, [pc, #140] ; (8002a28 ) - 800299c: 681b ldr r3, [r3, #0] - 800299e: f023 020f bic.w r2, r3, #15 - 80029a2: 4921 ldr r1, [pc, #132] ; (8002a28 ) - 80029a4: 683b ldr r3, [r7, #0] - 80029a6: 4313 orrs r3, r2 - 80029a8: 600b str r3, [r1, #0] + 8002a1e: 4b23 ldr r3, [pc, #140] ; (8002aac ) + 8002a20: 681b ldr r3, [r3, #0] + 8002a22: f023 020f bic.w r2, r3, #15 + 8002a26: 4921 ldr r1, [pc, #132] ; (8002aac ) + 8002a28: 683b ldr r3, [r7, #0] + 8002a2a: 4313 orrs r3, r2 + 8002a2c: 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) - 80029aa: 4b1f ldr r3, [pc, #124] ; (8002a28 ) - 80029ac: 681b ldr r3, [r3, #0] - 80029ae: f003 030f and.w r3, r3, #15 - 80029b2: 683a ldr r2, [r7, #0] - 80029b4: 429a cmp r2, r3 - 80029b6: d001 beq.n 80029bc + 8002a2e: 4b1f ldr r3, [pc, #124] ; (8002aac ) + 8002a30: 681b ldr r3, [r3, #0] + 8002a32: f003 030f and.w r3, r3, #15 + 8002a36: 683a ldr r2, [r7, #0] + 8002a38: 429a cmp r2, r3 + 8002a3a: d001 beq.n 8002a40 { return HAL_ERROR; - 80029b8: 2301 movs r3, #1 - 80029ba: e030 b.n 8002a1e + 8002a3c: 2301 movs r3, #1 + 8002a3e: e030 b.n 8002aa2 } } /*-------------------------- PCLK1 Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - 80029bc: 687b ldr r3, [r7, #4] - 80029be: 681b ldr r3, [r3, #0] - 80029c0: f003 0304 and.w r3, r3, #4 - 80029c4: 2b00 cmp r3, #0 - 80029c6: d008 beq.n 80029da + 8002a40: 687b ldr r3, [r7, #4] + 8002a42: 681b ldr r3, [r3, #0] + 8002a44: f003 0304 and.w r3, r3, #4 + 8002a48: 2b00 cmp r3, #0 + 8002a4a: d008 beq.n 8002a5e { assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); - 80029c8: 4b18 ldr r3, [pc, #96] ; (8002a2c ) - 80029ca: 689b ldr r3, [r3, #8] - 80029cc: f423 52e0 bic.w r2, r3, #7168 ; 0x1c00 - 80029d0: 687b ldr r3, [r7, #4] - 80029d2: 68db ldr r3, [r3, #12] - 80029d4: 4915 ldr r1, [pc, #84] ; (8002a2c ) - 80029d6: 4313 orrs r3, r2 - 80029d8: 608b str r3, [r1, #8] + 8002a4c: 4b18 ldr r3, [pc, #96] ; (8002ab0 ) + 8002a4e: 689b ldr r3, [r3, #8] + 8002a50: f423 52e0 bic.w r2, r3, #7168 ; 0x1c00 + 8002a54: 687b ldr r3, [r7, #4] + 8002a56: 68db ldr r3, [r3, #12] + 8002a58: 4915 ldr r1, [pc, #84] ; (8002ab0 ) + 8002a5a: 4313 orrs r3, r2 + 8002a5c: 608b str r3, [r1, #8] } /*-------------------------- PCLK2 Configuration ---------------------------*/ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - 80029da: 687b ldr r3, [r7, #4] - 80029dc: 681b ldr r3, [r3, #0] - 80029de: f003 0308 and.w r3, r3, #8 - 80029e2: 2b00 cmp r3, #0 - 80029e4: d009 beq.n 80029fa + 8002a5e: 687b ldr r3, [r7, #4] + 8002a60: 681b ldr r3, [r3, #0] + 8002a62: f003 0308 and.w r3, r3, #8 + 8002a66: 2b00 cmp r3, #0 + 8002a68: d009 beq.n 8002a7e { assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3)); - 80029e6: 4b11 ldr r3, [pc, #68] ; (8002a2c ) - 80029e8: 689b ldr r3, [r3, #8] - 80029ea: f423 4260 bic.w r2, r3, #57344 ; 0xe000 - 80029ee: 687b ldr r3, [r7, #4] - 80029f0: 691b ldr r3, [r3, #16] - 80029f2: 00db lsls r3, r3, #3 - 80029f4: 490d ldr r1, [pc, #52] ; (8002a2c ) - 80029f6: 4313 orrs r3, r2 - 80029f8: 608b str r3, [r1, #8] + 8002a6a: 4b11 ldr r3, [pc, #68] ; (8002ab0 ) + 8002a6c: 689b ldr r3, [r3, #8] + 8002a6e: f423 4260 bic.w r2, r3, #57344 ; 0xe000 + 8002a72: 687b ldr r3, [r7, #4] + 8002a74: 691b ldr r3, [r3, #16] + 8002a76: 00db lsls r3, r3, #3 + 8002a78: 490d ldr r1, [pc, #52] ; (8002ab0 ) + 8002a7a: 4313 orrs r3, r2 + 8002a7c: 608b str r3, [r1, #8] } /* Update the SystemCoreClock global variable */ SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; - 80029fa: f000 f81d bl 8002a38 - 80029fe: 4601 mov r1, r0 - 8002a00: 4b0a ldr r3, [pc, #40] ; (8002a2c ) - 8002a02: 689b ldr r3, [r3, #8] - 8002a04: 091b lsrs r3, r3, #4 - 8002a06: f003 030f and.w r3, r3, #15 - 8002a0a: 4a09 ldr r2, [pc, #36] ; (8002a30 ) - 8002a0c: 5cd3 ldrb r3, [r2, r3] - 8002a0e: fa21 f303 lsr.w r3, r1, r3 - 8002a12: 4a08 ldr r2, [pc, #32] ; (8002a34 ) - 8002a14: 6013 str r3, [r2, #0] + 8002a7e: f000 f81d bl 8002abc + 8002a82: 4601 mov r1, r0 + 8002a84: 4b0a ldr r3, [pc, #40] ; (8002ab0 ) + 8002a86: 689b ldr r3, [r3, #8] + 8002a88: 091b lsrs r3, r3, #4 + 8002a8a: f003 030f and.w r3, r3, #15 + 8002a8e: 4a09 ldr r2, [pc, #36] ; (8002ab4 ) + 8002a90: 5cd3 ldrb r3, [r2, r3] + 8002a92: fa21 f303 lsr.w r3, r1, r3 + 8002a96: 4a08 ldr r2, [pc, #32] ; (8002ab8 ) + 8002a98: 6013 str r3, [r2, #0] /* Configure the source of time base considering new system clocks settings*/ HAL_InitTick (TICK_INT_PRIORITY); - 8002a16: 2000 movs r0, #0 - 8002a18: f7ff f954 bl 8001cc4 + 8002a9a: 2000 movs r0, #0 + 8002a9c: f7ff f954 bl 8001d48 return HAL_OK; - 8002a1c: 2300 movs r3, #0 + 8002aa0: 2300 movs r3, #0 } - 8002a1e: 4618 mov r0, r3 - 8002a20: 3710 adds r7, #16 - 8002a22: 46bd mov sp, r7 - 8002a24: bd80 pop {r7, pc} - 8002a26: bf00 nop - 8002a28: 40023c00 .word 0x40023c00 - 8002a2c: 40023800 .word 0x40023800 - 8002a30: 0800555c .word 0x0800555c - 8002a34: 20000004 .word 0x20000004 - -08002a38 : + 8002aa2: 4618 mov r0, r3 + 8002aa4: 3710 adds r7, #16 + 8002aa6: 46bd mov sp, r7 + 8002aa8: bd80 pop {r7, pc} + 8002aaa: bf00 nop + 8002aac: 40023c00 .word 0x40023c00 + 8002ab0: 40023800 .word 0x40023800 + 8002ab4: 080055e0 .word 0x080055e0 + 8002ab8: 20000004 .word 0x20000004 + +08002abc : * * * @retval SYSCLK frequency */ uint32_t HAL_RCC_GetSysClockFreq(void) { - 8002a38: b5f0 push {r4, r5, r6, r7, lr} - 8002a3a: b085 sub sp, #20 - 8002a3c: af00 add r7, sp, #0 + 8002abc: b5f0 push {r4, r5, r6, r7, lr} + 8002abe: b085 sub sp, #20 + 8002ac0: af00 add r7, sp, #0 uint32_t pllm = 0, pllvco = 0, pllp = 0; - 8002a3e: 2300 movs r3, #0 - 8002a40: 607b str r3, [r7, #4] - 8002a42: 2300 movs r3, #0 - 8002a44: 60fb str r3, [r7, #12] - 8002a46: 2300 movs r3, #0 - 8002a48: 603b str r3, [r7, #0] + 8002ac2: 2300 movs r3, #0 + 8002ac4: 607b str r3, [r7, #4] + 8002ac6: 2300 movs r3, #0 + 8002ac8: 60fb str r3, [r7, #12] + 8002aca: 2300 movs r3, #0 + 8002acc: 603b str r3, [r7, #0] uint32_t sysclockfreq = 0; - 8002a4a: 2300 movs r3, #0 - 8002a4c: 60bb str r3, [r7, #8] + 8002ace: 2300 movs r3, #0 + 8002ad0: 60bb str r3, [r7, #8] /* Get SYSCLK source -------------------------------------------------------*/ switch (RCC->CFGR & RCC_CFGR_SWS) - 8002a4e: 4b50 ldr r3, [pc, #320] ; (8002b90 ) - 8002a50: 689b ldr r3, [r3, #8] - 8002a52: f003 030c and.w r3, r3, #12 - 8002a56: 2b04 cmp r3, #4 - 8002a58: d007 beq.n 8002a6a - 8002a5a: 2b08 cmp r3, #8 - 8002a5c: d008 beq.n 8002a70 - 8002a5e: 2b00 cmp r3, #0 - 8002a60: f040 808d bne.w 8002b7e + 8002ad2: 4b50 ldr r3, [pc, #320] ; (8002c14 ) + 8002ad4: 689b ldr r3, [r3, #8] + 8002ad6: f003 030c and.w r3, r3, #12 + 8002ada: 2b04 cmp r3, #4 + 8002adc: d007 beq.n 8002aee + 8002ade: 2b08 cmp r3, #8 + 8002ae0: d008 beq.n 8002af4 + 8002ae2: 2b00 cmp r3, #0 + 8002ae4: f040 808d bne.w 8002c02 { case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */ { sysclockfreq = HSI_VALUE; - 8002a64: 4b4b ldr r3, [pc, #300] ; (8002b94 ) - 8002a66: 60bb str r3, [r7, #8] + 8002ae8: 4b4b ldr r3, [pc, #300] ; (8002c18 ) + 8002aea: 60bb str r3, [r7, #8] break; - 8002a68: e08c b.n 8002b84 + 8002aec: e08c b.n 8002c08 } case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock source */ { sysclockfreq = HSE_VALUE; - 8002a6a: 4b4b ldr r3, [pc, #300] ; (8002b98 ) - 8002a6c: 60bb str r3, [r7, #8] + 8002aee: 4b4b ldr r3, [pc, #300] ; (8002c1c ) + 8002af0: 60bb str r3, [r7, #8] break; - 8002a6e: e089 b.n 8002b84 + 8002af2: e089 b.n 8002c08 } 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; - 8002a70: 4b47 ldr r3, [pc, #284] ; (8002b90 ) - 8002a72: 685b ldr r3, [r3, #4] - 8002a74: f003 033f and.w r3, r3, #63 ; 0x3f - 8002a78: 607b str r3, [r7, #4] + 8002af4: 4b47 ldr r3, [pc, #284] ; (8002c14 ) + 8002af6: 685b ldr r3, [r3, #4] + 8002af8: f003 033f and.w r3, r3, #63 ; 0x3f + 8002afc: 607b str r3, [r7, #4] if (__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLCFGR_PLLSRC_HSI) - 8002a7a: 4b45 ldr r3, [pc, #276] ; (8002b90 ) - 8002a7c: 685b ldr r3, [r3, #4] - 8002a7e: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 8002a82: 2b00 cmp r3, #0 - 8002a84: d023 beq.n 8002ace + 8002afe: 4b45 ldr r3, [pc, #276] ; (8002c14 ) + 8002b00: 685b ldr r3, [r3, #4] + 8002b02: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8002b06: 2b00 cmp r3, #0 + 8002b08: d023 beq.n 8002b52 { /* 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); - 8002a86: 4b42 ldr r3, [pc, #264] ; (8002b90 ) - 8002a88: 685b ldr r3, [r3, #4] - 8002a8a: 099b lsrs r3, r3, #6 - 8002a8c: f04f 0400 mov.w r4, #0 - 8002a90: f240 11ff movw r1, #511 ; 0x1ff - 8002a94: f04f 0200 mov.w r2, #0 - 8002a98: ea03 0501 and.w r5, r3, r1 - 8002a9c: ea04 0602 and.w r6, r4, r2 - 8002aa0: 4a3d ldr r2, [pc, #244] ; (8002b98 ) - 8002aa2: fb02 f106 mul.w r1, r2, r6 - 8002aa6: 2200 movs r2, #0 - 8002aa8: fb02 f205 mul.w r2, r2, r5 - 8002aac: 440a add r2, r1 - 8002aae: 493a ldr r1, [pc, #232] ; (8002b98 ) - 8002ab0: fba5 0101 umull r0, r1, r5, r1 - 8002ab4: 1853 adds r3, r2, r1 - 8002ab6: 4619 mov r1, r3 - 8002ab8: 687b ldr r3, [r7, #4] - 8002aba: f04f 0400 mov.w r4, #0 - 8002abe: 461a mov r2, r3 - 8002ac0: 4623 mov r3, r4 - 8002ac2: f7fd fbb9 bl 8000238 <__aeabi_uldivmod> - 8002ac6: 4603 mov r3, r0 - 8002ac8: 460c mov r4, r1 - 8002aca: 60fb str r3, [r7, #12] - 8002acc: e049 b.n 8002b62 + 8002b0a: 4b42 ldr r3, [pc, #264] ; (8002c14 ) + 8002b0c: 685b ldr r3, [r3, #4] + 8002b0e: 099b lsrs r3, r3, #6 + 8002b10: f04f 0400 mov.w r4, #0 + 8002b14: f240 11ff movw r1, #511 ; 0x1ff + 8002b18: f04f 0200 mov.w r2, #0 + 8002b1c: ea03 0501 and.w r5, r3, r1 + 8002b20: ea04 0602 and.w r6, r4, r2 + 8002b24: 4a3d ldr r2, [pc, #244] ; (8002c1c ) + 8002b26: fb02 f106 mul.w r1, r2, r6 + 8002b2a: 2200 movs r2, #0 + 8002b2c: fb02 f205 mul.w r2, r2, r5 + 8002b30: 440a add r2, r1 + 8002b32: 493a ldr r1, [pc, #232] ; (8002c1c ) + 8002b34: fba5 0101 umull r0, r1, r5, r1 + 8002b38: 1853 adds r3, r2, r1 + 8002b3a: 4619 mov r1, r3 + 8002b3c: 687b ldr r3, [r7, #4] + 8002b3e: f04f 0400 mov.w r4, #0 + 8002b42: 461a mov r2, r3 + 8002b44: 4623 mov r3, r4 + 8002b46: f7fd fb77 bl 8000238 <__aeabi_uldivmod> + 8002b4a: 4603 mov r3, r0 + 8002b4c: 460c mov r4, r1 + 8002b4e: 60fb str r3, [r7, #12] + 8002b50: e049 b.n 8002be6 } 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); - 8002ace: 4b30 ldr r3, [pc, #192] ; (8002b90 ) - 8002ad0: 685b ldr r3, [r3, #4] - 8002ad2: 099b lsrs r3, r3, #6 - 8002ad4: f04f 0400 mov.w r4, #0 - 8002ad8: f240 11ff movw r1, #511 ; 0x1ff - 8002adc: f04f 0200 mov.w r2, #0 - 8002ae0: ea03 0501 and.w r5, r3, r1 - 8002ae4: ea04 0602 and.w r6, r4, r2 - 8002ae8: 4629 mov r1, r5 - 8002aea: 4632 mov r2, r6 - 8002aec: f04f 0300 mov.w r3, #0 - 8002af0: f04f 0400 mov.w r4, #0 - 8002af4: 0154 lsls r4, r2, #5 - 8002af6: ea44 64d1 orr.w r4, r4, r1, lsr #27 - 8002afa: 014b lsls r3, r1, #5 - 8002afc: 4619 mov r1, r3 - 8002afe: 4622 mov r2, r4 - 8002b00: 1b49 subs r1, r1, r5 - 8002b02: eb62 0206 sbc.w r2, r2, r6 - 8002b06: f04f 0300 mov.w r3, #0 - 8002b0a: f04f 0400 mov.w r4, #0 - 8002b0e: 0194 lsls r4, r2, #6 - 8002b10: ea44 6491 orr.w r4, r4, r1, lsr #26 - 8002b14: 018b lsls r3, r1, #6 - 8002b16: 1a5b subs r3, r3, r1 - 8002b18: eb64 0402 sbc.w r4, r4, r2 - 8002b1c: f04f 0100 mov.w r1, #0 - 8002b20: f04f 0200 mov.w r2, #0 - 8002b24: 00e2 lsls r2, r4, #3 - 8002b26: ea42 7253 orr.w r2, r2, r3, lsr #29 - 8002b2a: 00d9 lsls r1, r3, #3 - 8002b2c: 460b mov r3, r1 - 8002b2e: 4614 mov r4, r2 - 8002b30: 195b adds r3, r3, r5 - 8002b32: eb44 0406 adc.w r4, r4, r6 - 8002b36: f04f 0100 mov.w r1, #0 - 8002b3a: f04f 0200 mov.w r2, #0 - 8002b3e: 02a2 lsls r2, r4, #10 - 8002b40: ea42 5293 orr.w r2, r2, r3, lsr #22 - 8002b44: 0299 lsls r1, r3, #10 - 8002b46: 460b mov r3, r1 - 8002b48: 4614 mov r4, r2 - 8002b4a: 4618 mov r0, r3 - 8002b4c: 4621 mov r1, r4 - 8002b4e: 687b ldr r3, [r7, #4] - 8002b50: f04f 0400 mov.w r4, #0 - 8002b54: 461a mov r2, r3 - 8002b56: 4623 mov r3, r4 - 8002b58: f7fd fb6e bl 8000238 <__aeabi_uldivmod> - 8002b5c: 4603 mov r3, r0 - 8002b5e: 460c mov r4, r1 - 8002b60: 60fb str r3, [r7, #12] + 8002b52: 4b30 ldr r3, [pc, #192] ; (8002c14 ) + 8002b54: 685b ldr r3, [r3, #4] + 8002b56: 099b lsrs r3, r3, #6 + 8002b58: f04f 0400 mov.w r4, #0 + 8002b5c: f240 11ff movw r1, #511 ; 0x1ff + 8002b60: f04f 0200 mov.w r2, #0 + 8002b64: ea03 0501 and.w r5, r3, r1 + 8002b68: ea04 0602 and.w r6, r4, r2 + 8002b6c: 4629 mov r1, r5 + 8002b6e: 4632 mov r2, r6 + 8002b70: f04f 0300 mov.w r3, #0 + 8002b74: f04f 0400 mov.w r4, #0 + 8002b78: 0154 lsls r4, r2, #5 + 8002b7a: ea44 64d1 orr.w r4, r4, r1, lsr #27 + 8002b7e: 014b lsls r3, r1, #5 + 8002b80: 4619 mov r1, r3 + 8002b82: 4622 mov r2, r4 + 8002b84: 1b49 subs r1, r1, r5 + 8002b86: eb62 0206 sbc.w r2, r2, r6 + 8002b8a: f04f 0300 mov.w r3, #0 + 8002b8e: f04f 0400 mov.w r4, #0 + 8002b92: 0194 lsls r4, r2, #6 + 8002b94: ea44 6491 orr.w r4, r4, r1, lsr #26 + 8002b98: 018b lsls r3, r1, #6 + 8002b9a: 1a5b subs r3, r3, r1 + 8002b9c: eb64 0402 sbc.w r4, r4, r2 + 8002ba0: f04f 0100 mov.w r1, #0 + 8002ba4: f04f 0200 mov.w r2, #0 + 8002ba8: 00e2 lsls r2, r4, #3 + 8002baa: ea42 7253 orr.w r2, r2, r3, lsr #29 + 8002bae: 00d9 lsls r1, r3, #3 + 8002bb0: 460b mov r3, r1 + 8002bb2: 4614 mov r4, r2 + 8002bb4: 195b adds r3, r3, r5 + 8002bb6: eb44 0406 adc.w r4, r4, r6 + 8002bba: f04f 0100 mov.w r1, #0 + 8002bbe: f04f 0200 mov.w r2, #0 + 8002bc2: 02a2 lsls r2, r4, #10 + 8002bc4: ea42 5293 orr.w r2, r2, r3, lsr #22 + 8002bc8: 0299 lsls r1, r3, #10 + 8002bca: 460b mov r3, r1 + 8002bcc: 4614 mov r4, r2 + 8002bce: 4618 mov r0, r3 + 8002bd0: 4621 mov r1, r4 + 8002bd2: 687b ldr r3, [r7, #4] + 8002bd4: f04f 0400 mov.w r4, #0 + 8002bd8: 461a mov r2, r3 + 8002bda: 4623 mov r3, r4 + 8002bdc: f7fd fb2c bl 8000238 <__aeabi_uldivmod> + 8002be0: 4603 mov r3, r0 + 8002be2: 460c mov r4, r1 + 8002be4: 60fb str r3, [r7, #12] } pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1 ) *2); - 8002b62: 4b0b ldr r3, [pc, #44] ; (8002b90 ) - 8002b64: 685b ldr r3, [r3, #4] - 8002b66: 0c1b lsrs r3, r3, #16 - 8002b68: f003 0303 and.w r3, r3, #3 - 8002b6c: 3301 adds r3, #1 - 8002b6e: 005b lsls r3, r3, #1 - 8002b70: 603b str r3, [r7, #0] + 8002be6: 4b0b ldr r3, [pc, #44] ; (8002c14 ) + 8002be8: 685b ldr r3, [r3, #4] + 8002bea: 0c1b lsrs r3, r3, #16 + 8002bec: f003 0303 and.w r3, r3, #3 + 8002bf0: 3301 adds r3, #1 + 8002bf2: 005b lsls r3, r3, #1 + 8002bf4: 603b str r3, [r7, #0] sysclockfreq = pllvco/pllp; - 8002b72: 68fa ldr r2, [r7, #12] - 8002b74: 683b ldr r3, [r7, #0] - 8002b76: fbb2 f3f3 udiv r3, r2, r3 - 8002b7a: 60bb str r3, [r7, #8] + 8002bf6: 68fa ldr r2, [r7, #12] + 8002bf8: 683b ldr r3, [r7, #0] + 8002bfa: fbb2 f3f3 udiv r3, r2, r3 + 8002bfe: 60bb str r3, [r7, #8] break; - 8002b7c: e002 b.n 8002b84 + 8002c00: e002 b.n 8002c08 } default: { sysclockfreq = HSI_VALUE; - 8002b7e: 4b05 ldr r3, [pc, #20] ; (8002b94 ) - 8002b80: 60bb str r3, [r7, #8] + 8002c02: 4b05 ldr r3, [pc, #20] ; (8002c18 ) + 8002c04: 60bb str r3, [r7, #8] break; - 8002b82: bf00 nop + 8002c06: bf00 nop } } return sysclockfreq; - 8002b84: 68bb ldr r3, [r7, #8] + 8002c08: 68bb ldr r3, [r7, #8] } - 8002b86: 4618 mov r0, r3 - 8002b88: 3714 adds r7, #20 - 8002b8a: 46bd mov sp, r7 - 8002b8c: bdf0 pop {r4, r5, r6, r7, pc} - 8002b8e: bf00 nop - 8002b90: 40023800 .word 0x40023800 - 8002b94: 00f42400 .word 0x00f42400 - 8002b98: 017d7840 .word 0x017d7840 - -08002b9c : + 8002c0a: 4618 mov r0, r3 + 8002c0c: 3714 adds r7, #20 + 8002c0e: 46bd mov sp, r7 + 8002c10: bdf0 pop {r4, r5, r6, r7, pc} + 8002c12: bf00 nop + 8002c14: 40023800 .word 0x40023800 + 8002c18: 00f42400 .word 0x00f42400 + 8002c1c: 017d7840 .word 0x017d7840 + +08002c20 : * 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) { - 8002b9c: b480 push {r7} - 8002b9e: af00 add r7, sp, #0 + 8002c20: b480 push {r7} + 8002c22: af00 add r7, sp, #0 return SystemCoreClock; - 8002ba0: 4b03 ldr r3, [pc, #12] ; (8002bb0 ) - 8002ba2: 681b ldr r3, [r3, #0] + 8002c24: 4b03 ldr r3, [pc, #12] ; (8002c34 ) + 8002c26: 681b ldr r3, [r3, #0] } - 8002ba4: 4618 mov r0, r3 - 8002ba6: 46bd mov sp, r7 - 8002ba8: f85d 7b04 ldr.w r7, [sp], #4 - 8002bac: 4770 bx lr - 8002bae: bf00 nop - 8002bb0: 20000004 .word 0x20000004 - -08002bb4 : + 8002c28: 4618 mov r0, r3 + 8002c2a: 46bd mov sp, r7 + 8002c2c: f85d 7b04 ldr.w r7, [sp], #4 + 8002c30: 4770 bx lr + 8002c32: bf00 nop + 8002c34: 20000004 .word 0x20000004 + +08002c38 : * @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) { - 8002bb4: b580 push {r7, lr} - 8002bb6: af00 add r7, sp, #0 + 8002c38: b580 push {r7, lr} + 8002c3a: 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]); - 8002bb8: f7ff fff0 bl 8002b9c - 8002bbc: 4601 mov r1, r0 - 8002bbe: 4b05 ldr r3, [pc, #20] ; (8002bd4 ) - 8002bc0: 689b ldr r3, [r3, #8] - 8002bc2: 0a9b lsrs r3, r3, #10 - 8002bc4: f003 0307 and.w r3, r3, #7 - 8002bc8: 4a03 ldr r2, [pc, #12] ; (8002bd8 ) - 8002bca: 5cd3 ldrb r3, [r2, r3] - 8002bcc: fa21 f303 lsr.w r3, r1, r3 + 8002c3c: f7ff fff0 bl 8002c20 + 8002c40: 4601 mov r1, r0 + 8002c42: 4b05 ldr r3, [pc, #20] ; (8002c58 ) + 8002c44: 689b ldr r3, [r3, #8] + 8002c46: 0a9b lsrs r3, r3, #10 + 8002c48: f003 0307 and.w r3, r3, #7 + 8002c4c: 4a03 ldr r2, [pc, #12] ; (8002c5c ) + 8002c4e: 5cd3 ldrb r3, [r2, r3] + 8002c50: fa21 f303 lsr.w r3, r1, r3 } - 8002bd0: 4618 mov r0, r3 - 8002bd2: bd80 pop {r7, pc} - 8002bd4: 40023800 .word 0x40023800 - 8002bd8: 0800556c .word 0x0800556c + 8002c54: 4618 mov r0, r3 + 8002c56: bd80 pop {r7, pc} + 8002c58: 40023800 .word 0x40023800 + 8002c5c: 080055f0 .word 0x080055f0 -08002bdc : +08002c60 : * @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) { - 8002bdc: b580 push {r7, lr} - 8002bde: af00 add r7, sp, #0 + 8002c60: b580 push {r7, lr} + 8002c62: 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]); - 8002be0: f7ff ffdc bl 8002b9c - 8002be4: 4601 mov r1, r0 - 8002be6: 4b05 ldr r3, [pc, #20] ; (8002bfc ) - 8002be8: 689b ldr r3, [r3, #8] - 8002bea: 0b5b lsrs r3, r3, #13 - 8002bec: f003 0307 and.w r3, r3, #7 - 8002bf0: 4a03 ldr r2, [pc, #12] ; (8002c00 ) - 8002bf2: 5cd3 ldrb r3, [r2, r3] - 8002bf4: fa21 f303 lsr.w r3, r1, r3 + 8002c64: f7ff ffdc bl 8002c20 + 8002c68: 4601 mov r1, r0 + 8002c6a: 4b05 ldr r3, [pc, #20] ; (8002c80 ) + 8002c6c: 689b ldr r3, [r3, #8] + 8002c6e: 0b5b lsrs r3, r3, #13 + 8002c70: f003 0307 and.w r3, r3, #7 + 8002c74: 4a03 ldr r2, [pc, #12] ; (8002c84 ) + 8002c76: 5cd3 ldrb r3, [r2, r3] + 8002c78: fa21 f303 lsr.w r3, r1, r3 } - 8002bf8: 4618 mov r0, r3 - 8002bfa: bd80 pop {r7, pc} - 8002bfc: 40023800 .word 0x40023800 - 8002c00: 0800556c .word 0x0800556c + 8002c7c: 4618 mov r0, r3 + 8002c7e: bd80 pop {r7, pc} + 8002c80: 40023800 .word 0x40023800 + 8002c84: 080055f0 .word 0x080055f0 -08002c04 : +08002c88 : * the backup registers) are set to their reset values. * * @retval HAL status */ HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) { - 8002c04: b580 push {r7, lr} - 8002c06: b088 sub sp, #32 - 8002c08: af00 add r7, sp, #0 - 8002c0a: 6078 str r0, [r7, #4] + 8002c88: b580 push {r7, lr} + 8002c8a: b088 sub sp, #32 + 8002c8c: af00 add r7, sp, #0 + 8002c8e: 6078 str r0, [r7, #4] uint32_t tickstart = 0; - 8002c0c: 2300 movs r3, #0 - 8002c0e: 617b str r3, [r7, #20] + 8002c90: 2300 movs r3, #0 + 8002c92: 617b str r3, [r7, #20] uint32_t tmpreg0 = 0; - 8002c10: 2300 movs r3, #0 - 8002c12: 613b str r3, [r7, #16] + 8002c94: 2300 movs r3, #0 + 8002c96: 613b str r3, [r7, #16] uint32_t tmpreg1 = 0; - 8002c14: 2300 movs r3, #0 - 8002c16: 60fb str r3, [r7, #12] + 8002c98: 2300 movs r3, #0 + 8002c9a: 60fb str r3, [r7, #12] uint32_t plli2sused = 0; - 8002c18: 2300 movs r3, #0 - 8002c1a: 61fb str r3, [r7, #28] + 8002c9c: 2300 movs r3, #0 + 8002c9e: 61fb str r3, [r7, #28] uint32_t pllsaiused = 0; - 8002c1c: 2300 movs r3, #0 - 8002c1e: 61bb str r3, [r7, #24] + 8002ca0: 2300 movs r3, #0 + 8002ca2: 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)) - 8002c20: 687b ldr r3, [r7, #4] - 8002c22: 681b ldr r3, [r3, #0] - 8002c24: f003 0301 and.w r3, r3, #1 - 8002c28: 2b00 cmp r3, #0 - 8002c2a: d012 beq.n 8002c52 + 8002ca4: 687b ldr r3, [r7, #4] + 8002ca6: 681b ldr r3, [r3, #0] + 8002ca8: f003 0301 and.w r3, r3, #1 + 8002cac: 2b00 cmp r3, #0 + 8002cae: d012 beq.n 8002cd6 { /* Check the parameters */ assert_param(IS_RCC_I2SCLKSOURCE(PeriphClkInit->I2sClockSelection)); /* Configure I2S Clock source */ __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2sClockSelection); - 8002c2c: 4b69 ldr r3, [pc, #420] ; (8002dd4 ) - 8002c2e: 689b ldr r3, [r3, #8] - 8002c30: 4a68 ldr r2, [pc, #416] ; (8002dd4 ) - 8002c32: f423 0300 bic.w r3, r3, #8388608 ; 0x800000 - 8002c36: 6093 str r3, [r2, #8] - 8002c38: 4b66 ldr r3, [pc, #408] ; (8002dd4 ) - 8002c3a: 689a ldr r2, [r3, #8] - 8002c3c: 687b ldr r3, [r7, #4] - 8002c3e: 6b5b ldr r3, [r3, #52] ; 0x34 - 8002c40: 4964 ldr r1, [pc, #400] ; (8002dd4 ) - 8002c42: 4313 orrs r3, r2 - 8002c44: 608b str r3, [r1, #8] + 8002cb0: 4b69 ldr r3, [pc, #420] ; (8002e58 ) + 8002cb2: 689b ldr r3, [r3, #8] + 8002cb4: 4a68 ldr r2, [pc, #416] ; (8002e58 ) + 8002cb6: f423 0300 bic.w r3, r3, #8388608 ; 0x800000 + 8002cba: 6093 str r3, [r2, #8] + 8002cbc: 4b66 ldr r3, [pc, #408] ; (8002e58 ) + 8002cbe: 689a ldr r2, [r3, #8] + 8002cc0: 687b ldr r3, [r7, #4] + 8002cc2: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002cc4: 4964 ldr r1, [pc, #400] ; (8002e58 ) + 8002cc6: 4313 orrs r3, r2 + 8002cc8: 608b str r3, [r1, #8] /* Enable the PLLI2S when it's used as clock source for I2S */ if(PeriphClkInit->I2sClockSelection == RCC_I2SCLKSOURCE_PLLI2S) - 8002c46: 687b ldr r3, [r7, #4] - 8002c48: 6b5b ldr r3, [r3, #52] ; 0x34 - 8002c4a: 2b00 cmp r3, #0 - 8002c4c: d101 bne.n 8002c52 + 8002cca: 687b ldr r3, [r7, #4] + 8002ccc: 6b5b ldr r3, [r3, #52] ; 0x34 + 8002cce: 2b00 cmp r3, #0 + 8002cd0: d101 bne.n 8002cd6 { plli2sused = 1; - 8002c4e: 2301 movs r3, #1 - 8002c50: 61fb str r3, [r7, #28] + 8002cd2: 2301 movs r3, #1 + 8002cd4: 61fb str r3, [r7, #28] } } /*------------------------------------ SAI1 configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) - 8002c52: 687b ldr r3, [r7, #4] - 8002c54: 681b ldr r3, [r3, #0] - 8002c56: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 8002c5a: 2b00 cmp r3, #0 - 8002c5c: d017 beq.n 8002c8e + 8002cd6: 687b ldr r3, [r7, #4] + 8002cd8: 681b ldr r3, [r3, #0] + 8002cda: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8002cde: 2b00 cmp r3, #0 + 8002ce0: d017 beq.n 8002d12 { /* Check the parameters */ assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); /* Configure SAI1 Clock source */ __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); - 8002c5e: 4b5d ldr r3, [pc, #372] ; (8002dd4 ) - 8002c60: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002c64: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 - 8002c68: 687b ldr r3, [r7, #4] - 8002c6a: 6bdb ldr r3, [r3, #60] ; 0x3c - 8002c6c: 4959 ldr r1, [pc, #356] ; (8002dd4 ) - 8002c6e: 4313 orrs r3, r2 - 8002c70: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002ce2: 4b5d ldr r3, [pc, #372] ; (8002e58 ) + 8002ce4: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002ce8: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 8002cec: 687b ldr r3, [r7, #4] + 8002cee: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002cf0: 4959 ldr r1, [pc, #356] ; (8002e58 ) + 8002cf2: 4313 orrs r3, r2 + 8002cf4: 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) - 8002c74: 687b ldr r3, [r7, #4] - 8002c76: 6bdb ldr r3, [r3, #60] ; 0x3c - 8002c78: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 8002c7c: d101 bne.n 8002c82 + 8002cf8: 687b ldr r3, [r7, #4] + 8002cfa: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002cfc: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8002d00: d101 bne.n 8002d06 { plli2sused = 1; - 8002c7e: 2301 movs r3, #1 - 8002c80: 61fb str r3, [r7, #28] + 8002d02: 2301 movs r3, #1 + 8002d04: 61fb str r3, [r7, #28] } /* Enable the PLLSAI when it's used as clock source for SAI */ if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) - 8002c82: 687b ldr r3, [r7, #4] - 8002c84: 6bdb ldr r3, [r3, #60] ; 0x3c - 8002c86: 2b00 cmp r3, #0 - 8002c88: d101 bne.n 8002c8e + 8002d06: 687b ldr r3, [r7, #4] + 8002d08: 6bdb ldr r3, [r3, #60] ; 0x3c + 8002d0a: 2b00 cmp r3, #0 + 8002d0c: d101 bne.n 8002d12 { pllsaiused = 1; - 8002c8a: 2301 movs r3, #1 - 8002c8c: 61bb str r3, [r7, #24] + 8002d0e: 2301 movs r3, #1 + 8002d10: 61bb str r3, [r7, #24] } } /*------------------------------------ SAI2 configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) - 8002c8e: 687b ldr r3, [r7, #4] - 8002c90: 681b ldr r3, [r3, #0] - 8002c92: f403 1380 and.w r3, r3, #1048576 ; 0x100000 - 8002c96: 2b00 cmp r3, #0 - 8002c98: d017 beq.n 8002cca + 8002d12: 687b ldr r3, [r7, #4] + 8002d14: 681b ldr r3, [r3, #0] + 8002d16: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8002d1a: 2b00 cmp r3, #0 + 8002d1c: d017 beq.n 8002d4e { /* Check the parameters */ assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); /* Configure SAI2 Clock source */ __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); - 8002c9a: 4b4e ldr r3, [pc, #312] ; (8002dd4 ) - 8002c9c: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002ca0: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 - 8002ca4: 687b ldr r3, [r7, #4] - 8002ca6: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002ca8: 494a ldr r1, [pc, #296] ; (8002dd4 ) - 8002caa: 4313 orrs r3, r2 - 8002cac: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002d1e: 4b4e ldr r3, [pc, #312] ; (8002e58 ) + 8002d20: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002d24: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 8002d28: 687b ldr r3, [r7, #4] + 8002d2a: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002d2c: 494a ldr r1, [pc, #296] ; (8002e58 ) + 8002d2e: 4313 orrs r3, r2 + 8002d30: 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) - 8002cb0: 687b ldr r3, [r7, #4] - 8002cb2: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002cb4: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 8002cb8: d101 bne.n 8002cbe + 8002d34: 687b ldr r3, [r7, #4] + 8002d36: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002d38: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8002d3c: d101 bne.n 8002d42 { plli2sused = 1; - 8002cba: 2301 movs r3, #1 - 8002cbc: 61fb str r3, [r7, #28] + 8002d3e: 2301 movs r3, #1 + 8002d40: 61fb str r3, [r7, #28] } /* Enable the PLLSAI when it's used as clock source for SAI */ if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) - 8002cbe: 687b ldr r3, [r7, #4] - 8002cc0: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002cc2: 2b00 cmp r3, #0 - 8002cc4: d101 bne.n 8002cca + 8002d42: 687b ldr r3, [r7, #4] + 8002d44: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002d46: 2b00 cmp r3, #0 + 8002d48: d101 bne.n 8002d4e { pllsaiused = 1; - 8002cc6: 2301 movs r3, #1 - 8002cc8: 61bb str r3, [r7, #24] + 8002d4a: 2301 movs r3, #1 + 8002d4c: 61bb str r3, [r7, #24] } } /*-------------------------------------- SPDIF-RX Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) - 8002cca: 687b ldr r3, [r7, #4] - 8002ccc: 681b ldr r3, [r3, #0] - 8002cce: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 - 8002cd2: 2b00 cmp r3, #0 - 8002cd4: d001 beq.n 8002cda + 8002d4e: 687b ldr r3, [r7, #4] + 8002d50: 681b ldr r3, [r3, #0] + 8002d52: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8002d56: 2b00 cmp r3, #0 + 8002d58: d001 beq.n 8002d5e { plli2sused = 1; - 8002cd6: 2301 movs r3, #1 - 8002cd8: 61fb str r3, [r7, #28] + 8002d5a: 2301 movs r3, #1 + 8002d5c: 61fb str r3, [r7, #28] } /*------------------------------------ RTC configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - 8002cda: 687b ldr r3, [r7, #4] - 8002cdc: 681b ldr r3, [r3, #0] - 8002cde: f003 0320 and.w r3, r3, #32 - 8002ce2: 2b00 cmp r3, #0 - 8002ce4: f000 808b beq.w 8002dfe + 8002d5e: 687b ldr r3, [r7, #4] + 8002d60: 681b ldr r3, [r3, #0] + 8002d62: f003 0320 and.w r3, r3, #32 + 8002d66: 2b00 cmp r3, #0 + 8002d68: f000 808b beq.w 8002e82 { /* Check for RTC Parameters used to output RTCCLK */ assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); /* Enable Power Clock*/ __HAL_RCC_PWR_CLK_ENABLE(); - 8002ce8: 4b3a ldr r3, [pc, #232] ; (8002dd4 ) - 8002cea: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002cec: 4a39 ldr r2, [pc, #228] ; (8002dd4 ) - 8002cee: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8002cf2: 6413 str r3, [r2, #64] ; 0x40 - 8002cf4: 4b37 ldr r3, [pc, #220] ; (8002dd4 ) - 8002cf6: 6c1b ldr r3, [r3, #64] ; 0x40 - 8002cf8: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 8002cfc: 60bb str r3, [r7, #8] - 8002cfe: 68bb ldr r3, [r7, #8] + 8002d6c: 4b3a ldr r3, [pc, #232] ; (8002e58 ) + 8002d6e: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002d70: 4a39 ldr r2, [pc, #228] ; (8002e58 ) + 8002d72: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 8002d76: 6413 str r3, [r2, #64] ; 0x40 + 8002d78: 4b37 ldr r3, [pc, #220] ; (8002e58 ) + 8002d7a: 6c1b ldr r3, [r3, #64] ; 0x40 + 8002d7c: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8002d80: 60bb str r3, [r7, #8] + 8002d82: 68bb ldr r3, [r7, #8] /* Enable write access to Backup domain */ PWR->CR1 |= PWR_CR1_DBP; - 8002d00: 4b35 ldr r3, [pc, #212] ; (8002dd8 ) - 8002d02: 681b ldr r3, [r3, #0] - 8002d04: 4a34 ldr r2, [pc, #208] ; (8002dd8 ) - 8002d06: f443 7380 orr.w r3, r3, #256 ; 0x100 - 8002d0a: 6013 str r3, [r2, #0] + 8002d84: 4b35 ldr r3, [pc, #212] ; (8002e5c ) + 8002d86: 681b ldr r3, [r3, #0] + 8002d88: 4a34 ldr r2, [pc, #208] ; (8002e5c ) + 8002d8a: f443 7380 orr.w r3, r3, #256 ; 0x100 + 8002d8e: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002d0c: f7ff f81e bl 8001d4c - 8002d10: 6178 str r0, [r7, #20] + 8002d90: f7ff f81e bl 8001dd0 + 8002d94: 6178 str r0, [r7, #20] /* Wait for Backup domain Write protection disable */ while((PWR->CR1 & PWR_CR1_DBP) == RESET) - 8002d12: e008 b.n 8002d26 + 8002d96: e008 b.n 8002daa { if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - 8002d14: f7ff f81a bl 8001d4c - 8002d18: 4602 mov r2, r0 - 8002d1a: 697b ldr r3, [r7, #20] - 8002d1c: 1ad3 subs r3, r2, r3 - 8002d1e: 2b64 cmp r3, #100 ; 0x64 - 8002d20: d901 bls.n 8002d26 + 8002d98: f7ff f81a bl 8001dd0 + 8002d9c: 4602 mov r2, r0 + 8002d9e: 697b ldr r3, [r7, #20] + 8002da0: 1ad3 subs r3, r2, r3 + 8002da2: 2b64 cmp r3, #100 ; 0x64 + 8002da4: d901 bls.n 8002daa { return HAL_TIMEOUT; - 8002d22: 2303 movs r3, #3 - 8002d24: e38d b.n 8003442 + 8002da6: 2303 movs r3, #3 + 8002da8: e38d b.n 80034c6 while((PWR->CR1 & PWR_CR1_DBP) == RESET) - 8002d26: 4b2c ldr r3, [pc, #176] ; (8002dd8 ) - 8002d28: 681b ldr r3, [r3, #0] - 8002d2a: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002d2e: 2b00 cmp r3, #0 - 8002d30: d0f0 beq.n 8002d14 + 8002daa: 4b2c ldr r3, [pc, #176] ; (8002e5c ) + 8002dac: 681b ldr r3, [r3, #0] + 8002dae: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002db2: 2b00 cmp r3, #0 + 8002db4: d0f0 beq.n 8002d98 } } /* Reset the Backup domain only if the RTC Clock source selection is modified */ tmpreg0 = (RCC->BDCR & RCC_BDCR_RTCSEL); - 8002d32: 4b28 ldr r3, [pc, #160] ; (8002dd4 ) - 8002d34: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002d36: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002d3a: 613b str r3, [r7, #16] + 8002db6: 4b28 ldr r3, [pc, #160] ; (8002e58 ) + 8002db8: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002dba: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002dbe: 613b str r3, [r7, #16] if((tmpreg0 != 0x00000000U) && (tmpreg0 != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - 8002d3c: 693b ldr r3, [r7, #16] - 8002d3e: 2b00 cmp r3, #0 - 8002d40: d035 beq.n 8002dae - 8002d42: 687b ldr r3, [r7, #4] - 8002d44: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002d46: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002d4a: 693a ldr r2, [r7, #16] - 8002d4c: 429a cmp r2, r3 - 8002d4e: d02e beq.n 8002dae + 8002dc0: 693b ldr r3, [r7, #16] + 8002dc2: 2b00 cmp r3, #0 + 8002dc4: d035 beq.n 8002e32 + 8002dc6: 687b ldr r3, [r7, #4] + 8002dc8: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002dca: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002dce: 693a ldr r2, [r7, #16] + 8002dd0: 429a cmp r2, r3 + 8002dd2: d02e beq.n 8002e32 { /* Store the content of BDCR register before the reset of Backup Domain */ tmpreg0 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - 8002d50: 4b20 ldr r3, [pc, #128] ; (8002dd4 ) - 8002d52: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002d54: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8002d58: 613b str r3, [r7, #16] + 8002dd4: 4b20 ldr r3, [pc, #128] ; (8002e58 ) + 8002dd6: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002dd8: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8002ddc: 613b str r3, [r7, #16] /* RTC Clock selection can be changed only if the Backup Domain is reset */ __HAL_RCC_BACKUPRESET_FORCE(); - 8002d5a: 4b1e ldr r3, [pc, #120] ; (8002dd4 ) - 8002d5c: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002d5e: 4a1d ldr r2, [pc, #116] ; (8002dd4 ) - 8002d60: f443 3380 orr.w r3, r3, #65536 ; 0x10000 - 8002d64: 6713 str r3, [r2, #112] ; 0x70 + 8002dde: 4b1e ldr r3, [pc, #120] ; (8002e58 ) + 8002de0: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002de2: 4a1d ldr r2, [pc, #116] ; (8002e58 ) + 8002de4: f443 3380 orr.w r3, r3, #65536 ; 0x10000 + 8002de8: 6713 str r3, [r2, #112] ; 0x70 __HAL_RCC_BACKUPRESET_RELEASE(); - 8002d66: 4b1b ldr r3, [pc, #108] ; (8002dd4 ) - 8002d68: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002d6a: 4a1a ldr r2, [pc, #104] ; (8002dd4 ) - 8002d6c: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 8002d70: 6713 str r3, [r2, #112] ; 0x70 + 8002dea: 4b1b ldr r3, [pc, #108] ; (8002e58 ) + 8002dec: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002dee: 4a1a ldr r2, [pc, #104] ; (8002e58 ) + 8002df0: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 8002df4: 6713 str r3, [r2, #112] ; 0x70 /* Restore the Content of BDCR register */ RCC->BDCR = tmpreg0; - 8002d72: 4a18 ldr r2, [pc, #96] ; (8002dd4 ) - 8002d74: 693b ldr r3, [r7, #16] - 8002d76: 6713 str r3, [r2, #112] ; 0x70 + 8002df6: 4a18 ldr r2, [pc, #96] ; (8002e58 ) + 8002df8: 693b ldr r3, [r7, #16] + 8002dfa: 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)) - 8002d78: 4b16 ldr r3, [pc, #88] ; (8002dd4 ) - 8002d7a: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002d7c: f003 0301 and.w r3, r3, #1 - 8002d80: 2b01 cmp r3, #1 - 8002d82: d114 bne.n 8002dae + 8002dfc: 4b16 ldr r3, [pc, #88] ; (8002e58 ) + 8002dfe: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002e00: f003 0301 and.w r3, r3, #1 + 8002e04: 2b01 cmp r3, #1 + 8002e06: d114 bne.n 8002e32 { /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8002d84: f7fe ffe2 bl 8001d4c - 8002d88: 6178 str r0, [r7, #20] + 8002e08: f7fe ffe2 bl 8001dd0 + 8002e0c: 6178 str r0, [r7, #20] /* Wait till LSE is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002d8a: e00a b.n 8002da2 + 8002e0e: e00a b.n 8002e26 { if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - 8002d8c: f7fe ffde bl 8001d4c - 8002d90: 4602 mov r2, r0 - 8002d92: 697b ldr r3, [r7, #20] - 8002d94: 1ad3 subs r3, r2, r3 - 8002d96: f241 3288 movw r2, #5000 ; 0x1388 - 8002d9a: 4293 cmp r3, r2 - 8002d9c: d901 bls.n 8002da2 + 8002e10: f7fe ffde bl 8001dd0 + 8002e14: 4602 mov r2, r0 + 8002e16: 697b ldr r3, [r7, #20] + 8002e18: 1ad3 subs r3, r2, r3 + 8002e1a: f241 3288 movw r2, #5000 ; 0x1388 + 8002e1e: 4293 cmp r3, r2 + 8002e20: d901 bls.n 8002e26 { return HAL_TIMEOUT; - 8002d9e: 2303 movs r3, #3 - 8002da0: e34f b.n 8003442 + 8002e22: 2303 movs r3, #3 + 8002e24: e34f b.n 80034c6 while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - 8002da2: 4b0c ldr r3, [pc, #48] ; (8002dd4 ) - 8002da4: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002da6: f003 0302 and.w r3, r3, #2 - 8002daa: 2b00 cmp r3, #0 - 8002dac: d0ee beq.n 8002d8c + 8002e26: 4b0c ldr r3, [pc, #48] ; (8002e58 ) + 8002e28: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002e2a: f003 0302 and.w r3, r3, #2 + 8002e2e: 2b00 cmp r3, #0 + 8002e30: d0ee beq.n 8002e10 } } } } __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - 8002dae: 687b ldr r3, [r7, #4] - 8002db0: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002db2: f403 7340 and.w r3, r3, #768 ; 0x300 - 8002db6: f5b3 7f40 cmp.w r3, #768 ; 0x300 - 8002dba: d111 bne.n 8002de0 - 8002dbc: 4b05 ldr r3, [pc, #20] ; (8002dd4 ) - 8002dbe: 689b ldr r3, [r3, #8] - 8002dc0: f423 12f8 bic.w r2, r3, #2031616 ; 0x1f0000 - 8002dc4: 687b ldr r3, [r7, #4] - 8002dc6: 6b19 ldr r1, [r3, #48] ; 0x30 - 8002dc8: 4b04 ldr r3, [pc, #16] ; (8002ddc ) - 8002dca: 400b ands r3, r1 - 8002dcc: 4901 ldr r1, [pc, #4] ; (8002dd4 ) - 8002dce: 4313 orrs r3, r2 - 8002dd0: 608b str r3, [r1, #8] - 8002dd2: e00b b.n 8002dec - 8002dd4: 40023800 .word 0x40023800 - 8002dd8: 40007000 .word 0x40007000 - 8002ddc: 0ffffcff .word 0x0ffffcff - 8002de0: 4bb3 ldr r3, [pc, #716] ; (80030b0 ) - 8002de2: 689b ldr r3, [r3, #8] - 8002de4: 4ab2 ldr r2, [pc, #712] ; (80030b0 ) - 8002de6: f423 13f8 bic.w r3, r3, #2031616 ; 0x1f0000 - 8002dea: 6093 str r3, [r2, #8] - 8002dec: 4bb0 ldr r3, [pc, #704] ; (80030b0 ) - 8002dee: 6f1a ldr r2, [r3, #112] ; 0x70 - 8002df0: 687b ldr r3, [r7, #4] - 8002df2: 6b1b ldr r3, [r3, #48] ; 0x30 - 8002df4: f3c3 030b ubfx r3, r3, #0, #12 - 8002df8: 49ad ldr r1, [pc, #692] ; (80030b0 ) - 8002dfa: 4313 orrs r3, r2 - 8002dfc: 670b str r3, [r1, #112] ; 0x70 + 8002e32: 687b ldr r3, [r7, #4] + 8002e34: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002e36: f403 7340 and.w r3, r3, #768 ; 0x300 + 8002e3a: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8002e3e: d111 bne.n 8002e64 + 8002e40: 4b05 ldr r3, [pc, #20] ; (8002e58 ) + 8002e42: 689b ldr r3, [r3, #8] + 8002e44: f423 12f8 bic.w r2, r3, #2031616 ; 0x1f0000 + 8002e48: 687b ldr r3, [r7, #4] + 8002e4a: 6b19 ldr r1, [r3, #48] ; 0x30 + 8002e4c: 4b04 ldr r3, [pc, #16] ; (8002e60 ) + 8002e4e: 400b ands r3, r1 + 8002e50: 4901 ldr r1, [pc, #4] ; (8002e58 ) + 8002e52: 4313 orrs r3, r2 + 8002e54: 608b str r3, [r1, #8] + 8002e56: e00b b.n 8002e70 + 8002e58: 40023800 .word 0x40023800 + 8002e5c: 40007000 .word 0x40007000 + 8002e60: 0ffffcff .word 0x0ffffcff + 8002e64: 4bb3 ldr r3, [pc, #716] ; (8003134 ) + 8002e66: 689b ldr r3, [r3, #8] + 8002e68: 4ab2 ldr r2, [pc, #712] ; (8003134 ) + 8002e6a: f423 13f8 bic.w r3, r3, #2031616 ; 0x1f0000 + 8002e6e: 6093 str r3, [r2, #8] + 8002e70: 4bb0 ldr r3, [pc, #704] ; (8003134 ) + 8002e72: 6f1a ldr r2, [r3, #112] ; 0x70 + 8002e74: 687b ldr r3, [r7, #4] + 8002e76: 6b1b ldr r3, [r3, #48] ; 0x30 + 8002e78: f3c3 030b ubfx r3, r3, #0, #12 + 8002e7c: 49ad ldr r1, [pc, #692] ; (8003134 ) + 8002e7e: 4313 orrs r3, r2 + 8002e80: 670b str r3, [r1, #112] ; 0x70 } /*------------------------------------ TIM configuration --------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - 8002dfe: 687b ldr r3, [r7, #4] - 8002e00: 681b ldr r3, [r3, #0] - 8002e02: f003 0310 and.w r3, r3, #16 - 8002e06: 2b00 cmp r3, #0 - 8002e08: d010 beq.n 8002e2c + 8002e82: 687b ldr r3, [r7, #4] + 8002e84: 681b ldr r3, [r3, #0] + 8002e86: f003 0310 and.w r3, r3, #16 + 8002e8a: 2b00 cmp r3, #0 + 8002e8c: d010 beq.n 8002eb0 { /* Check the parameters */ assert_param(IS_RCC_TIMPRES(PeriphClkInit->TIMPresSelection)); /* Configure Timer Prescaler */ __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - 8002e0a: 4ba9 ldr r3, [pc, #676] ; (80030b0 ) - 8002e0c: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8002e10: 4aa7 ldr r2, [pc, #668] ; (80030b0 ) - 8002e12: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 - 8002e16: f8c2 308c str.w r3, [r2, #140] ; 0x8c - 8002e1a: 4ba5 ldr r3, [pc, #660] ; (80030b0 ) - 8002e1c: f8d3 208c ldr.w r2, [r3, #140] ; 0x8c - 8002e20: 687b ldr r3, [r7, #4] - 8002e22: 6b9b ldr r3, [r3, #56] ; 0x38 - 8002e24: 49a2 ldr r1, [pc, #648] ; (80030b0 ) - 8002e26: 4313 orrs r3, r2 - 8002e28: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8002e8e: 4ba9 ldr r3, [pc, #676] ; (8003134 ) + 8002e90: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8002e94: 4aa7 ldr r2, [pc, #668] ; (8003134 ) + 8002e96: f023 7380 bic.w r3, r3, #16777216 ; 0x1000000 + 8002e9a: f8c2 308c str.w r3, [r2, #140] ; 0x8c + 8002e9e: 4ba5 ldr r3, [pc, #660] ; (8003134 ) + 8002ea0: f8d3 208c ldr.w r2, [r3, #140] ; 0x8c + 8002ea4: 687b ldr r3, [r7, #4] + 8002ea6: 6b9b ldr r3, [r3, #56] ; 0x38 + 8002ea8: 49a2 ldr r1, [pc, #648] ; (8003134 ) + 8002eaa: 4313 orrs r3, r2 + 8002eac: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*-------------------------------------- I2C1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C1) == RCC_PERIPHCLK_I2C1) - 8002e2c: 687b ldr r3, [r7, #4] - 8002e2e: 681b ldr r3, [r3, #0] - 8002e30: f403 4380 and.w r3, r3, #16384 ; 0x4000 - 8002e34: 2b00 cmp r3, #0 - 8002e36: d00a beq.n 8002e4e + 8002eb0: 687b ldr r3, [r7, #4] + 8002eb2: 681b ldr r3, [r3, #0] + 8002eb4: f403 4380 and.w r3, r3, #16384 ; 0x4000 + 8002eb8: 2b00 cmp r3, #0 + 8002eba: d00a beq.n 8002ed2 { /* Check the parameters */ assert_param(IS_RCC_I2C1CLKSOURCE(PeriphClkInit->I2c1ClockSelection)); /* Configure the I2C1 clock source */ __HAL_RCC_I2C1_CONFIG(PeriphClkInit->I2c1ClockSelection); - 8002e38: 4b9d ldr r3, [pc, #628] ; (80030b0 ) - 8002e3a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002e3e: f423 3240 bic.w r2, r3, #196608 ; 0x30000 - 8002e42: 687b ldr r3, [r7, #4] - 8002e44: 6e5b ldr r3, [r3, #100] ; 0x64 - 8002e46: 499a ldr r1, [pc, #616] ; (80030b0 ) - 8002e48: 4313 orrs r3, r2 - 8002e4a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002ebc: 4b9d ldr r3, [pc, #628] ; (8003134 ) + 8002ebe: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002ec2: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8002ec6: 687b ldr r3, [r7, #4] + 8002ec8: 6e5b ldr r3, [r3, #100] ; 0x64 + 8002eca: 499a ldr r1, [pc, #616] ; (8003134 ) + 8002ecc: 4313 orrs r3, r2 + 8002ece: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C2 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C2) == RCC_PERIPHCLK_I2C2) - 8002e4e: 687b ldr r3, [r7, #4] - 8002e50: 681b ldr r3, [r3, #0] - 8002e52: f403 4300 and.w r3, r3, #32768 ; 0x8000 - 8002e56: 2b00 cmp r3, #0 - 8002e58: d00a beq.n 8002e70 + 8002ed2: 687b ldr r3, [r7, #4] + 8002ed4: 681b ldr r3, [r3, #0] + 8002ed6: f403 4300 and.w r3, r3, #32768 ; 0x8000 + 8002eda: 2b00 cmp r3, #0 + 8002edc: d00a beq.n 8002ef4 { /* Check the parameters */ assert_param(IS_RCC_I2C2CLKSOURCE(PeriphClkInit->I2c2ClockSelection)); /* Configure the I2C2 clock source */ __HAL_RCC_I2C2_CONFIG(PeriphClkInit->I2c2ClockSelection); - 8002e5a: 4b95 ldr r3, [pc, #596] ; (80030b0 ) - 8002e5c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002e60: f423 2240 bic.w r2, r3, #786432 ; 0xc0000 - 8002e64: 687b ldr r3, [r7, #4] - 8002e66: 6e9b ldr r3, [r3, #104] ; 0x68 - 8002e68: 4991 ldr r1, [pc, #580] ; (80030b0 ) - 8002e6a: 4313 orrs r3, r2 - 8002e6c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002ede: 4b95 ldr r3, [pc, #596] ; (8003134 ) + 8002ee0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002ee4: f423 2240 bic.w r2, r3, #786432 ; 0xc0000 + 8002ee8: 687b ldr r3, [r7, #4] + 8002eea: 6e9b ldr r3, [r3, #104] ; 0x68 + 8002eec: 4991 ldr r1, [pc, #580] ; (8003134 ) + 8002eee: 4313 orrs r3, r2 + 8002ef0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C3 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C3) == RCC_PERIPHCLK_I2C3) - 8002e70: 687b ldr r3, [r7, #4] - 8002e72: 681b ldr r3, [r3, #0] - 8002e74: f403 3380 and.w r3, r3, #65536 ; 0x10000 - 8002e78: 2b00 cmp r3, #0 - 8002e7a: d00a beq.n 8002e92 + 8002ef4: 687b ldr r3, [r7, #4] + 8002ef6: 681b ldr r3, [r3, #0] + 8002ef8: f403 3380 and.w r3, r3, #65536 ; 0x10000 + 8002efc: 2b00 cmp r3, #0 + 8002efe: d00a beq.n 8002f16 { /* Check the parameters */ assert_param(IS_RCC_I2C3CLKSOURCE(PeriphClkInit->I2c3ClockSelection)); /* Configure the I2C3 clock source */ __HAL_RCC_I2C3_CONFIG(PeriphClkInit->I2c3ClockSelection); - 8002e7c: 4b8c ldr r3, [pc, #560] ; (80030b0 ) - 8002e7e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002e82: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 - 8002e86: 687b ldr r3, [r7, #4] - 8002e88: 6edb ldr r3, [r3, #108] ; 0x6c - 8002e8a: 4989 ldr r1, [pc, #548] ; (80030b0 ) - 8002e8c: 4313 orrs r3, r2 - 8002e8e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002f00: 4b8c ldr r3, [pc, #560] ; (8003134 ) + 8002f02: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002f06: f423 1240 bic.w r2, r3, #3145728 ; 0x300000 + 8002f0a: 687b ldr r3, [r7, #4] + 8002f0c: 6edb ldr r3, [r3, #108] ; 0x6c + 8002f0e: 4989 ldr r1, [pc, #548] ; (8003134 ) + 8002f10: 4313 orrs r3, r2 + 8002f12: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- I2C4 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C4) == RCC_PERIPHCLK_I2C4) - 8002e92: 687b ldr r3, [r7, #4] - 8002e94: 681b ldr r3, [r3, #0] - 8002e96: f403 3300 and.w r3, r3, #131072 ; 0x20000 - 8002e9a: 2b00 cmp r3, #0 - 8002e9c: d00a beq.n 8002eb4 + 8002f16: 687b ldr r3, [r7, #4] + 8002f18: 681b ldr r3, [r3, #0] + 8002f1a: f403 3300 and.w r3, r3, #131072 ; 0x20000 + 8002f1e: 2b00 cmp r3, #0 + 8002f20: d00a beq.n 8002f38 { /* Check the parameters */ assert_param(IS_RCC_I2C4CLKSOURCE(PeriphClkInit->I2c4ClockSelection)); /* Configure the I2C4 clock source */ __HAL_RCC_I2C4_CONFIG(PeriphClkInit->I2c4ClockSelection); - 8002e9e: 4b84 ldr r3, [pc, #528] ; (80030b0 ) - 8002ea0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002ea4: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 - 8002ea8: 687b ldr r3, [r7, #4] - 8002eaa: 6f1b ldr r3, [r3, #112] ; 0x70 - 8002eac: 4980 ldr r1, [pc, #512] ; (80030b0 ) - 8002eae: 4313 orrs r3, r2 - 8002eb0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002f22: 4b84 ldr r3, [pc, #528] ; (8003134 ) + 8002f24: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002f28: f423 0240 bic.w r2, r3, #12582912 ; 0xc00000 + 8002f2c: 687b ldr r3, [r7, #4] + 8002f2e: 6f1b ldr r3, [r3, #112] ; 0x70 + 8002f30: 4980 ldr r1, [pc, #512] ; (8003134 ) + 8002f32: 4313 orrs r3, r2 + 8002f34: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART1) == RCC_PERIPHCLK_USART1) - 8002eb4: 687b ldr r3, [r7, #4] - 8002eb6: 681b ldr r3, [r3, #0] - 8002eb8: f003 0340 and.w r3, r3, #64 ; 0x40 - 8002ebc: 2b00 cmp r3, #0 - 8002ebe: d00a beq.n 8002ed6 + 8002f38: 687b ldr r3, [r7, #4] + 8002f3a: 681b ldr r3, [r3, #0] + 8002f3c: f003 0340 and.w r3, r3, #64 ; 0x40 + 8002f40: 2b00 cmp r3, #0 + 8002f42: d00a beq.n 8002f5a { /* Check the parameters */ assert_param(IS_RCC_USART1CLKSOURCE(PeriphClkInit->Usart1ClockSelection)); /* Configure the USART1 clock source */ __HAL_RCC_USART1_CONFIG(PeriphClkInit->Usart1ClockSelection); - 8002ec0: 4b7b ldr r3, [pc, #492] ; (80030b0 ) - 8002ec2: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002ec6: f023 0203 bic.w r2, r3, #3 - 8002eca: 687b ldr r3, [r7, #4] - 8002ecc: 6c5b ldr r3, [r3, #68] ; 0x44 - 8002ece: 4978 ldr r1, [pc, #480] ; (80030b0 ) - 8002ed0: 4313 orrs r3, r2 - 8002ed2: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002f44: 4b7b ldr r3, [pc, #492] ; (8003134 ) + 8002f46: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002f4a: f023 0203 bic.w r2, r3, #3 + 8002f4e: 687b ldr r3, [r7, #4] + 8002f50: 6c5b ldr r3, [r3, #68] ; 0x44 + 8002f52: 4978 ldr r1, [pc, #480] ; (8003134 ) + 8002f54: 4313 orrs r3, r2 + 8002f56: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART2 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART2) == RCC_PERIPHCLK_USART2) - 8002ed6: 687b ldr r3, [r7, #4] - 8002ed8: 681b ldr r3, [r3, #0] - 8002eda: f003 0380 and.w r3, r3, #128 ; 0x80 - 8002ede: 2b00 cmp r3, #0 - 8002ee0: d00a beq.n 8002ef8 + 8002f5a: 687b ldr r3, [r7, #4] + 8002f5c: 681b ldr r3, [r3, #0] + 8002f5e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8002f62: 2b00 cmp r3, #0 + 8002f64: d00a beq.n 8002f7c { /* Check the parameters */ assert_param(IS_RCC_USART2CLKSOURCE(PeriphClkInit->Usart2ClockSelection)); /* Configure the USART2 clock source */ __HAL_RCC_USART2_CONFIG(PeriphClkInit->Usart2ClockSelection); - 8002ee2: 4b73 ldr r3, [pc, #460] ; (80030b0 ) - 8002ee4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002ee8: f023 020c bic.w r2, r3, #12 - 8002eec: 687b ldr r3, [r7, #4] - 8002eee: 6c9b ldr r3, [r3, #72] ; 0x48 - 8002ef0: 496f ldr r1, [pc, #444] ; (80030b0 ) - 8002ef2: 4313 orrs r3, r2 - 8002ef4: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002f66: 4b73 ldr r3, [pc, #460] ; (8003134 ) + 8002f68: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002f6c: f023 020c bic.w r2, r3, #12 + 8002f70: 687b ldr r3, [r7, #4] + 8002f72: 6c9b ldr r3, [r3, #72] ; 0x48 + 8002f74: 496f ldr r1, [pc, #444] ; (8003134 ) + 8002f76: 4313 orrs r3, r2 + 8002f78: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART3 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART3) == RCC_PERIPHCLK_USART3) - 8002ef8: 687b ldr r3, [r7, #4] - 8002efa: 681b ldr r3, [r3, #0] - 8002efc: f403 7380 and.w r3, r3, #256 ; 0x100 - 8002f00: 2b00 cmp r3, #0 - 8002f02: d00a beq.n 8002f1a + 8002f7c: 687b ldr r3, [r7, #4] + 8002f7e: 681b ldr r3, [r3, #0] + 8002f80: f403 7380 and.w r3, r3, #256 ; 0x100 + 8002f84: 2b00 cmp r3, #0 + 8002f86: d00a beq.n 8002f9e { /* Check the parameters */ assert_param(IS_RCC_USART3CLKSOURCE(PeriphClkInit->Usart3ClockSelection)); /* Configure the USART3 clock source */ __HAL_RCC_USART3_CONFIG(PeriphClkInit->Usart3ClockSelection); - 8002f04: 4b6a ldr r3, [pc, #424] ; (80030b0 ) - 8002f06: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002f0a: f023 0230 bic.w r2, r3, #48 ; 0x30 - 8002f0e: 687b ldr r3, [r7, #4] - 8002f10: 6cdb ldr r3, [r3, #76] ; 0x4c - 8002f12: 4967 ldr r1, [pc, #412] ; (80030b0 ) - 8002f14: 4313 orrs r3, r2 - 8002f16: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002f88: 4b6a ldr r3, [pc, #424] ; (8003134 ) + 8002f8a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002f8e: f023 0230 bic.w r2, r3, #48 ; 0x30 + 8002f92: 687b ldr r3, [r7, #4] + 8002f94: 6cdb ldr r3, [r3, #76] ; 0x4c + 8002f96: 4967 ldr r1, [pc, #412] ; (8003134 ) + 8002f98: 4313 orrs r3, r2 + 8002f9a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART4 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART4) == RCC_PERIPHCLK_UART4) - 8002f1a: 687b ldr r3, [r7, #4] - 8002f1c: 681b ldr r3, [r3, #0] - 8002f1e: f403 7300 and.w r3, r3, #512 ; 0x200 - 8002f22: 2b00 cmp r3, #0 - 8002f24: d00a beq.n 8002f3c + 8002f9e: 687b ldr r3, [r7, #4] + 8002fa0: 681b ldr r3, [r3, #0] + 8002fa2: f403 7300 and.w r3, r3, #512 ; 0x200 + 8002fa6: 2b00 cmp r3, #0 + 8002fa8: d00a beq.n 8002fc0 { /* Check the parameters */ assert_param(IS_RCC_UART4CLKSOURCE(PeriphClkInit->Uart4ClockSelection)); /* Configure the UART4 clock source */ __HAL_RCC_UART4_CONFIG(PeriphClkInit->Uart4ClockSelection); - 8002f26: 4b62 ldr r3, [pc, #392] ; (80030b0 ) - 8002f28: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002f2c: f023 02c0 bic.w r2, r3, #192 ; 0xc0 - 8002f30: 687b ldr r3, [r7, #4] - 8002f32: 6d1b ldr r3, [r3, #80] ; 0x50 - 8002f34: 495e ldr r1, [pc, #376] ; (80030b0 ) - 8002f36: 4313 orrs r3, r2 - 8002f38: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002faa: 4b62 ldr r3, [pc, #392] ; (8003134 ) + 8002fac: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002fb0: f023 02c0 bic.w r2, r3, #192 ; 0xc0 + 8002fb4: 687b ldr r3, [r7, #4] + 8002fb6: 6d1b ldr r3, [r3, #80] ; 0x50 + 8002fb8: 495e ldr r1, [pc, #376] ; (8003134 ) + 8002fba: 4313 orrs r3, r2 + 8002fbc: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART5 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART5) == RCC_PERIPHCLK_UART5) - 8002f3c: 687b ldr r3, [r7, #4] - 8002f3e: 681b ldr r3, [r3, #0] - 8002f40: f403 6380 and.w r3, r3, #1024 ; 0x400 - 8002f44: 2b00 cmp r3, #0 - 8002f46: d00a beq.n 8002f5e + 8002fc0: 687b ldr r3, [r7, #4] + 8002fc2: 681b ldr r3, [r3, #0] + 8002fc4: f403 6380 and.w r3, r3, #1024 ; 0x400 + 8002fc8: 2b00 cmp r3, #0 + 8002fca: d00a beq.n 8002fe2 { /* Check the parameters */ assert_param(IS_RCC_UART5CLKSOURCE(PeriphClkInit->Uart5ClockSelection)); /* Configure the UART5 clock source */ __HAL_RCC_UART5_CONFIG(PeriphClkInit->Uart5ClockSelection); - 8002f48: 4b59 ldr r3, [pc, #356] ; (80030b0 ) - 8002f4a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002f4e: f423 7240 bic.w r2, r3, #768 ; 0x300 - 8002f52: 687b ldr r3, [r7, #4] - 8002f54: 6d5b ldr r3, [r3, #84] ; 0x54 - 8002f56: 4956 ldr r1, [pc, #344] ; (80030b0 ) - 8002f58: 4313 orrs r3, r2 - 8002f5a: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002fcc: 4b59 ldr r3, [pc, #356] ; (8003134 ) + 8002fce: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002fd2: f423 7240 bic.w r2, r3, #768 ; 0x300 + 8002fd6: 687b ldr r3, [r7, #4] + 8002fd8: 6d5b ldr r3, [r3, #84] ; 0x54 + 8002fda: 4956 ldr r1, [pc, #344] ; (8003134 ) + 8002fdc: 4313 orrs r3, r2 + 8002fde: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- USART6 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART6) == RCC_PERIPHCLK_USART6) - 8002f5e: 687b ldr r3, [r7, #4] - 8002f60: 681b ldr r3, [r3, #0] - 8002f62: f403 6300 and.w r3, r3, #2048 ; 0x800 - 8002f66: 2b00 cmp r3, #0 - 8002f68: d00a beq.n 8002f80 + 8002fe2: 687b ldr r3, [r7, #4] + 8002fe4: 681b ldr r3, [r3, #0] + 8002fe6: f403 6300 and.w r3, r3, #2048 ; 0x800 + 8002fea: 2b00 cmp r3, #0 + 8002fec: d00a beq.n 8003004 { /* Check the parameters */ assert_param(IS_RCC_USART6CLKSOURCE(PeriphClkInit->Usart6ClockSelection)); /* Configure the USART6 clock source */ __HAL_RCC_USART6_CONFIG(PeriphClkInit->Usart6ClockSelection); - 8002f6a: 4b51 ldr r3, [pc, #324] ; (80030b0 ) - 8002f6c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002f70: f423 6240 bic.w r2, r3, #3072 ; 0xc00 - 8002f74: 687b ldr r3, [r7, #4] - 8002f76: 6d9b ldr r3, [r3, #88] ; 0x58 - 8002f78: 494d ldr r1, [pc, #308] ; (80030b0 ) - 8002f7a: 4313 orrs r3, r2 - 8002f7c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8002fee: 4b51 ldr r3, [pc, #324] ; (8003134 ) + 8002ff0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8002ff4: f423 6240 bic.w r2, r3, #3072 ; 0xc00 + 8002ff8: 687b ldr r3, [r7, #4] + 8002ffa: 6d9b ldr r3, [r3, #88] ; 0x58 + 8002ffc: 494d ldr r1, [pc, #308] ; (8003134 ) + 8002ffe: 4313 orrs r3, r2 + 8003000: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART7 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART7) == RCC_PERIPHCLK_UART7) - 8002f80: 687b ldr r3, [r7, #4] - 8002f82: 681b ldr r3, [r3, #0] - 8002f84: f403 5380 and.w r3, r3, #4096 ; 0x1000 - 8002f88: 2b00 cmp r3, #0 - 8002f8a: d00a beq.n 8002fa2 + 8003004: 687b ldr r3, [r7, #4] + 8003006: 681b ldr r3, [r3, #0] + 8003008: f403 5380 and.w r3, r3, #4096 ; 0x1000 + 800300c: 2b00 cmp r3, #0 + 800300e: d00a beq.n 8003026 { /* Check the parameters */ assert_param(IS_RCC_UART7CLKSOURCE(PeriphClkInit->Uart7ClockSelection)); /* Configure the UART7 clock source */ __HAL_RCC_UART7_CONFIG(PeriphClkInit->Uart7ClockSelection); - 8002f8c: 4b48 ldr r3, [pc, #288] ; (80030b0 ) - 8002f8e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002f92: f423 5240 bic.w r2, r3, #12288 ; 0x3000 - 8002f96: 687b ldr r3, [r7, #4] - 8002f98: 6ddb ldr r3, [r3, #92] ; 0x5c - 8002f9a: 4945 ldr r1, [pc, #276] ; (80030b0 ) - 8002f9c: 4313 orrs r3, r2 - 8002f9e: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8003010: 4b48 ldr r3, [pc, #288] ; (8003134 ) + 8003012: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8003016: f423 5240 bic.w r2, r3, #12288 ; 0x3000 + 800301a: 687b ldr r3, [r7, #4] + 800301c: 6ddb ldr r3, [r3, #92] ; 0x5c + 800301e: 4945 ldr r1, [pc, #276] ; (8003134 ) + 8003020: 4313 orrs r3, r2 + 8003022: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- UART8 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_UART8) == RCC_PERIPHCLK_UART8) - 8002fa2: 687b ldr r3, [r7, #4] - 8002fa4: 681b ldr r3, [r3, #0] - 8002fa6: f403 5300 and.w r3, r3, #8192 ; 0x2000 - 8002faa: 2b00 cmp r3, #0 - 8002fac: d00a beq.n 8002fc4 + 8003026: 687b ldr r3, [r7, #4] + 8003028: 681b ldr r3, [r3, #0] + 800302a: f403 5300 and.w r3, r3, #8192 ; 0x2000 + 800302e: 2b00 cmp r3, #0 + 8003030: d00a beq.n 8003048 { /* Check the parameters */ assert_param(IS_RCC_UART8CLKSOURCE(PeriphClkInit->Uart8ClockSelection)); /* Configure the UART8 clock source */ __HAL_RCC_UART8_CONFIG(PeriphClkInit->Uart8ClockSelection); - 8002fae: 4b40 ldr r3, [pc, #256] ; (80030b0 ) - 8002fb0: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002fb4: f423 4240 bic.w r2, r3, #49152 ; 0xc000 - 8002fb8: 687b ldr r3, [r7, #4] - 8002fba: 6e1b ldr r3, [r3, #96] ; 0x60 - 8002fbc: 493c ldr r1, [pc, #240] ; (80030b0 ) - 8002fbe: 4313 orrs r3, r2 - 8002fc0: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8003032: 4b40 ldr r3, [pc, #256] ; (8003134 ) + 8003034: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8003038: f423 4240 bic.w r2, r3, #49152 ; 0xc000 + 800303c: 687b ldr r3, [r7, #4] + 800303e: 6e1b ldr r3, [r3, #96] ; 0x60 + 8003040: 493c ldr r1, [pc, #240] ; (8003134 ) + 8003042: 4313 orrs r3, r2 + 8003044: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*--------------------------------------- CEC Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) - 8002fc4: 687b ldr r3, [r7, #4] - 8002fc6: 681b ldr r3, [r3, #0] - 8002fc8: f403 0380 and.w r3, r3, #4194304 ; 0x400000 - 8002fcc: 2b00 cmp r3, #0 - 8002fce: d00a beq.n 8002fe6 + 8003048: 687b ldr r3, [r7, #4] + 800304a: 681b ldr r3, [r3, #0] + 800304c: f403 0380 and.w r3, r3, #4194304 ; 0x400000 + 8003050: 2b00 cmp r3, #0 + 8003052: d00a beq.n 800306a { /* Check the parameters */ assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); /* Configure the CEC clock source */ __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); - 8002fd0: 4b37 ldr r3, [pc, #220] ; (80030b0 ) - 8002fd2: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002fd6: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 - 8002fda: 687b ldr r3, [r7, #4] - 8002fdc: 6f9b ldr r3, [r3, #120] ; 0x78 - 8002fde: 4934 ldr r1, [pc, #208] ; (80030b0 ) - 8002fe0: 4313 orrs r3, r2 - 8002fe2: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8003054: 4b37 ldr r3, [pc, #220] ; (8003134 ) + 8003056: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 800305a: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 800305e: 687b ldr r3, [r7, #4] + 8003060: 6f9b ldr r3, [r3, #120] ; 0x78 + 8003062: 4934 ldr r1, [pc, #208] ; (8003134 ) + 8003064: 4313 orrs r3, r2 + 8003066: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*-------------------------------------- CK48 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - 8002fe6: 687b ldr r3, [r7, #4] - 8002fe8: 681b ldr r3, [r3, #0] - 8002fea: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 8002fee: 2b00 cmp r3, #0 - 8002ff0: d011 beq.n 8003016 + 800306a: 687b ldr r3, [r7, #4] + 800306c: 681b ldr r3, [r3, #0] + 800306e: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 8003072: 2b00 cmp r3, #0 + 8003074: d011 beq.n 800309a { /* Check the parameters */ assert_param(IS_RCC_CLK48SOURCE(PeriphClkInit->Clk48ClockSelection)); /* Configure the CLK48 source */ __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - 8002ff2: 4b2f ldr r3, [pc, #188] ; (80030b0 ) - 8002ff4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8002ff8: f023 6200 bic.w r2, r3, #134217728 ; 0x8000000 - 8002ffc: 687b ldr r3, [r7, #4] - 8002ffe: 6fdb ldr r3, [r3, #124] ; 0x7c - 8003000: 492b ldr r1, [pc, #172] ; (80030b0 ) - 8003002: 4313 orrs r3, r2 - 8003004: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 8003076: 4b2f ldr r3, [pc, #188] ; (8003134 ) + 8003078: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 800307c: f023 6200 bic.w r2, r3, #134217728 ; 0x8000000 + 8003080: 687b ldr r3, [r7, #4] + 8003082: 6fdb ldr r3, [r3, #124] ; 0x7c + 8003084: 492b ldr r1, [pc, #172] ; (8003134 ) + 8003086: 4313 orrs r3, r2 + 8003088: 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) - 8003008: 687b ldr r3, [r7, #4] - 800300a: 6fdb ldr r3, [r3, #124] ; 0x7c - 800300c: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 - 8003010: d101 bne.n 8003016 + 800308c: 687b ldr r3, [r7, #4] + 800308e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8003090: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 8003094: d101 bne.n 800309a { pllsaiused = 1; - 8003012: 2301 movs r3, #1 - 8003014: 61bb str r3, [r7, #24] + 8003096: 2301 movs r3, #1 + 8003098: 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) - 8003016: 687b ldr r3, [r7, #4] - 8003018: 681b ldr r3, [r3, #0] - 800301a: f003 0308 and.w r3, r3, #8 - 800301e: 2b00 cmp r3, #0 - 8003020: d001 beq.n 8003026 + 800309a: 687b ldr r3, [r7, #4] + 800309c: 681b ldr r3, [r3, #0] + 800309e: f003 0308 and.w r3, r3, #8 + 80030a2: 2b00 cmp r3, #0 + 80030a4: d001 beq.n 80030aa { pllsaiused = 1; - 8003022: 2301 movs r3, #1 - 8003024: 61bb str r3, [r7, #24] + 80030a6: 2301 movs r3, #1 + 80030a8: 61bb str r3, [r7, #24] } #endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ /*-------------------------------------- LPTIM1 Configuration -----------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - 8003026: 687b ldr r3, [r7, #4] - 8003028: 681b ldr r3, [r3, #0] - 800302a: f403 2380 and.w r3, r3, #262144 ; 0x40000 - 800302e: 2b00 cmp r3, #0 - 8003030: d00a beq.n 8003048 + 80030aa: 687b ldr r3, [r7, #4] + 80030ac: 681b ldr r3, [r3, #0] + 80030ae: f403 2380 and.w r3, r3, #262144 ; 0x40000 + 80030b2: 2b00 cmp r3, #0 + 80030b4: d00a beq.n 80030cc { /* Check the parameters */ assert_param(IS_RCC_LPTIM1CLK(PeriphClkInit->Lptim1ClockSelection)); /* Configure the LTPIM1 clock source */ __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - 8003032: 4b1f ldr r3, [pc, #124] ; (80030b0 ) - 8003034: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8003038: f023 7240 bic.w r2, r3, #50331648 ; 0x3000000 - 800303c: 687b ldr r3, [r7, #4] - 800303e: 6f5b ldr r3, [r3, #116] ; 0x74 - 8003040: 491b ldr r1, [pc, #108] ; (80030b0 ) - 8003042: 4313 orrs r3, r2 - 8003044: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 80030b6: 4b1f ldr r3, [pc, #124] ; (8003134 ) + 80030b8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80030bc: f023 7240 bic.w r2, r3, #50331648 ; 0x3000000 + 80030c0: 687b ldr r3, [r7, #4] + 80030c2: 6f5b ldr r3, [r3, #116] ; 0x74 + 80030c4: 491b ldr r1, [pc, #108] ; (8003134 ) + 80030c6: 4313 orrs r3, r2 + 80030c8: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*------------------------------------- SDMMC1 Configuration ------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDMMC1) == RCC_PERIPHCLK_SDMMC1) - 8003048: 687b ldr r3, [r7, #4] - 800304a: 681b ldr r3, [r3, #0] - 800304c: f403 0300 and.w r3, r3, #8388608 ; 0x800000 - 8003050: 2b00 cmp r3, #0 - 8003052: d00b beq.n 800306c + 80030cc: 687b ldr r3, [r7, #4] + 80030ce: 681b ldr r3, [r3, #0] + 80030d0: f403 0300 and.w r3, r3, #8388608 ; 0x800000 + 80030d4: 2b00 cmp r3, #0 + 80030d6: d00b beq.n 80030f0 { /* Check the parameters */ assert_param(IS_RCC_SDMMC1CLKSOURCE(PeriphClkInit->Sdmmc1ClockSelection)); /* Configure the SDMMC1 clock source */ __HAL_RCC_SDMMC1_CONFIG(PeriphClkInit->Sdmmc1ClockSelection); - 8003054: 4b16 ldr r3, [pc, #88] ; (80030b0 ) - 8003056: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 800305a: f023 5280 bic.w r2, r3, #268435456 ; 0x10000000 - 800305e: 687b ldr r3, [r7, #4] - 8003060: f8d3 3080 ldr.w r3, [r3, #128] ; 0x80 - 8003064: 4912 ldr r1, [pc, #72] ; (80030b0 ) - 8003066: 4313 orrs r3, r2 - 8003068: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 80030d8: 4b16 ldr r3, [pc, #88] ; (8003134 ) + 80030da: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 80030de: f023 5280 bic.w r2, r3, #268435456 ; 0x10000000 + 80030e2: 687b ldr r3, [r7, #4] + 80030e4: f8d3 3080 ldr.w r3, [r3, #128] ; 0x80 + 80030e8: 4912 ldr r1, [pc, #72] ; (8003134 ) + 80030ea: 4313 orrs r3, r2 + 80030ec: 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) - 800306c: 687b ldr r3, [r7, #4] - 800306e: 681b ldr r3, [r3, #0] - 8003070: f003 6380 and.w r3, r3, #67108864 ; 0x4000000 - 8003074: 2b00 cmp r3, #0 - 8003076: d00b beq.n 8003090 + 80030f0: 687b ldr r3, [r7, #4] + 80030f2: 681b ldr r3, [r3, #0] + 80030f4: f003 6380 and.w r3, r3, #67108864 ; 0x4000000 + 80030f8: 2b00 cmp r3, #0 + 80030fa: d00b beq.n 8003114 { /* Check the parameters */ assert_param(IS_RCC_SDMMC2CLKSOURCE(PeriphClkInit->Sdmmc2ClockSelection)); /* Configure the SDMMC2 clock source */ __HAL_RCC_SDMMC2_CONFIG(PeriphClkInit->Sdmmc2ClockSelection); - 8003078: 4b0d ldr r3, [pc, #52] ; (80030b0 ) - 800307a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 800307e: f023 5200 bic.w r2, r3, #536870912 ; 0x20000000 - 8003082: 687b ldr r3, [r7, #4] - 8003084: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8003088: 4909 ldr r1, [pc, #36] ; (80030b0 ) - 800308a: 4313 orrs r3, r2 - 800308c: f8c1 3090 str.w r3, [r1, #144] ; 0x90 + 80030fc: 4b0d ldr r3, [pc, #52] ; (8003134 ) + 80030fe: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8003102: f023 5200 bic.w r2, r3, #536870912 ; 0x20000000 + 8003106: 687b ldr r3, [r7, #4] + 8003108: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 800310c: 4909 ldr r1, [pc, #36] ; (8003134 ) + 800310e: 4313 orrs r3, r2 + 8003110: f8c1 3090 str.w r3, [r1, #144] ; 0x90 } /*------------------------------------- DFSDM1 Configuration -------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) - 8003090: 687b ldr r3, [r7, #4] - 8003092: 681b ldr r3, [r3, #0] - 8003094: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 8003098: 2b00 cmp r3, #0 - 800309a: d00f beq.n 80030bc + 8003114: 687b ldr r3, [r7, #4] + 8003116: 681b ldr r3, [r3, #0] + 8003118: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 800311c: 2b00 cmp r3, #0 + 800311e: d00f beq.n 8003140 { /* Check the parameters */ assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); /* Configure the DFSDM1 interface clock source */ __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); - 800309c: 4b04 ldr r3, [pc, #16] ; (80030b0 ) - 800309e: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80030a2: f023 7200 bic.w r2, r3, #33554432 ; 0x2000000 - 80030a6: 687b ldr r3, [r7, #4] - 80030a8: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 80030ac: e002 b.n 80030b4 - 80030ae: bf00 nop - 80030b0: 40023800 .word 0x40023800 - 80030b4: 4985 ldr r1, [pc, #532] ; (80032cc ) - 80030b6: 4313 orrs r3, r2 - 80030b8: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8003120: 4b04 ldr r3, [pc, #16] ; (8003134 ) + 8003122: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003126: f023 7200 bic.w r2, r3, #33554432 ; 0x2000000 + 800312a: 687b ldr r3, [r7, #4] + 800312c: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003130: e002 b.n 8003138 + 8003132: bf00 nop + 8003134: 40023800 .word 0x40023800 + 8003138: 4985 ldr r1, [pc, #532] ; (8003350 ) + 800313a: 4313 orrs r3, r2 + 800313c: f8c1 308c str.w r3, [r1, #140] ; 0x8c } /*------------------------------------- DFSDM AUDIO Configuration -------------------------------------*/ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) - 80030bc: 687b ldr r3, [r7, #4] - 80030be: 681b ldr r3, [r3, #0] - 80030c0: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 - 80030c4: 2b00 cmp r3, #0 - 80030c6: d00b beq.n 80030e0 + 8003140: 687b ldr r3, [r7, #4] + 8003142: 681b ldr r3, [r3, #0] + 8003144: f003 5380 and.w r3, r3, #268435456 ; 0x10000000 + 8003148: 2b00 cmp r3, #0 + 800314a: d00b beq.n 8003164 { /* Check the parameters */ assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); /* Configure the DFSDM interface clock source */ __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); - 80030c8: 4b80 ldr r3, [pc, #512] ; (80032cc ) - 80030ca: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80030ce: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 - 80030d2: 687b ldr r3, [r7, #4] - 80030d4: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80030d8: 497c ldr r1, [pc, #496] ; (80032cc ) - 80030da: 4313 orrs r3, r2 - 80030dc: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 800314c: 4b80 ldr r3, [pc, #512] ; (8003350 ) + 800314e: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003152: f023 6280 bic.w r2, r3, #67108864 ; 0x4000000 + 8003156: 687b ldr r3, [r7, #4] + 8003158: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 800315c: 497c ldr r1, [pc, #496] ; (8003350 ) + 800315e: 4313 orrs r3, r2 + 8003160: 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)) - 80030e0: 69fb ldr r3, [r7, #28] - 80030e2: 2b01 cmp r3, #1 - 80030e4: d005 beq.n 80030f2 - 80030e6: 687b ldr r3, [r7, #4] - 80030e8: 681b ldr r3, [r3, #0] - 80030ea: f1b3 7f00 cmp.w r3, #33554432 ; 0x2000000 - 80030ee: f040 80d6 bne.w 800329e + 8003164: 69fb ldr r3, [r7, #28] + 8003166: 2b01 cmp r3, #1 + 8003168: d005 beq.n 8003176 + 800316a: 687b ldr r3, [r7, #4] + 800316c: 681b ldr r3, [r3, #0] + 800316e: f1b3 7f00 cmp.w r3, #33554432 ; 0x2000000 + 8003172: f040 80d6 bne.w 8003322 { /* Disable the PLLI2S */ __HAL_RCC_PLLI2S_DISABLE(); - 80030f2: 4b76 ldr r3, [pc, #472] ; (80032cc ) - 80030f4: 681b ldr r3, [r3, #0] - 80030f6: 4a75 ldr r2, [pc, #468] ; (80032cc ) - 80030f8: f023 6380 bic.w r3, r3, #67108864 ; 0x4000000 - 80030fc: 6013 str r3, [r2, #0] + 8003176: 4b76 ldr r3, [pc, #472] ; (8003350 ) + 8003178: 681b ldr r3, [r3, #0] + 800317a: 4a75 ldr r2, [pc, #468] ; (8003350 ) + 800317c: f023 6380 bic.w r3, r3, #67108864 ; 0x4000000 + 8003180: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80030fe: f7fe fe25 bl 8001d4c - 8003102: 6178 str r0, [r7, #20] + 8003182: f7fe fe25 bl 8001dd0 + 8003186: 6178 str r0, [r7, #20] /* Wait till PLLI2S is disabled */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - 8003104: e008 b.n 8003118 + 8003188: e008 b.n 800319c { if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - 8003106: f7fe fe21 bl 8001d4c - 800310a: 4602 mov r2, r0 - 800310c: 697b ldr r3, [r7, #20] - 800310e: 1ad3 subs r3, r2, r3 - 8003110: 2b64 cmp r3, #100 ; 0x64 - 8003112: d901 bls.n 8003118 + 800318a: f7fe fe21 bl 8001dd0 + 800318e: 4602 mov r2, r0 + 8003190: 697b ldr r3, [r7, #20] + 8003192: 1ad3 subs r3, r2, r3 + 8003194: 2b64 cmp r3, #100 ; 0x64 + 8003196: d901 bls.n 800319c { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 8003114: 2303 movs r3, #3 - 8003116: e194 b.n 8003442 + 8003198: 2303 movs r3, #3 + 800319a: e194 b.n 80034c6 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - 8003118: 4b6c ldr r3, [pc, #432] ; (80032cc ) - 800311a: 681b ldr r3, [r3, #0] - 800311c: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 8003120: 2b00 cmp r3, #0 - 8003122: d1f0 bne.n 8003106 + 800319c: 4b6c ldr r3, [pc, #432] ; (8003350 ) + 800319e: 681b ldr r3, [r3, #0] + 80031a0: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 80031a4: 2b00 cmp r3, #0 + 80031a6: d1f0 bne.n 800318a /* 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))) - 8003124: 687b ldr r3, [r7, #4] - 8003126: 681b ldr r3, [r3, #0] - 8003128: f003 0301 and.w r3, r3, #1 - 800312c: 2b00 cmp r3, #0 - 800312e: d021 beq.n 8003174 - 8003130: 687b ldr r3, [r7, #4] - 8003132: 6b5b ldr r3, [r3, #52] ; 0x34 - 8003134: 2b00 cmp r3, #0 - 8003136: d11d bne.n 8003174 + 80031a8: 687b ldr r3, [r7, #4] + 80031aa: 681b ldr r3, [r3, #0] + 80031ac: f003 0301 and.w r3, r3, #1 + 80031b0: 2b00 cmp r3, #0 + 80031b2: d021 beq.n 80031f8 + 80031b4: 687b ldr r3, [r7, #4] + 80031b6: 6b5b ldr r3, [r3, #52] ; 0x34 + 80031b8: 2b00 cmp r3, #0 + 80031ba: d11d bne.n 80031f8 { /* 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); - 8003138: 4b64 ldr r3, [pc, #400] ; (80032cc ) - 800313a: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 800313e: 0c1b lsrs r3, r3, #16 - 8003140: f003 0303 and.w r3, r3, #3 - 8003144: 613b str r3, [r7, #16] + 80031bc: 4b64 ldr r3, [pc, #400] ; (8003350 ) + 80031be: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 80031c2: 0c1b lsrs r3, r3, #16 + 80031c4: f003 0303 and.w r3, r3, #3 + 80031c8: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - 8003146: 4b61 ldr r3, [pc, #388] ; (80032cc ) - 8003148: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 800314c: 0e1b lsrs r3, r3, #24 - 800314e: f003 030f and.w r3, r3, #15 - 8003152: 60fb str r3, [r7, #12] + 80031ca: 4b61 ldr r3, [pc, #388] ; (8003350 ) + 80031cc: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 80031d0: 0e1b lsrs r3, r3, #24 + 80031d2: f003 030f and.w r3, r3, #15 + 80031d6: 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); - 8003154: 687b ldr r3, [r7, #4] - 8003156: 685b ldr r3, [r3, #4] - 8003158: 019a lsls r2, r3, #6 - 800315a: 693b ldr r3, [r7, #16] - 800315c: 041b lsls r3, r3, #16 - 800315e: 431a orrs r2, r3 - 8003160: 68fb ldr r3, [r7, #12] - 8003162: 061b lsls r3, r3, #24 - 8003164: 431a orrs r2, r3 - 8003166: 687b ldr r3, [r7, #4] - 8003168: 689b ldr r3, [r3, #8] - 800316a: 071b lsls r3, r3, #28 - 800316c: 4957 ldr r1, [pc, #348] ; (80032cc ) - 800316e: 4313 orrs r3, r2 - 8003170: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 80031d8: 687b ldr r3, [r7, #4] + 80031da: 685b ldr r3, [r3, #4] + 80031dc: 019a lsls r2, r3, #6 + 80031de: 693b ldr r3, [r7, #16] + 80031e0: 041b lsls r3, r3, #16 + 80031e2: 431a orrs r2, r3 + 80031e4: 68fb ldr r3, [r7, #12] + 80031e6: 061b lsls r3, r3, #24 + 80031e8: 431a orrs r2, r3 + 80031ea: 687b ldr r3, [r7, #4] + 80031ec: 689b ldr r3, [r3, #8] + 80031ee: 071b lsls r3, r3, #28 + 80031f0: 4957 ldr r1, [pc, #348] ; (8003350 ) + 80031f2: 4313 orrs r3, r2 + 80031f4: 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)) || - 8003174: 687b ldr r3, [r7, #4] - 8003176: 681b ldr r3, [r3, #0] - 8003178: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 800317c: 2b00 cmp r3, #0 - 800317e: d004 beq.n 800318a - 8003180: 687b ldr r3, [r7, #4] - 8003182: 6bdb ldr r3, [r3, #60] ; 0x3c - 8003184: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 8003188: d00a beq.n 80031a0 + 80031f8: 687b ldr r3, [r7, #4] + 80031fa: 681b ldr r3, [r3, #0] + 80031fc: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 8003200: 2b00 cmp r3, #0 + 8003202: d004 beq.n 800320e + 8003204: 687b ldr r3, [r7, #4] + 8003206: 6bdb ldr r3, [r3, #60] ; 0x3c + 8003208: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 800320c: d00a beq.n 8003224 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - 800318a: 687b ldr r3, [r7, #4] - 800318c: 681b ldr r3, [r3, #0] - 800318e: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 800320e: 687b ldr r3, [r7, #4] + 8003210: 681b ldr r3, [r3, #0] + 8003212: f403 1380 and.w r3, r3, #1048576 ; 0x100000 if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || - 8003192: 2b00 cmp r3, #0 - 8003194: d02e beq.n 80031f4 + 8003216: 2b00 cmp r3, #0 + 8003218: d02e beq.n 8003278 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - 8003196: 687b ldr r3, [r7, #4] - 8003198: 6c1b ldr r3, [r3, #64] ; 0x40 - 800319a: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 - 800319e: d129 bne.n 80031f4 + 800321a: 687b ldr r3, [r7, #4] + 800321c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800321e: f5b3 0f80 cmp.w r3, #4194304 ; 0x400000 + 8003222: d129 bne.n 8003278 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); - 80031a0: 4b4a ldr r3, [pc, #296] ; (80032cc ) - 80031a2: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 80031a6: 0c1b lsrs r3, r3, #16 - 80031a8: f003 0303 and.w r3, r3, #3 - 80031ac: 613b str r3, [r7, #16] + 8003224: 4b4a ldr r3, [pc, #296] ; (8003350 ) + 8003226: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 800322a: 0c1b lsrs r3, r3, #16 + 800322c: f003 0303 and.w r3, r3, #3 + 8003230: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - 80031ae: 4b47 ldr r3, [pc, #284] ; (80032cc ) - 80031b0: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 80031b4: 0f1b lsrs r3, r3, #28 - 80031b6: f003 0307 and.w r3, r3, #7 - 80031ba: 60fb str r3, [r7, #12] + 8003232: 4b47 ldr r3, [pc, #284] ; (8003350 ) + 8003234: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8003238: 0f1b lsrs r3, r3, #28 + 800323a: f003 0307 and.w r3, r3, #7 + 800323e: 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); - 80031bc: 687b ldr r3, [r7, #4] - 80031be: 685b ldr r3, [r3, #4] - 80031c0: 019a lsls r2, r3, #6 - 80031c2: 693b ldr r3, [r7, #16] - 80031c4: 041b lsls r3, r3, #16 - 80031c6: 431a orrs r2, r3 - 80031c8: 687b ldr r3, [r7, #4] - 80031ca: 68db ldr r3, [r3, #12] - 80031cc: 061b lsls r3, r3, #24 - 80031ce: 431a orrs r2, r3 - 80031d0: 68fb ldr r3, [r7, #12] - 80031d2: 071b lsls r3, r3, #28 - 80031d4: 493d ldr r1, [pc, #244] ; (80032cc ) - 80031d6: 4313 orrs r3, r2 - 80031d8: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 8003240: 687b ldr r3, [r7, #4] + 8003242: 685b ldr r3, [r3, #4] + 8003244: 019a lsls r2, r3, #6 + 8003246: 693b ldr r3, [r7, #16] + 8003248: 041b lsls r3, r3, #16 + 800324a: 431a orrs r2, r3 + 800324c: 687b ldr r3, [r7, #4] + 800324e: 68db ldr r3, [r3, #12] + 8003250: 061b lsls r3, r3, #24 + 8003252: 431a orrs r2, r3 + 8003254: 68fb ldr r3, [r7, #12] + 8003256: 071b lsls r3, r3, #28 + 8003258: 493d ldr r1, [pc, #244] ; (8003350 ) + 800325a: 4313 orrs r3, r2 + 800325c: f8c1 3084 str.w r3, [r1, #132] ; 0x84 /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - 80031dc: 4b3b ldr r3, [pc, #236] ; (80032cc ) - 80031de: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80031e2: f023 021f bic.w r2, r3, #31 - 80031e6: 687b ldr r3, [r7, #4] - 80031e8: 6a5b ldr r3, [r3, #36] ; 0x24 - 80031ea: 3b01 subs r3, #1 - 80031ec: 4937 ldr r1, [pc, #220] ; (80032cc ) - 80031ee: 4313 orrs r3, r2 - 80031f0: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 8003260: 4b3b ldr r3, [pc, #236] ; (8003350 ) + 8003262: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003266: f023 021f bic.w r2, r3, #31 + 800326a: 687b ldr r3, [r7, #4] + 800326c: 6a5b ldr r3, [r3, #36] ; 0x24 + 800326e: 3b01 subs r3, #1 + 8003270: 4937 ldr r1, [pc, #220] ; (8003350 ) + 8003272: 4313 orrs r3, r2 + 8003274: 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) - 80031f4: 687b ldr r3, [r7, #4] - 80031f6: 681b ldr r3, [r3, #0] - 80031f8: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 - 80031fc: 2b00 cmp r3, #0 - 80031fe: d01d beq.n 800323c + 8003278: 687b ldr r3, [r7, #4] + 800327a: 681b ldr r3, [r3, #0] + 800327c: f003 7380 and.w r3, r3, #16777216 ; 0x1000000 + 8003280: 2b00 cmp r3, #0 + 8003282: d01d beq.n 80032c0 { /* 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); - 8003200: 4b32 ldr r3, [pc, #200] ; (80032cc ) - 8003202: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8003206: 0e1b lsrs r3, r3, #24 - 8003208: f003 030f and.w r3, r3, #15 - 800320c: 613b str r3, [r7, #16] + 8003284: 4b32 ldr r3, [pc, #200] ; (8003350 ) + 8003286: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 800328a: 0e1b lsrs r3, r3, #24 + 800328c: f003 030f and.w r3, r3, #15 + 8003290: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - 800320e: 4b2f ldr r3, [pc, #188] ; (80032cc ) - 8003210: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 - 8003214: 0f1b lsrs r3, r3, #28 - 8003216: f003 0307 and.w r3, r3, #7 - 800321a: 60fb str r3, [r7, #12] + 8003292: 4b2f ldr r3, [pc, #188] ; (8003350 ) + 8003294: f8d3 3084 ldr.w r3, [r3, #132] ; 0x84 + 8003298: 0f1b lsrs r3, r3, #28 + 800329a: f003 0307 and.w r3, r3, #7 + 800329e: 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); - 800321c: 687b ldr r3, [r7, #4] - 800321e: 685b ldr r3, [r3, #4] - 8003220: 019a lsls r2, r3, #6 - 8003222: 687b ldr r3, [r7, #4] - 8003224: 691b ldr r3, [r3, #16] - 8003226: 041b lsls r3, r3, #16 - 8003228: 431a orrs r2, r3 - 800322a: 693b ldr r3, [r7, #16] - 800322c: 061b lsls r3, r3, #24 - 800322e: 431a orrs r2, r3 - 8003230: 68fb ldr r3, [r7, #12] - 8003232: 071b lsls r3, r3, #28 - 8003234: 4925 ldr r1, [pc, #148] ; (80032cc ) - 8003236: 4313 orrs r3, r2 - 8003238: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 80032a0: 687b ldr r3, [r7, #4] + 80032a2: 685b ldr r3, [r3, #4] + 80032a4: 019a lsls r2, r3, #6 + 80032a6: 687b ldr r3, [r7, #4] + 80032a8: 691b ldr r3, [r3, #16] + 80032aa: 041b lsls r3, r3, #16 + 80032ac: 431a orrs r2, r3 + 80032ae: 693b ldr r3, [r7, #16] + 80032b0: 061b lsls r3, r3, #24 + 80032b2: 431a orrs r2, r3 + 80032b4: 68fb ldr r3, [r7, #12] + 80032b6: 071b lsls r3, r3, #28 + 80032b8: 4925 ldr r1, [pc, #148] ; (8003350 ) + 80032ba: 4313 orrs r3, r2 + 80032bc: f8c1 3084 str.w r3, [r1, #132] ; 0x84 } /*----------------- In Case of PLLI2S is just selected -----------------*/ if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - 800323c: 687b ldr r3, [r7, #4] - 800323e: 681b ldr r3, [r3, #0] - 8003240: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 - 8003244: 2b00 cmp r3, #0 - 8003246: d011 beq.n 800326c + 80032c0: 687b ldr r3, [r7, #4] + 80032c2: 681b ldr r3, [r3, #0] + 80032c4: f003 7300 and.w r3, r3, #33554432 ; 0x2000000 + 80032c8: 2b00 cmp r3, #0 + 80032ca: d011 beq.n 80032f0 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); - 8003248: 687b ldr r3, [r7, #4] - 800324a: 685b ldr r3, [r3, #4] - 800324c: 019a lsls r2, r3, #6 - 800324e: 687b ldr r3, [r7, #4] - 8003250: 691b ldr r3, [r3, #16] - 8003252: 041b lsls r3, r3, #16 - 8003254: 431a orrs r2, r3 - 8003256: 687b ldr r3, [r7, #4] - 8003258: 68db ldr r3, [r3, #12] - 800325a: 061b lsls r3, r3, #24 - 800325c: 431a orrs r2, r3 - 800325e: 687b ldr r3, [r7, #4] - 8003260: 689b ldr r3, [r3, #8] - 8003262: 071b lsls r3, r3, #28 - 8003264: 4919 ldr r1, [pc, #100] ; (80032cc ) - 8003266: 4313 orrs r3, r2 - 8003268: f8c1 3084 str.w r3, [r1, #132] ; 0x84 + 80032cc: 687b ldr r3, [r7, #4] + 80032ce: 685b ldr r3, [r3, #4] + 80032d0: 019a lsls r2, r3, #6 + 80032d2: 687b ldr r3, [r7, #4] + 80032d4: 691b ldr r3, [r3, #16] + 80032d6: 041b lsls r3, r3, #16 + 80032d8: 431a orrs r2, r3 + 80032da: 687b ldr r3, [r7, #4] + 80032dc: 68db ldr r3, [r3, #12] + 80032de: 061b lsls r3, r3, #24 + 80032e0: 431a orrs r2, r3 + 80032e2: 687b ldr r3, [r7, #4] + 80032e4: 689b ldr r3, [r3, #8] + 80032e6: 071b lsls r3, r3, #28 + 80032e8: 4919 ldr r1, [pc, #100] ; (8003350 ) + 80032ea: 4313 orrs r3, r2 + 80032ec: f8c1 3084 str.w r3, [r1, #132] ; 0x84 } /* Enable the PLLI2S */ __HAL_RCC_PLLI2S_ENABLE(); - 800326c: 4b17 ldr r3, [pc, #92] ; (80032cc ) - 800326e: 681b ldr r3, [r3, #0] - 8003270: 4a16 ldr r2, [pc, #88] ; (80032cc ) - 8003272: f043 6380 orr.w r3, r3, #67108864 ; 0x4000000 - 8003276: 6013 str r3, [r2, #0] + 80032f0: 4b17 ldr r3, [pc, #92] ; (8003350 ) + 80032f2: 681b ldr r3, [r3, #0] + 80032f4: 4a16 ldr r2, [pc, #88] ; (8003350 ) + 80032f6: f043 6380 orr.w r3, r3, #67108864 ; 0x4000000 + 80032fa: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8003278: f7fe fd68 bl 8001d4c - 800327c: 6178 str r0, [r7, #20] + 80032fc: f7fe fd68 bl 8001dd0 + 8003300: 6178 str r0, [r7, #20] /* Wait till PLLI2S is ready */ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - 800327e: e008 b.n 8003292 + 8003302: e008 b.n 8003316 { if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - 8003280: f7fe fd64 bl 8001d4c - 8003284: 4602 mov r2, r0 - 8003286: 697b ldr r3, [r7, #20] - 8003288: 1ad3 subs r3, r2, r3 - 800328a: 2b64 cmp r3, #100 ; 0x64 - 800328c: d901 bls.n 8003292 + 8003304: f7fe fd64 bl 8001dd0 + 8003308: 4602 mov r2, r0 + 800330a: 697b ldr r3, [r7, #20] + 800330c: 1ad3 subs r3, r2, r3 + 800330e: 2b64 cmp r3, #100 ; 0x64 + 8003310: d901 bls.n 8003316 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 800328e: 2303 movs r3, #3 - 8003290: e0d7 b.n 8003442 + 8003312: 2303 movs r3, #3 + 8003314: e0d7 b.n 80034c6 while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - 8003292: 4b0e ldr r3, [pc, #56] ; (80032cc ) - 8003294: 681b ldr r3, [r3, #0] - 8003296: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 - 800329a: 2b00 cmp r3, #0 - 800329c: d0f0 beq.n 8003280 + 8003316: 4b0e ldr r3, [pc, #56] ; (8003350 ) + 8003318: 681b ldr r3, [r3, #0] + 800331a: f003 6300 and.w r3, r3, #134217728 ; 0x8000000 + 800331e: 2b00 cmp r3, #0 + 8003320: d0f0 beq.n 8003304 } } /*-------------------------------------- PLLSAI Configuration ---------------------------------*/ /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, LTDC or CK48 */ if(pllsaiused == 1) - 800329e: 69bb ldr r3, [r7, #24] - 80032a0: 2b01 cmp r3, #1 - 80032a2: f040 80cd bne.w 8003440 + 8003322: 69bb ldr r3, [r7, #24] + 8003324: 2b01 cmp r3, #1 + 8003326: f040 80cd bne.w 80034c4 { /* Disable PLLSAI Clock */ __HAL_RCC_PLLSAI_DISABLE(); - 80032a6: 4b09 ldr r3, [pc, #36] ; (80032cc ) - 80032a8: 681b ldr r3, [r3, #0] - 80032aa: 4a08 ldr r2, [pc, #32] ; (80032cc ) - 80032ac: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 - 80032b0: 6013 str r3, [r2, #0] + 800332a: 4b09 ldr r3, [pc, #36] ; (8003350 ) + 800332c: 681b ldr r3, [r3, #0] + 800332e: 4a08 ldr r2, [pc, #32] ; (8003350 ) + 8003330: f023 5380 bic.w r3, r3, #268435456 ; 0x10000000 + 8003334: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 80032b2: f7fe fd4b bl 8001d4c - 80032b6: 6178 str r0, [r7, #20] + 8003336: f7fe fd4b bl 8001dd0 + 800333a: 6178 str r0, [r7, #20] /* Wait till PLLSAI is disabled */ while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - 80032b8: e00a b.n 80032d0 + 800333c: e00a b.n 8003354 { if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - 80032ba: f7fe fd47 bl 8001d4c - 80032be: 4602 mov r2, r0 - 80032c0: 697b ldr r3, [r7, #20] - 80032c2: 1ad3 subs r3, r2, r3 - 80032c4: 2b64 cmp r3, #100 ; 0x64 - 80032c6: d903 bls.n 80032d0 + 800333e: f7fe fd47 bl 8001dd0 + 8003342: 4602 mov r2, r0 + 8003344: 697b ldr r3, [r7, #20] + 8003346: 1ad3 subs r3, r2, r3 + 8003348: 2b64 cmp r3, #100 ; 0x64 + 800334a: d903 bls.n 8003354 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 80032c8: 2303 movs r3, #3 - 80032ca: e0ba b.n 8003442 - 80032cc: 40023800 .word 0x40023800 + 800334c: 2303 movs r3, #3 + 800334e: e0ba b.n 80034c6 + 8003350: 40023800 .word 0x40023800 while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - 80032d0: 4b5e ldr r3, [pc, #376] ; (800344c ) - 80032d2: 681b ldr r3, [r3, #0] - 80032d4: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 - 80032d8: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 - 80032dc: d0ed beq.n 80032ba + 8003354: 4b5e ldr r3, [pc, #376] ; (80034d0 ) + 8003356: 681b ldr r3, [r3, #0] + 8003358: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 800335c: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 8003360: d0ed beq.n 800333e /* 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)) ||\ - 80032de: 687b ldr r3, [r7, #4] - 80032e0: 681b ldr r3, [r3, #0] - 80032e2: f403 2300 and.w r3, r3, #524288 ; 0x80000 - 80032e6: 2b00 cmp r3, #0 - 80032e8: d003 beq.n 80032f2 - 80032ea: 687b ldr r3, [r7, #4] - 80032ec: 6bdb ldr r3, [r3, #60] ; 0x3c - 80032ee: 2b00 cmp r3, #0 - 80032f0: d009 beq.n 8003306 + 8003362: 687b ldr r3, [r7, #4] + 8003364: 681b ldr r3, [r3, #0] + 8003366: f403 2300 and.w r3, r3, #524288 ; 0x80000 + 800336a: 2b00 cmp r3, #0 + 800336c: d003 beq.n 8003376 + 800336e: 687b ldr r3, [r7, #4] + 8003370: 6bdb ldr r3, [r3, #60] ; 0x3c + 8003372: 2b00 cmp r3, #0 + 8003374: d009 beq.n 800338a ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - 80032f2: 687b ldr r3, [r7, #4] - 80032f4: 681b ldr r3, [r3, #0] - 80032f6: f403 1380 and.w r3, r3, #1048576 ; 0x100000 + 8003376: 687b ldr r3, [r7, #4] + 8003378: 681b ldr r3, [r3, #0] + 800337a: f403 1380 and.w r3, r3, #1048576 ; 0x100000 if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) ||\ - 80032fa: 2b00 cmp r3, #0 - 80032fc: d02e beq.n 800335c + 800337e: 2b00 cmp r3, #0 + 8003380: d02e beq.n 80033e0 ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - 80032fe: 687b ldr r3, [r7, #4] - 8003300: 6c1b ldr r3, [r3, #64] ; 0x40 - 8003302: 2b00 cmp r3, #0 - 8003304: d12a bne.n 800335c + 8003382: 687b ldr r3, [r7, #4] + 8003384: 6c1b ldr r3, [r3, #64] ; 0x40 + 8003386: 2b00 cmp r3, #0 + 8003388: d12a bne.n 80033e0 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); - 8003306: 4b51 ldr r3, [pc, #324] ; (800344c ) - 8003308: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 800330c: 0c1b lsrs r3, r3, #16 - 800330e: f003 0303 and.w r3, r3, #3 - 8003312: 613b str r3, [r7, #16] + 800338a: 4b51 ldr r3, [pc, #324] ; (80034d0 ) + 800338c: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003390: 0c1b lsrs r3, r3, #16 + 8003392: f003 0303 and.w r3, r3, #3 + 8003396: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - 8003314: 4b4d ldr r3, [pc, #308] ; (800344c ) - 8003316: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 800331a: 0f1b lsrs r3, r3, #28 - 800331c: f003 0307 and.w r3, r3, #7 - 8003320: 60fb str r3, [r7, #12] + 8003398: 4b4d ldr r3, [pc, #308] ; (80034d0 ) + 800339a: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800339e: 0f1b lsrs r3, r3, #28 + 80033a0: f003 0307 and.w r3, r3, #7 + 80033a4: 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); - 8003322: 687b ldr r3, [r7, #4] - 8003324: 695b ldr r3, [r3, #20] - 8003326: 019a lsls r2, r3, #6 - 8003328: 693b ldr r3, [r7, #16] - 800332a: 041b lsls r3, r3, #16 - 800332c: 431a orrs r2, r3 - 800332e: 687b ldr r3, [r7, #4] - 8003330: 699b ldr r3, [r3, #24] - 8003332: 061b lsls r3, r3, #24 - 8003334: 431a orrs r2, r3 - 8003336: 68fb ldr r3, [r7, #12] - 8003338: 071b lsls r3, r3, #28 - 800333a: 4944 ldr r1, [pc, #272] ; (800344c ) - 800333c: 4313 orrs r3, r2 - 800333e: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 80033a6: 687b ldr r3, [r7, #4] + 80033a8: 695b ldr r3, [r3, #20] + 80033aa: 019a lsls r2, r3, #6 + 80033ac: 693b ldr r3, [r7, #16] + 80033ae: 041b lsls r3, r3, #16 + 80033b0: 431a orrs r2, r3 + 80033b2: 687b ldr r3, [r7, #4] + 80033b4: 699b ldr r3, [r3, #24] + 80033b6: 061b lsls r3, r3, #24 + 80033b8: 431a orrs r2, r3 + 80033ba: 68fb ldr r3, [r7, #12] + 80033bc: 071b lsls r3, r3, #28 + 80033be: 4944 ldr r1, [pc, #272] ; (80034d0 ) + 80033c0: 4313 orrs r3, r2 + 80033c2: f8c1 3088 str.w r3, [r1, #136] ; 0x88 /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - 8003342: 4b42 ldr r3, [pc, #264] ; (800344c ) - 8003344: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 8003348: f423 52f8 bic.w r2, r3, #7936 ; 0x1f00 - 800334c: 687b ldr r3, [r7, #4] - 800334e: 6a9b ldr r3, [r3, #40] ; 0x28 - 8003350: 3b01 subs r3, #1 - 8003352: 021b lsls r3, r3, #8 - 8003354: 493d ldr r1, [pc, #244] ; (800344c ) - 8003356: 4313 orrs r3, r2 - 8003358: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 80033c6: 4b42 ldr r3, [pc, #264] ; (80034d0 ) + 80033c8: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 80033cc: f423 52f8 bic.w r2, r3, #7936 ; 0x1f00 + 80033d0: 687b ldr r3, [r7, #4] + 80033d2: 6a9b ldr r3, [r3, #40] ; 0x28 + 80033d4: 3b01 subs r3, #1 + 80033d6: 021b lsls r3, r3, #8 + 80033d8: 493d ldr r1, [pc, #244] ; (80034d0 ) + 80033da: 4313 orrs r3, r2 + 80033dc: 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)) - 800335c: 687b ldr r3, [r7, #4] - 800335e: 681b ldr r3, [r3, #0] - 8003360: f403 1300 and.w r3, r3, #2097152 ; 0x200000 - 8003364: 2b00 cmp r3, #0 - 8003366: d022 beq.n 80033ae - 8003368: 687b ldr r3, [r7, #4] - 800336a: 6fdb ldr r3, [r3, #124] ; 0x7c - 800336c: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 - 8003370: d11d bne.n 80033ae + 80033e0: 687b ldr r3, [r7, #4] + 80033e2: 681b ldr r3, [r3, #0] + 80033e4: f403 1300 and.w r3, r3, #2097152 ; 0x200000 + 80033e8: 2b00 cmp r3, #0 + 80033ea: d022 beq.n 8003432 + 80033ec: 687b ldr r3, [r7, #4] + 80033ee: 6fdb ldr r3, [r3, #124] ; 0x7c + 80033f0: f1b3 6f00 cmp.w r3, #134217728 ; 0x8000000 + 80033f4: d11d bne.n 8003432 { /* 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); - 8003372: 4b36 ldr r3, [pc, #216] ; (800344c ) - 8003374: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8003378: 0e1b lsrs r3, r3, #24 - 800337a: f003 030f and.w r3, r3, #15 - 800337e: 613b str r3, [r7, #16] + 80033f6: 4b36 ldr r3, [pc, #216] ; (80034d0 ) + 80033f8: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 80033fc: 0e1b lsrs r3, r3, #24 + 80033fe: f003 030f and.w r3, r3, #15 + 8003402: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - 8003380: 4b32 ldr r3, [pc, #200] ; (800344c ) - 8003382: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 8003386: 0f1b lsrs r3, r3, #28 - 8003388: f003 0307 and.w r3, r3, #7 - 800338c: 60fb str r3, [r7, #12] + 8003404: 4b32 ldr r3, [pc, #200] ; (80034d0 ) + 8003406: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 800340a: 0f1b lsrs r3, r3, #28 + 800340c: f003 0307 and.w r3, r3, #7 + 8003410: 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); - 800338e: 687b ldr r3, [r7, #4] - 8003390: 695b ldr r3, [r3, #20] - 8003392: 019a lsls r2, r3, #6 - 8003394: 687b ldr r3, [r7, #4] - 8003396: 6a1b ldr r3, [r3, #32] - 8003398: 041b lsls r3, r3, #16 - 800339a: 431a orrs r2, r3 - 800339c: 693b ldr r3, [r7, #16] - 800339e: 061b lsls r3, r3, #24 - 80033a0: 431a orrs r2, r3 - 80033a2: 68fb ldr r3, [r7, #12] - 80033a4: 071b lsls r3, r3, #28 - 80033a6: 4929 ldr r1, [pc, #164] ; (800344c ) - 80033a8: 4313 orrs r3, r2 - 80033aa: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 8003412: 687b ldr r3, [r7, #4] + 8003414: 695b ldr r3, [r3, #20] + 8003416: 019a lsls r2, r3, #6 + 8003418: 687b ldr r3, [r7, #4] + 800341a: 6a1b ldr r3, [r3, #32] + 800341c: 041b lsls r3, r3, #16 + 800341e: 431a orrs r2, r3 + 8003420: 693b ldr r3, [r7, #16] + 8003422: 061b lsls r3, r3, #24 + 8003424: 431a orrs r2, r3 + 8003426: 68fb ldr r3, [r7, #12] + 8003428: 071b lsls r3, r3, #28 + 800342a: 4929 ldr r1, [pc, #164] ; (80034d0 ) + 800342c: 4313 orrs r3, r2 + 800342e: 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)) - 80033ae: 687b ldr r3, [r7, #4] - 80033b0: 681b ldr r3, [r3, #0] - 80033b2: f003 0308 and.w r3, r3, #8 - 80033b6: 2b00 cmp r3, #0 - 80033b8: d028 beq.n 800340c + 8003432: 687b ldr r3, [r7, #4] + 8003434: 681b ldr r3, [r3, #0] + 8003436: f003 0308 and.w r3, r3, #8 + 800343a: 2b00 cmp r3, #0 + 800343c: d028 beq.n 8003490 { 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); - 80033ba: 4b24 ldr r3, [pc, #144] ; (800344c ) - 80033bc: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 80033c0: 0e1b lsrs r3, r3, #24 - 80033c2: f003 030f and.w r3, r3, #15 - 80033c6: 613b str r3, [r7, #16] + 800343e: 4b24 ldr r3, [pc, #144] ; (80034d0 ) + 8003440: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003444: 0e1b lsrs r3, r3, #24 + 8003446: f003 030f and.w r3, r3, #15 + 800344a: 613b str r3, [r7, #16] tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos); - 80033c8: 4b20 ldr r3, [pc, #128] ; (800344c ) - 80033ca: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 - 80033ce: 0c1b lsrs r3, r3, #16 - 80033d0: f003 0303 and.w r3, r3, #3 - 80033d4: 60fb str r3, [r7, #12] + 800344c: 4b20 ldr r3, [pc, #128] ; (80034d0 ) + 800344e: f8d3 3088 ldr.w r3, [r3, #136] ; 0x88 + 8003452: 0c1b lsrs r3, r3, #16 + 8003454: f003 0303 and.w r3, r3, #3 + 8003458: 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); - 80033d6: 687b ldr r3, [r7, #4] - 80033d8: 695b ldr r3, [r3, #20] - 80033da: 019a lsls r2, r3, #6 - 80033dc: 68fb ldr r3, [r7, #12] - 80033de: 041b lsls r3, r3, #16 - 80033e0: 431a orrs r2, r3 - 80033e2: 693b ldr r3, [r7, #16] - 80033e4: 061b lsls r3, r3, #24 - 80033e6: 431a orrs r2, r3 - 80033e8: 687b ldr r3, [r7, #4] - 80033ea: 69db ldr r3, [r3, #28] - 80033ec: 071b lsls r3, r3, #28 - 80033ee: 4917 ldr r1, [pc, #92] ; (800344c ) - 80033f0: 4313 orrs r3, r2 - 80033f2: f8c1 3088 str.w r3, [r1, #136] ; 0x88 + 800345a: 687b ldr r3, [r7, #4] + 800345c: 695b ldr r3, [r3, #20] + 800345e: 019a lsls r2, r3, #6 + 8003460: 68fb ldr r3, [r7, #12] + 8003462: 041b lsls r3, r3, #16 + 8003464: 431a orrs r2, r3 + 8003466: 693b ldr r3, [r7, #16] + 8003468: 061b lsls r3, r3, #24 + 800346a: 431a orrs r2, r3 + 800346c: 687b ldr r3, [r7, #4] + 800346e: 69db ldr r3, [r3, #28] + 8003470: 071b lsls r3, r3, #28 + 8003472: 4917 ldr r1, [pc, #92] ; (80034d0 ) + 8003474: 4313 orrs r3, r2 + 8003476: f8c1 3088 str.w r3, [r1, #136] ; 0x88 /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - 80033f6: 4b15 ldr r3, [pc, #84] ; (800344c ) - 80033f8: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c - 80033fc: f423 3240 bic.w r2, r3, #196608 ; 0x30000 - 8003400: 687b ldr r3, [r7, #4] - 8003402: 6adb ldr r3, [r3, #44] ; 0x2c - 8003404: 4911 ldr r1, [pc, #68] ; (800344c ) - 8003406: 4313 orrs r3, r2 - 8003408: f8c1 308c str.w r3, [r1, #140] ; 0x8c + 800347a: 4b15 ldr r3, [pc, #84] ; (80034d0 ) + 800347c: f8d3 308c ldr.w r3, [r3, #140] ; 0x8c + 8003480: f423 3240 bic.w r2, r3, #196608 ; 0x30000 + 8003484: 687b ldr r3, [r7, #4] + 8003486: 6adb ldr r3, [r3, #44] ; 0x2c + 8003488: 4911 ldr r1, [pc, #68] ; (80034d0 ) + 800348a: 4313 orrs r3, r2 + 800348c: f8c1 308c str.w r3, [r1, #140] ; 0x8c } #endif /* STM32F746xx || STM32F756xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx || STM32F750xx */ /* Enable PLLSAI Clock */ __HAL_RCC_PLLSAI_ENABLE(); - 800340c: 4b0f ldr r3, [pc, #60] ; (800344c ) - 800340e: 681b ldr r3, [r3, #0] - 8003410: 4a0e ldr r2, [pc, #56] ; (800344c ) - 8003412: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 - 8003416: 6013 str r3, [r2, #0] + 8003490: 4b0f ldr r3, [pc, #60] ; (80034d0 ) + 8003492: 681b ldr r3, [r3, #0] + 8003494: 4a0e ldr r2, [pc, #56] ; (80034d0 ) + 8003496: f043 5380 orr.w r3, r3, #268435456 ; 0x10000000 + 800349a: 6013 str r3, [r2, #0] /* Get Start Tick*/ tickstart = HAL_GetTick(); - 8003418: f7fe fc98 bl 8001d4c - 800341c: 6178 str r0, [r7, #20] + 800349c: f7fe fc98 bl 8001dd0 + 80034a0: 6178 str r0, [r7, #20] /* Wait till PLLSAI is ready */ while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - 800341e: e008 b.n 8003432 + 80034a2: e008 b.n 80034b6 { if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - 8003420: f7fe fc94 bl 8001d4c - 8003424: 4602 mov r2, r0 - 8003426: 697b ldr r3, [r7, #20] - 8003428: 1ad3 subs r3, r2, r3 - 800342a: 2b64 cmp r3, #100 ; 0x64 - 800342c: d901 bls.n 8003432 + 80034a4: f7fe fc94 bl 8001dd0 + 80034a8: 4602 mov r2, r0 + 80034aa: 697b ldr r3, [r7, #20] + 80034ac: 1ad3 subs r3, r2, r3 + 80034ae: 2b64 cmp r3, #100 ; 0x64 + 80034b0: d901 bls.n 80034b6 { /* return in case of Timeout detected */ return HAL_TIMEOUT; - 800342e: 2303 movs r3, #3 - 8003430: e007 b.n 8003442 + 80034b2: 2303 movs r3, #3 + 80034b4: e007 b.n 80034c6 while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - 8003432: 4b06 ldr r3, [pc, #24] ; (800344c ) - 8003434: 681b ldr r3, [r3, #0] - 8003436: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 - 800343a: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 - 800343e: d1ef bne.n 8003420 + 80034b6: 4b06 ldr r3, [pc, #24] ; (80034d0 ) + 80034b8: 681b ldr r3, [r3, #0] + 80034ba: f003 5300 and.w r3, r3, #536870912 ; 0x20000000 + 80034be: f1b3 5f00 cmp.w r3, #536870912 ; 0x20000000 + 80034c2: d1ef bne.n 80034a4 } } } return HAL_OK; - 8003440: 2300 movs r3, #0 + 80034c4: 2300 movs r3, #0 } - 8003442: 4618 mov r0, r3 - 8003444: 3720 adds r7, #32 - 8003446: 46bd mov sp, r7 - 8003448: bd80 pop {r7, pc} - 800344a: bf00 nop - 800344c: 40023800 .word 0x40023800 - -08003450 : + 80034c6: 4618 mov r0, r3 + 80034c8: 3720 adds r7, #32 + 80034ca: 46bd mov sp, r7 + 80034cc: bd80 pop {r7, pc} + 80034ce: bf00 nop + 80034d0: 40023800 .word 0x40023800 + +080034d4 : * 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) { - 8003450: b580 push {r7, lr} - 8003452: b082 sub sp, #8 - 8003454: af00 add r7, sp, #0 - 8003456: 6078 str r0, [r7, #4] + 80034d4: b580 push {r7, lr} + 80034d6: b082 sub sp, #8 + 80034d8: af00 add r7, sp, #0 + 80034da: 6078 str r0, [r7, #4] /* Check the TIM handle allocation */ if (htim == NULL) - 8003458: 687b ldr r3, [r7, #4] - 800345a: 2b00 cmp r3, #0 - 800345c: d101 bne.n 8003462 + 80034dc: 687b ldr r3, [r7, #4] + 80034de: 2b00 cmp r3, #0 + 80034e0: d101 bne.n 80034e6 { return HAL_ERROR; - 800345e: 2301 movs r3, #1 - 8003460: e01d b.n 800349e + 80034e2: 2301 movs r3, #1 + 80034e4: e01d b.n 8003522 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) - 8003462: 687b ldr r3, [r7, #4] - 8003464: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 8003468: b2db uxtb r3, r3 - 800346a: 2b00 cmp r3, #0 - 800346c: d106 bne.n 800347c + 80034e6: 687b ldr r3, [r7, #4] + 80034e8: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 80034ec: b2db uxtb r3, r3 + 80034ee: 2b00 cmp r3, #0 + 80034f0: d106 bne.n 8003500 { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 800346e: 687b ldr r3, [r7, #4] - 8003470: 2200 movs r2, #0 - 8003472: f883 203c strb.w r2, [r3, #60] ; 0x3c + 80034f2: 687b ldr r3, [r7, #4] + 80034f4: 2200 movs r2, #0 + 80034f6: 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); - 8003476: 6878 ldr r0, [r7, #4] - 8003478: f7fe faa0 bl 80019bc + 80034fa: 6878 ldr r0, [r7, #4] + 80034fc: f7fe faa0 bl 8001a40 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 800347c: 687b ldr r3, [r7, #4] - 800347e: 2202 movs r2, #2 - 8003480: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003500: 687b ldr r3, [r7, #4] + 8003502: 2202 movs r2, #2 + 8003504: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Set the Time Base configuration */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 8003484: 687b ldr r3, [r7, #4] - 8003486: 681a ldr r2, [r3, #0] - 8003488: 687b ldr r3, [r7, #4] - 800348a: 3304 adds r3, #4 - 800348c: 4619 mov r1, r3 - 800348e: 4610 mov r0, r2 - 8003490: f000 fc90 bl 8003db4 + 8003508: 687b ldr r3, [r7, #4] + 800350a: 681a ldr r2, [r3, #0] + 800350c: 687b ldr r3, [r7, #4] + 800350e: 3304 adds r3, #4 + 8003510: 4619 mov r1, r3 + 8003512: 4610 mov r0, r2 + 8003514: f000 fc90 bl 8003e38 /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 8003494: 687b ldr r3, [r7, #4] - 8003496: 2201 movs r2, #1 - 8003498: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003518: 687b ldr r3, [r7, #4] + 800351a: 2201 movs r2, #1 + 800351c: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 800349c: 2300 movs r3, #0 + 8003520: 2300 movs r3, #0 } - 800349e: 4618 mov r0, r3 - 80034a0: 3708 adds r7, #8 - 80034a2: 46bd mov sp, r7 - 80034a4: bd80 pop {r7, pc} + 8003522: 4618 mov r0, r3 + 8003524: 3708 adds r7, #8 + 8003526: 46bd mov sp, r7 + 8003528: bd80 pop {r7, pc} ... -080034a8 : +0800352c : * @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) { - 80034a8: b480 push {r7} - 80034aa: b085 sub sp, #20 - 80034ac: af00 add r7, sp, #0 - 80034ae: 6078 str r0, [r7, #4] + 800352c: b480 push {r7} + 800352e: b085 sub sp, #20 + 8003530: af00 add r7, sp, #0 + 8003532: 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); - 80034b0: 687b ldr r3, [r7, #4] - 80034b2: 681b ldr r3, [r3, #0] - 80034b4: 68da ldr r2, [r3, #12] - 80034b6: 687b ldr r3, [r7, #4] - 80034b8: 681b ldr r3, [r3, #0] - 80034ba: f042 0201 orr.w r2, r2, #1 - 80034be: 60da str r2, [r3, #12] + 8003534: 687b ldr r3, [r7, #4] + 8003536: 681b ldr r3, [r3, #0] + 8003538: 68da ldr r2, [r3, #12] + 800353a: 687b ldr r3, [r7, #4] + 800353c: 681b ldr r3, [r3, #0] + 800353e: f042 0201 orr.w r2, r2, #1 + 8003542: 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; - 80034c0: 687b ldr r3, [r7, #4] - 80034c2: 681b ldr r3, [r3, #0] - 80034c4: 689a ldr r2, [r3, #8] - 80034c6: 4b0c ldr r3, [pc, #48] ; (80034f8 ) - 80034c8: 4013 ands r3, r2 - 80034ca: 60fb str r3, [r7, #12] + 8003544: 687b ldr r3, [r7, #4] + 8003546: 681b ldr r3, [r3, #0] + 8003548: 689a ldr r2, [r3, #8] + 800354a: 4b0c ldr r3, [pc, #48] ; (800357c ) + 800354c: 4013 ands r3, r2 + 800354e: 60fb str r3, [r7, #12] if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - 80034cc: 68fb ldr r3, [r7, #12] - 80034ce: 2b06 cmp r3, #6 - 80034d0: d00b beq.n 80034ea - 80034d2: 68fb ldr r3, [r7, #12] - 80034d4: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 80034d8: d007 beq.n 80034ea + 8003550: 68fb ldr r3, [r7, #12] + 8003552: 2b06 cmp r3, #6 + 8003554: d00b beq.n 800356e + 8003556: 68fb ldr r3, [r7, #12] + 8003558: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 800355c: d007 beq.n 800356e { __HAL_TIM_ENABLE(htim); - 80034da: 687b ldr r3, [r7, #4] - 80034dc: 681b ldr r3, [r3, #0] - 80034de: 681a ldr r2, [r3, #0] - 80034e0: 687b ldr r3, [r7, #4] - 80034e2: 681b ldr r3, [r3, #0] - 80034e4: f042 0201 orr.w r2, r2, #1 - 80034e8: 601a str r2, [r3, #0] + 800355e: 687b ldr r3, [r7, #4] + 8003560: 681b ldr r3, [r3, #0] + 8003562: 681a ldr r2, [r3, #0] + 8003564: 687b ldr r3, [r7, #4] + 8003566: 681b ldr r3, [r3, #0] + 8003568: f042 0201 orr.w r2, r2, #1 + 800356c: 601a str r2, [r3, #0] } /* Return function status */ return HAL_OK; - 80034ea: 2300 movs r3, #0 + 800356e: 2300 movs r3, #0 } - 80034ec: 4618 mov r0, r3 - 80034ee: 3714 adds r7, #20 - 80034f0: 46bd mov sp, r7 - 80034f2: f85d 7b04 ldr.w r7, [sp], #4 - 80034f6: 4770 bx lr - 80034f8: 00010007 .word 0x00010007 - -080034fc : + 8003570: 4618 mov r0, r3 + 8003572: 3714 adds r7, #20 + 8003574: 46bd mov sp, r7 + 8003576: f85d 7b04 ldr.w r7, [sp], #4 + 800357a: 4770 bx lr + 800357c: 00010007 .word 0x00010007 + +08003580 : * 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) { - 80034fc: b580 push {r7, lr} - 80034fe: b082 sub sp, #8 - 8003500: af00 add r7, sp, #0 - 8003502: 6078 str r0, [r7, #4] + 8003580: b580 push {r7, lr} + 8003582: b082 sub sp, #8 + 8003584: af00 add r7, sp, #0 + 8003586: 6078 str r0, [r7, #4] /* Check the TIM handle allocation */ if (htim == NULL) - 8003504: 687b ldr r3, [r7, #4] - 8003506: 2b00 cmp r3, #0 - 8003508: d101 bne.n 800350e + 8003588: 687b ldr r3, [r7, #4] + 800358a: 2b00 cmp r3, #0 + 800358c: d101 bne.n 8003592 { return HAL_ERROR; - 800350a: 2301 movs r3, #1 - 800350c: e01d b.n 800354a + 800358e: 2301 movs r3, #1 + 8003590: e01d b.n 80035ce 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) - 800350e: 687b ldr r3, [r7, #4] - 8003510: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 8003514: b2db uxtb r3, r3 - 8003516: 2b00 cmp r3, #0 - 8003518: d106 bne.n 8003528 + 8003592: 687b ldr r3, [r7, #4] + 8003594: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 8003598: b2db uxtb r3, r3 + 800359a: 2b00 cmp r3, #0 + 800359c: d106 bne.n 80035ac { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 800351a: 687b ldr r3, [r7, #4] - 800351c: 2200 movs r2, #0 - 800351e: f883 203c strb.w r2, [r3, #60] ; 0x3c + 800359e: 687b ldr r3, [r7, #4] + 80035a0: 2200 movs r2, #0 + 80035a2: 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); - 8003522: 6878 ldr r0, [r7, #4] - 8003524: f000 f815 bl 8003552 + 80035a6: 6878 ldr r0, [r7, #4] + 80035a8: f000 f815 bl 80035d6 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 8003528: 687b ldr r3, [r7, #4] - 800352a: 2202 movs r2, #2 - 800352c: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80035ac: 687b ldr r3, [r7, #4] + 80035ae: 2202 movs r2, #2 + 80035b0: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Init the base time for the PWM */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 8003530: 687b ldr r3, [r7, #4] - 8003532: 681a ldr r2, [r3, #0] - 8003534: 687b ldr r3, [r7, #4] - 8003536: 3304 adds r3, #4 - 8003538: 4619 mov r1, r3 - 800353a: 4610 mov r0, r2 - 800353c: f000 fc3a bl 8003db4 + 80035b4: 687b ldr r3, [r7, #4] + 80035b6: 681a ldr r2, [r3, #0] + 80035b8: 687b ldr r3, [r7, #4] + 80035ba: 3304 adds r3, #4 + 80035bc: 4619 mov r1, r3 + 80035be: 4610 mov r0, r2 + 80035c0: f000 fc3a bl 8003e38 /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 8003540: 687b ldr r3, [r7, #4] - 8003542: 2201 movs r2, #1 - 8003544: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80035c4: 687b ldr r3, [r7, #4] + 80035c6: 2201 movs r2, #1 + 80035c8: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 8003548: 2300 movs r3, #0 + 80035cc: 2300 movs r3, #0 } - 800354a: 4618 mov r0, r3 - 800354c: 3708 adds r7, #8 - 800354e: 46bd mov sp, r7 - 8003550: bd80 pop {r7, pc} + 80035ce: 4618 mov r0, r3 + 80035d0: 3708 adds r7, #8 + 80035d2: 46bd mov sp, r7 + 80035d4: bd80 pop {r7, pc} -08003552 : +080035d6 : * @brief Initializes the TIM PWM MSP. * @param htim TIM PWM handle * @retval None */ __weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) { - 8003552: b480 push {r7} - 8003554: b083 sub sp, #12 - 8003556: af00 add r7, sp, #0 - 8003558: 6078 str r0, [r7, #4] + 80035d6: b480 push {r7} + 80035d8: b083 sub sp, #12 + 80035da: af00 add r7, sp, #0 + 80035dc: 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 */ } - 800355a: bf00 nop - 800355c: 370c adds r7, #12 - 800355e: 46bd mov sp, r7 - 8003560: f85d 7b04 ldr.w r7, [sp], #4 - 8003564: 4770 bx lr + 80035de: bf00 nop + 80035e0: 370c adds r7, #12 + 80035e2: 46bd mov sp, r7 + 80035e4: f85d 7b04 ldr.w r7, [sp], #4 + 80035e8: 4770 bx lr ... -08003568 : +080035ec : * @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) { - 8003568: b580 push {r7, lr} - 800356a: b084 sub sp, #16 - 800356c: af00 add r7, sp, #0 - 800356e: 6078 str r0, [r7, #4] - 8003570: 6039 str r1, [r7, #0] + 80035ec: b580 push {r7, lr} + 80035ee: b084 sub sp, #16 + 80035f0: af00 add r7, sp, #0 + 80035f2: 6078 str r0, [r7, #4] + 80035f4: 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); - 8003572: 687b ldr r3, [r7, #4] - 8003574: 681b ldr r3, [r3, #0] - 8003576: 2201 movs r2, #1 - 8003578: 6839 ldr r1, [r7, #0] - 800357a: 4618 mov r0, r3 - 800357c: f000 ffb2 bl 80044e4 + 80035f6: 687b ldr r3, [r7, #4] + 80035f8: 681b ldr r3, [r3, #0] + 80035fa: 2201 movs r2, #1 + 80035fc: 6839 ldr r1, [r7, #0] + 80035fe: 4618 mov r0, r3 + 8003600: f000 ffb2 bl 8004568 if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - 8003580: 687b ldr r3, [r7, #4] - 8003582: 681b ldr r3, [r3, #0] - 8003584: 4a17 ldr r2, [pc, #92] ; (80035e4 ) - 8003586: 4293 cmp r3, r2 - 8003588: d004 beq.n 8003594 - 800358a: 687b ldr r3, [r7, #4] - 800358c: 681b ldr r3, [r3, #0] - 800358e: 4a16 ldr r2, [pc, #88] ; (80035e8 ) - 8003590: 4293 cmp r3, r2 - 8003592: d101 bne.n 8003598 - 8003594: 2301 movs r3, #1 - 8003596: e000 b.n 800359a - 8003598: 2300 movs r3, #0 - 800359a: 2b00 cmp r3, #0 - 800359c: d007 beq.n 80035ae + 8003604: 687b ldr r3, [r7, #4] + 8003606: 681b ldr r3, [r3, #0] + 8003608: 4a17 ldr r2, [pc, #92] ; (8003668 ) + 800360a: 4293 cmp r3, r2 + 800360c: d004 beq.n 8003618 + 800360e: 687b ldr r3, [r7, #4] + 8003610: 681b ldr r3, [r3, #0] + 8003612: 4a16 ldr r2, [pc, #88] ; (800366c ) + 8003614: 4293 cmp r3, r2 + 8003616: d101 bne.n 800361c + 8003618: 2301 movs r3, #1 + 800361a: e000 b.n 800361e + 800361c: 2300 movs r3, #0 + 800361e: 2b00 cmp r3, #0 + 8003620: d007 beq.n 8003632 { /* Enable the main output */ __HAL_TIM_MOE_ENABLE(htim); - 800359e: 687b ldr r3, [r7, #4] - 80035a0: 681b ldr r3, [r3, #0] - 80035a2: 6c5a ldr r2, [r3, #68] ; 0x44 - 80035a4: 687b ldr r3, [r7, #4] - 80035a6: 681b ldr r3, [r3, #0] - 80035a8: f442 4200 orr.w r2, r2, #32768 ; 0x8000 - 80035ac: 645a str r2, [r3, #68] ; 0x44 + 8003622: 687b ldr r3, [r7, #4] + 8003624: 681b ldr r3, [r3, #0] + 8003626: 6c5a ldr r2, [r3, #68] ; 0x44 + 8003628: 687b ldr r3, [r7, #4] + 800362a: 681b ldr r3, [r3, #0] + 800362c: f442 4200 orr.w r2, r2, #32768 ; 0x8000 + 8003630: 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; - 80035ae: 687b ldr r3, [r7, #4] - 80035b0: 681b ldr r3, [r3, #0] - 80035b2: 689a ldr r2, [r3, #8] - 80035b4: 4b0d ldr r3, [pc, #52] ; (80035ec ) - 80035b6: 4013 ands r3, r2 - 80035b8: 60fb str r3, [r7, #12] + 8003632: 687b ldr r3, [r7, #4] + 8003634: 681b ldr r3, [r3, #0] + 8003636: 689a ldr r2, [r3, #8] + 8003638: 4b0d ldr r3, [pc, #52] ; (8003670 ) + 800363a: 4013 ands r3, r2 + 800363c: 60fb str r3, [r7, #12] if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - 80035ba: 68fb ldr r3, [r7, #12] - 80035bc: 2b06 cmp r3, #6 - 80035be: d00b beq.n 80035d8 - 80035c0: 68fb ldr r3, [r7, #12] - 80035c2: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 80035c6: d007 beq.n 80035d8 + 800363e: 68fb ldr r3, [r7, #12] + 8003640: 2b06 cmp r3, #6 + 8003642: d00b beq.n 800365c + 8003644: 68fb ldr r3, [r7, #12] + 8003646: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 800364a: d007 beq.n 800365c { __HAL_TIM_ENABLE(htim); - 80035c8: 687b ldr r3, [r7, #4] - 80035ca: 681b ldr r3, [r3, #0] - 80035cc: 681a ldr r2, [r3, #0] - 80035ce: 687b ldr r3, [r7, #4] - 80035d0: 681b ldr r3, [r3, #0] - 80035d2: f042 0201 orr.w r2, r2, #1 - 80035d6: 601a str r2, [r3, #0] + 800364c: 687b ldr r3, [r7, #4] + 800364e: 681b ldr r3, [r3, #0] + 8003650: 681a ldr r2, [r3, #0] + 8003652: 687b ldr r3, [r7, #4] + 8003654: 681b ldr r3, [r3, #0] + 8003656: f042 0201 orr.w r2, r2, #1 + 800365a: 601a str r2, [r3, #0] } /* Return function status */ return HAL_OK; - 80035d8: 2300 movs r3, #0 + 800365c: 2300 movs r3, #0 } - 80035da: 4618 mov r0, r3 - 80035dc: 3710 adds r7, #16 - 80035de: 46bd mov sp, r7 - 80035e0: bd80 pop {r7, pc} - 80035e2: bf00 nop - 80035e4: 40010000 .word 0x40010000 - 80035e8: 40010400 .word 0x40010400 - 80035ec: 00010007 .word 0x00010007 - -080035f0 : + 800365e: 4618 mov r0, r3 + 8003660: 3710 adds r7, #16 + 8003662: 46bd mov sp, r7 + 8003664: bd80 pop {r7, pc} + 8003666: bf00 nop + 8003668: 40010000 .word 0x40010000 + 800366c: 40010400 .word 0x40010400 + 8003670: 00010007 .word 0x00010007 + +08003674 : * @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) { - 80035f0: b580 push {r7, lr} - 80035f2: b086 sub sp, #24 - 80035f4: af00 add r7, sp, #0 - 80035f6: 6078 str r0, [r7, #4] - 80035f8: 6039 str r1, [r7, #0] + 8003674: b580 push {r7, lr} + 8003676: b086 sub sp, #24 + 8003678: af00 add r7, sp, #0 + 800367a: 6078 str r0, [r7, #4] + 800367c: 6039 str r1, [r7, #0] uint32_t tmpsmcr; uint32_t tmpccmr1; uint32_t tmpccer; /* Check the TIM handle allocation */ if (htim == NULL) - 80035fa: 687b ldr r3, [r7, #4] - 80035fc: 2b00 cmp r3, #0 - 80035fe: d101 bne.n 8003604 + 800367e: 687b ldr r3, [r7, #4] + 8003680: 2b00 cmp r3, #0 + 8003682: d101 bne.n 8003688 { return HAL_ERROR; - 8003600: 2301 movs r3, #1 - 8003602: e07b b.n 80036fc + 8003684: 2301 movs r3, #1 + 8003686: e07b b.n 8003780 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) - 8003604: 687b ldr r3, [r7, #4] - 8003606: f893 303d ldrb.w r3, [r3, #61] ; 0x3d - 800360a: b2db uxtb r3, r3 - 800360c: 2b00 cmp r3, #0 - 800360e: d106 bne.n 800361e + 8003688: 687b ldr r3, [r7, #4] + 800368a: f893 303d ldrb.w r3, [r3, #61] ; 0x3d + 800368e: b2db uxtb r3, r3 + 8003690: 2b00 cmp r3, #0 + 8003692: d106 bne.n 80036a2 { /* Allocate lock resource and initialize it */ htim->Lock = HAL_UNLOCKED; - 8003610: 687b ldr r3, [r7, #4] - 8003612: 2200 movs r2, #0 - 8003614: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003694: 687b ldr r3, [r7, #4] + 8003696: 2200 movs r2, #0 + 8003698: 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); - 8003618: 6878 ldr r0, [r7, #4] - 800361a: f7fe f93f bl 800189c + 800369c: 6878 ldr r0, [r7, #4] + 800369e: f7fe f93f bl 8001920 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } /* Set the TIM state */ htim->State = HAL_TIM_STATE_BUSY; - 800361e: 687b ldr r3, [r7, #4] - 8003620: 2202 movs r2, #2 - 8003622: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80036a2: 687b ldr r3, [r7, #4] + 80036a4: 2202 movs r2, #2 + 80036a6: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Reset the SMS and ECE bits */ htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); - 8003626: 687b ldr r3, [r7, #4] - 8003628: 681b ldr r3, [r3, #0] - 800362a: 6899 ldr r1, [r3, #8] - 800362c: 687b ldr r3, [r7, #4] - 800362e: 681a ldr r2, [r3, #0] - 8003630: 4b34 ldr r3, [pc, #208] ; (8003704 ) - 8003632: 400b ands r3, r1 - 8003634: 6093 str r3, [r2, #8] + 80036aa: 687b ldr r3, [r7, #4] + 80036ac: 681b ldr r3, [r3, #0] + 80036ae: 6899 ldr r1, [r3, #8] + 80036b0: 687b ldr r3, [r7, #4] + 80036b2: 681a ldr r2, [r3, #0] + 80036b4: 4b34 ldr r3, [pc, #208] ; (8003788 ) + 80036b6: 400b ands r3, r1 + 80036b8: 6093 str r3, [r2, #8] /* Configure the Time base in the Encoder Mode */ TIM_Base_SetConfig(htim->Instance, &htim->Init); - 8003636: 687b ldr r3, [r7, #4] - 8003638: 681a ldr r2, [r3, #0] - 800363a: 687b ldr r3, [r7, #4] - 800363c: 3304 adds r3, #4 - 800363e: 4619 mov r1, r3 - 8003640: 4610 mov r0, r2 - 8003642: f000 fbb7 bl 8003db4 + 80036ba: 687b ldr r3, [r7, #4] + 80036bc: 681a ldr r2, [r3, #0] + 80036be: 687b ldr r3, [r7, #4] + 80036c0: 3304 adds r3, #4 + 80036c2: 4619 mov r1, r3 + 80036c4: 4610 mov r0, r2 + 80036c6: f000 fbb7 bl 8003e38 /* Get the TIMx SMCR register value */ tmpsmcr = htim->Instance->SMCR; - 8003646: 687b ldr r3, [r7, #4] - 8003648: 681b ldr r3, [r3, #0] - 800364a: 689b ldr r3, [r3, #8] - 800364c: 617b str r3, [r7, #20] + 80036ca: 687b ldr r3, [r7, #4] + 80036cc: 681b ldr r3, [r3, #0] + 80036ce: 689b ldr r3, [r3, #8] + 80036d0: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmr1 = htim->Instance->CCMR1; - 800364e: 687b ldr r3, [r7, #4] - 8003650: 681b ldr r3, [r3, #0] - 8003652: 699b ldr r3, [r3, #24] - 8003654: 613b str r3, [r7, #16] + 80036d2: 687b ldr r3, [r7, #4] + 80036d4: 681b ldr r3, [r3, #0] + 80036d6: 699b ldr r3, [r3, #24] + 80036d8: 613b str r3, [r7, #16] /* Get the TIMx CCER register value */ tmpccer = htim->Instance->CCER; - 8003656: 687b ldr r3, [r7, #4] - 8003658: 681b ldr r3, [r3, #0] - 800365a: 6a1b ldr r3, [r3, #32] - 800365c: 60fb str r3, [r7, #12] + 80036da: 687b ldr r3, [r7, #4] + 80036dc: 681b ldr r3, [r3, #0] + 80036de: 6a1b ldr r3, [r3, #32] + 80036e0: 60fb str r3, [r7, #12] /* Set the encoder Mode */ tmpsmcr |= sConfig->EncoderMode; - 800365e: 683b ldr r3, [r7, #0] - 8003660: 681b ldr r3, [r3, #0] - 8003662: 697a ldr r2, [r7, #20] - 8003664: 4313 orrs r3, r2 - 8003666: 617b str r3, [r7, #20] + 80036e2: 683b ldr r3, [r7, #0] + 80036e4: 681b ldr r3, [r3, #0] + 80036e6: 697a ldr r2, [r7, #20] + 80036e8: 4313 orrs r3, r2 + 80036ea: 617b str r3, [r7, #20] /* Select the Capture Compare 1 and the Capture Compare 2 as input */ tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); - 8003668: 693a ldr r2, [r7, #16] - 800366a: 4b27 ldr r3, [pc, #156] ; (8003708 ) - 800366c: 4013 ands r3, r2 - 800366e: 613b str r3, [r7, #16] + 80036ec: 693a ldr r2, [r7, #16] + 80036ee: 4b27 ldr r3, [pc, #156] ; (800378c ) + 80036f0: 4013 ands r3, r2 + 80036f2: 613b str r3, [r7, #16] tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); - 8003670: 683b ldr r3, [r7, #0] - 8003672: 689a ldr r2, [r3, #8] - 8003674: 683b ldr r3, [r7, #0] - 8003676: 699b ldr r3, [r3, #24] - 8003678: 021b lsls r3, r3, #8 - 800367a: 4313 orrs r3, r2 - 800367c: 693a ldr r2, [r7, #16] - 800367e: 4313 orrs r3, r2 - 8003680: 613b str r3, [r7, #16] + 80036f4: 683b ldr r3, [r7, #0] + 80036f6: 689a ldr r2, [r3, #8] + 80036f8: 683b ldr r3, [r7, #0] + 80036fa: 699b ldr r3, [r3, #24] + 80036fc: 021b lsls r3, r3, #8 + 80036fe: 4313 orrs r3, r2 + 8003700: 693a ldr r2, [r7, #16] + 8003702: 4313 orrs r3, r2 + 8003704: 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); - 8003682: 693a ldr r2, [r7, #16] - 8003684: 4b21 ldr r3, [pc, #132] ; (800370c ) - 8003686: 4013 ands r3, r2 - 8003688: 613b str r3, [r7, #16] + 8003706: 693a ldr r2, [r7, #16] + 8003708: 4b21 ldr r3, [pc, #132] ; (8003790 ) + 800370a: 4013 ands r3, r2 + 800370c: 613b str r3, [r7, #16] tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); - 800368a: 693a ldr r2, [r7, #16] - 800368c: 4b20 ldr r3, [pc, #128] ; (8003710 ) - 800368e: 4013 ands r3, r2 - 8003690: 613b str r3, [r7, #16] + 800370e: 693a ldr r2, [r7, #16] + 8003710: 4b20 ldr r3, [pc, #128] ; (8003794 ) + 8003712: 4013 ands r3, r2 + 8003714: 613b str r3, [r7, #16] tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); - 8003692: 683b ldr r3, [r7, #0] - 8003694: 68da ldr r2, [r3, #12] - 8003696: 683b ldr r3, [r7, #0] - 8003698: 69db ldr r3, [r3, #28] - 800369a: 021b lsls r3, r3, #8 - 800369c: 4313 orrs r3, r2 - 800369e: 693a ldr r2, [r7, #16] - 80036a0: 4313 orrs r3, r2 - 80036a2: 613b str r3, [r7, #16] + 8003716: 683b ldr r3, [r7, #0] + 8003718: 68da ldr r2, [r3, #12] + 800371a: 683b ldr r3, [r7, #0] + 800371c: 69db ldr r3, [r3, #28] + 800371e: 021b lsls r3, r3, #8 + 8003720: 4313 orrs r3, r2 + 8003722: 693a ldr r2, [r7, #16] + 8003724: 4313 orrs r3, r2 + 8003726: 613b str r3, [r7, #16] tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); - 80036a4: 683b ldr r3, [r7, #0] - 80036a6: 691b ldr r3, [r3, #16] - 80036a8: 011a lsls r2, r3, #4 - 80036aa: 683b ldr r3, [r7, #0] - 80036ac: 6a1b ldr r3, [r3, #32] - 80036ae: 031b lsls r3, r3, #12 - 80036b0: 4313 orrs r3, r2 - 80036b2: 693a ldr r2, [r7, #16] - 80036b4: 4313 orrs r3, r2 - 80036b6: 613b str r3, [r7, #16] + 8003728: 683b ldr r3, [r7, #0] + 800372a: 691b ldr r3, [r3, #16] + 800372c: 011a lsls r2, r3, #4 + 800372e: 683b ldr r3, [r7, #0] + 8003730: 6a1b ldr r3, [r3, #32] + 8003732: 031b lsls r3, r3, #12 + 8003734: 4313 orrs r3, r2 + 8003736: 693a ldr r2, [r7, #16] + 8003738: 4313 orrs r3, r2 + 800373a: 613b str r3, [r7, #16] /* Set the TI1 and the TI2 Polarities */ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); - 80036b8: 68fb ldr r3, [r7, #12] - 80036ba: f023 0322 bic.w r3, r3, #34 ; 0x22 - 80036be: 60fb str r3, [r7, #12] + 800373c: 68fb ldr r3, [r7, #12] + 800373e: f023 0322 bic.w r3, r3, #34 ; 0x22 + 8003742: 60fb str r3, [r7, #12] tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); - 80036c0: 68fb ldr r3, [r7, #12] - 80036c2: f023 0388 bic.w r3, r3, #136 ; 0x88 - 80036c6: 60fb str r3, [r7, #12] + 8003744: 68fb ldr r3, [r7, #12] + 8003746: f023 0388 bic.w r3, r3, #136 ; 0x88 + 800374a: 60fb str r3, [r7, #12] tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); - 80036c8: 683b ldr r3, [r7, #0] - 80036ca: 685a ldr r2, [r3, #4] - 80036cc: 683b ldr r3, [r7, #0] - 80036ce: 695b ldr r3, [r3, #20] - 80036d0: 011b lsls r3, r3, #4 - 80036d2: 4313 orrs r3, r2 - 80036d4: 68fa ldr r2, [r7, #12] - 80036d6: 4313 orrs r3, r2 - 80036d8: 60fb str r3, [r7, #12] + 800374c: 683b ldr r3, [r7, #0] + 800374e: 685a ldr r2, [r3, #4] + 8003750: 683b ldr r3, [r7, #0] + 8003752: 695b ldr r3, [r3, #20] + 8003754: 011b lsls r3, r3, #4 + 8003756: 4313 orrs r3, r2 + 8003758: 68fa ldr r2, [r7, #12] + 800375a: 4313 orrs r3, r2 + 800375c: 60fb str r3, [r7, #12] /* Write to TIMx SMCR */ htim->Instance->SMCR = tmpsmcr; - 80036da: 687b ldr r3, [r7, #4] - 80036dc: 681b ldr r3, [r3, #0] - 80036de: 697a ldr r2, [r7, #20] - 80036e0: 609a str r2, [r3, #8] + 800375e: 687b ldr r3, [r7, #4] + 8003760: 681b ldr r3, [r3, #0] + 8003762: 697a ldr r2, [r7, #20] + 8003764: 609a str r2, [r3, #8] /* Write to TIMx CCMR1 */ htim->Instance->CCMR1 = tmpccmr1; - 80036e2: 687b ldr r3, [r7, #4] - 80036e4: 681b ldr r3, [r3, #0] - 80036e6: 693a ldr r2, [r7, #16] - 80036e8: 619a str r2, [r3, #24] + 8003766: 687b ldr r3, [r7, #4] + 8003768: 681b ldr r3, [r3, #0] + 800376a: 693a ldr r2, [r7, #16] + 800376c: 619a str r2, [r3, #24] /* Write to TIMx CCER */ htim->Instance->CCER = tmpccer; - 80036ea: 687b ldr r3, [r7, #4] - 80036ec: 681b ldr r3, [r3, #0] - 80036ee: 68fa ldr r2, [r7, #12] - 80036f0: 621a str r2, [r3, #32] + 800376e: 687b ldr r3, [r7, #4] + 8003770: 681b ldr r3, [r3, #0] + 8003772: 68fa ldr r2, [r7, #12] + 8003774: 621a str r2, [r3, #32] /* Initialize the TIM state*/ htim->State = HAL_TIM_STATE_READY; - 80036f2: 687b ldr r3, [r7, #4] - 80036f4: 2201 movs r2, #1 - 80036f6: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003776: 687b ldr r3, [r7, #4] + 8003778: 2201 movs r2, #1 + 800377a: f883 203d strb.w r2, [r3, #61] ; 0x3d return HAL_OK; - 80036fa: 2300 movs r3, #0 + 800377e: 2300 movs r3, #0 } - 80036fc: 4618 mov r0, r3 - 80036fe: 3718 adds r7, #24 - 8003700: 46bd mov sp, r7 - 8003702: bd80 pop {r7, pc} - 8003704: fffebff8 .word 0xfffebff8 - 8003708: fffffcfc .word 0xfffffcfc - 800370c: fffff3f3 .word 0xfffff3f3 - 8003710: ffff0f0f .word 0xffff0f0f - -08003714 : + 8003780: 4618 mov r0, r3 + 8003782: 3718 adds r7, #24 + 8003784: 46bd mov sp, r7 + 8003786: bd80 pop {r7, pc} + 8003788: fffebff8 .word 0xfffebff8 + 800378c: fffffcfc .word 0xfffffcfc + 8003790: fffff3f3 .word 0xfffff3f3 + 8003794: ffff0f0f .word 0xffff0f0f + +08003798 : * @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) { - 8003714: b580 push {r7, lr} - 8003716: b082 sub sp, #8 - 8003718: af00 add r7, sp, #0 - 800371a: 6078 str r0, [r7, #4] - 800371c: 6039 str r1, [r7, #0] + 8003798: b580 push {r7, lr} + 800379a: b082 sub sp, #8 + 800379c: af00 add r7, sp, #0 + 800379e: 6078 str r0, [r7, #4] + 80037a0: 6039 str r1, [r7, #0] /* Check the parameters */ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); /* Enable the encoder interface channels */ switch (Channel) - 800371e: 683b ldr r3, [r7, #0] - 8003720: 2b00 cmp r3, #0 - 8003722: d002 beq.n 800372a - 8003724: 2b04 cmp r3, #4 - 8003726: d008 beq.n 800373a - 8003728: e00f b.n 800374a + 80037a2: 683b ldr r3, [r7, #0] + 80037a4: 2b00 cmp r3, #0 + 80037a6: d002 beq.n 80037ae + 80037a8: 2b04 cmp r3, #4 + 80037aa: d008 beq.n 80037be + 80037ac: e00f b.n 80037ce { case TIM_CHANNEL_1: { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - 800372a: 687b ldr r3, [r7, #4] - 800372c: 681b ldr r3, [r3, #0] - 800372e: 2201 movs r2, #1 - 8003730: 2100 movs r1, #0 - 8003732: 4618 mov r0, r3 - 8003734: f000 fed6 bl 80044e4 + 80037ae: 687b ldr r3, [r7, #4] + 80037b0: 681b ldr r3, [r3, #0] + 80037b2: 2201 movs r2, #1 + 80037b4: 2100 movs r1, #0 + 80037b6: 4618 mov r0, r3 + 80037b8: f000 fed6 bl 8004568 break; - 8003738: e016 b.n 8003768 + 80037bc: e016 b.n 80037ec } case TIM_CHANNEL_2: { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - 800373a: 687b ldr r3, [r7, #4] - 800373c: 681b ldr r3, [r3, #0] - 800373e: 2201 movs r2, #1 - 8003740: 2104 movs r1, #4 - 8003742: 4618 mov r0, r3 - 8003744: f000 fece bl 80044e4 + 80037be: 687b ldr r3, [r7, #4] + 80037c0: 681b ldr r3, [r3, #0] + 80037c2: 2201 movs r2, #1 + 80037c4: 2104 movs r1, #4 + 80037c6: 4618 mov r0, r3 + 80037c8: f000 fece bl 8004568 break; - 8003748: e00e b.n 8003768 + 80037cc: e00e b.n 80037ec } default : { TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - 800374a: 687b ldr r3, [r7, #4] - 800374c: 681b ldr r3, [r3, #0] - 800374e: 2201 movs r2, #1 - 8003750: 2100 movs r1, #0 - 8003752: 4618 mov r0, r3 - 8003754: f000 fec6 bl 80044e4 + 80037ce: 687b ldr r3, [r7, #4] + 80037d0: 681b ldr r3, [r3, #0] + 80037d2: 2201 movs r2, #1 + 80037d4: 2100 movs r1, #0 + 80037d6: 4618 mov r0, r3 + 80037d8: f000 fec6 bl 8004568 TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - 8003758: 687b ldr r3, [r7, #4] - 800375a: 681b ldr r3, [r3, #0] - 800375c: 2201 movs r2, #1 - 800375e: 2104 movs r1, #4 - 8003760: 4618 mov r0, r3 - 8003762: f000 febf bl 80044e4 + 80037dc: 687b ldr r3, [r7, #4] + 80037de: 681b ldr r3, [r3, #0] + 80037e0: 2201 movs r2, #1 + 80037e2: 2104 movs r1, #4 + 80037e4: 4618 mov r0, r3 + 80037e6: f000 febf bl 8004568 break; - 8003766: bf00 nop + 80037ea: bf00 nop } } /* Enable the Peripheral */ __HAL_TIM_ENABLE(htim); - 8003768: 687b ldr r3, [r7, #4] - 800376a: 681b ldr r3, [r3, #0] - 800376c: 681a ldr r2, [r3, #0] - 800376e: 687b ldr r3, [r7, #4] - 8003770: 681b ldr r3, [r3, #0] - 8003772: f042 0201 orr.w r2, r2, #1 - 8003776: 601a str r2, [r3, #0] + 80037ec: 687b ldr r3, [r7, #4] + 80037ee: 681b ldr r3, [r3, #0] + 80037f0: 681a ldr r2, [r3, #0] + 80037f2: 687b ldr r3, [r7, #4] + 80037f4: 681b ldr r3, [r3, #0] + 80037f6: f042 0201 orr.w r2, r2, #1 + 80037fa: 601a str r2, [r3, #0] /* Return function status */ return HAL_OK; - 8003778: 2300 movs r3, #0 + 80037fc: 2300 movs r3, #0 } - 800377a: 4618 mov r0, r3 - 800377c: 3708 adds r7, #8 - 800377e: 46bd mov sp, r7 - 8003780: bd80 pop {r7, pc} + 80037fe: 4618 mov r0, r3 + 8003800: 3708 adds r7, #8 + 8003802: 46bd mov sp, r7 + 8003804: bd80 pop {r7, pc} -08003782 : +08003806 : * @brief This function handles TIM interrupts requests. * @param htim TIM handle * @retval None */ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) { - 8003782: b580 push {r7, lr} - 8003784: b082 sub sp, #8 - 8003786: af00 add r7, sp, #0 - 8003788: 6078 str r0, [r7, #4] + 8003806: b580 push {r7, lr} + 8003808: b082 sub sp, #8 + 800380a: af00 add r7, sp, #0 + 800380c: 6078 str r0, [r7, #4] /* Capture compare 1 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) - 800378a: 687b ldr r3, [r7, #4] - 800378c: 681b ldr r3, [r3, #0] - 800378e: 691b ldr r3, [r3, #16] - 8003790: f003 0302 and.w r3, r3, #2 - 8003794: 2b02 cmp r3, #2 - 8003796: d122 bne.n 80037de + 800380e: 687b ldr r3, [r7, #4] + 8003810: 681b ldr r3, [r3, #0] + 8003812: 691b ldr r3, [r3, #16] + 8003814: f003 0302 and.w r3, r3, #2 + 8003818: 2b02 cmp r3, #2 + 800381a: d122 bne.n 8003862 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) - 8003798: 687b ldr r3, [r7, #4] - 800379a: 681b ldr r3, [r3, #0] - 800379c: 68db ldr r3, [r3, #12] - 800379e: f003 0302 and.w r3, r3, #2 - 80037a2: 2b02 cmp r3, #2 - 80037a4: d11b bne.n 80037de + 800381c: 687b ldr r3, [r7, #4] + 800381e: 681b ldr r3, [r3, #0] + 8003820: 68db ldr r3, [r3, #12] + 8003822: f003 0302 and.w r3, r3, #2 + 8003826: 2b02 cmp r3, #2 + 8003828: d11b bne.n 8003862 { { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); - 80037a6: 687b ldr r3, [r7, #4] - 80037a8: 681b ldr r3, [r3, #0] - 80037aa: f06f 0202 mvn.w r2, #2 - 80037ae: 611a str r2, [r3, #16] + 800382a: 687b ldr r3, [r7, #4] + 800382c: 681b ldr r3, [r3, #0] + 800382e: f06f 0202 mvn.w r2, #2 + 8003832: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - 80037b0: 687b ldr r3, [r7, #4] - 80037b2: 2201 movs r2, #1 - 80037b4: 771a strb r2, [r3, #28] + 8003834: 687b ldr r3, [r7, #4] + 8003836: 2201 movs r2, #1 + 8003838: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) - 80037b6: 687b ldr r3, [r7, #4] - 80037b8: 681b ldr r3, [r3, #0] - 80037ba: 699b ldr r3, [r3, #24] - 80037bc: f003 0303 and.w r3, r3, #3 - 80037c0: 2b00 cmp r3, #0 - 80037c2: d003 beq.n 80037cc + 800383a: 687b ldr r3, [r7, #4] + 800383c: 681b ldr r3, [r3, #0] + 800383e: 699b ldr r3, [r3, #24] + 8003840: f003 0303 and.w r3, r3, #3 + 8003844: 2b00 cmp r3, #0 + 8003846: d003 beq.n 8003850 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 80037c4: 6878 ldr r0, [r7, #4] - 80037c6: f000 fad7 bl 8003d78 - 80037ca: e005 b.n 80037d8 + 8003848: 6878 ldr r0, [r7, #4] + 800384a: f000 fad7 bl 8003dfc + 800384e: e005 b.n 800385c { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 80037cc: 6878 ldr r0, [r7, #4] - 80037ce: f000 fac9 bl 8003d64 + 8003850: 6878 ldr r0, [r7, #4] + 8003852: f000 fac9 bl 8003de8 HAL_TIM_PWM_PulseFinishedCallback(htim); - 80037d2: 6878 ldr r0, [r7, #4] - 80037d4: f000 fada bl 8003d8c + 8003856: 6878 ldr r0, [r7, #4] + 8003858: f000 fada bl 8003e10 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 80037d8: 687b ldr r3, [r7, #4] - 80037da: 2200 movs r2, #0 - 80037dc: 771a strb r2, [r3, #28] + 800385c: 687b ldr r3, [r7, #4] + 800385e: 2200 movs r2, #0 + 8003860: 771a strb r2, [r3, #28] } } } /* Capture compare 2 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) - 80037de: 687b ldr r3, [r7, #4] - 80037e0: 681b ldr r3, [r3, #0] - 80037e2: 691b ldr r3, [r3, #16] - 80037e4: f003 0304 and.w r3, r3, #4 - 80037e8: 2b04 cmp r3, #4 - 80037ea: d122 bne.n 8003832 + 8003862: 687b ldr r3, [r7, #4] + 8003864: 681b ldr r3, [r3, #0] + 8003866: 691b ldr r3, [r3, #16] + 8003868: f003 0304 and.w r3, r3, #4 + 800386c: 2b04 cmp r3, #4 + 800386e: d122 bne.n 80038b6 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) - 80037ec: 687b ldr r3, [r7, #4] - 80037ee: 681b ldr r3, [r3, #0] - 80037f0: 68db ldr r3, [r3, #12] - 80037f2: f003 0304 and.w r3, r3, #4 - 80037f6: 2b04 cmp r3, #4 - 80037f8: d11b bne.n 8003832 + 8003870: 687b ldr r3, [r7, #4] + 8003872: 681b ldr r3, [r3, #0] + 8003874: 68db ldr r3, [r3, #12] + 8003876: f003 0304 and.w r3, r3, #4 + 800387a: 2b04 cmp r3, #4 + 800387c: d11b bne.n 80038b6 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); - 80037fa: 687b ldr r3, [r7, #4] - 80037fc: 681b ldr r3, [r3, #0] - 80037fe: f06f 0204 mvn.w r2, #4 - 8003802: 611a str r2, [r3, #16] + 800387e: 687b ldr r3, [r7, #4] + 8003880: 681b ldr r3, [r3, #0] + 8003882: f06f 0204 mvn.w r2, #4 + 8003886: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - 8003804: 687b ldr r3, [r7, #4] - 8003806: 2202 movs r2, #2 - 8003808: 771a strb r2, [r3, #28] + 8003888: 687b ldr r3, [r7, #4] + 800388a: 2202 movs r2, #2 + 800388c: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) - 800380a: 687b ldr r3, [r7, #4] - 800380c: 681b ldr r3, [r3, #0] - 800380e: 699b ldr r3, [r3, #24] - 8003810: f403 7340 and.w r3, r3, #768 ; 0x300 - 8003814: 2b00 cmp r3, #0 - 8003816: d003 beq.n 8003820 + 800388e: 687b ldr r3, [r7, #4] + 8003890: 681b ldr r3, [r3, #0] + 8003892: 699b ldr r3, [r3, #24] + 8003894: f403 7340 and.w r3, r3, #768 ; 0x300 + 8003898: 2b00 cmp r3, #0 + 800389a: d003 beq.n 80038a4 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 8003818: 6878 ldr r0, [r7, #4] - 800381a: f000 faad bl 8003d78 - 800381e: e005 b.n 800382c + 800389c: 6878 ldr r0, [r7, #4] + 800389e: f000 faad bl 8003dfc + 80038a2: e005 b.n 80038b0 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 8003820: 6878 ldr r0, [r7, #4] - 8003822: f000 fa9f bl 8003d64 + 80038a4: 6878 ldr r0, [r7, #4] + 80038a6: f000 fa9f bl 8003de8 HAL_TIM_PWM_PulseFinishedCallback(htim); - 8003826: 6878 ldr r0, [r7, #4] - 8003828: f000 fab0 bl 8003d8c + 80038aa: 6878 ldr r0, [r7, #4] + 80038ac: f000 fab0 bl 8003e10 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 800382c: 687b ldr r3, [r7, #4] - 800382e: 2200 movs r2, #0 - 8003830: 771a strb r2, [r3, #28] + 80038b0: 687b ldr r3, [r7, #4] + 80038b2: 2200 movs r2, #0 + 80038b4: 771a strb r2, [r3, #28] } } /* Capture compare 3 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) - 8003832: 687b ldr r3, [r7, #4] - 8003834: 681b ldr r3, [r3, #0] - 8003836: 691b ldr r3, [r3, #16] - 8003838: f003 0308 and.w r3, r3, #8 - 800383c: 2b08 cmp r3, #8 - 800383e: d122 bne.n 8003886 + 80038b6: 687b ldr r3, [r7, #4] + 80038b8: 681b ldr r3, [r3, #0] + 80038ba: 691b ldr r3, [r3, #16] + 80038bc: f003 0308 and.w r3, r3, #8 + 80038c0: 2b08 cmp r3, #8 + 80038c2: d122 bne.n 800390a { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) - 8003840: 687b ldr r3, [r7, #4] - 8003842: 681b ldr r3, [r3, #0] - 8003844: 68db ldr r3, [r3, #12] - 8003846: f003 0308 and.w r3, r3, #8 - 800384a: 2b08 cmp r3, #8 - 800384c: d11b bne.n 8003886 + 80038c4: 687b ldr r3, [r7, #4] + 80038c6: 681b ldr r3, [r3, #0] + 80038c8: 68db ldr r3, [r3, #12] + 80038ca: f003 0308 and.w r3, r3, #8 + 80038ce: 2b08 cmp r3, #8 + 80038d0: d11b bne.n 800390a { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); - 800384e: 687b ldr r3, [r7, #4] - 8003850: 681b ldr r3, [r3, #0] - 8003852: f06f 0208 mvn.w r2, #8 - 8003856: 611a str r2, [r3, #16] + 80038d2: 687b ldr r3, [r7, #4] + 80038d4: 681b ldr r3, [r3, #0] + 80038d6: f06f 0208 mvn.w r2, #8 + 80038da: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - 8003858: 687b ldr r3, [r7, #4] - 800385a: 2204 movs r2, #4 - 800385c: 771a strb r2, [r3, #28] + 80038dc: 687b ldr r3, [r7, #4] + 80038de: 2204 movs r2, #4 + 80038e0: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) - 800385e: 687b ldr r3, [r7, #4] - 8003860: 681b ldr r3, [r3, #0] - 8003862: 69db ldr r3, [r3, #28] - 8003864: f003 0303 and.w r3, r3, #3 - 8003868: 2b00 cmp r3, #0 - 800386a: d003 beq.n 8003874 + 80038e2: 687b ldr r3, [r7, #4] + 80038e4: 681b ldr r3, [r3, #0] + 80038e6: 69db ldr r3, [r3, #28] + 80038e8: f003 0303 and.w r3, r3, #3 + 80038ec: 2b00 cmp r3, #0 + 80038ee: d003 beq.n 80038f8 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 800386c: 6878 ldr r0, [r7, #4] - 800386e: f000 fa83 bl 8003d78 - 8003872: e005 b.n 8003880 + 80038f0: 6878 ldr r0, [r7, #4] + 80038f2: f000 fa83 bl 8003dfc + 80038f6: e005 b.n 8003904 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 8003874: 6878 ldr r0, [r7, #4] - 8003876: f000 fa75 bl 8003d64 + 80038f8: 6878 ldr r0, [r7, #4] + 80038fa: f000 fa75 bl 8003de8 HAL_TIM_PWM_PulseFinishedCallback(htim); - 800387a: 6878 ldr r0, [r7, #4] - 800387c: f000 fa86 bl 8003d8c + 80038fe: 6878 ldr r0, [r7, #4] + 8003900: f000 fa86 bl 8003e10 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 8003880: 687b ldr r3, [r7, #4] - 8003882: 2200 movs r2, #0 - 8003884: 771a strb r2, [r3, #28] + 8003904: 687b ldr r3, [r7, #4] + 8003906: 2200 movs r2, #0 + 8003908: 771a strb r2, [r3, #28] } } /* Capture compare 4 event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) - 8003886: 687b ldr r3, [r7, #4] - 8003888: 681b ldr r3, [r3, #0] - 800388a: 691b ldr r3, [r3, #16] - 800388c: f003 0310 and.w r3, r3, #16 - 8003890: 2b10 cmp r3, #16 - 8003892: d122 bne.n 80038da + 800390a: 687b ldr r3, [r7, #4] + 800390c: 681b ldr r3, [r3, #0] + 800390e: 691b ldr r3, [r3, #16] + 8003910: f003 0310 and.w r3, r3, #16 + 8003914: 2b10 cmp r3, #16 + 8003916: d122 bne.n 800395e { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) - 8003894: 687b ldr r3, [r7, #4] - 8003896: 681b ldr r3, [r3, #0] - 8003898: 68db ldr r3, [r3, #12] - 800389a: f003 0310 and.w r3, r3, #16 - 800389e: 2b10 cmp r3, #16 - 80038a0: d11b bne.n 80038da + 8003918: 687b ldr r3, [r7, #4] + 800391a: 681b ldr r3, [r3, #0] + 800391c: 68db ldr r3, [r3, #12] + 800391e: f003 0310 and.w r3, r3, #16 + 8003922: 2b10 cmp r3, #16 + 8003924: d11b bne.n 800395e { __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); - 80038a2: 687b ldr r3, [r7, #4] - 80038a4: 681b ldr r3, [r3, #0] - 80038a6: f06f 0210 mvn.w r2, #16 - 80038aa: 611a str r2, [r3, #16] + 8003926: 687b ldr r3, [r7, #4] + 8003928: 681b ldr r3, [r3, #0] + 800392a: f06f 0210 mvn.w r2, #16 + 800392e: 611a str r2, [r3, #16] htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - 80038ac: 687b ldr r3, [r7, #4] - 80038ae: 2208 movs r2, #8 - 80038b0: 771a strb r2, [r3, #28] + 8003930: 687b ldr r3, [r7, #4] + 8003932: 2208 movs r2, #8 + 8003934: 771a strb r2, [r3, #28] /* Input capture event */ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) - 80038b2: 687b ldr r3, [r7, #4] - 80038b4: 681b ldr r3, [r3, #0] - 80038b6: 69db ldr r3, [r3, #28] - 80038b8: f403 7340 and.w r3, r3, #768 ; 0x300 - 80038bc: 2b00 cmp r3, #0 - 80038be: d003 beq.n 80038c8 + 8003936: 687b ldr r3, [r7, #4] + 8003938: 681b ldr r3, [r3, #0] + 800393a: 69db ldr r3, [r3, #28] + 800393c: f403 7340 and.w r3, r3, #768 ; 0x300 + 8003940: 2b00 cmp r3, #0 + 8003942: d003 beq.n 800394c { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->IC_CaptureCallback(htim); #else HAL_TIM_IC_CaptureCallback(htim); - 80038c0: 6878 ldr r0, [r7, #4] - 80038c2: f000 fa59 bl 8003d78 - 80038c6: e005 b.n 80038d4 + 8003944: 6878 ldr r0, [r7, #4] + 8003946: f000 fa59 bl 8003dfc + 800394a: e005 b.n 8003958 { #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->OC_DelayElapsedCallback(htim); htim->PWM_PulseFinishedCallback(htim); #else HAL_TIM_OC_DelayElapsedCallback(htim); - 80038c8: 6878 ldr r0, [r7, #4] - 80038ca: f000 fa4b bl 8003d64 + 800394c: 6878 ldr r0, [r7, #4] + 800394e: f000 fa4b bl 8003de8 HAL_TIM_PWM_PulseFinishedCallback(htim); - 80038ce: 6878 ldr r0, [r7, #4] - 80038d0: f000 fa5c bl 8003d8c + 8003952: 6878 ldr r0, [r7, #4] + 8003954: f000 fa5c bl 8003e10 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - 80038d4: 687b ldr r3, [r7, #4] - 80038d6: 2200 movs r2, #0 - 80038d8: 771a strb r2, [r3, #28] + 8003958: 687b ldr r3, [r7, #4] + 800395a: 2200 movs r2, #0 + 800395c: 771a strb r2, [r3, #28] } } /* TIM Update event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) - 80038da: 687b ldr r3, [r7, #4] - 80038dc: 681b ldr r3, [r3, #0] - 80038de: 691b ldr r3, [r3, #16] - 80038e0: f003 0301 and.w r3, r3, #1 - 80038e4: 2b01 cmp r3, #1 - 80038e6: d10e bne.n 8003906 + 800395e: 687b ldr r3, [r7, #4] + 8003960: 681b ldr r3, [r3, #0] + 8003962: 691b ldr r3, [r3, #16] + 8003964: f003 0301 and.w r3, r3, #1 + 8003968: 2b01 cmp r3, #1 + 800396a: d10e bne.n 800398a { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) - 80038e8: 687b ldr r3, [r7, #4] - 80038ea: 681b ldr r3, [r3, #0] - 80038ec: 68db ldr r3, [r3, #12] - 80038ee: f003 0301 and.w r3, r3, #1 - 80038f2: 2b01 cmp r3, #1 - 80038f4: d107 bne.n 8003906 + 800396c: 687b ldr r3, [r7, #4] + 800396e: 681b ldr r3, [r3, #0] + 8003970: 68db ldr r3, [r3, #12] + 8003972: f003 0301 and.w r3, r3, #1 + 8003976: 2b01 cmp r3, #1 + 8003978: d107 bne.n 800398a { __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); - 80038f6: 687b ldr r3, [r7, #4] - 80038f8: 681b ldr r3, [r3, #0] - 80038fa: f06f 0201 mvn.w r2, #1 - 80038fe: 611a str r2, [r3, #16] + 800397a: 687b ldr r3, [r7, #4] + 800397c: 681b ldr r3, [r3, #0] + 800397e: f06f 0201 mvn.w r2, #1 + 8003982: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->PeriodElapsedCallback(htim); #else HAL_TIM_PeriodElapsedCallback(htim); - 8003900: 6878 ldr r0, [r7, #4] - 8003902: f7fd fdb7 bl 8001474 + 8003984: 6878 ldr r0, [r7, #4] + 8003986: f7fd fcf9 bl 800137c #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Break input event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) - 8003906: 687b ldr r3, [r7, #4] - 8003908: 681b ldr r3, [r3, #0] - 800390a: 691b ldr r3, [r3, #16] - 800390c: f003 0380 and.w r3, r3, #128 ; 0x80 - 8003910: 2b80 cmp r3, #128 ; 0x80 - 8003912: d10e bne.n 8003932 + 800398a: 687b ldr r3, [r7, #4] + 800398c: 681b ldr r3, [r3, #0] + 800398e: 691b ldr r3, [r3, #16] + 8003990: f003 0380 and.w r3, r3, #128 ; 0x80 + 8003994: 2b80 cmp r3, #128 ; 0x80 + 8003996: d10e bne.n 80039b6 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - 8003914: 687b ldr r3, [r7, #4] - 8003916: 681b ldr r3, [r3, #0] - 8003918: 68db ldr r3, [r3, #12] - 800391a: f003 0380 and.w r3, r3, #128 ; 0x80 - 800391e: 2b80 cmp r3, #128 ; 0x80 - 8003920: d107 bne.n 8003932 + 8003998: 687b ldr r3, [r7, #4] + 800399a: 681b ldr r3, [r3, #0] + 800399c: 68db ldr r3, [r3, #12] + 800399e: f003 0380 and.w r3, r3, #128 ; 0x80 + 80039a2: 2b80 cmp r3, #128 ; 0x80 + 80039a4: d107 bne.n 80039b6 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); - 8003922: 687b ldr r3, [r7, #4] - 8003924: 681b ldr r3, [r3, #0] - 8003926: f06f 0280 mvn.w r2, #128 ; 0x80 - 800392a: 611a str r2, [r3, #16] + 80039a6: 687b ldr r3, [r7, #4] + 80039a8: 681b ldr r3, [r3, #0] + 80039aa: f06f 0280 mvn.w r2, #128 ; 0x80 + 80039ae: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->BreakCallback(htim); #else HAL_TIMEx_BreakCallback(htim); - 800392c: 6878 ldr r0, [r7, #4] - 800392e: f000 fe65 bl 80045fc + 80039b0: 6878 ldr r0, [r7, #4] + 80039b2: f000 fe65 bl 8004680 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Break2 input event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK2) != RESET) - 8003932: 687b ldr r3, [r7, #4] - 8003934: 681b ldr r3, [r3, #0] - 8003936: 691b ldr r3, [r3, #16] - 8003938: f403 7380 and.w r3, r3, #256 ; 0x100 - 800393c: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 8003940: d10e bne.n 8003960 + 80039b6: 687b ldr r3, [r7, #4] + 80039b8: 681b ldr r3, [r3, #0] + 80039ba: 691b ldr r3, [r3, #16] + 80039bc: f403 7380 and.w r3, r3, #256 ; 0x100 + 80039c0: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 80039c4: d10e bne.n 80039e4 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - 8003942: 687b ldr r3, [r7, #4] - 8003944: 681b ldr r3, [r3, #0] - 8003946: 68db ldr r3, [r3, #12] - 8003948: f003 0380 and.w r3, r3, #128 ; 0x80 - 800394c: 2b80 cmp r3, #128 ; 0x80 - 800394e: d107 bne.n 8003960 + 80039c6: 687b ldr r3, [r7, #4] + 80039c8: 681b ldr r3, [r3, #0] + 80039ca: 68db ldr r3, [r3, #12] + 80039cc: f003 0380 and.w r3, r3, #128 ; 0x80 + 80039d0: 2b80 cmp r3, #128 ; 0x80 + 80039d2: d107 bne.n 80039e4 { __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_BREAK2); - 8003950: 687b ldr r3, [r7, #4] - 8003952: 681b ldr r3, [r3, #0] - 8003954: f46f 7280 mvn.w r2, #256 ; 0x100 - 8003958: 611a str r2, [r3, #16] + 80039d4: 687b ldr r3, [r7, #4] + 80039d6: 681b ldr r3, [r3, #0] + 80039d8: f46f 7280 mvn.w r2, #256 ; 0x100 + 80039dc: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->Break2Callback(htim); #else HAL_TIMEx_Break2Callback(htim); - 800395a: 6878 ldr r0, [r7, #4] - 800395c: f000 fe58 bl 8004610 + 80039de: 6878 ldr r0, [r7, #4] + 80039e0: f000 fe58 bl 8004694 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM Trigger detection event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) - 8003960: 687b ldr r3, [r7, #4] - 8003962: 681b ldr r3, [r3, #0] - 8003964: 691b ldr r3, [r3, #16] - 8003966: f003 0340 and.w r3, r3, #64 ; 0x40 - 800396a: 2b40 cmp r3, #64 ; 0x40 - 800396c: d10e bne.n 800398c + 80039e4: 687b ldr r3, [r7, #4] + 80039e6: 681b ldr r3, [r3, #0] + 80039e8: 691b ldr r3, [r3, #16] + 80039ea: f003 0340 and.w r3, r3, #64 ; 0x40 + 80039ee: 2b40 cmp r3, #64 ; 0x40 + 80039f0: d10e bne.n 8003a10 { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) - 800396e: 687b ldr r3, [r7, #4] - 8003970: 681b ldr r3, [r3, #0] - 8003972: 68db ldr r3, [r3, #12] - 8003974: f003 0340 and.w r3, r3, #64 ; 0x40 - 8003978: 2b40 cmp r3, #64 ; 0x40 - 800397a: d107 bne.n 800398c + 80039f2: 687b ldr r3, [r7, #4] + 80039f4: 681b ldr r3, [r3, #0] + 80039f6: 68db ldr r3, [r3, #12] + 80039f8: f003 0340 and.w r3, r3, #64 ; 0x40 + 80039fc: 2b40 cmp r3, #64 ; 0x40 + 80039fe: d107 bne.n 8003a10 { __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); - 800397c: 687b ldr r3, [r7, #4] - 800397e: 681b ldr r3, [r3, #0] - 8003980: f06f 0240 mvn.w r2, #64 ; 0x40 - 8003984: 611a str r2, [r3, #16] + 8003a00: 687b ldr r3, [r7, #4] + 8003a02: 681b ldr r3, [r3, #0] + 8003a04: f06f 0240 mvn.w r2, #64 ; 0x40 + 8003a08: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->TriggerCallback(htim); #else HAL_TIM_TriggerCallback(htim); - 8003986: 6878 ldr r0, [r7, #4] - 8003988: f000 fa0a bl 8003da0 + 8003a0a: 6878 ldr r0, [r7, #4] + 8003a0c: f000 fa0a bl 8003e24 #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } /* TIM commutation event */ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) - 800398c: 687b ldr r3, [r7, #4] - 800398e: 681b ldr r3, [r3, #0] - 8003990: 691b ldr r3, [r3, #16] - 8003992: f003 0320 and.w r3, r3, #32 - 8003996: 2b20 cmp r3, #32 - 8003998: d10e bne.n 80039b8 + 8003a10: 687b ldr r3, [r7, #4] + 8003a12: 681b ldr r3, [r3, #0] + 8003a14: 691b ldr r3, [r3, #16] + 8003a16: f003 0320 and.w r3, r3, #32 + 8003a1a: 2b20 cmp r3, #32 + 8003a1c: d10e bne.n 8003a3c { if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) - 800399a: 687b ldr r3, [r7, #4] - 800399c: 681b ldr r3, [r3, #0] - 800399e: 68db ldr r3, [r3, #12] - 80039a0: f003 0320 and.w r3, r3, #32 - 80039a4: 2b20 cmp r3, #32 - 80039a6: d107 bne.n 80039b8 + 8003a1e: 687b ldr r3, [r7, #4] + 8003a20: 681b ldr r3, [r3, #0] + 8003a22: 68db ldr r3, [r3, #12] + 8003a24: f003 0320 and.w r3, r3, #32 + 8003a28: 2b20 cmp r3, #32 + 8003a2a: d107 bne.n 8003a3c { __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); - 80039a8: 687b ldr r3, [r7, #4] - 80039aa: 681b ldr r3, [r3, #0] - 80039ac: f06f 0220 mvn.w r2, #32 - 80039b0: 611a str r2, [r3, #16] + 8003a2c: 687b ldr r3, [r7, #4] + 8003a2e: 681b ldr r3, [r3, #0] + 8003a30: f06f 0220 mvn.w r2, #32 + 8003a34: 611a str r2, [r3, #16] #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) htim->CommutationCallback(htim); #else HAL_TIMEx_CommutCallback(htim); - 80039b2: 6878 ldr r0, [r7, #4] - 80039b4: f000 fe18 bl 80045e8 + 8003a36: 6878 ldr r0, [r7, #4] + 8003a38: f000 fe18 bl 800466c #endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ } } } - 80039b8: bf00 nop - 80039ba: 3708 adds r7, #8 - 80039bc: 46bd mov sp, r7 - 80039be: bd80 pop {r7, pc} + 8003a3c: bf00 nop + 8003a3e: 3708 adds r7, #8 + 8003a40: 46bd mov sp, r7 + 8003a42: bd80 pop {r7, pc} -080039c0 : +08003a44 : * @retval HAL status */ HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel) { - 80039c0: b580 push {r7, lr} - 80039c2: b084 sub sp, #16 - 80039c4: af00 add r7, sp, #0 - 80039c6: 60f8 str r0, [r7, #12] - 80039c8: 60b9 str r1, [r7, #8] - 80039ca: 607a str r2, [r7, #4] + 8003a44: b580 push {r7, lr} + 8003a46: b084 sub sp, #16 + 8003a48: af00 add r7, sp, #0 + 8003a4a: 60f8 str r0, [r7, #12] + 8003a4c: 60b9 str r1, [r7, #8] + 8003a4e: 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); - 80039cc: 68fb ldr r3, [r7, #12] - 80039ce: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 80039d2: 2b01 cmp r3, #1 - 80039d4: d101 bne.n 80039da - 80039d6: 2302 movs r3, #2 - 80039d8: e105 b.n 8003be6 - 80039da: 68fb ldr r3, [r7, #12] - 80039dc: 2201 movs r2, #1 - 80039de: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003a50: 68fb ldr r3, [r7, #12] + 8003a52: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8003a56: 2b01 cmp r3, #1 + 8003a58: d101 bne.n 8003a5e + 8003a5a: 2302 movs r3, #2 + 8003a5c: e105 b.n 8003c6a + 8003a5e: 68fb ldr r3, [r7, #12] + 8003a60: 2201 movs r2, #1 + 8003a62: f883 203c strb.w r2, [r3, #60] ; 0x3c htim->State = HAL_TIM_STATE_BUSY; - 80039e2: 68fb ldr r3, [r7, #12] - 80039e4: 2202 movs r2, #2 - 80039e6: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003a66: 68fb ldr r3, [r7, #12] + 8003a68: 2202 movs r2, #2 + 8003a6a: f883 203d strb.w r2, [r3, #61] ; 0x3d switch (Channel) - 80039ea: 687b ldr r3, [r7, #4] - 80039ec: 2b14 cmp r3, #20 - 80039ee: f200 80f0 bhi.w 8003bd2 - 80039f2: a201 add r2, pc, #4 ; (adr r2, 80039f8 ) - 80039f4: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 80039f8: 08003a4d .word 0x08003a4d - 80039fc: 08003bd3 .word 0x08003bd3 - 8003a00: 08003bd3 .word 0x08003bd3 - 8003a04: 08003bd3 .word 0x08003bd3 - 8003a08: 08003a8d .word 0x08003a8d - 8003a0c: 08003bd3 .word 0x08003bd3 - 8003a10: 08003bd3 .word 0x08003bd3 - 8003a14: 08003bd3 .word 0x08003bd3 - 8003a18: 08003acf .word 0x08003acf - 8003a1c: 08003bd3 .word 0x08003bd3 - 8003a20: 08003bd3 .word 0x08003bd3 - 8003a24: 08003bd3 .word 0x08003bd3 - 8003a28: 08003b0f .word 0x08003b0f - 8003a2c: 08003bd3 .word 0x08003bd3 - 8003a30: 08003bd3 .word 0x08003bd3 - 8003a34: 08003bd3 .word 0x08003bd3 - 8003a38: 08003b51 .word 0x08003b51 - 8003a3c: 08003bd3 .word 0x08003bd3 - 8003a40: 08003bd3 .word 0x08003bd3 - 8003a44: 08003bd3 .word 0x08003bd3 - 8003a48: 08003b91 .word 0x08003b91 + 8003a6e: 687b ldr r3, [r7, #4] + 8003a70: 2b14 cmp r3, #20 + 8003a72: f200 80f0 bhi.w 8003c56 + 8003a76: a201 add r2, pc, #4 ; (adr r2, 8003a7c ) + 8003a78: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8003a7c: 08003ad1 .word 0x08003ad1 + 8003a80: 08003c57 .word 0x08003c57 + 8003a84: 08003c57 .word 0x08003c57 + 8003a88: 08003c57 .word 0x08003c57 + 8003a8c: 08003b11 .word 0x08003b11 + 8003a90: 08003c57 .word 0x08003c57 + 8003a94: 08003c57 .word 0x08003c57 + 8003a98: 08003c57 .word 0x08003c57 + 8003a9c: 08003b53 .word 0x08003b53 + 8003aa0: 08003c57 .word 0x08003c57 + 8003aa4: 08003c57 .word 0x08003c57 + 8003aa8: 08003c57 .word 0x08003c57 + 8003aac: 08003b93 .word 0x08003b93 + 8003ab0: 08003c57 .word 0x08003c57 + 8003ab4: 08003c57 .word 0x08003c57 + 8003ab8: 08003c57 .word 0x08003c57 + 8003abc: 08003bd5 .word 0x08003bd5 + 8003ac0: 08003c57 .word 0x08003c57 + 8003ac4: 08003c57 .word 0x08003c57 + 8003ac8: 08003c57 .word 0x08003c57 + 8003acc: 08003c15 .word 0x08003c15 { /* Check the parameters */ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); /* Configure the Channel 1 in PWM mode */ TIM_OC1_SetConfig(htim->Instance, sConfig); - 8003a4c: 68fb ldr r3, [r7, #12] - 8003a4e: 681b ldr r3, [r3, #0] - 8003a50: 68b9 ldr r1, [r7, #8] - 8003a52: 4618 mov r0, r3 - 8003a54: f000 fa4e bl 8003ef4 + 8003ad0: 68fb ldr r3, [r7, #12] + 8003ad2: 681b ldr r3, [r3, #0] + 8003ad4: 68b9 ldr r1, [r7, #8] + 8003ad6: 4618 mov r0, r3 + 8003ad8: f000 fa4e bl 8003f78 /* Set the Preload enable bit for channel1 */ htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; - 8003a58: 68fb ldr r3, [r7, #12] - 8003a5a: 681b ldr r3, [r3, #0] - 8003a5c: 699a ldr r2, [r3, #24] - 8003a5e: 68fb ldr r3, [r7, #12] - 8003a60: 681b ldr r3, [r3, #0] - 8003a62: f042 0208 orr.w r2, r2, #8 - 8003a66: 619a str r2, [r3, #24] + 8003adc: 68fb ldr r3, [r7, #12] + 8003ade: 681b ldr r3, [r3, #0] + 8003ae0: 699a ldr r2, [r3, #24] + 8003ae2: 68fb ldr r3, [r7, #12] + 8003ae4: 681b ldr r3, [r3, #0] + 8003ae6: f042 0208 orr.w r2, r2, #8 + 8003aea: 619a str r2, [r3, #24] /* Configure the Output Fast mode */ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; - 8003a68: 68fb ldr r3, [r7, #12] - 8003a6a: 681b ldr r3, [r3, #0] - 8003a6c: 699a ldr r2, [r3, #24] - 8003a6e: 68fb ldr r3, [r7, #12] - 8003a70: 681b ldr r3, [r3, #0] - 8003a72: f022 0204 bic.w r2, r2, #4 - 8003a76: 619a str r2, [r3, #24] + 8003aec: 68fb ldr r3, [r7, #12] + 8003aee: 681b ldr r3, [r3, #0] + 8003af0: 699a ldr r2, [r3, #24] + 8003af2: 68fb ldr r3, [r7, #12] + 8003af4: 681b ldr r3, [r3, #0] + 8003af6: f022 0204 bic.w r2, r2, #4 + 8003afa: 619a str r2, [r3, #24] htim->Instance->CCMR1 |= sConfig->OCFastMode; - 8003a78: 68fb ldr r3, [r7, #12] - 8003a7a: 681b ldr r3, [r3, #0] - 8003a7c: 6999 ldr r1, [r3, #24] - 8003a7e: 68bb ldr r3, [r7, #8] - 8003a80: 691a ldr r2, [r3, #16] - 8003a82: 68fb ldr r3, [r7, #12] - 8003a84: 681b ldr r3, [r3, #0] - 8003a86: 430a orrs r2, r1 - 8003a88: 619a str r2, [r3, #24] + 8003afc: 68fb ldr r3, [r7, #12] + 8003afe: 681b ldr r3, [r3, #0] + 8003b00: 6999 ldr r1, [r3, #24] + 8003b02: 68bb ldr r3, [r7, #8] + 8003b04: 691a ldr r2, [r3, #16] + 8003b06: 68fb ldr r3, [r7, #12] + 8003b08: 681b ldr r3, [r3, #0] + 8003b0a: 430a orrs r2, r1 + 8003b0c: 619a str r2, [r3, #24] break; - 8003a8a: e0a3 b.n 8003bd4 + 8003b0e: e0a3 b.n 8003c58 { /* Check the parameters */ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); /* Configure the Channel 2 in PWM mode */ TIM_OC2_SetConfig(htim->Instance, sConfig); - 8003a8c: 68fb ldr r3, [r7, #12] - 8003a8e: 681b ldr r3, [r3, #0] - 8003a90: 68b9 ldr r1, [r7, #8] - 8003a92: 4618 mov r0, r3 - 8003a94: f000 faa0 bl 8003fd8 + 8003b10: 68fb ldr r3, [r7, #12] + 8003b12: 681b ldr r3, [r3, #0] + 8003b14: 68b9 ldr r1, [r7, #8] + 8003b16: 4618 mov r0, r3 + 8003b18: f000 faa0 bl 800405c /* Set the Preload enable bit for channel2 */ htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; - 8003a98: 68fb ldr r3, [r7, #12] - 8003a9a: 681b ldr r3, [r3, #0] - 8003a9c: 699a ldr r2, [r3, #24] - 8003a9e: 68fb ldr r3, [r7, #12] - 8003aa0: 681b ldr r3, [r3, #0] - 8003aa2: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003aa6: 619a str r2, [r3, #24] + 8003b1c: 68fb ldr r3, [r7, #12] + 8003b1e: 681b ldr r3, [r3, #0] + 8003b20: 699a ldr r2, [r3, #24] + 8003b22: 68fb ldr r3, [r7, #12] + 8003b24: 681b ldr r3, [r3, #0] + 8003b26: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 8003b2a: 619a str r2, [r3, #24] /* Configure the Output Fast mode */ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; - 8003aa8: 68fb ldr r3, [r7, #12] - 8003aaa: 681b ldr r3, [r3, #0] - 8003aac: 699a ldr r2, [r3, #24] - 8003aae: 68fb ldr r3, [r7, #12] - 8003ab0: 681b ldr r3, [r3, #0] - 8003ab2: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 8003ab6: 619a str r2, [r3, #24] + 8003b2c: 68fb ldr r3, [r7, #12] + 8003b2e: 681b ldr r3, [r3, #0] + 8003b30: 699a ldr r2, [r3, #24] + 8003b32: 68fb ldr r3, [r7, #12] + 8003b34: 681b ldr r3, [r3, #0] + 8003b36: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 8003b3a: 619a str r2, [r3, #24] htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; - 8003ab8: 68fb ldr r3, [r7, #12] - 8003aba: 681b ldr r3, [r3, #0] - 8003abc: 6999 ldr r1, [r3, #24] - 8003abe: 68bb ldr r3, [r7, #8] - 8003ac0: 691b ldr r3, [r3, #16] - 8003ac2: 021a lsls r2, r3, #8 - 8003ac4: 68fb ldr r3, [r7, #12] - 8003ac6: 681b ldr r3, [r3, #0] - 8003ac8: 430a orrs r2, r1 - 8003aca: 619a str r2, [r3, #24] + 8003b3c: 68fb ldr r3, [r7, #12] + 8003b3e: 681b ldr r3, [r3, #0] + 8003b40: 6999 ldr r1, [r3, #24] + 8003b42: 68bb ldr r3, [r7, #8] + 8003b44: 691b ldr r3, [r3, #16] + 8003b46: 021a lsls r2, r3, #8 + 8003b48: 68fb ldr r3, [r7, #12] + 8003b4a: 681b ldr r3, [r3, #0] + 8003b4c: 430a orrs r2, r1 + 8003b4e: 619a str r2, [r3, #24] break; - 8003acc: e082 b.n 8003bd4 + 8003b50: e082 b.n 8003c58 { /* Check the parameters */ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); /* Configure the Channel 3 in PWM mode */ TIM_OC3_SetConfig(htim->Instance, sConfig); - 8003ace: 68fb ldr r3, [r7, #12] - 8003ad0: 681b ldr r3, [r3, #0] - 8003ad2: 68b9 ldr r1, [r7, #8] - 8003ad4: 4618 mov r0, r3 - 8003ad6: f000 faf7 bl 80040c8 + 8003b52: 68fb ldr r3, [r7, #12] + 8003b54: 681b ldr r3, [r3, #0] + 8003b56: 68b9 ldr r1, [r7, #8] + 8003b58: 4618 mov r0, r3 + 8003b5a: f000 faf7 bl 800414c /* Set the Preload enable bit for channel3 */ htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; - 8003ada: 68fb ldr r3, [r7, #12] - 8003adc: 681b ldr r3, [r3, #0] - 8003ade: 69da ldr r2, [r3, #28] - 8003ae0: 68fb ldr r3, [r7, #12] - 8003ae2: 681b ldr r3, [r3, #0] - 8003ae4: f042 0208 orr.w r2, r2, #8 - 8003ae8: 61da str r2, [r3, #28] + 8003b5e: 68fb ldr r3, [r7, #12] + 8003b60: 681b ldr r3, [r3, #0] + 8003b62: 69da ldr r2, [r3, #28] + 8003b64: 68fb ldr r3, [r7, #12] + 8003b66: 681b ldr r3, [r3, #0] + 8003b68: f042 0208 orr.w r2, r2, #8 + 8003b6c: 61da str r2, [r3, #28] /* Configure the Output Fast mode */ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; - 8003aea: 68fb ldr r3, [r7, #12] - 8003aec: 681b ldr r3, [r3, #0] - 8003aee: 69da ldr r2, [r3, #28] - 8003af0: 68fb ldr r3, [r7, #12] - 8003af2: 681b ldr r3, [r3, #0] - 8003af4: f022 0204 bic.w r2, r2, #4 - 8003af8: 61da str r2, [r3, #28] + 8003b6e: 68fb ldr r3, [r7, #12] + 8003b70: 681b ldr r3, [r3, #0] + 8003b72: 69da ldr r2, [r3, #28] + 8003b74: 68fb ldr r3, [r7, #12] + 8003b76: 681b ldr r3, [r3, #0] + 8003b78: f022 0204 bic.w r2, r2, #4 + 8003b7c: 61da str r2, [r3, #28] htim->Instance->CCMR2 |= sConfig->OCFastMode; - 8003afa: 68fb ldr r3, [r7, #12] - 8003afc: 681b ldr r3, [r3, #0] - 8003afe: 69d9 ldr r1, [r3, #28] - 8003b00: 68bb ldr r3, [r7, #8] - 8003b02: 691a ldr r2, [r3, #16] - 8003b04: 68fb ldr r3, [r7, #12] - 8003b06: 681b ldr r3, [r3, #0] - 8003b08: 430a orrs r2, r1 - 8003b0a: 61da str r2, [r3, #28] + 8003b7e: 68fb ldr r3, [r7, #12] + 8003b80: 681b ldr r3, [r3, #0] + 8003b82: 69d9 ldr r1, [r3, #28] + 8003b84: 68bb ldr r3, [r7, #8] + 8003b86: 691a ldr r2, [r3, #16] + 8003b88: 68fb ldr r3, [r7, #12] + 8003b8a: 681b ldr r3, [r3, #0] + 8003b8c: 430a orrs r2, r1 + 8003b8e: 61da str r2, [r3, #28] break; - 8003b0c: e062 b.n 8003bd4 + 8003b90: e062 b.n 8003c58 { /* Check the parameters */ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); /* Configure the Channel 4 in PWM mode */ TIM_OC4_SetConfig(htim->Instance, sConfig); - 8003b0e: 68fb ldr r3, [r7, #12] - 8003b10: 681b ldr r3, [r3, #0] - 8003b12: 68b9 ldr r1, [r7, #8] - 8003b14: 4618 mov r0, r3 - 8003b16: f000 fb4d bl 80041b4 + 8003b92: 68fb ldr r3, [r7, #12] + 8003b94: 681b ldr r3, [r3, #0] + 8003b96: 68b9 ldr r1, [r7, #8] + 8003b98: 4618 mov r0, r3 + 8003b9a: f000 fb4d bl 8004238 /* Set the Preload enable bit for channel4 */ htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; - 8003b1a: 68fb ldr r3, [r7, #12] - 8003b1c: 681b ldr r3, [r3, #0] - 8003b1e: 69da ldr r2, [r3, #28] - 8003b20: 68fb ldr r3, [r7, #12] - 8003b22: 681b ldr r3, [r3, #0] - 8003b24: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003b28: 61da str r2, [r3, #28] + 8003b9e: 68fb ldr r3, [r7, #12] + 8003ba0: 681b ldr r3, [r3, #0] + 8003ba2: 69da ldr r2, [r3, #28] + 8003ba4: 68fb ldr r3, [r7, #12] + 8003ba6: 681b ldr r3, [r3, #0] + 8003ba8: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 8003bac: 61da str r2, [r3, #28] /* Configure the Output Fast mode */ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; - 8003b2a: 68fb ldr r3, [r7, #12] - 8003b2c: 681b ldr r3, [r3, #0] - 8003b2e: 69da ldr r2, [r3, #28] - 8003b30: 68fb ldr r3, [r7, #12] - 8003b32: 681b ldr r3, [r3, #0] - 8003b34: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 8003b38: 61da str r2, [r3, #28] + 8003bae: 68fb ldr r3, [r7, #12] + 8003bb0: 681b ldr r3, [r3, #0] + 8003bb2: 69da ldr r2, [r3, #28] + 8003bb4: 68fb ldr r3, [r7, #12] + 8003bb6: 681b ldr r3, [r3, #0] + 8003bb8: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 8003bbc: 61da str r2, [r3, #28] htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; - 8003b3a: 68fb ldr r3, [r7, #12] - 8003b3c: 681b ldr r3, [r3, #0] - 8003b3e: 69d9 ldr r1, [r3, #28] - 8003b40: 68bb ldr r3, [r7, #8] - 8003b42: 691b ldr r3, [r3, #16] - 8003b44: 021a lsls r2, r3, #8 - 8003b46: 68fb ldr r3, [r7, #12] - 8003b48: 681b ldr r3, [r3, #0] - 8003b4a: 430a orrs r2, r1 - 8003b4c: 61da str r2, [r3, #28] + 8003bbe: 68fb ldr r3, [r7, #12] + 8003bc0: 681b ldr r3, [r3, #0] + 8003bc2: 69d9 ldr r1, [r3, #28] + 8003bc4: 68bb ldr r3, [r7, #8] + 8003bc6: 691b ldr r3, [r3, #16] + 8003bc8: 021a lsls r2, r3, #8 + 8003bca: 68fb ldr r3, [r7, #12] + 8003bcc: 681b ldr r3, [r3, #0] + 8003bce: 430a orrs r2, r1 + 8003bd0: 61da str r2, [r3, #28] break; - 8003b4e: e041 b.n 8003bd4 + 8003bd2: e041 b.n 8003c58 { /* Check the parameters */ assert_param(IS_TIM_CC5_INSTANCE(htim->Instance)); /* Configure the Channel 5 in PWM mode */ TIM_OC5_SetConfig(htim->Instance, sConfig); - 8003b50: 68fb ldr r3, [r7, #12] - 8003b52: 681b ldr r3, [r3, #0] - 8003b54: 68b9 ldr r1, [r7, #8] - 8003b56: 4618 mov r0, r3 - 8003b58: f000 fb84 bl 8004264 + 8003bd4: 68fb ldr r3, [r7, #12] + 8003bd6: 681b ldr r3, [r3, #0] + 8003bd8: 68b9 ldr r1, [r7, #8] + 8003bda: 4618 mov r0, r3 + 8003bdc: f000 fb84 bl 80042e8 /* Set the Preload enable bit for channel5*/ htim->Instance->CCMR3 |= TIM_CCMR3_OC5PE; - 8003b5c: 68fb ldr r3, [r7, #12] - 8003b5e: 681b ldr r3, [r3, #0] - 8003b60: 6d5a ldr r2, [r3, #84] ; 0x54 - 8003b62: 68fb ldr r3, [r7, #12] - 8003b64: 681b ldr r3, [r3, #0] - 8003b66: f042 0208 orr.w r2, r2, #8 - 8003b6a: 655a str r2, [r3, #84] ; 0x54 + 8003be0: 68fb ldr r3, [r7, #12] + 8003be2: 681b ldr r3, [r3, #0] + 8003be4: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003be6: 68fb ldr r3, [r7, #12] + 8003be8: 681b ldr r3, [r3, #0] + 8003bea: f042 0208 orr.w r2, r2, #8 + 8003bee: 655a str r2, [r3, #84] ; 0x54 /* Configure the Output Fast mode */ htim->Instance->CCMR3 &= ~TIM_CCMR3_OC5FE; - 8003b6c: 68fb ldr r3, [r7, #12] - 8003b6e: 681b ldr r3, [r3, #0] - 8003b70: 6d5a ldr r2, [r3, #84] ; 0x54 - 8003b72: 68fb ldr r3, [r7, #12] - 8003b74: 681b ldr r3, [r3, #0] - 8003b76: f022 0204 bic.w r2, r2, #4 - 8003b7a: 655a str r2, [r3, #84] ; 0x54 + 8003bf0: 68fb ldr r3, [r7, #12] + 8003bf2: 681b ldr r3, [r3, #0] + 8003bf4: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003bf6: 68fb ldr r3, [r7, #12] + 8003bf8: 681b ldr r3, [r3, #0] + 8003bfa: f022 0204 bic.w r2, r2, #4 + 8003bfe: 655a str r2, [r3, #84] ; 0x54 htim->Instance->CCMR3 |= sConfig->OCFastMode; - 8003b7c: 68fb ldr r3, [r7, #12] - 8003b7e: 681b ldr r3, [r3, #0] - 8003b80: 6d59 ldr r1, [r3, #84] ; 0x54 - 8003b82: 68bb ldr r3, [r7, #8] - 8003b84: 691a ldr r2, [r3, #16] - 8003b86: 68fb ldr r3, [r7, #12] - 8003b88: 681b ldr r3, [r3, #0] - 8003b8a: 430a orrs r2, r1 - 8003b8c: 655a str r2, [r3, #84] ; 0x54 + 8003c00: 68fb ldr r3, [r7, #12] + 8003c02: 681b ldr r3, [r3, #0] + 8003c04: 6d59 ldr r1, [r3, #84] ; 0x54 + 8003c06: 68bb ldr r3, [r7, #8] + 8003c08: 691a ldr r2, [r3, #16] + 8003c0a: 68fb ldr r3, [r7, #12] + 8003c0c: 681b ldr r3, [r3, #0] + 8003c0e: 430a orrs r2, r1 + 8003c10: 655a str r2, [r3, #84] ; 0x54 break; - 8003b8e: e021 b.n 8003bd4 + 8003c12: e021 b.n 8003c58 { /* Check the parameters */ assert_param(IS_TIM_CC6_INSTANCE(htim->Instance)); /* Configure the Channel 6 in PWM mode */ TIM_OC6_SetConfig(htim->Instance, sConfig); - 8003b90: 68fb ldr r3, [r7, #12] - 8003b92: 681b ldr r3, [r3, #0] - 8003b94: 68b9 ldr r1, [r7, #8] - 8003b96: 4618 mov r0, r3 - 8003b98: f000 fbb6 bl 8004308 + 8003c14: 68fb ldr r3, [r7, #12] + 8003c16: 681b ldr r3, [r3, #0] + 8003c18: 68b9 ldr r1, [r7, #8] + 8003c1a: 4618 mov r0, r3 + 8003c1c: f000 fbb6 bl 800438c /* Set the Preload enable bit for channel6 */ htim->Instance->CCMR3 |= TIM_CCMR3_OC6PE; - 8003b9c: 68fb ldr r3, [r7, #12] - 8003b9e: 681b ldr r3, [r3, #0] - 8003ba0: 6d5a ldr r2, [r3, #84] ; 0x54 - 8003ba2: 68fb ldr r3, [r7, #12] - 8003ba4: 681b ldr r3, [r3, #0] - 8003ba6: f442 6200 orr.w r2, r2, #2048 ; 0x800 - 8003baa: 655a str r2, [r3, #84] ; 0x54 + 8003c20: 68fb ldr r3, [r7, #12] + 8003c22: 681b ldr r3, [r3, #0] + 8003c24: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003c26: 68fb ldr r3, [r7, #12] + 8003c28: 681b ldr r3, [r3, #0] + 8003c2a: f442 6200 orr.w r2, r2, #2048 ; 0x800 + 8003c2e: 655a str r2, [r3, #84] ; 0x54 /* Configure the Output Fast mode */ htim->Instance->CCMR3 &= ~TIM_CCMR3_OC6FE; - 8003bac: 68fb ldr r3, [r7, #12] - 8003bae: 681b ldr r3, [r3, #0] - 8003bb0: 6d5a ldr r2, [r3, #84] ; 0x54 - 8003bb2: 68fb ldr r3, [r7, #12] - 8003bb4: 681b ldr r3, [r3, #0] - 8003bb6: f422 6280 bic.w r2, r2, #1024 ; 0x400 - 8003bba: 655a str r2, [r3, #84] ; 0x54 + 8003c30: 68fb ldr r3, [r7, #12] + 8003c32: 681b ldr r3, [r3, #0] + 8003c34: 6d5a ldr r2, [r3, #84] ; 0x54 + 8003c36: 68fb ldr r3, [r7, #12] + 8003c38: 681b ldr r3, [r3, #0] + 8003c3a: f422 6280 bic.w r2, r2, #1024 ; 0x400 + 8003c3e: 655a str r2, [r3, #84] ; 0x54 htim->Instance->CCMR3 |= sConfig->OCFastMode << 8U; - 8003bbc: 68fb ldr r3, [r7, #12] - 8003bbe: 681b ldr r3, [r3, #0] - 8003bc0: 6d59 ldr r1, [r3, #84] ; 0x54 - 8003bc2: 68bb ldr r3, [r7, #8] - 8003bc4: 691b ldr r3, [r3, #16] - 8003bc6: 021a lsls r2, r3, #8 - 8003bc8: 68fb ldr r3, [r7, #12] - 8003bca: 681b ldr r3, [r3, #0] - 8003bcc: 430a orrs r2, r1 - 8003bce: 655a str r2, [r3, #84] ; 0x54 + 8003c40: 68fb ldr r3, [r7, #12] + 8003c42: 681b ldr r3, [r3, #0] + 8003c44: 6d59 ldr r1, [r3, #84] ; 0x54 + 8003c46: 68bb ldr r3, [r7, #8] + 8003c48: 691b ldr r3, [r3, #16] + 8003c4a: 021a lsls r2, r3, #8 + 8003c4c: 68fb ldr r3, [r7, #12] + 8003c4e: 681b ldr r3, [r3, #0] + 8003c50: 430a orrs r2, r1 + 8003c52: 655a str r2, [r3, #84] ; 0x54 break; - 8003bd0: e000 b.n 8003bd4 + 8003c54: e000 b.n 8003c58 } default: break; - 8003bd2: bf00 nop + 8003c56: bf00 nop } htim->State = HAL_TIM_STATE_READY; - 8003bd4: 68fb ldr r3, [r7, #12] - 8003bd6: 2201 movs r2, #1 - 8003bd8: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003c58: 68fb ldr r3, [r7, #12] + 8003c5a: 2201 movs r2, #1 + 8003c5c: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 8003bdc: 68fb ldr r3, [r7, #12] - 8003bde: 2200 movs r2, #0 - 8003be0: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003c60: 68fb ldr r3, [r7, #12] + 8003c62: 2200 movs r2, #0 + 8003c64: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 8003be4: 2300 movs r3, #0 + 8003c68: 2300 movs r3, #0 } - 8003be6: 4618 mov r0, r3 - 8003be8: 3710 adds r7, #16 - 8003bea: 46bd mov sp, r7 - 8003bec: bd80 pop {r7, pc} - 8003bee: bf00 nop + 8003c6a: 4618 mov r0, r3 + 8003c6c: 3710 adds r7, #16 + 8003c6e: 46bd mov sp, r7 + 8003c70: bd80 pop {r7, pc} + 8003c72: bf00 nop -08003bf0 : +08003c74 : * @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) { - 8003bf0: b580 push {r7, lr} - 8003bf2: b084 sub sp, #16 - 8003bf4: af00 add r7, sp, #0 - 8003bf6: 6078 str r0, [r7, #4] - 8003bf8: 6039 str r1, [r7, #0] + 8003c74: b580 push {r7, lr} + 8003c76: b084 sub sp, #16 + 8003c78: af00 add r7, sp, #0 + 8003c7a: 6078 str r0, [r7, #4] + 8003c7c: 6039 str r1, [r7, #0] uint32_t tmpsmcr; /* Process Locked */ __HAL_LOCK(htim); - 8003bfa: 687b ldr r3, [r7, #4] - 8003bfc: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 8003c00: 2b01 cmp r3, #1 - 8003c02: d101 bne.n 8003c08 - 8003c04: 2302 movs r3, #2 - 8003c06: e0a6 b.n 8003d56 - 8003c08: 687b ldr r3, [r7, #4] - 8003c0a: 2201 movs r2, #1 - 8003c0c: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003c7e: 687b ldr r3, [r7, #4] + 8003c80: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 8003c84: 2b01 cmp r3, #1 + 8003c86: d101 bne.n 8003c8c + 8003c88: 2302 movs r3, #2 + 8003c8a: e0a6 b.n 8003dda + 8003c8c: 687b ldr r3, [r7, #4] + 8003c8e: 2201 movs r2, #1 + 8003c90: f883 203c strb.w r2, [r3, #60] ; 0x3c htim->State = HAL_TIM_STATE_BUSY; - 8003c10: 687b ldr r3, [r7, #4] - 8003c12: 2202 movs r2, #2 - 8003c14: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003c94: 687b ldr r3, [r7, #4] + 8003c96: 2202 movs r2, #2 + 8003c98: 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; - 8003c18: 687b ldr r3, [r7, #4] - 8003c1a: 681b ldr r3, [r3, #0] - 8003c1c: 689b ldr r3, [r3, #8] - 8003c1e: 60fb str r3, [r7, #12] + 8003c9c: 687b ldr r3, [r7, #4] + 8003c9e: 681b ldr r3, [r3, #0] + 8003ca0: 689b ldr r3, [r3, #8] + 8003ca2: 60fb str r3, [r7, #12] tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); - 8003c20: 68fa ldr r2, [r7, #12] - 8003c22: 4b4f ldr r3, [pc, #316] ; (8003d60 ) - 8003c24: 4013 ands r3, r2 - 8003c26: 60fb str r3, [r7, #12] + 8003ca4: 68fa ldr r2, [r7, #12] + 8003ca6: 4b4f ldr r3, [pc, #316] ; (8003de4 ) + 8003ca8: 4013 ands r3, r2 + 8003caa: 60fb str r3, [r7, #12] tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - 8003c28: 68fb ldr r3, [r7, #12] - 8003c2a: f423 437f bic.w r3, r3, #65280 ; 0xff00 - 8003c2e: 60fb str r3, [r7, #12] + 8003cac: 68fb ldr r3, [r7, #12] + 8003cae: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 8003cb2: 60fb str r3, [r7, #12] htim->Instance->SMCR = tmpsmcr; - 8003c30: 687b ldr r3, [r7, #4] - 8003c32: 681b ldr r3, [r3, #0] - 8003c34: 68fa ldr r2, [r7, #12] - 8003c36: 609a str r2, [r3, #8] + 8003cb4: 687b ldr r3, [r7, #4] + 8003cb6: 681b ldr r3, [r3, #0] + 8003cb8: 68fa ldr r2, [r7, #12] + 8003cba: 609a str r2, [r3, #8] switch (sClockSourceConfig->ClockSource) - 8003c38: 683b ldr r3, [r7, #0] - 8003c3a: 681b ldr r3, [r3, #0] - 8003c3c: 2b40 cmp r3, #64 ; 0x40 - 8003c3e: d067 beq.n 8003d10 - 8003c40: 2b40 cmp r3, #64 ; 0x40 - 8003c42: d80b bhi.n 8003c5c - 8003c44: 2b10 cmp r3, #16 - 8003c46: d073 beq.n 8003d30 - 8003c48: 2b10 cmp r3, #16 - 8003c4a: d802 bhi.n 8003c52 - 8003c4c: 2b00 cmp r3, #0 - 8003c4e: d06f beq.n 8003d30 + 8003cbc: 683b ldr r3, [r7, #0] + 8003cbe: 681b ldr r3, [r3, #0] + 8003cc0: 2b40 cmp r3, #64 ; 0x40 + 8003cc2: d067 beq.n 8003d94 + 8003cc4: 2b40 cmp r3, #64 ; 0x40 + 8003cc6: d80b bhi.n 8003ce0 + 8003cc8: 2b10 cmp r3, #16 + 8003cca: d073 beq.n 8003db4 + 8003ccc: 2b10 cmp r3, #16 + 8003cce: d802 bhi.n 8003cd6 + 8003cd0: 2b00 cmp r3, #0 + 8003cd2: d06f beq.n 8003db4 TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); break; } default: break; - 8003c50: e078 b.n 8003d44 + 8003cd4: e078 b.n 8003dc8 switch (sClockSourceConfig->ClockSource) - 8003c52: 2b20 cmp r3, #32 - 8003c54: d06c beq.n 8003d30 - 8003c56: 2b30 cmp r3, #48 ; 0x30 - 8003c58: d06a beq.n 8003d30 + 8003cd6: 2b20 cmp r3, #32 + 8003cd8: d06c beq.n 8003db4 + 8003cda: 2b30 cmp r3, #48 ; 0x30 + 8003cdc: d06a beq.n 8003db4 break; - 8003c5a: e073 b.n 8003d44 + 8003cde: e073 b.n 8003dc8 switch (sClockSourceConfig->ClockSource) - 8003c5c: 2b70 cmp r3, #112 ; 0x70 - 8003c5e: d00d beq.n 8003c7c - 8003c60: 2b70 cmp r3, #112 ; 0x70 - 8003c62: d804 bhi.n 8003c6e - 8003c64: 2b50 cmp r3, #80 ; 0x50 - 8003c66: d033 beq.n 8003cd0 - 8003c68: 2b60 cmp r3, #96 ; 0x60 - 8003c6a: d041 beq.n 8003cf0 + 8003ce0: 2b70 cmp r3, #112 ; 0x70 + 8003ce2: d00d beq.n 8003d00 + 8003ce4: 2b70 cmp r3, #112 ; 0x70 + 8003ce6: d804 bhi.n 8003cf2 + 8003ce8: 2b50 cmp r3, #80 ; 0x50 + 8003cea: d033 beq.n 8003d54 + 8003cec: 2b60 cmp r3, #96 ; 0x60 + 8003cee: d041 beq.n 8003d74 break; - 8003c6c: e06a b.n 8003d44 + 8003cf0: e06a b.n 8003dc8 switch (sClockSourceConfig->ClockSource) - 8003c6e: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8003c72: d066 beq.n 8003d42 - 8003c74: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 8003c78: d017 beq.n 8003caa + 8003cf2: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8003cf6: d066 beq.n 8003dc6 + 8003cf8: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8003cfc: d017 beq.n 8003d2e break; - 8003c7a: e063 b.n 8003d44 + 8003cfe: e063 b.n 8003dc8 TIM_ETR_SetConfig(htim->Instance, - 8003c7c: 687b ldr r3, [r7, #4] - 8003c7e: 6818 ldr r0, [r3, #0] - 8003c80: 683b ldr r3, [r7, #0] - 8003c82: 6899 ldr r1, [r3, #8] - 8003c84: 683b ldr r3, [r7, #0] - 8003c86: 685a ldr r2, [r3, #4] - 8003c88: 683b ldr r3, [r7, #0] - 8003c8a: 68db ldr r3, [r3, #12] - 8003c8c: f000 fc0a bl 80044a4 + 8003d00: 687b ldr r3, [r7, #4] + 8003d02: 6818 ldr r0, [r3, #0] + 8003d04: 683b ldr r3, [r7, #0] + 8003d06: 6899 ldr r1, [r3, #8] + 8003d08: 683b ldr r3, [r7, #0] + 8003d0a: 685a ldr r2, [r3, #4] + 8003d0c: 683b ldr r3, [r7, #0] + 8003d0e: 68db ldr r3, [r3, #12] + 8003d10: f000 fc0a bl 8004528 tmpsmcr = htim->Instance->SMCR; - 8003c90: 687b ldr r3, [r7, #4] - 8003c92: 681b ldr r3, [r3, #0] - 8003c94: 689b ldr r3, [r3, #8] - 8003c96: 60fb str r3, [r7, #12] + 8003d14: 687b ldr r3, [r7, #4] + 8003d16: 681b ldr r3, [r3, #0] + 8003d18: 689b ldr r3, [r3, #8] + 8003d1a: 60fb str r3, [r7, #12] tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); - 8003c98: 68fb ldr r3, [r7, #12] - 8003c9a: f043 0377 orr.w r3, r3, #119 ; 0x77 - 8003c9e: 60fb str r3, [r7, #12] + 8003d1c: 68fb ldr r3, [r7, #12] + 8003d1e: f043 0377 orr.w r3, r3, #119 ; 0x77 + 8003d22: 60fb str r3, [r7, #12] htim->Instance->SMCR = tmpsmcr; - 8003ca0: 687b ldr r3, [r7, #4] - 8003ca2: 681b ldr r3, [r3, #0] - 8003ca4: 68fa ldr r2, [r7, #12] - 8003ca6: 609a str r2, [r3, #8] + 8003d24: 687b ldr r3, [r7, #4] + 8003d26: 681b ldr r3, [r3, #0] + 8003d28: 68fa ldr r2, [r7, #12] + 8003d2a: 609a str r2, [r3, #8] break; - 8003ca8: e04c b.n 8003d44 + 8003d2c: e04c b.n 8003dc8 TIM_ETR_SetConfig(htim->Instance, - 8003caa: 687b ldr r3, [r7, #4] - 8003cac: 6818 ldr r0, [r3, #0] - 8003cae: 683b ldr r3, [r7, #0] - 8003cb0: 6899 ldr r1, [r3, #8] - 8003cb2: 683b ldr r3, [r7, #0] - 8003cb4: 685a ldr r2, [r3, #4] - 8003cb6: 683b ldr r3, [r7, #0] - 8003cb8: 68db ldr r3, [r3, #12] - 8003cba: f000 fbf3 bl 80044a4 + 8003d2e: 687b ldr r3, [r7, #4] + 8003d30: 6818 ldr r0, [r3, #0] + 8003d32: 683b ldr r3, [r7, #0] + 8003d34: 6899 ldr r1, [r3, #8] + 8003d36: 683b ldr r3, [r7, #0] + 8003d38: 685a ldr r2, [r3, #4] + 8003d3a: 683b ldr r3, [r7, #0] + 8003d3c: 68db ldr r3, [r3, #12] + 8003d3e: f000 fbf3 bl 8004528 htim->Instance->SMCR |= TIM_SMCR_ECE; - 8003cbe: 687b ldr r3, [r7, #4] - 8003cc0: 681b ldr r3, [r3, #0] - 8003cc2: 689a ldr r2, [r3, #8] - 8003cc4: 687b ldr r3, [r7, #4] - 8003cc6: 681b ldr r3, [r3, #0] - 8003cc8: f442 4280 orr.w r2, r2, #16384 ; 0x4000 - 8003ccc: 609a str r2, [r3, #8] + 8003d42: 687b ldr r3, [r7, #4] + 8003d44: 681b ldr r3, [r3, #0] + 8003d46: 689a ldr r2, [r3, #8] + 8003d48: 687b ldr r3, [r7, #4] + 8003d4a: 681b ldr r3, [r3, #0] + 8003d4c: f442 4280 orr.w r2, r2, #16384 ; 0x4000 + 8003d50: 609a str r2, [r3, #8] break; - 8003cce: e039 b.n 8003d44 + 8003d52: e039 b.n 8003dc8 TIM_TI1_ConfigInputStage(htim->Instance, - 8003cd0: 687b ldr r3, [r7, #4] - 8003cd2: 6818 ldr r0, [r3, #0] - 8003cd4: 683b ldr r3, [r7, #0] - 8003cd6: 6859 ldr r1, [r3, #4] - 8003cd8: 683b ldr r3, [r7, #0] - 8003cda: 68db ldr r3, [r3, #12] - 8003cdc: 461a mov r2, r3 - 8003cde: f000 fb67 bl 80043b0 + 8003d54: 687b ldr r3, [r7, #4] + 8003d56: 6818 ldr r0, [r3, #0] + 8003d58: 683b ldr r3, [r7, #0] + 8003d5a: 6859 ldr r1, [r3, #4] + 8003d5c: 683b ldr r3, [r7, #0] + 8003d5e: 68db ldr r3, [r3, #12] + 8003d60: 461a mov r2, r3 + 8003d62: f000 fb67 bl 8004434 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); - 8003ce2: 687b ldr r3, [r7, #4] - 8003ce4: 681b ldr r3, [r3, #0] - 8003ce6: 2150 movs r1, #80 ; 0x50 - 8003ce8: 4618 mov r0, r3 - 8003cea: f000 fbc0 bl 800446e + 8003d66: 687b ldr r3, [r7, #4] + 8003d68: 681b ldr r3, [r3, #0] + 8003d6a: 2150 movs r1, #80 ; 0x50 + 8003d6c: 4618 mov r0, r3 + 8003d6e: f000 fbc0 bl 80044f2 break; - 8003cee: e029 b.n 8003d44 + 8003d72: e029 b.n 8003dc8 TIM_TI2_ConfigInputStage(htim->Instance, - 8003cf0: 687b ldr r3, [r7, #4] - 8003cf2: 6818 ldr r0, [r3, #0] - 8003cf4: 683b ldr r3, [r7, #0] - 8003cf6: 6859 ldr r1, [r3, #4] - 8003cf8: 683b ldr r3, [r7, #0] - 8003cfa: 68db ldr r3, [r3, #12] - 8003cfc: 461a mov r2, r3 - 8003cfe: f000 fb86 bl 800440e + 8003d74: 687b ldr r3, [r7, #4] + 8003d76: 6818 ldr r0, [r3, #0] + 8003d78: 683b ldr r3, [r7, #0] + 8003d7a: 6859 ldr r1, [r3, #4] + 8003d7c: 683b ldr r3, [r7, #0] + 8003d7e: 68db ldr r3, [r3, #12] + 8003d80: 461a mov r2, r3 + 8003d82: f000 fb86 bl 8004492 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); - 8003d02: 687b ldr r3, [r7, #4] - 8003d04: 681b ldr r3, [r3, #0] - 8003d06: 2160 movs r1, #96 ; 0x60 - 8003d08: 4618 mov r0, r3 - 8003d0a: f000 fbb0 bl 800446e + 8003d86: 687b ldr r3, [r7, #4] + 8003d88: 681b ldr r3, [r3, #0] + 8003d8a: 2160 movs r1, #96 ; 0x60 + 8003d8c: 4618 mov r0, r3 + 8003d8e: f000 fbb0 bl 80044f2 break; - 8003d0e: e019 b.n 8003d44 + 8003d92: e019 b.n 8003dc8 TIM_TI1_ConfigInputStage(htim->Instance, - 8003d10: 687b ldr r3, [r7, #4] - 8003d12: 6818 ldr r0, [r3, #0] - 8003d14: 683b ldr r3, [r7, #0] - 8003d16: 6859 ldr r1, [r3, #4] - 8003d18: 683b ldr r3, [r7, #0] - 8003d1a: 68db ldr r3, [r3, #12] - 8003d1c: 461a mov r2, r3 - 8003d1e: f000 fb47 bl 80043b0 + 8003d94: 687b ldr r3, [r7, #4] + 8003d96: 6818 ldr r0, [r3, #0] + 8003d98: 683b ldr r3, [r7, #0] + 8003d9a: 6859 ldr r1, [r3, #4] + 8003d9c: 683b ldr r3, [r7, #0] + 8003d9e: 68db ldr r3, [r3, #12] + 8003da0: 461a mov r2, r3 + 8003da2: f000 fb47 bl 8004434 TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); - 8003d22: 687b ldr r3, [r7, #4] - 8003d24: 681b ldr r3, [r3, #0] - 8003d26: 2140 movs r1, #64 ; 0x40 - 8003d28: 4618 mov r0, r3 - 8003d2a: f000 fba0 bl 800446e + 8003da6: 687b ldr r3, [r7, #4] + 8003da8: 681b ldr r3, [r3, #0] + 8003daa: 2140 movs r1, #64 ; 0x40 + 8003dac: 4618 mov r0, r3 + 8003dae: f000 fba0 bl 80044f2 break; - 8003d2e: e009 b.n 8003d44 + 8003db2: e009 b.n 8003dc8 TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); - 8003d30: 687b ldr r3, [r7, #4] - 8003d32: 681a ldr r2, [r3, #0] - 8003d34: 683b ldr r3, [r7, #0] - 8003d36: 681b ldr r3, [r3, #0] - 8003d38: 4619 mov r1, r3 - 8003d3a: 4610 mov r0, r2 - 8003d3c: f000 fb97 bl 800446e + 8003db4: 687b ldr r3, [r7, #4] + 8003db6: 681a ldr r2, [r3, #0] + 8003db8: 683b ldr r3, [r7, #0] + 8003dba: 681b ldr r3, [r3, #0] + 8003dbc: 4619 mov r1, r3 + 8003dbe: 4610 mov r0, r2 + 8003dc0: f000 fb97 bl 80044f2 break; - 8003d40: e000 b.n 8003d44 + 8003dc4: e000 b.n 8003dc8 break; - 8003d42: bf00 nop + 8003dc6: bf00 nop } htim->State = HAL_TIM_STATE_READY; - 8003d44: 687b ldr r3, [r7, #4] - 8003d46: 2201 movs r2, #1 - 8003d48: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8003dc8: 687b ldr r3, [r7, #4] + 8003dca: 2201 movs r2, #1 + 8003dcc: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 8003d4c: 687b ldr r3, [r7, #4] - 8003d4e: 2200 movs r2, #0 - 8003d50: f883 203c strb.w r2, [r3, #60] ; 0x3c + 8003dd0: 687b ldr r3, [r7, #4] + 8003dd2: 2200 movs r2, #0 + 8003dd4: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 8003d54: 2300 movs r3, #0 + 8003dd8: 2300 movs r3, #0 } - 8003d56: 4618 mov r0, r3 - 8003d58: 3710 adds r7, #16 - 8003d5a: 46bd mov sp, r7 - 8003d5c: bd80 pop {r7, pc} - 8003d5e: bf00 nop - 8003d60: fffeff88 .word 0xfffeff88 - -08003d64 : + 8003dda: 4618 mov r0, r3 + 8003ddc: 3710 adds r7, #16 + 8003dde: 46bd mov sp, r7 + 8003de0: bd80 pop {r7, pc} + 8003de2: bf00 nop + 8003de4: fffeff88 .word 0xfffeff88 + +08003de8 : * @brief Output Compare callback in non-blocking mode * @param htim TIM OC handle * @retval None */ __weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) { - 8003d64: b480 push {r7} - 8003d66: b083 sub sp, #12 - 8003d68: af00 add r7, sp, #0 - 8003d6a: 6078 str r0, [r7, #4] + 8003de8: b480 push {r7} + 8003dea: b083 sub sp, #12 + 8003dec: af00 add r7, sp, #0 + 8003dee: 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 */ } - 8003d6c: bf00 nop - 8003d6e: 370c adds r7, #12 - 8003d70: 46bd mov sp, r7 - 8003d72: f85d 7b04 ldr.w r7, [sp], #4 - 8003d76: 4770 bx lr + 8003df0: bf00 nop + 8003df2: 370c adds r7, #12 + 8003df4: 46bd mov sp, r7 + 8003df6: f85d 7b04 ldr.w r7, [sp], #4 + 8003dfa: 4770 bx lr -08003d78 : +08003dfc : * @brief Input Capture callback in non-blocking mode * @param htim TIM IC handle * @retval None */ __weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) { - 8003d78: b480 push {r7} - 8003d7a: b083 sub sp, #12 - 8003d7c: af00 add r7, sp, #0 - 8003d7e: 6078 str r0, [r7, #4] + 8003dfc: b480 push {r7} + 8003dfe: b083 sub sp, #12 + 8003e00: af00 add r7, sp, #0 + 8003e02: 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 */ } - 8003d80: bf00 nop - 8003d82: 370c adds r7, #12 - 8003d84: 46bd mov sp, r7 - 8003d86: f85d 7b04 ldr.w r7, [sp], #4 - 8003d8a: 4770 bx lr + 8003e04: bf00 nop + 8003e06: 370c adds r7, #12 + 8003e08: 46bd mov sp, r7 + 8003e0a: f85d 7b04 ldr.w r7, [sp], #4 + 8003e0e: 4770 bx lr -08003d8c : +08003e10 : * @brief PWM Pulse finished callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) { - 8003d8c: b480 push {r7} - 8003d8e: b083 sub sp, #12 - 8003d90: af00 add r7, sp, #0 - 8003d92: 6078 str r0, [r7, #4] + 8003e10: b480 push {r7} + 8003e12: b083 sub sp, #12 + 8003e14: af00 add r7, sp, #0 + 8003e16: 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 */ } - 8003d94: bf00 nop - 8003d96: 370c adds r7, #12 - 8003d98: 46bd mov sp, r7 - 8003d9a: f85d 7b04 ldr.w r7, [sp], #4 - 8003d9e: 4770 bx lr + 8003e18: bf00 nop + 8003e1a: 370c adds r7, #12 + 8003e1c: 46bd mov sp, r7 + 8003e1e: f85d 7b04 ldr.w r7, [sp], #4 + 8003e22: 4770 bx lr -08003da0 : +08003e24 : * @brief Hall Trigger detection callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) { - 8003da0: b480 push {r7} - 8003da2: b083 sub sp, #12 - 8003da4: af00 add r7, sp, #0 - 8003da6: 6078 str r0, [r7, #4] + 8003e24: b480 push {r7} + 8003e26: b083 sub sp, #12 + 8003e28: af00 add r7, sp, #0 + 8003e2a: 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 */ } - 8003da8: bf00 nop - 8003daa: 370c adds r7, #12 - 8003dac: 46bd mov sp, r7 - 8003dae: f85d 7b04 ldr.w r7, [sp], #4 - 8003db2: 4770 bx lr + 8003e2c: bf00 nop + 8003e2e: 370c adds r7, #12 + 8003e30: 46bd mov sp, r7 + 8003e32: f85d 7b04 ldr.w r7, [sp], #4 + 8003e36: 4770 bx lr -08003db4 : +08003e38 : * @param TIMx TIM peripheral * @param Structure TIM Base configuration structure * @retval None */ void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) { - 8003db4: b480 push {r7} - 8003db6: b085 sub sp, #20 - 8003db8: af00 add r7, sp, #0 - 8003dba: 6078 str r0, [r7, #4] - 8003dbc: 6039 str r1, [r7, #0] + 8003e38: b480 push {r7} + 8003e3a: b085 sub sp, #20 + 8003e3c: af00 add r7, sp, #0 + 8003e3e: 6078 str r0, [r7, #4] + 8003e40: 6039 str r1, [r7, #0] uint32_t tmpcr1; tmpcr1 = TIMx->CR1; - 8003dbe: 687b ldr r3, [r7, #4] - 8003dc0: 681b ldr r3, [r3, #0] - 8003dc2: 60fb str r3, [r7, #12] + 8003e42: 687b ldr r3, [r7, #4] + 8003e44: 681b ldr r3, [r3, #0] + 8003e46: 60fb str r3, [r7, #12] /* Set TIM Time Base Unit parameters ---------------------------------------*/ if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) - 8003dc4: 687b ldr r3, [r7, #4] - 8003dc6: 4a40 ldr r2, [pc, #256] ; (8003ec8 ) - 8003dc8: 4293 cmp r3, r2 - 8003dca: d013 beq.n 8003df4 - 8003dcc: 687b ldr r3, [r7, #4] - 8003dce: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 8003dd2: d00f beq.n 8003df4 - 8003dd4: 687b ldr r3, [r7, #4] - 8003dd6: 4a3d ldr r2, [pc, #244] ; (8003ecc ) - 8003dd8: 4293 cmp r3, r2 - 8003dda: d00b beq.n 8003df4 - 8003ddc: 687b ldr r3, [r7, #4] - 8003dde: 4a3c ldr r2, [pc, #240] ; (8003ed0 ) - 8003de0: 4293 cmp r3, r2 - 8003de2: d007 beq.n 8003df4 - 8003de4: 687b ldr r3, [r7, #4] - 8003de6: 4a3b ldr r2, [pc, #236] ; (8003ed4 ) - 8003de8: 4293 cmp r3, r2 - 8003dea: d003 beq.n 8003df4 - 8003dec: 687b ldr r3, [r7, #4] - 8003dee: 4a3a ldr r2, [pc, #232] ; (8003ed8 ) - 8003df0: 4293 cmp r3, r2 - 8003df2: d108 bne.n 8003e06 + 8003e48: 687b ldr r3, [r7, #4] + 8003e4a: 4a40 ldr r2, [pc, #256] ; (8003f4c ) + 8003e4c: 4293 cmp r3, r2 + 8003e4e: d013 beq.n 8003e78 + 8003e50: 687b ldr r3, [r7, #4] + 8003e52: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003e56: d00f beq.n 8003e78 + 8003e58: 687b ldr r3, [r7, #4] + 8003e5a: 4a3d ldr r2, [pc, #244] ; (8003f50 ) + 8003e5c: 4293 cmp r3, r2 + 8003e5e: d00b beq.n 8003e78 + 8003e60: 687b ldr r3, [r7, #4] + 8003e62: 4a3c ldr r2, [pc, #240] ; (8003f54 ) + 8003e64: 4293 cmp r3, r2 + 8003e66: d007 beq.n 8003e78 + 8003e68: 687b ldr r3, [r7, #4] + 8003e6a: 4a3b ldr r2, [pc, #236] ; (8003f58 ) + 8003e6c: 4293 cmp r3, r2 + 8003e6e: d003 beq.n 8003e78 + 8003e70: 687b ldr r3, [r7, #4] + 8003e72: 4a3a ldr r2, [pc, #232] ; (8003f5c ) + 8003e74: 4293 cmp r3, r2 + 8003e76: d108 bne.n 8003e8a { /* Select the Counter Mode */ tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); - 8003df4: 68fb ldr r3, [r7, #12] - 8003df6: f023 0370 bic.w r3, r3, #112 ; 0x70 - 8003dfa: 60fb str r3, [r7, #12] + 8003e78: 68fb ldr r3, [r7, #12] + 8003e7a: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8003e7e: 60fb str r3, [r7, #12] tmpcr1 |= Structure->CounterMode; - 8003dfc: 683b ldr r3, [r7, #0] - 8003dfe: 685b ldr r3, [r3, #4] - 8003e00: 68fa ldr r2, [r7, #12] - 8003e02: 4313 orrs r3, r2 - 8003e04: 60fb str r3, [r7, #12] + 8003e80: 683b ldr r3, [r7, #0] + 8003e82: 685b ldr r3, [r3, #4] + 8003e84: 68fa ldr r2, [r7, #12] + 8003e86: 4313 orrs r3, r2 + 8003e88: 60fb str r3, [r7, #12] } if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) - 8003e06: 687b ldr r3, [r7, #4] - 8003e08: 4a2f ldr r2, [pc, #188] ; (8003ec8 ) - 8003e0a: 4293 cmp r3, r2 - 8003e0c: d02b beq.n 8003e66 - 8003e0e: 687b ldr r3, [r7, #4] - 8003e10: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 - 8003e14: d027 beq.n 8003e66 - 8003e16: 687b ldr r3, [r7, #4] - 8003e18: 4a2c ldr r2, [pc, #176] ; (8003ecc ) - 8003e1a: 4293 cmp r3, r2 - 8003e1c: d023 beq.n 8003e66 - 8003e1e: 687b ldr r3, [r7, #4] - 8003e20: 4a2b ldr r2, [pc, #172] ; (8003ed0 ) - 8003e22: 4293 cmp r3, r2 - 8003e24: d01f beq.n 8003e66 - 8003e26: 687b ldr r3, [r7, #4] - 8003e28: 4a2a ldr r2, [pc, #168] ; (8003ed4 ) - 8003e2a: 4293 cmp r3, r2 - 8003e2c: d01b beq.n 8003e66 - 8003e2e: 687b ldr r3, [r7, #4] - 8003e30: 4a29 ldr r2, [pc, #164] ; (8003ed8 ) - 8003e32: 4293 cmp r3, r2 - 8003e34: d017 beq.n 8003e66 - 8003e36: 687b ldr r3, [r7, #4] - 8003e38: 4a28 ldr r2, [pc, #160] ; (8003edc ) - 8003e3a: 4293 cmp r3, r2 - 8003e3c: d013 beq.n 8003e66 - 8003e3e: 687b ldr r3, [r7, #4] - 8003e40: 4a27 ldr r2, [pc, #156] ; (8003ee0 ) - 8003e42: 4293 cmp r3, r2 - 8003e44: d00f beq.n 8003e66 - 8003e46: 687b ldr r3, [r7, #4] - 8003e48: 4a26 ldr r2, [pc, #152] ; (8003ee4 ) - 8003e4a: 4293 cmp r3, r2 - 8003e4c: d00b beq.n 8003e66 - 8003e4e: 687b ldr r3, [r7, #4] - 8003e50: 4a25 ldr r2, [pc, #148] ; (8003ee8 ) - 8003e52: 4293 cmp r3, r2 - 8003e54: d007 beq.n 8003e66 - 8003e56: 687b ldr r3, [r7, #4] - 8003e58: 4a24 ldr r2, [pc, #144] ; (8003eec ) - 8003e5a: 4293 cmp r3, r2 - 8003e5c: d003 beq.n 8003e66 - 8003e5e: 687b ldr r3, [r7, #4] - 8003e60: 4a23 ldr r2, [pc, #140] ; (8003ef0 ) - 8003e62: 4293 cmp r3, r2 - 8003e64: d108 bne.n 8003e78 + 8003e8a: 687b ldr r3, [r7, #4] + 8003e8c: 4a2f ldr r2, [pc, #188] ; (8003f4c ) + 8003e8e: 4293 cmp r3, r2 + 8003e90: d02b beq.n 8003eea + 8003e92: 687b ldr r3, [r7, #4] + 8003e94: f1b3 4f80 cmp.w r3, #1073741824 ; 0x40000000 + 8003e98: d027 beq.n 8003eea + 8003e9a: 687b ldr r3, [r7, #4] + 8003e9c: 4a2c ldr r2, [pc, #176] ; (8003f50 ) + 8003e9e: 4293 cmp r3, r2 + 8003ea0: d023 beq.n 8003eea + 8003ea2: 687b ldr r3, [r7, #4] + 8003ea4: 4a2b ldr r2, [pc, #172] ; (8003f54 ) + 8003ea6: 4293 cmp r3, r2 + 8003ea8: d01f beq.n 8003eea + 8003eaa: 687b ldr r3, [r7, #4] + 8003eac: 4a2a ldr r2, [pc, #168] ; (8003f58 ) + 8003eae: 4293 cmp r3, r2 + 8003eb0: d01b beq.n 8003eea + 8003eb2: 687b ldr r3, [r7, #4] + 8003eb4: 4a29 ldr r2, [pc, #164] ; (8003f5c ) + 8003eb6: 4293 cmp r3, r2 + 8003eb8: d017 beq.n 8003eea + 8003eba: 687b ldr r3, [r7, #4] + 8003ebc: 4a28 ldr r2, [pc, #160] ; (8003f60 ) + 8003ebe: 4293 cmp r3, r2 + 8003ec0: d013 beq.n 8003eea + 8003ec2: 687b ldr r3, [r7, #4] + 8003ec4: 4a27 ldr r2, [pc, #156] ; (8003f64 ) + 8003ec6: 4293 cmp r3, r2 + 8003ec8: d00f beq.n 8003eea + 8003eca: 687b ldr r3, [r7, #4] + 8003ecc: 4a26 ldr r2, [pc, #152] ; (8003f68 ) + 8003ece: 4293 cmp r3, r2 + 8003ed0: d00b beq.n 8003eea + 8003ed2: 687b ldr r3, [r7, #4] + 8003ed4: 4a25 ldr r2, [pc, #148] ; (8003f6c ) + 8003ed6: 4293 cmp r3, r2 + 8003ed8: d007 beq.n 8003eea + 8003eda: 687b ldr r3, [r7, #4] + 8003edc: 4a24 ldr r2, [pc, #144] ; (8003f70 ) + 8003ede: 4293 cmp r3, r2 + 8003ee0: d003 beq.n 8003eea + 8003ee2: 687b ldr r3, [r7, #4] + 8003ee4: 4a23 ldr r2, [pc, #140] ; (8003f74 ) + 8003ee6: 4293 cmp r3, r2 + 8003ee8: d108 bne.n 8003efc { /* Set the clock division */ tmpcr1 &= ~TIM_CR1_CKD; - 8003e66: 68fb ldr r3, [r7, #12] - 8003e68: f423 7340 bic.w r3, r3, #768 ; 0x300 - 8003e6c: 60fb str r3, [r7, #12] + 8003eea: 68fb ldr r3, [r7, #12] + 8003eec: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8003ef0: 60fb str r3, [r7, #12] tmpcr1 |= (uint32_t)Structure->ClockDivision; - 8003e6e: 683b ldr r3, [r7, #0] - 8003e70: 68db ldr r3, [r3, #12] - 8003e72: 68fa ldr r2, [r7, #12] - 8003e74: 4313 orrs r3, r2 - 8003e76: 60fb str r3, [r7, #12] + 8003ef2: 683b ldr r3, [r7, #0] + 8003ef4: 68db ldr r3, [r3, #12] + 8003ef6: 68fa ldr r2, [r7, #12] + 8003ef8: 4313 orrs r3, r2 + 8003efa: 60fb str r3, [r7, #12] } /* Set the auto-reload preload */ MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); - 8003e78: 68fb ldr r3, [r7, #12] - 8003e7a: f023 0280 bic.w r2, r3, #128 ; 0x80 - 8003e7e: 683b ldr r3, [r7, #0] - 8003e80: 695b ldr r3, [r3, #20] - 8003e82: 4313 orrs r3, r2 - 8003e84: 60fb str r3, [r7, #12] + 8003efc: 68fb ldr r3, [r7, #12] + 8003efe: f023 0280 bic.w r2, r3, #128 ; 0x80 + 8003f02: 683b ldr r3, [r7, #0] + 8003f04: 695b ldr r3, [r3, #20] + 8003f06: 4313 orrs r3, r2 + 8003f08: 60fb str r3, [r7, #12] TIMx->CR1 = tmpcr1; - 8003e86: 687b ldr r3, [r7, #4] - 8003e88: 68fa ldr r2, [r7, #12] - 8003e8a: 601a str r2, [r3, #0] + 8003f0a: 687b ldr r3, [r7, #4] + 8003f0c: 68fa ldr r2, [r7, #12] + 8003f0e: 601a str r2, [r3, #0] /* Set the Autoreload value */ TIMx->ARR = (uint32_t)Structure->Period ; - 8003e8c: 683b ldr r3, [r7, #0] - 8003e8e: 689a ldr r2, [r3, #8] - 8003e90: 687b ldr r3, [r7, #4] - 8003e92: 62da str r2, [r3, #44] ; 0x2c + 8003f10: 683b ldr r3, [r7, #0] + 8003f12: 689a ldr r2, [r3, #8] + 8003f14: 687b ldr r3, [r7, #4] + 8003f16: 62da str r2, [r3, #44] ; 0x2c /* Set the Prescaler value */ TIMx->PSC = Structure->Prescaler; - 8003e94: 683b ldr r3, [r7, #0] - 8003e96: 681a ldr r2, [r3, #0] - 8003e98: 687b ldr r3, [r7, #4] - 8003e9a: 629a str r2, [r3, #40] ; 0x28 + 8003f18: 683b ldr r3, [r7, #0] + 8003f1a: 681a ldr r2, [r3, #0] + 8003f1c: 687b ldr r3, [r7, #4] + 8003f1e: 629a str r2, [r3, #40] ; 0x28 if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) - 8003e9c: 687b ldr r3, [r7, #4] - 8003e9e: 4a0a ldr r2, [pc, #40] ; (8003ec8 ) - 8003ea0: 4293 cmp r3, r2 - 8003ea2: d003 beq.n 8003eac - 8003ea4: 687b ldr r3, [r7, #4] - 8003ea6: 4a0c ldr r2, [pc, #48] ; (8003ed8 ) - 8003ea8: 4293 cmp r3, r2 - 8003eaa: d103 bne.n 8003eb4 + 8003f20: 687b ldr r3, [r7, #4] + 8003f22: 4a0a ldr r2, [pc, #40] ; (8003f4c ) + 8003f24: 4293 cmp r3, r2 + 8003f26: d003 beq.n 8003f30 + 8003f28: 687b ldr r3, [r7, #4] + 8003f2a: 4a0c ldr r2, [pc, #48] ; (8003f5c ) + 8003f2c: 4293 cmp r3, r2 + 8003f2e: d103 bne.n 8003f38 { /* Set the Repetition Counter value */ TIMx->RCR = Structure->RepetitionCounter; - 8003eac: 683b ldr r3, [r7, #0] - 8003eae: 691a ldr r2, [r3, #16] - 8003eb0: 687b ldr r3, [r7, #4] - 8003eb2: 631a str r2, [r3, #48] ; 0x30 + 8003f30: 683b ldr r3, [r7, #0] + 8003f32: 691a ldr r2, [r3, #16] + 8003f34: 687b ldr r3, [r7, #4] + 8003f36: 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; - 8003eb4: 687b ldr r3, [r7, #4] - 8003eb6: 2201 movs r2, #1 - 8003eb8: 615a str r2, [r3, #20] + 8003f38: 687b ldr r3, [r7, #4] + 8003f3a: 2201 movs r2, #1 + 8003f3c: 615a str r2, [r3, #20] } - 8003eba: bf00 nop - 8003ebc: 3714 adds r7, #20 - 8003ebe: 46bd mov sp, r7 - 8003ec0: f85d 7b04 ldr.w r7, [sp], #4 - 8003ec4: 4770 bx lr - 8003ec6: bf00 nop - 8003ec8: 40010000 .word 0x40010000 - 8003ecc: 40000400 .word 0x40000400 - 8003ed0: 40000800 .word 0x40000800 - 8003ed4: 40000c00 .word 0x40000c00 - 8003ed8: 40010400 .word 0x40010400 - 8003edc: 40014000 .word 0x40014000 - 8003ee0: 40014400 .word 0x40014400 - 8003ee4: 40014800 .word 0x40014800 - 8003ee8: 40001800 .word 0x40001800 - 8003eec: 40001c00 .word 0x40001c00 - 8003ef0: 40002000 .word 0x40002000 - -08003ef4 : + 8003f3e: bf00 nop + 8003f40: 3714 adds r7, #20 + 8003f42: 46bd mov sp, r7 + 8003f44: f85d 7b04 ldr.w r7, [sp], #4 + 8003f48: 4770 bx lr + 8003f4a: bf00 nop + 8003f4c: 40010000 .word 0x40010000 + 8003f50: 40000400 .word 0x40000400 + 8003f54: 40000800 .word 0x40000800 + 8003f58: 40000c00 .word 0x40000c00 + 8003f5c: 40010400 .word 0x40010400 + 8003f60: 40014000 .word 0x40014000 + 8003f64: 40014400 .word 0x40014400 + 8003f68: 40014800 .word 0x40014800 + 8003f6c: 40001800 .word 0x40001800 + 8003f70: 40001c00 .word 0x40001c00 + 8003f74: 40002000 .word 0x40002000 + +08003f78 : * @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) { - 8003ef4: b480 push {r7} - 8003ef6: b087 sub sp, #28 - 8003ef8: af00 add r7, sp, #0 - 8003efa: 6078 str r0, [r7, #4] - 8003efc: 6039 str r1, [r7, #0] + 8003f78: b480 push {r7} + 8003f7a: b087 sub sp, #28 + 8003f7c: af00 add r7, sp, #0 + 8003f7e: 6078 str r0, [r7, #4] + 8003f80: 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; - 8003efe: 687b ldr r3, [r7, #4] - 8003f00: 6a1b ldr r3, [r3, #32] - 8003f02: f023 0201 bic.w r2, r3, #1 - 8003f06: 687b ldr r3, [r7, #4] - 8003f08: 621a str r2, [r3, #32] + 8003f82: 687b ldr r3, [r7, #4] + 8003f84: 6a1b ldr r3, [r3, #32] + 8003f86: f023 0201 bic.w r2, r3, #1 + 8003f8a: 687b ldr r3, [r7, #4] + 8003f8c: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003f0a: 687b ldr r3, [r7, #4] - 8003f0c: 6a1b ldr r3, [r3, #32] - 8003f0e: 617b str r3, [r7, #20] + 8003f8e: 687b ldr r3, [r7, #4] + 8003f90: 6a1b ldr r3, [r3, #32] + 8003f92: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003f10: 687b ldr r3, [r7, #4] - 8003f12: 685b ldr r3, [r3, #4] - 8003f14: 613b str r3, [r7, #16] + 8003f94: 687b ldr r3, [r7, #4] + 8003f96: 685b ldr r3, [r3, #4] + 8003f98: 613b str r3, [r7, #16] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR1; - 8003f16: 687b ldr r3, [r7, #4] - 8003f18: 699b ldr r3, [r3, #24] - 8003f1a: 60fb str r3, [r7, #12] + 8003f9a: 687b ldr r3, [r7, #4] + 8003f9c: 699b ldr r3, [r3, #24] + 8003f9e: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~TIM_CCMR1_OC1M; - 8003f1c: 68fa ldr r2, [r7, #12] - 8003f1e: 4b2b ldr r3, [pc, #172] ; (8003fcc ) - 8003f20: 4013 ands r3, r2 - 8003f22: 60fb str r3, [r7, #12] + 8003fa0: 68fa ldr r2, [r7, #12] + 8003fa2: 4b2b ldr r3, [pc, #172] ; (8004050 ) + 8003fa4: 4013 ands r3, r2 + 8003fa6: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR1_CC1S; - 8003f24: 68fb ldr r3, [r7, #12] - 8003f26: f023 0303 bic.w r3, r3, #3 - 8003f2a: 60fb str r3, [r7, #12] + 8003fa8: 68fb ldr r3, [r7, #12] + 8003faa: f023 0303 bic.w r3, r3, #3 + 8003fae: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8003f2c: 683b ldr r3, [r7, #0] - 8003f2e: 681b ldr r3, [r3, #0] - 8003f30: 68fa ldr r2, [r7, #12] - 8003f32: 4313 orrs r3, r2 - 8003f34: 60fb str r3, [r7, #12] + 8003fb0: 683b ldr r3, [r7, #0] + 8003fb2: 681b ldr r3, [r3, #0] + 8003fb4: 68fa ldr r2, [r7, #12] + 8003fb6: 4313 orrs r3, r2 + 8003fb8: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC1P; - 8003f36: 697b ldr r3, [r7, #20] - 8003f38: f023 0302 bic.w r3, r3, #2 - 8003f3c: 617b str r3, [r7, #20] + 8003fba: 697b ldr r3, [r7, #20] + 8003fbc: f023 0302 bic.w r3, r3, #2 + 8003fc0: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= OC_Config->OCPolarity; - 8003f3e: 683b ldr r3, [r7, #0] - 8003f40: 689b ldr r3, [r3, #8] - 8003f42: 697a ldr r2, [r7, #20] - 8003f44: 4313 orrs r3, r2 - 8003f46: 617b str r3, [r7, #20] + 8003fc2: 683b ldr r3, [r7, #0] + 8003fc4: 689b ldr r3, [r3, #8] + 8003fc6: 697a ldr r2, [r7, #20] + 8003fc8: 4313 orrs r3, r2 + 8003fca: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) - 8003f48: 687b ldr r3, [r7, #4] - 8003f4a: 4a21 ldr r2, [pc, #132] ; (8003fd0 ) - 8003f4c: 4293 cmp r3, r2 - 8003f4e: d003 beq.n 8003f58 - 8003f50: 687b ldr r3, [r7, #4] - 8003f52: 4a20 ldr r2, [pc, #128] ; (8003fd4 ) - 8003f54: 4293 cmp r3, r2 - 8003f56: d10c bne.n 8003f72 + 8003fcc: 687b ldr r3, [r7, #4] + 8003fce: 4a21 ldr r2, [pc, #132] ; (8004054 ) + 8003fd0: 4293 cmp r3, r2 + 8003fd2: d003 beq.n 8003fdc + 8003fd4: 687b ldr r3, [r7, #4] + 8003fd6: 4a20 ldr r2, [pc, #128] ; (8004058 ) + 8003fd8: 4293 cmp r3, r2 + 8003fda: d10c bne.n 8003ff6 { /* Check parameters */ assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC1NP; - 8003f58: 697b ldr r3, [r7, #20] - 8003f5a: f023 0308 bic.w r3, r3, #8 - 8003f5e: 617b str r3, [r7, #20] + 8003fdc: 697b ldr r3, [r7, #20] + 8003fde: f023 0308 bic.w r3, r3, #8 + 8003fe2: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= OC_Config->OCNPolarity; - 8003f60: 683b ldr r3, [r7, #0] - 8003f62: 68db ldr r3, [r3, #12] - 8003f64: 697a ldr r2, [r7, #20] - 8003f66: 4313 orrs r3, r2 - 8003f68: 617b str r3, [r7, #20] + 8003fe4: 683b ldr r3, [r7, #0] + 8003fe6: 68db ldr r3, [r3, #12] + 8003fe8: 697a ldr r2, [r7, #20] + 8003fea: 4313 orrs r3, r2 + 8003fec: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC1NE; - 8003f6a: 697b ldr r3, [r7, #20] - 8003f6c: f023 0304 bic.w r3, r3, #4 - 8003f70: 617b str r3, [r7, #20] + 8003fee: 697b ldr r3, [r7, #20] + 8003ff0: f023 0304 bic.w r3, r3, #4 + 8003ff4: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8003f72: 687b ldr r3, [r7, #4] - 8003f74: 4a16 ldr r2, [pc, #88] ; (8003fd0 ) - 8003f76: 4293 cmp r3, r2 - 8003f78: d003 beq.n 8003f82 - 8003f7a: 687b ldr r3, [r7, #4] - 8003f7c: 4a15 ldr r2, [pc, #84] ; (8003fd4 ) - 8003f7e: 4293 cmp r3, r2 - 8003f80: d111 bne.n 8003fa6 + 8003ff6: 687b ldr r3, [r7, #4] + 8003ff8: 4a16 ldr r2, [pc, #88] ; (8004054 ) + 8003ffa: 4293 cmp r3, r2 + 8003ffc: d003 beq.n 8004006 + 8003ffe: 687b ldr r3, [r7, #4] + 8004000: 4a15 ldr r2, [pc, #84] ; (8004058 ) + 8004002: 4293 cmp r3, r2 + 8004004: d111 bne.n 800402a /* 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; - 8003f82: 693b ldr r3, [r7, #16] - 8003f84: f423 7380 bic.w r3, r3, #256 ; 0x100 - 8003f88: 613b str r3, [r7, #16] + 8004006: 693b ldr r3, [r7, #16] + 8004008: f423 7380 bic.w r3, r3, #256 ; 0x100 + 800400c: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS1N; - 8003f8a: 693b ldr r3, [r7, #16] - 8003f8c: f423 7300 bic.w r3, r3, #512 ; 0x200 - 8003f90: 613b str r3, [r7, #16] + 800400e: 693b ldr r3, [r7, #16] + 8004010: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8004014: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= OC_Config->OCIdleState; - 8003f92: 683b ldr r3, [r7, #0] - 8003f94: 695b ldr r3, [r3, #20] - 8003f96: 693a ldr r2, [r7, #16] - 8003f98: 4313 orrs r3, r2 - 8003f9a: 613b str r3, [r7, #16] + 8004016: 683b ldr r3, [r7, #0] + 8004018: 695b ldr r3, [r3, #20] + 800401a: 693a ldr r2, [r7, #16] + 800401c: 4313 orrs r3, r2 + 800401e: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= OC_Config->OCNIdleState; - 8003f9c: 683b ldr r3, [r7, #0] - 8003f9e: 699b ldr r3, [r3, #24] - 8003fa0: 693a ldr r2, [r7, #16] - 8003fa2: 4313 orrs r3, r2 - 8003fa4: 613b str r3, [r7, #16] + 8004020: 683b ldr r3, [r7, #0] + 8004022: 699b ldr r3, [r3, #24] + 8004024: 693a ldr r2, [r7, #16] + 8004026: 4313 orrs r3, r2 + 8004028: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8003fa6: 687b ldr r3, [r7, #4] - 8003fa8: 693a ldr r2, [r7, #16] - 8003faa: 605a str r2, [r3, #4] + 800402a: 687b ldr r3, [r7, #4] + 800402c: 693a ldr r2, [r7, #16] + 800402e: 605a str r2, [r3, #4] /* Write to TIMx CCMR1 */ TIMx->CCMR1 = tmpccmrx; - 8003fac: 687b ldr r3, [r7, #4] - 8003fae: 68fa ldr r2, [r7, #12] - 8003fb0: 619a str r2, [r3, #24] + 8004030: 687b ldr r3, [r7, #4] + 8004032: 68fa ldr r2, [r7, #12] + 8004034: 619a str r2, [r3, #24] /* Set the Capture Compare Register value */ TIMx->CCR1 = OC_Config->Pulse; - 8003fb2: 683b ldr r3, [r7, #0] - 8003fb4: 685a ldr r2, [r3, #4] - 8003fb6: 687b ldr r3, [r7, #4] - 8003fb8: 635a str r2, [r3, #52] ; 0x34 + 8004036: 683b ldr r3, [r7, #0] + 8004038: 685a ldr r2, [r3, #4] + 800403a: 687b ldr r3, [r7, #4] + 800403c: 635a str r2, [r3, #52] ; 0x34 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8003fba: 687b ldr r3, [r7, #4] - 8003fbc: 697a ldr r2, [r7, #20] - 8003fbe: 621a str r2, [r3, #32] + 800403e: 687b ldr r3, [r7, #4] + 8004040: 697a ldr r2, [r7, #20] + 8004042: 621a str r2, [r3, #32] } - 8003fc0: bf00 nop - 8003fc2: 371c adds r7, #28 - 8003fc4: 46bd mov sp, r7 - 8003fc6: f85d 7b04 ldr.w r7, [sp], #4 - 8003fca: 4770 bx lr - 8003fcc: fffeff8f .word 0xfffeff8f - 8003fd0: 40010000 .word 0x40010000 - 8003fd4: 40010400 .word 0x40010400 - -08003fd8 : + 8004044: bf00 nop + 8004046: 371c adds r7, #28 + 8004048: 46bd mov sp, r7 + 800404a: f85d 7b04 ldr.w r7, [sp], #4 + 800404e: 4770 bx lr + 8004050: fffeff8f .word 0xfffeff8f + 8004054: 40010000 .word 0x40010000 + 8004058: 40010400 .word 0x40010400 + +0800405c : * @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) { - 8003fd8: b480 push {r7} - 8003fda: b087 sub sp, #28 - 8003fdc: af00 add r7, sp, #0 - 8003fde: 6078 str r0, [r7, #4] - 8003fe0: 6039 str r1, [r7, #0] + 800405c: b480 push {r7} + 800405e: b087 sub sp, #28 + 8004060: af00 add r7, sp, #0 + 8004062: 6078 str r0, [r7, #4] + 8004064: 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; - 8003fe2: 687b ldr r3, [r7, #4] - 8003fe4: 6a1b ldr r3, [r3, #32] - 8003fe6: f023 0210 bic.w r2, r3, #16 - 8003fea: 687b ldr r3, [r7, #4] - 8003fec: 621a str r2, [r3, #32] + 8004066: 687b ldr r3, [r7, #4] + 8004068: 6a1b ldr r3, [r3, #32] + 800406a: f023 0210 bic.w r2, r3, #16 + 800406e: 687b ldr r3, [r7, #4] + 8004070: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 8003fee: 687b ldr r3, [r7, #4] - 8003ff0: 6a1b ldr r3, [r3, #32] - 8003ff2: 617b str r3, [r7, #20] + 8004072: 687b ldr r3, [r7, #4] + 8004074: 6a1b ldr r3, [r3, #32] + 8004076: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8003ff4: 687b ldr r3, [r7, #4] - 8003ff6: 685b ldr r3, [r3, #4] - 8003ff8: 613b str r3, [r7, #16] + 8004078: 687b ldr r3, [r7, #4] + 800407a: 685b ldr r3, [r3, #4] + 800407c: 613b str r3, [r7, #16] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR1; - 8003ffa: 687b ldr r3, [r7, #4] - 8003ffc: 699b ldr r3, [r3, #24] - 8003ffe: 60fb str r3, [r7, #12] + 800407e: 687b ldr r3, [r7, #4] + 8004080: 699b ldr r3, [r3, #24] + 8004082: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR1_OC2M; - 8004000: 68fa ldr r2, [r7, #12] - 8004002: 4b2e ldr r3, [pc, #184] ; (80040bc ) - 8004004: 4013 ands r3, r2 - 8004006: 60fb str r3, [r7, #12] + 8004084: 68fa ldr r2, [r7, #12] + 8004086: 4b2e ldr r3, [pc, #184] ; (8004140 ) + 8004088: 4013 ands r3, r2 + 800408a: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR1_CC2S; - 8004008: 68fb ldr r3, [r7, #12] - 800400a: f423 7340 bic.w r3, r3, #768 ; 0x300 - 800400e: 60fb str r3, [r7, #12] + 800408c: 68fb ldr r3, [r7, #12] + 800408e: f423 7340 bic.w r3, r3, #768 ; 0x300 + 8004092: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 8004010: 683b ldr r3, [r7, #0] - 8004012: 681b ldr r3, [r3, #0] - 8004014: 021b lsls r3, r3, #8 - 8004016: 68fa ldr r2, [r7, #12] - 8004018: 4313 orrs r3, r2 - 800401a: 60fb str r3, [r7, #12] + 8004094: 683b ldr r3, [r7, #0] + 8004096: 681b ldr r3, [r3, #0] + 8004098: 021b lsls r3, r3, #8 + 800409a: 68fa ldr r2, [r7, #12] + 800409c: 4313 orrs r3, r2 + 800409e: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC2P; - 800401c: 697b ldr r3, [r7, #20] - 800401e: f023 0320 bic.w r3, r3, #32 - 8004022: 617b str r3, [r7, #20] + 80040a0: 697b ldr r3, [r7, #20] + 80040a2: f023 0320 bic.w r3, r3, #32 + 80040a6: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 4U); - 8004024: 683b ldr r3, [r7, #0] - 8004026: 689b ldr r3, [r3, #8] - 8004028: 011b lsls r3, r3, #4 - 800402a: 697a ldr r2, [r7, #20] - 800402c: 4313 orrs r3, r2 - 800402e: 617b str r3, [r7, #20] + 80040a8: 683b ldr r3, [r7, #0] + 80040aa: 689b ldr r3, [r3, #8] + 80040ac: 011b lsls r3, r3, #4 + 80040ae: 697a ldr r2, [r7, #20] + 80040b0: 4313 orrs r3, r2 + 80040b2: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) - 8004030: 687b ldr r3, [r7, #4] - 8004032: 4a23 ldr r2, [pc, #140] ; (80040c0 ) - 8004034: 4293 cmp r3, r2 - 8004036: d003 beq.n 8004040 - 8004038: 687b ldr r3, [r7, #4] - 800403a: 4a22 ldr r2, [pc, #136] ; (80040c4 ) - 800403c: 4293 cmp r3, r2 - 800403e: d10d bne.n 800405c + 80040b4: 687b ldr r3, [r7, #4] + 80040b6: 4a23 ldr r2, [pc, #140] ; (8004144 ) + 80040b8: 4293 cmp r3, r2 + 80040ba: d003 beq.n 80040c4 + 80040bc: 687b ldr r3, [r7, #4] + 80040be: 4a22 ldr r2, [pc, #136] ; (8004148 ) + 80040c0: 4293 cmp r3, r2 + 80040c2: d10d bne.n 80040e0 { assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC2NP; - 8004040: 697b ldr r3, [r7, #20] - 8004042: f023 0380 bic.w r3, r3, #128 ; 0x80 - 8004046: 617b str r3, [r7, #20] + 80040c4: 697b ldr r3, [r7, #20] + 80040c6: f023 0380 bic.w r3, r3, #128 ; 0x80 + 80040ca: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= (OC_Config->OCNPolarity << 4U); - 8004048: 683b ldr r3, [r7, #0] - 800404a: 68db ldr r3, [r3, #12] - 800404c: 011b lsls r3, r3, #4 - 800404e: 697a ldr r2, [r7, #20] - 8004050: 4313 orrs r3, r2 - 8004052: 617b str r3, [r7, #20] + 80040cc: 683b ldr r3, [r7, #0] + 80040ce: 68db ldr r3, [r3, #12] + 80040d0: 011b lsls r3, r3, #4 + 80040d2: 697a ldr r2, [r7, #20] + 80040d4: 4313 orrs r3, r2 + 80040d6: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC2NE; - 8004054: 697b ldr r3, [r7, #20] - 8004056: f023 0340 bic.w r3, r3, #64 ; 0x40 - 800405a: 617b str r3, [r7, #20] + 80040d8: 697b ldr r3, [r7, #20] + 80040da: f023 0340 bic.w r3, r3, #64 ; 0x40 + 80040de: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 800405c: 687b ldr r3, [r7, #4] - 800405e: 4a18 ldr r2, [pc, #96] ; (80040c0 ) - 8004060: 4293 cmp r3, r2 - 8004062: d003 beq.n 800406c - 8004064: 687b ldr r3, [r7, #4] - 8004066: 4a17 ldr r2, [pc, #92] ; (80040c4 ) - 8004068: 4293 cmp r3, r2 - 800406a: d113 bne.n 8004094 + 80040e0: 687b ldr r3, [r7, #4] + 80040e2: 4a18 ldr r2, [pc, #96] ; (8004144 ) + 80040e4: 4293 cmp r3, r2 + 80040e6: d003 beq.n 80040f0 + 80040e8: 687b ldr r3, [r7, #4] + 80040ea: 4a17 ldr r2, [pc, #92] ; (8004148 ) + 80040ec: 4293 cmp r3, r2 + 80040ee: d113 bne.n 8004118 /* 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; - 800406c: 693b ldr r3, [r7, #16] - 800406e: f423 6380 bic.w r3, r3, #1024 ; 0x400 - 8004072: 613b str r3, [r7, #16] + 80040f0: 693b ldr r3, [r7, #16] + 80040f2: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 80040f6: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS2N; - 8004074: 693b ldr r3, [r7, #16] - 8004076: f423 6300 bic.w r3, r3, #2048 ; 0x800 - 800407a: 613b str r3, [r7, #16] + 80040f8: 693b ldr r3, [r7, #16] + 80040fa: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 80040fe: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 2U); - 800407c: 683b ldr r3, [r7, #0] - 800407e: 695b ldr r3, [r3, #20] - 8004080: 009b lsls r3, r3, #2 - 8004082: 693a ldr r2, [r7, #16] - 8004084: 4313 orrs r3, r2 - 8004086: 613b str r3, [r7, #16] + 8004100: 683b ldr r3, [r7, #0] + 8004102: 695b ldr r3, [r3, #20] + 8004104: 009b lsls r3, r3, #2 + 8004106: 693a ldr r2, [r7, #16] + 8004108: 4313 orrs r3, r2 + 800410a: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= (OC_Config->OCNIdleState << 2U); - 8004088: 683b ldr r3, [r7, #0] - 800408a: 699b ldr r3, [r3, #24] - 800408c: 009b lsls r3, r3, #2 - 800408e: 693a ldr r2, [r7, #16] - 8004090: 4313 orrs r3, r2 - 8004092: 613b str r3, [r7, #16] + 800410c: 683b ldr r3, [r7, #0] + 800410e: 699b ldr r3, [r3, #24] + 8004110: 009b lsls r3, r3, #2 + 8004112: 693a ldr r2, [r7, #16] + 8004114: 4313 orrs r3, r2 + 8004116: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8004094: 687b ldr r3, [r7, #4] - 8004096: 693a ldr r2, [r7, #16] - 8004098: 605a str r2, [r3, #4] + 8004118: 687b ldr r3, [r7, #4] + 800411a: 693a ldr r2, [r7, #16] + 800411c: 605a str r2, [r3, #4] /* Write to TIMx CCMR1 */ TIMx->CCMR1 = tmpccmrx; - 800409a: 687b ldr r3, [r7, #4] - 800409c: 68fa ldr r2, [r7, #12] - 800409e: 619a str r2, [r3, #24] + 800411e: 687b ldr r3, [r7, #4] + 8004120: 68fa ldr r2, [r7, #12] + 8004122: 619a str r2, [r3, #24] /* Set the Capture Compare Register value */ TIMx->CCR2 = OC_Config->Pulse; - 80040a0: 683b ldr r3, [r7, #0] - 80040a2: 685a ldr r2, [r3, #4] - 80040a4: 687b ldr r3, [r7, #4] - 80040a6: 639a str r2, [r3, #56] ; 0x38 + 8004124: 683b ldr r3, [r7, #0] + 8004126: 685a ldr r2, [r3, #4] + 8004128: 687b ldr r3, [r7, #4] + 800412a: 639a str r2, [r3, #56] ; 0x38 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 80040a8: 687b ldr r3, [r7, #4] - 80040aa: 697a ldr r2, [r7, #20] - 80040ac: 621a str r2, [r3, #32] + 800412c: 687b ldr r3, [r7, #4] + 800412e: 697a ldr r2, [r7, #20] + 8004130: 621a str r2, [r3, #32] } - 80040ae: bf00 nop - 80040b0: 371c adds r7, #28 - 80040b2: 46bd mov sp, r7 - 80040b4: f85d 7b04 ldr.w r7, [sp], #4 - 80040b8: 4770 bx lr - 80040ba: bf00 nop - 80040bc: feff8fff .word 0xfeff8fff - 80040c0: 40010000 .word 0x40010000 - 80040c4: 40010400 .word 0x40010400 - -080040c8 : + 8004132: bf00 nop + 8004134: 371c adds r7, #28 + 8004136: 46bd mov sp, r7 + 8004138: f85d 7b04 ldr.w r7, [sp], #4 + 800413c: 4770 bx lr + 800413e: bf00 nop + 8004140: feff8fff .word 0xfeff8fff + 8004144: 40010000 .word 0x40010000 + 8004148: 40010400 .word 0x40010400 + +0800414c : * @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) { - 80040c8: b480 push {r7} - 80040ca: b087 sub sp, #28 - 80040cc: af00 add r7, sp, #0 - 80040ce: 6078 str r0, [r7, #4] - 80040d0: 6039 str r1, [r7, #0] + 800414c: b480 push {r7} + 800414e: b087 sub sp, #28 + 8004150: af00 add r7, sp, #0 + 8004152: 6078 str r0, [r7, #4] + 8004154: 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; - 80040d2: 687b ldr r3, [r7, #4] - 80040d4: 6a1b ldr r3, [r3, #32] - 80040d6: f423 7280 bic.w r2, r3, #256 ; 0x100 - 80040da: 687b ldr r3, [r7, #4] - 80040dc: 621a str r2, [r3, #32] + 8004156: 687b ldr r3, [r7, #4] + 8004158: 6a1b ldr r3, [r3, #32] + 800415a: f423 7280 bic.w r2, r3, #256 ; 0x100 + 800415e: 687b ldr r3, [r7, #4] + 8004160: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 80040de: 687b ldr r3, [r7, #4] - 80040e0: 6a1b ldr r3, [r3, #32] - 80040e2: 617b str r3, [r7, #20] + 8004162: 687b ldr r3, [r7, #4] + 8004164: 6a1b ldr r3, [r3, #32] + 8004166: 617b str r3, [r7, #20] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 80040e4: 687b ldr r3, [r7, #4] - 80040e6: 685b ldr r3, [r3, #4] - 80040e8: 613b str r3, [r7, #16] + 8004168: 687b ldr r3, [r7, #4] + 800416a: 685b ldr r3, [r3, #4] + 800416c: 613b str r3, [r7, #16] /* Get the TIMx CCMR2 register value */ tmpccmrx = TIMx->CCMR2; - 80040ea: 687b ldr r3, [r7, #4] - 80040ec: 69db ldr r3, [r3, #28] - 80040ee: 60fb str r3, [r7, #12] + 800416e: 687b ldr r3, [r7, #4] + 8004170: 69db ldr r3, [r3, #28] + 8004172: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR2_OC3M; - 80040f0: 68fa ldr r2, [r7, #12] - 80040f2: 4b2d ldr r3, [pc, #180] ; (80041a8 ) - 80040f4: 4013 ands r3, r2 - 80040f6: 60fb str r3, [r7, #12] + 8004174: 68fa ldr r2, [r7, #12] + 8004176: 4b2d ldr r3, [pc, #180] ; (800422c ) + 8004178: 4013 ands r3, r2 + 800417a: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR2_CC3S; - 80040f8: 68fb ldr r3, [r7, #12] - 80040fa: f023 0303 bic.w r3, r3, #3 - 80040fe: 60fb str r3, [r7, #12] + 800417c: 68fb ldr r3, [r7, #12] + 800417e: f023 0303 bic.w r3, r3, #3 + 8004182: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8004100: 683b ldr r3, [r7, #0] - 8004102: 681b ldr r3, [r3, #0] - 8004104: 68fa ldr r2, [r7, #12] - 8004106: 4313 orrs r3, r2 - 8004108: 60fb str r3, [r7, #12] + 8004184: 683b ldr r3, [r7, #0] + 8004186: 681b ldr r3, [r3, #0] + 8004188: 68fa ldr r2, [r7, #12] + 800418a: 4313 orrs r3, r2 + 800418c: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC3P; - 800410a: 697b ldr r3, [r7, #20] - 800410c: f423 7300 bic.w r3, r3, #512 ; 0x200 - 8004110: 617b str r3, [r7, #20] + 800418e: 697b ldr r3, [r7, #20] + 8004190: f423 7300 bic.w r3, r3, #512 ; 0x200 + 8004194: 617b str r3, [r7, #20] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 8U); - 8004112: 683b ldr r3, [r7, #0] - 8004114: 689b ldr r3, [r3, #8] - 8004116: 021b lsls r3, r3, #8 - 8004118: 697a ldr r2, [r7, #20] - 800411a: 4313 orrs r3, r2 - 800411c: 617b str r3, [r7, #20] + 8004196: 683b ldr r3, [r7, #0] + 8004198: 689b ldr r3, [r3, #8] + 800419a: 021b lsls r3, r3, #8 + 800419c: 697a ldr r2, [r7, #20] + 800419e: 4313 orrs r3, r2 + 80041a0: 617b str r3, [r7, #20] if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) - 800411e: 687b ldr r3, [r7, #4] - 8004120: 4a22 ldr r2, [pc, #136] ; (80041ac ) - 8004122: 4293 cmp r3, r2 - 8004124: d003 beq.n 800412e - 8004126: 687b ldr r3, [r7, #4] - 8004128: 4a21 ldr r2, [pc, #132] ; (80041b0 ) - 800412a: 4293 cmp r3, r2 - 800412c: d10d bne.n 800414a + 80041a2: 687b ldr r3, [r7, #4] + 80041a4: 4a22 ldr r2, [pc, #136] ; (8004230 ) + 80041a6: 4293 cmp r3, r2 + 80041a8: d003 beq.n 80041b2 + 80041aa: 687b ldr r3, [r7, #4] + 80041ac: 4a21 ldr r2, [pc, #132] ; (8004234 ) + 80041ae: 4293 cmp r3, r2 + 80041b0: d10d bne.n 80041ce { assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); /* Reset the Output N Polarity level */ tmpccer &= ~TIM_CCER_CC3NP; - 800412e: 697b ldr r3, [r7, #20] - 8004130: f423 6300 bic.w r3, r3, #2048 ; 0x800 - 8004134: 617b str r3, [r7, #20] + 80041b2: 697b ldr r3, [r7, #20] + 80041b4: f423 6300 bic.w r3, r3, #2048 ; 0x800 + 80041b8: 617b str r3, [r7, #20] /* Set the Output N Polarity */ tmpccer |= (OC_Config->OCNPolarity << 8U); - 8004136: 683b ldr r3, [r7, #0] - 8004138: 68db ldr r3, [r3, #12] - 800413a: 021b lsls r3, r3, #8 - 800413c: 697a ldr r2, [r7, #20] - 800413e: 4313 orrs r3, r2 - 8004140: 617b str r3, [r7, #20] + 80041ba: 683b ldr r3, [r7, #0] + 80041bc: 68db ldr r3, [r3, #12] + 80041be: 021b lsls r3, r3, #8 + 80041c0: 697a ldr r2, [r7, #20] + 80041c2: 4313 orrs r3, r2 + 80041c4: 617b str r3, [r7, #20] /* Reset the Output N State */ tmpccer &= ~TIM_CCER_CC3NE; - 8004142: 697b ldr r3, [r7, #20] - 8004144: f423 6380 bic.w r3, r3, #1024 ; 0x400 - 8004148: 617b str r3, [r7, #20] + 80041c6: 697b ldr r3, [r7, #20] + 80041c8: f423 6380 bic.w r3, r3, #1024 ; 0x400 + 80041cc: 617b str r3, [r7, #20] } if (IS_TIM_BREAK_INSTANCE(TIMx)) - 800414a: 687b ldr r3, [r7, #4] - 800414c: 4a17 ldr r2, [pc, #92] ; (80041ac ) - 800414e: 4293 cmp r3, r2 - 8004150: d003 beq.n 800415a - 8004152: 687b ldr r3, [r7, #4] - 8004154: 4a16 ldr r2, [pc, #88] ; (80041b0 ) - 8004156: 4293 cmp r3, r2 - 8004158: d113 bne.n 8004182 + 80041ce: 687b ldr r3, [r7, #4] + 80041d0: 4a17 ldr r2, [pc, #92] ; (8004230 ) + 80041d2: 4293 cmp r3, r2 + 80041d4: d003 beq.n 80041de + 80041d6: 687b ldr r3, [r7, #4] + 80041d8: 4a16 ldr r2, [pc, #88] ; (8004234 ) + 80041da: 4293 cmp r3, r2 + 80041dc: d113 bne.n 8004206 /* 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; - 800415a: 693b ldr r3, [r7, #16] - 800415c: f423 5380 bic.w r3, r3, #4096 ; 0x1000 - 8004160: 613b str r3, [r7, #16] + 80041de: 693b ldr r3, [r7, #16] + 80041e0: f423 5380 bic.w r3, r3, #4096 ; 0x1000 + 80041e4: 613b str r3, [r7, #16] tmpcr2 &= ~TIM_CR2_OIS3N; - 8004162: 693b ldr r3, [r7, #16] - 8004164: f423 5300 bic.w r3, r3, #8192 ; 0x2000 - 8004168: 613b str r3, [r7, #16] + 80041e6: 693b ldr r3, [r7, #16] + 80041e8: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 80041ec: 613b str r3, [r7, #16] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 4U); - 800416a: 683b ldr r3, [r7, #0] - 800416c: 695b ldr r3, [r3, #20] - 800416e: 011b lsls r3, r3, #4 - 8004170: 693a ldr r2, [r7, #16] - 8004172: 4313 orrs r3, r2 - 8004174: 613b str r3, [r7, #16] + 80041ee: 683b ldr r3, [r7, #0] + 80041f0: 695b ldr r3, [r3, #20] + 80041f2: 011b lsls r3, r3, #4 + 80041f4: 693a ldr r2, [r7, #16] + 80041f6: 4313 orrs r3, r2 + 80041f8: 613b str r3, [r7, #16] /* Set the Output N Idle state */ tmpcr2 |= (OC_Config->OCNIdleState << 4U); - 8004176: 683b ldr r3, [r7, #0] - 8004178: 699b ldr r3, [r3, #24] - 800417a: 011b lsls r3, r3, #4 - 800417c: 693a ldr r2, [r7, #16] - 800417e: 4313 orrs r3, r2 - 8004180: 613b str r3, [r7, #16] + 80041fa: 683b ldr r3, [r7, #0] + 80041fc: 699b ldr r3, [r3, #24] + 80041fe: 011b lsls r3, r3, #4 + 8004200: 693a ldr r2, [r7, #16] + 8004202: 4313 orrs r3, r2 + 8004204: 613b str r3, [r7, #16] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8004182: 687b ldr r3, [r7, #4] - 8004184: 693a ldr r2, [r7, #16] - 8004186: 605a str r2, [r3, #4] + 8004206: 687b ldr r3, [r7, #4] + 8004208: 693a ldr r2, [r7, #16] + 800420a: 605a str r2, [r3, #4] /* Write to TIMx CCMR2 */ TIMx->CCMR2 = tmpccmrx; - 8004188: 687b ldr r3, [r7, #4] - 800418a: 68fa ldr r2, [r7, #12] - 800418c: 61da str r2, [r3, #28] + 800420c: 687b ldr r3, [r7, #4] + 800420e: 68fa ldr r2, [r7, #12] + 8004210: 61da str r2, [r3, #28] /* Set the Capture Compare Register value */ TIMx->CCR3 = OC_Config->Pulse; - 800418e: 683b ldr r3, [r7, #0] - 8004190: 685a ldr r2, [r3, #4] - 8004192: 687b ldr r3, [r7, #4] - 8004194: 63da str r2, [r3, #60] ; 0x3c + 8004212: 683b ldr r3, [r7, #0] + 8004214: 685a ldr r2, [r3, #4] + 8004216: 687b ldr r3, [r7, #4] + 8004218: 63da str r2, [r3, #60] ; 0x3c /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8004196: 687b ldr r3, [r7, #4] - 8004198: 697a ldr r2, [r7, #20] - 800419a: 621a str r2, [r3, #32] + 800421a: 687b ldr r3, [r7, #4] + 800421c: 697a ldr r2, [r7, #20] + 800421e: 621a str r2, [r3, #32] } - 800419c: bf00 nop - 800419e: 371c adds r7, #28 - 80041a0: 46bd mov sp, r7 - 80041a2: f85d 7b04 ldr.w r7, [sp], #4 - 80041a6: 4770 bx lr - 80041a8: fffeff8f .word 0xfffeff8f - 80041ac: 40010000 .word 0x40010000 - 80041b0: 40010400 .word 0x40010400 - -080041b4 : + 8004220: bf00 nop + 8004222: 371c adds r7, #28 + 8004224: 46bd mov sp, r7 + 8004226: f85d 7b04 ldr.w r7, [sp], #4 + 800422a: 4770 bx lr + 800422c: fffeff8f .word 0xfffeff8f + 8004230: 40010000 .word 0x40010000 + 8004234: 40010400 .word 0x40010400 + +08004238 : * @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) { - 80041b4: b480 push {r7} - 80041b6: b087 sub sp, #28 - 80041b8: af00 add r7, sp, #0 - 80041ba: 6078 str r0, [r7, #4] - 80041bc: 6039 str r1, [r7, #0] + 8004238: b480 push {r7} + 800423a: b087 sub sp, #28 + 800423c: af00 add r7, sp, #0 + 800423e: 6078 str r0, [r7, #4] + 8004240: 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; - 80041be: 687b ldr r3, [r7, #4] - 80041c0: 6a1b ldr r3, [r3, #32] - 80041c2: f423 5280 bic.w r2, r3, #4096 ; 0x1000 - 80041c6: 687b ldr r3, [r7, #4] - 80041c8: 621a str r2, [r3, #32] + 8004242: 687b ldr r3, [r7, #4] + 8004244: 6a1b ldr r3, [r3, #32] + 8004246: f423 5280 bic.w r2, r3, #4096 ; 0x1000 + 800424a: 687b ldr r3, [r7, #4] + 800424c: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 80041ca: 687b ldr r3, [r7, #4] - 80041cc: 6a1b ldr r3, [r3, #32] - 80041ce: 613b str r3, [r7, #16] + 800424e: 687b ldr r3, [r7, #4] + 8004250: 6a1b ldr r3, [r3, #32] + 8004252: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 80041d0: 687b ldr r3, [r7, #4] - 80041d2: 685b ldr r3, [r3, #4] - 80041d4: 617b str r3, [r7, #20] + 8004254: 687b ldr r3, [r7, #4] + 8004256: 685b ldr r3, [r3, #4] + 8004258: 617b str r3, [r7, #20] /* Get the TIMx CCMR2 register value */ tmpccmrx = TIMx->CCMR2; - 80041d6: 687b ldr r3, [r7, #4] - 80041d8: 69db ldr r3, [r3, #28] - 80041da: 60fb str r3, [r7, #12] + 800425a: 687b ldr r3, [r7, #4] + 800425c: 69db ldr r3, [r3, #28] + 800425e: 60fb str r3, [r7, #12] /* Reset the Output Compare mode and Capture/Compare selection Bits */ tmpccmrx &= ~TIM_CCMR2_OC4M; - 80041dc: 68fa ldr r2, [r7, #12] - 80041de: 4b1e ldr r3, [pc, #120] ; (8004258 ) - 80041e0: 4013 ands r3, r2 - 80041e2: 60fb str r3, [r7, #12] + 8004260: 68fa ldr r2, [r7, #12] + 8004262: 4b1e ldr r3, [pc, #120] ; (80042dc ) + 8004264: 4013 ands r3, r2 + 8004266: 60fb str r3, [r7, #12] tmpccmrx &= ~TIM_CCMR2_CC4S; - 80041e4: 68fb ldr r3, [r7, #12] - 80041e6: f423 7340 bic.w r3, r3, #768 ; 0x300 - 80041ea: 60fb str r3, [r7, #12] + 8004268: 68fb ldr r3, [r7, #12] + 800426a: f423 7340 bic.w r3, r3, #768 ; 0x300 + 800426e: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 80041ec: 683b ldr r3, [r7, #0] - 80041ee: 681b ldr r3, [r3, #0] - 80041f0: 021b lsls r3, r3, #8 - 80041f2: 68fa ldr r2, [r7, #12] - 80041f4: 4313 orrs r3, r2 - 80041f6: 60fb str r3, [r7, #12] + 8004270: 683b ldr r3, [r7, #0] + 8004272: 681b ldr r3, [r3, #0] + 8004274: 021b lsls r3, r3, #8 + 8004276: 68fa ldr r2, [r7, #12] + 8004278: 4313 orrs r3, r2 + 800427a: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC4P; - 80041f8: 693b ldr r3, [r7, #16] - 80041fa: f423 5300 bic.w r3, r3, #8192 ; 0x2000 - 80041fe: 613b str r3, [r7, #16] + 800427c: 693b ldr r3, [r7, #16] + 800427e: f423 5300 bic.w r3, r3, #8192 ; 0x2000 + 8004282: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 12U); - 8004200: 683b ldr r3, [r7, #0] - 8004202: 689b ldr r3, [r3, #8] - 8004204: 031b lsls r3, r3, #12 - 8004206: 693a ldr r2, [r7, #16] - 8004208: 4313 orrs r3, r2 - 800420a: 613b str r3, [r7, #16] + 8004284: 683b ldr r3, [r7, #0] + 8004286: 689b ldr r3, [r3, #8] + 8004288: 031b lsls r3, r3, #12 + 800428a: 693a ldr r2, [r7, #16] + 800428c: 4313 orrs r3, r2 + 800428e: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 800420c: 687b ldr r3, [r7, #4] - 800420e: 4a13 ldr r2, [pc, #76] ; (800425c ) - 8004210: 4293 cmp r3, r2 - 8004212: d003 beq.n 800421c - 8004214: 687b ldr r3, [r7, #4] - 8004216: 4a12 ldr r2, [pc, #72] ; (8004260 ) - 8004218: 4293 cmp r3, r2 - 800421a: d109 bne.n 8004230 + 8004290: 687b ldr r3, [r7, #4] + 8004292: 4a13 ldr r2, [pc, #76] ; (80042e0 ) + 8004294: 4293 cmp r3, r2 + 8004296: d003 beq.n 80042a0 + 8004298: 687b ldr r3, [r7, #4] + 800429a: 4a12 ldr r2, [pc, #72] ; (80042e4 ) + 800429c: 4293 cmp r3, r2 + 800429e: d109 bne.n 80042b4 { /* Check parameters */ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS4; - 800421c: 697b ldr r3, [r7, #20] - 800421e: f423 4380 bic.w r3, r3, #16384 ; 0x4000 - 8004222: 617b str r3, [r7, #20] + 80042a0: 697b ldr r3, [r7, #20] + 80042a2: f423 4380 bic.w r3, r3, #16384 ; 0x4000 + 80042a6: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 6U); - 8004224: 683b ldr r3, [r7, #0] - 8004226: 695b ldr r3, [r3, #20] - 8004228: 019b lsls r3, r3, #6 - 800422a: 697a ldr r2, [r7, #20] - 800422c: 4313 orrs r3, r2 - 800422e: 617b str r3, [r7, #20] + 80042a8: 683b ldr r3, [r7, #0] + 80042aa: 695b ldr r3, [r3, #20] + 80042ac: 019b lsls r3, r3, #6 + 80042ae: 697a ldr r2, [r7, #20] + 80042b0: 4313 orrs r3, r2 + 80042b2: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 8004230: 687b ldr r3, [r7, #4] - 8004232: 697a ldr r2, [r7, #20] - 8004234: 605a str r2, [r3, #4] + 80042b4: 687b ldr r3, [r7, #4] + 80042b6: 697a ldr r2, [r7, #20] + 80042b8: 605a str r2, [r3, #4] /* Write to TIMx CCMR2 */ TIMx->CCMR2 = tmpccmrx; - 8004236: 687b ldr r3, [r7, #4] - 8004238: 68fa ldr r2, [r7, #12] - 800423a: 61da str r2, [r3, #28] + 80042ba: 687b ldr r3, [r7, #4] + 80042bc: 68fa ldr r2, [r7, #12] + 80042be: 61da str r2, [r3, #28] /* Set the Capture Compare Register value */ TIMx->CCR4 = OC_Config->Pulse; - 800423c: 683b ldr r3, [r7, #0] - 800423e: 685a ldr r2, [r3, #4] - 8004240: 687b ldr r3, [r7, #4] - 8004242: 641a str r2, [r3, #64] ; 0x40 + 80042c0: 683b ldr r3, [r7, #0] + 80042c2: 685a ldr r2, [r3, #4] + 80042c4: 687b ldr r3, [r7, #4] + 80042c6: 641a str r2, [r3, #64] ; 0x40 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8004244: 687b ldr r3, [r7, #4] - 8004246: 693a ldr r2, [r7, #16] - 8004248: 621a str r2, [r3, #32] + 80042c8: 687b ldr r3, [r7, #4] + 80042ca: 693a ldr r2, [r7, #16] + 80042cc: 621a str r2, [r3, #32] } - 800424a: bf00 nop - 800424c: 371c adds r7, #28 - 800424e: 46bd mov sp, r7 - 8004250: f85d 7b04 ldr.w r7, [sp], #4 - 8004254: 4770 bx lr - 8004256: bf00 nop - 8004258: feff8fff .word 0xfeff8fff - 800425c: 40010000 .word 0x40010000 - 8004260: 40010400 .word 0x40010400 - -08004264 : + 80042ce: bf00 nop + 80042d0: 371c adds r7, #28 + 80042d2: 46bd mov sp, r7 + 80042d4: f85d 7b04 ldr.w r7, [sp], #4 + 80042d8: 4770 bx lr + 80042da: bf00 nop + 80042dc: feff8fff .word 0xfeff8fff + 80042e0: 40010000 .word 0x40010000 + 80042e4: 40010400 .word 0x40010400 + +080042e8 : * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC5_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8004264: b480 push {r7} - 8004266: b087 sub sp, #28 - 8004268: af00 add r7, sp, #0 - 800426a: 6078 str r0, [r7, #4] - 800426c: 6039 str r1, [r7, #0] + 80042e8: b480 push {r7} + 80042ea: b087 sub sp, #28 + 80042ec: af00 add r7, sp, #0 + 80042ee: 6078 str r0, [r7, #4] + 80042f0: 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; - 800426e: 687b ldr r3, [r7, #4] - 8004270: 6a1b ldr r3, [r3, #32] - 8004272: f423 3280 bic.w r2, r3, #65536 ; 0x10000 - 8004276: 687b ldr r3, [r7, #4] - 8004278: 621a str r2, [r3, #32] + 80042f2: 687b ldr r3, [r7, #4] + 80042f4: 6a1b ldr r3, [r3, #32] + 80042f6: f423 3280 bic.w r2, r3, #65536 ; 0x10000 + 80042fa: 687b ldr r3, [r7, #4] + 80042fc: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 800427a: 687b ldr r3, [r7, #4] - 800427c: 6a1b ldr r3, [r3, #32] - 800427e: 613b str r3, [r7, #16] + 80042fe: 687b ldr r3, [r7, #4] + 8004300: 6a1b ldr r3, [r3, #32] + 8004302: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8004280: 687b ldr r3, [r7, #4] - 8004282: 685b ldr r3, [r3, #4] - 8004284: 617b str r3, [r7, #20] + 8004304: 687b ldr r3, [r7, #4] + 8004306: 685b ldr r3, [r3, #4] + 8004308: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR3; - 8004286: 687b ldr r3, [r7, #4] - 8004288: 6d5b ldr r3, [r3, #84] ; 0x54 - 800428a: 60fb str r3, [r7, #12] + 800430a: 687b ldr r3, [r7, #4] + 800430c: 6d5b ldr r3, [r3, #84] ; 0x54 + 800430e: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~(TIM_CCMR3_OC5M); - 800428c: 68fa ldr r2, [r7, #12] - 800428e: 4b1b ldr r3, [pc, #108] ; (80042fc ) - 8004290: 4013 ands r3, r2 - 8004292: 60fb str r3, [r7, #12] + 8004310: 68fa ldr r2, [r7, #12] + 8004312: 4b1b ldr r3, [pc, #108] ; (8004380 ) + 8004314: 4013 ands r3, r2 + 8004316: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= OC_Config->OCMode; - 8004294: 683b ldr r3, [r7, #0] - 8004296: 681b ldr r3, [r3, #0] - 8004298: 68fa ldr r2, [r7, #12] - 800429a: 4313 orrs r3, r2 - 800429c: 60fb str r3, [r7, #12] + 8004318: 683b ldr r3, [r7, #0] + 800431a: 681b ldr r3, [r3, #0] + 800431c: 68fa ldr r2, [r7, #12] + 800431e: 4313 orrs r3, r2 + 8004320: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= ~TIM_CCER_CC5P; - 800429e: 693b ldr r3, [r7, #16] - 80042a0: f423 3300 bic.w r3, r3, #131072 ; 0x20000 - 80042a4: 613b str r3, [r7, #16] + 8004322: 693b ldr r3, [r7, #16] + 8004324: f423 3300 bic.w r3, r3, #131072 ; 0x20000 + 8004328: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 16U); - 80042a6: 683b ldr r3, [r7, #0] - 80042a8: 689b ldr r3, [r3, #8] - 80042aa: 041b lsls r3, r3, #16 - 80042ac: 693a ldr r2, [r7, #16] - 80042ae: 4313 orrs r3, r2 - 80042b0: 613b str r3, [r7, #16] + 800432a: 683b ldr r3, [r7, #0] + 800432c: 689b ldr r3, [r3, #8] + 800432e: 041b lsls r3, r3, #16 + 8004330: 693a ldr r2, [r7, #16] + 8004332: 4313 orrs r3, r2 + 8004334: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 80042b2: 687b ldr r3, [r7, #4] - 80042b4: 4a12 ldr r2, [pc, #72] ; (8004300 ) - 80042b6: 4293 cmp r3, r2 - 80042b8: d003 beq.n 80042c2 - 80042ba: 687b ldr r3, [r7, #4] - 80042bc: 4a11 ldr r2, [pc, #68] ; (8004304 ) - 80042be: 4293 cmp r3, r2 - 80042c0: d109 bne.n 80042d6 + 8004336: 687b ldr r3, [r7, #4] + 8004338: 4a12 ldr r2, [pc, #72] ; (8004384 ) + 800433a: 4293 cmp r3, r2 + 800433c: d003 beq.n 8004346 + 800433e: 687b ldr r3, [r7, #4] + 8004340: 4a11 ldr r2, [pc, #68] ; (8004388 ) + 8004342: 4293 cmp r3, r2 + 8004344: d109 bne.n 800435a { /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS5; - 80042c2: 697b ldr r3, [r7, #20] - 80042c4: f423 3380 bic.w r3, r3, #65536 ; 0x10000 - 80042c8: 617b str r3, [r7, #20] + 8004346: 697b ldr r3, [r7, #20] + 8004348: f423 3380 bic.w r3, r3, #65536 ; 0x10000 + 800434c: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 8U); - 80042ca: 683b ldr r3, [r7, #0] - 80042cc: 695b ldr r3, [r3, #20] - 80042ce: 021b lsls r3, r3, #8 - 80042d0: 697a ldr r2, [r7, #20] - 80042d2: 4313 orrs r3, r2 - 80042d4: 617b str r3, [r7, #20] + 800434e: 683b ldr r3, [r7, #0] + 8004350: 695b ldr r3, [r3, #20] + 8004352: 021b lsls r3, r3, #8 + 8004354: 697a ldr r2, [r7, #20] + 8004356: 4313 orrs r3, r2 + 8004358: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 80042d6: 687b ldr r3, [r7, #4] - 80042d8: 697a ldr r2, [r7, #20] - 80042da: 605a str r2, [r3, #4] + 800435a: 687b ldr r3, [r7, #4] + 800435c: 697a ldr r2, [r7, #20] + 800435e: 605a str r2, [r3, #4] /* Write to TIMx CCMR3 */ TIMx->CCMR3 = tmpccmrx; - 80042dc: 687b ldr r3, [r7, #4] - 80042de: 68fa ldr r2, [r7, #12] - 80042e0: 655a str r2, [r3, #84] ; 0x54 + 8004360: 687b ldr r3, [r7, #4] + 8004362: 68fa ldr r2, [r7, #12] + 8004364: 655a str r2, [r3, #84] ; 0x54 /* Set the Capture Compare Register value */ TIMx->CCR5 = OC_Config->Pulse; - 80042e2: 683b ldr r3, [r7, #0] - 80042e4: 685a ldr r2, [r3, #4] - 80042e6: 687b ldr r3, [r7, #4] - 80042e8: 659a str r2, [r3, #88] ; 0x58 + 8004366: 683b ldr r3, [r7, #0] + 8004368: 685a ldr r2, [r3, #4] + 800436a: 687b ldr r3, [r7, #4] + 800436c: 659a str r2, [r3, #88] ; 0x58 /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 80042ea: 687b ldr r3, [r7, #4] - 80042ec: 693a ldr r2, [r7, #16] - 80042ee: 621a str r2, [r3, #32] + 800436e: 687b ldr r3, [r7, #4] + 8004370: 693a ldr r2, [r7, #16] + 8004372: 621a str r2, [r3, #32] } - 80042f0: bf00 nop - 80042f2: 371c adds r7, #28 - 80042f4: 46bd mov sp, r7 - 80042f6: f85d 7b04 ldr.w r7, [sp], #4 - 80042fa: 4770 bx lr - 80042fc: fffeff8f .word 0xfffeff8f - 8004300: 40010000 .word 0x40010000 - 8004304: 40010400 .word 0x40010400 - -08004308 : + 8004374: bf00 nop + 8004376: 371c adds r7, #28 + 8004378: 46bd mov sp, r7 + 800437a: f85d 7b04 ldr.w r7, [sp], #4 + 800437e: 4770 bx lr + 8004380: fffeff8f .word 0xfffeff8f + 8004384: 40010000 .word 0x40010000 + 8004388: 40010400 .word 0x40010400 + +0800438c : * @param OC_Config The ouput configuration structure * @retval None */ static void TIM_OC6_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) { - 8004308: b480 push {r7} - 800430a: b087 sub sp, #28 - 800430c: af00 add r7, sp, #0 - 800430e: 6078 str r0, [r7, #4] - 8004310: 6039 str r1, [r7, #0] + 800438c: b480 push {r7} + 800438e: b087 sub sp, #28 + 8004390: af00 add r7, sp, #0 + 8004392: 6078 str r0, [r7, #4] + 8004394: 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; - 8004312: 687b ldr r3, [r7, #4] - 8004314: 6a1b ldr r3, [r3, #32] - 8004316: f423 1280 bic.w r2, r3, #1048576 ; 0x100000 - 800431a: 687b ldr r3, [r7, #4] - 800431c: 621a str r2, [r3, #32] + 8004396: 687b ldr r3, [r7, #4] + 8004398: 6a1b ldr r3, [r3, #32] + 800439a: f423 1280 bic.w r2, r3, #1048576 ; 0x100000 + 800439e: 687b ldr r3, [r7, #4] + 80043a0: 621a str r2, [r3, #32] /* Get the TIMx CCER register value */ tmpccer = TIMx->CCER; - 800431e: 687b ldr r3, [r7, #4] - 8004320: 6a1b ldr r3, [r3, #32] - 8004322: 613b str r3, [r7, #16] + 80043a2: 687b ldr r3, [r7, #4] + 80043a4: 6a1b ldr r3, [r3, #32] + 80043a6: 613b str r3, [r7, #16] /* Get the TIMx CR2 register value */ tmpcr2 = TIMx->CR2; - 8004324: 687b ldr r3, [r7, #4] - 8004326: 685b ldr r3, [r3, #4] - 8004328: 617b str r3, [r7, #20] + 80043a8: 687b ldr r3, [r7, #4] + 80043aa: 685b ldr r3, [r3, #4] + 80043ac: 617b str r3, [r7, #20] /* Get the TIMx CCMR1 register value */ tmpccmrx = TIMx->CCMR3; - 800432a: 687b ldr r3, [r7, #4] - 800432c: 6d5b ldr r3, [r3, #84] ; 0x54 - 800432e: 60fb str r3, [r7, #12] + 80043ae: 687b ldr r3, [r7, #4] + 80043b0: 6d5b ldr r3, [r3, #84] ; 0x54 + 80043b2: 60fb str r3, [r7, #12] /* Reset the Output Compare Mode Bits */ tmpccmrx &= ~(TIM_CCMR3_OC6M); - 8004330: 68fa ldr r2, [r7, #12] - 8004332: 4b1c ldr r3, [pc, #112] ; (80043a4 ) - 8004334: 4013 ands r3, r2 - 8004336: 60fb str r3, [r7, #12] + 80043b4: 68fa ldr r2, [r7, #12] + 80043b6: 4b1c ldr r3, [pc, #112] ; (8004428 ) + 80043b8: 4013 ands r3, r2 + 80043ba: 60fb str r3, [r7, #12] /* Select the Output Compare Mode */ tmpccmrx |= (OC_Config->OCMode << 8U); - 8004338: 683b ldr r3, [r7, #0] - 800433a: 681b ldr r3, [r3, #0] - 800433c: 021b lsls r3, r3, #8 - 800433e: 68fa ldr r2, [r7, #12] - 8004340: 4313 orrs r3, r2 - 8004342: 60fb str r3, [r7, #12] + 80043bc: 683b ldr r3, [r7, #0] + 80043be: 681b ldr r3, [r3, #0] + 80043c0: 021b lsls r3, r3, #8 + 80043c2: 68fa ldr r2, [r7, #12] + 80043c4: 4313 orrs r3, r2 + 80043c6: 60fb str r3, [r7, #12] /* Reset the Output Polarity level */ tmpccer &= (uint32_t)~TIM_CCER_CC6P; - 8004344: 693b ldr r3, [r7, #16] - 8004346: f423 1300 bic.w r3, r3, #2097152 ; 0x200000 - 800434a: 613b str r3, [r7, #16] + 80043c8: 693b ldr r3, [r7, #16] + 80043ca: f423 1300 bic.w r3, r3, #2097152 ; 0x200000 + 80043ce: 613b str r3, [r7, #16] /* Set the Output Compare Polarity */ tmpccer |= (OC_Config->OCPolarity << 20U); - 800434c: 683b ldr r3, [r7, #0] - 800434e: 689b ldr r3, [r3, #8] - 8004350: 051b lsls r3, r3, #20 - 8004352: 693a ldr r2, [r7, #16] - 8004354: 4313 orrs r3, r2 - 8004356: 613b str r3, [r7, #16] + 80043d0: 683b ldr r3, [r7, #0] + 80043d2: 689b ldr r3, [r3, #8] + 80043d4: 051b lsls r3, r3, #20 + 80043d6: 693a ldr r2, [r7, #16] + 80043d8: 4313 orrs r3, r2 + 80043da: 613b str r3, [r7, #16] if (IS_TIM_BREAK_INSTANCE(TIMx)) - 8004358: 687b ldr r3, [r7, #4] - 800435a: 4a13 ldr r2, [pc, #76] ; (80043a8 ) - 800435c: 4293 cmp r3, r2 - 800435e: d003 beq.n 8004368 - 8004360: 687b ldr r3, [r7, #4] - 8004362: 4a12 ldr r2, [pc, #72] ; (80043ac ) - 8004364: 4293 cmp r3, r2 - 8004366: d109 bne.n 800437c + 80043dc: 687b ldr r3, [r7, #4] + 80043de: 4a13 ldr r2, [pc, #76] ; (800442c ) + 80043e0: 4293 cmp r3, r2 + 80043e2: d003 beq.n 80043ec + 80043e4: 687b ldr r3, [r7, #4] + 80043e6: 4a12 ldr r2, [pc, #72] ; (8004430 ) + 80043e8: 4293 cmp r3, r2 + 80043ea: d109 bne.n 8004400 { /* Reset the Output Compare IDLE State */ tmpcr2 &= ~TIM_CR2_OIS6; - 8004368: 697b ldr r3, [r7, #20] - 800436a: f423 2380 bic.w r3, r3, #262144 ; 0x40000 - 800436e: 617b str r3, [r7, #20] + 80043ec: 697b ldr r3, [r7, #20] + 80043ee: f423 2380 bic.w r3, r3, #262144 ; 0x40000 + 80043f2: 617b str r3, [r7, #20] /* Set the Output Idle state */ tmpcr2 |= (OC_Config->OCIdleState << 10U); - 8004370: 683b ldr r3, [r7, #0] - 8004372: 695b ldr r3, [r3, #20] - 8004374: 029b lsls r3, r3, #10 - 8004376: 697a ldr r2, [r7, #20] - 8004378: 4313 orrs r3, r2 - 800437a: 617b str r3, [r7, #20] + 80043f4: 683b ldr r3, [r7, #0] + 80043f6: 695b ldr r3, [r3, #20] + 80043f8: 029b lsls r3, r3, #10 + 80043fa: 697a ldr r2, [r7, #20] + 80043fc: 4313 orrs r3, r2 + 80043fe: 617b str r3, [r7, #20] } /* Write to TIMx CR2 */ TIMx->CR2 = tmpcr2; - 800437c: 687b ldr r3, [r7, #4] - 800437e: 697a ldr r2, [r7, #20] - 8004380: 605a str r2, [r3, #4] + 8004400: 687b ldr r3, [r7, #4] + 8004402: 697a ldr r2, [r7, #20] + 8004404: 605a str r2, [r3, #4] /* Write to TIMx CCMR3 */ TIMx->CCMR3 = tmpccmrx; - 8004382: 687b ldr r3, [r7, #4] - 8004384: 68fa ldr r2, [r7, #12] - 8004386: 655a str r2, [r3, #84] ; 0x54 + 8004406: 687b ldr r3, [r7, #4] + 8004408: 68fa ldr r2, [r7, #12] + 800440a: 655a str r2, [r3, #84] ; 0x54 /* Set the Capture Compare Register value */ TIMx->CCR6 = OC_Config->Pulse; - 8004388: 683b ldr r3, [r7, #0] - 800438a: 685a ldr r2, [r3, #4] - 800438c: 687b ldr r3, [r7, #4] - 800438e: 65da str r2, [r3, #92] ; 0x5c + 800440c: 683b ldr r3, [r7, #0] + 800440e: 685a ldr r2, [r3, #4] + 8004410: 687b ldr r3, [r7, #4] + 8004412: 65da str r2, [r3, #92] ; 0x5c /* Write to TIMx CCER */ TIMx->CCER = tmpccer; - 8004390: 687b ldr r3, [r7, #4] - 8004392: 693a ldr r2, [r7, #16] - 8004394: 621a str r2, [r3, #32] + 8004414: 687b ldr r3, [r7, #4] + 8004416: 693a ldr r2, [r7, #16] + 8004418: 621a str r2, [r3, #32] } - 8004396: bf00 nop - 8004398: 371c adds r7, #28 - 800439a: 46bd mov sp, r7 - 800439c: f85d 7b04 ldr.w r7, [sp], #4 - 80043a0: 4770 bx lr - 80043a2: bf00 nop - 80043a4: feff8fff .word 0xfeff8fff - 80043a8: 40010000 .word 0x40010000 - 80043ac: 40010400 .word 0x40010400 - -080043b0 : + 800441a: bf00 nop + 800441c: 371c adds r7, #28 + 800441e: 46bd mov sp, r7 + 8004420: f85d 7b04 ldr.w r7, [sp], #4 + 8004424: 4770 bx lr + 8004426: bf00 nop + 8004428: feff8fff .word 0xfeff8fff + 800442c: 40010000 .word 0x40010000 + 8004430: 40010400 .word 0x40010400 + +08004434 : * @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) { - 80043b0: b480 push {r7} - 80043b2: b087 sub sp, #28 - 80043b4: af00 add r7, sp, #0 - 80043b6: 60f8 str r0, [r7, #12] - 80043b8: 60b9 str r1, [r7, #8] - 80043ba: 607a str r2, [r7, #4] + 8004434: b480 push {r7} + 8004436: b087 sub sp, #28 + 8004438: af00 add r7, sp, #0 + 800443a: 60f8 str r0, [r7, #12] + 800443c: 60b9 str r1, [r7, #8] + 800443e: 607a str r2, [r7, #4] uint32_t tmpccmr1; uint32_t tmpccer; /* Disable the Channel 1: Reset the CC1E Bit */ tmpccer = TIMx->CCER; - 80043bc: 68fb ldr r3, [r7, #12] - 80043be: 6a1b ldr r3, [r3, #32] - 80043c0: 617b str r3, [r7, #20] + 8004440: 68fb ldr r3, [r7, #12] + 8004442: 6a1b ldr r3, [r3, #32] + 8004444: 617b str r3, [r7, #20] TIMx->CCER &= ~TIM_CCER_CC1E; - 80043c2: 68fb ldr r3, [r7, #12] - 80043c4: 6a1b ldr r3, [r3, #32] - 80043c6: f023 0201 bic.w r2, r3, #1 - 80043ca: 68fb ldr r3, [r7, #12] - 80043cc: 621a str r2, [r3, #32] + 8004446: 68fb ldr r3, [r7, #12] + 8004448: 6a1b ldr r3, [r3, #32] + 800444a: f023 0201 bic.w r2, r3, #1 + 800444e: 68fb ldr r3, [r7, #12] + 8004450: 621a str r2, [r3, #32] tmpccmr1 = TIMx->CCMR1; - 80043ce: 68fb ldr r3, [r7, #12] - 80043d0: 699b ldr r3, [r3, #24] - 80043d2: 613b str r3, [r7, #16] + 8004452: 68fb ldr r3, [r7, #12] + 8004454: 699b ldr r3, [r3, #24] + 8004456: 613b str r3, [r7, #16] /* Set the filter */ tmpccmr1 &= ~TIM_CCMR1_IC1F; - 80043d4: 693b ldr r3, [r7, #16] - 80043d6: f023 03f0 bic.w r3, r3, #240 ; 0xf0 - 80043da: 613b str r3, [r7, #16] + 8004458: 693b ldr r3, [r7, #16] + 800445a: f023 03f0 bic.w r3, r3, #240 ; 0xf0 + 800445e: 613b str r3, [r7, #16] tmpccmr1 |= (TIM_ICFilter << 4U); - 80043dc: 687b ldr r3, [r7, #4] - 80043de: 011b lsls r3, r3, #4 - 80043e0: 693a ldr r2, [r7, #16] - 80043e2: 4313 orrs r3, r2 - 80043e4: 613b str r3, [r7, #16] + 8004460: 687b ldr r3, [r7, #4] + 8004462: 011b lsls r3, r3, #4 + 8004464: 693a ldr r2, [r7, #16] + 8004466: 4313 orrs r3, r2 + 8004468: 613b str r3, [r7, #16] /* Select the Polarity and set the CC1E Bit */ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - 80043e6: 697b ldr r3, [r7, #20] - 80043e8: f023 030a bic.w r3, r3, #10 - 80043ec: 617b str r3, [r7, #20] + 800446a: 697b ldr r3, [r7, #20] + 800446c: f023 030a bic.w r3, r3, #10 + 8004470: 617b str r3, [r7, #20] tmpccer |= TIM_ICPolarity; - 80043ee: 697a ldr r2, [r7, #20] - 80043f0: 68bb ldr r3, [r7, #8] - 80043f2: 4313 orrs r3, r2 - 80043f4: 617b str r3, [r7, #20] + 8004472: 697a ldr r2, [r7, #20] + 8004474: 68bb ldr r3, [r7, #8] + 8004476: 4313 orrs r3, r2 + 8004478: 617b str r3, [r7, #20] /* Write to TIMx CCMR1 and CCER registers */ TIMx->CCMR1 = tmpccmr1; - 80043f6: 68fb ldr r3, [r7, #12] - 80043f8: 693a ldr r2, [r7, #16] - 80043fa: 619a str r2, [r3, #24] + 800447a: 68fb ldr r3, [r7, #12] + 800447c: 693a ldr r2, [r7, #16] + 800447e: 619a str r2, [r3, #24] TIMx->CCER = tmpccer; - 80043fc: 68fb ldr r3, [r7, #12] - 80043fe: 697a ldr r2, [r7, #20] - 8004400: 621a str r2, [r3, #32] + 8004480: 68fb ldr r3, [r7, #12] + 8004482: 697a ldr r2, [r7, #20] + 8004484: 621a str r2, [r3, #32] } - 8004402: bf00 nop - 8004404: 371c adds r7, #28 - 8004406: 46bd mov sp, r7 - 8004408: f85d 7b04 ldr.w r7, [sp], #4 - 800440c: 4770 bx lr + 8004486: bf00 nop + 8004488: 371c adds r7, #28 + 800448a: 46bd mov sp, r7 + 800448c: f85d 7b04 ldr.w r7, [sp], #4 + 8004490: 4770 bx lr -0800440e : +08004492 : * @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) { - 800440e: b480 push {r7} - 8004410: b087 sub sp, #28 - 8004412: af00 add r7, sp, #0 - 8004414: 60f8 str r0, [r7, #12] - 8004416: 60b9 str r1, [r7, #8] - 8004418: 607a str r2, [r7, #4] + 8004492: b480 push {r7} + 8004494: b087 sub sp, #28 + 8004496: af00 add r7, sp, #0 + 8004498: 60f8 str r0, [r7, #12] + 800449a: 60b9 str r1, [r7, #8] + 800449c: 607a str r2, [r7, #4] uint32_t tmpccmr1; uint32_t tmpccer; /* Disable the Channel 2: Reset the CC2E Bit */ TIMx->CCER &= ~TIM_CCER_CC2E; - 800441a: 68fb ldr r3, [r7, #12] - 800441c: 6a1b ldr r3, [r3, #32] - 800441e: f023 0210 bic.w r2, r3, #16 - 8004422: 68fb ldr r3, [r7, #12] - 8004424: 621a str r2, [r3, #32] + 800449e: 68fb ldr r3, [r7, #12] + 80044a0: 6a1b ldr r3, [r3, #32] + 80044a2: f023 0210 bic.w r2, r3, #16 + 80044a6: 68fb ldr r3, [r7, #12] + 80044a8: 621a str r2, [r3, #32] tmpccmr1 = TIMx->CCMR1; - 8004426: 68fb ldr r3, [r7, #12] - 8004428: 699b ldr r3, [r3, #24] - 800442a: 617b str r3, [r7, #20] + 80044aa: 68fb ldr r3, [r7, #12] + 80044ac: 699b ldr r3, [r3, #24] + 80044ae: 617b str r3, [r7, #20] tmpccer = TIMx->CCER; - 800442c: 68fb ldr r3, [r7, #12] - 800442e: 6a1b ldr r3, [r3, #32] - 8004430: 613b str r3, [r7, #16] + 80044b0: 68fb ldr r3, [r7, #12] + 80044b2: 6a1b ldr r3, [r3, #32] + 80044b4: 613b str r3, [r7, #16] /* Set the filter */ tmpccmr1 &= ~TIM_CCMR1_IC2F; - 8004432: 697b ldr r3, [r7, #20] - 8004434: f423 4370 bic.w r3, r3, #61440 ; 0xf000 - 8004438: 617b str r3, [r7, #20] + 80044b6: 697b ldr r3, [r7, #20] + 80044b8: f423 4370 bic.w r3, r3, #61440 ; 0xf000 + 80044bc: 617b str r3, [r7, #20] tmpccmr1 |= (TIM_ICFilter << 12U); - 800443a: 687b ldr r3, [r7, #4] - 800443c: 031b lsls r3, r3, #12 - 800443e: 697a ldr r2, [r7, #20] - 8004440: 4313 orrs r3, r2 - 8004442: 617b str r3, [r7, #20] + 80044be: 687b ldr r3, [r7, #4] + 80044c0: 031b lsls r3, r3, #12 + 80044c2: 697a ldr r2, [r7, #20] + 80044c4: 4313 orrs r3, r2 + 80044c6: 617b str r3, [r7, #20] /* Select the Polarity and set the CC2E Bit */ tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - 8004444: 693b ldr r3, [r7, #16] - 8004446: f023 03a0 bic.w r3, r3, #160 ; 0xa0 - 800444a: 613b str r3, [r7, #16] + 80044c8: 693b ldr r3, [r7, #16] + 80044ca: f023 03a0 bic.w r3, r3, #160 ; 0xa0 + 80044ce: 613b str r3, [r7, #16] tmpccer |= (TIM_ICPolarity << 4U); - 800444c: 68bb ldr r3, [r7, #8] - 800444e: 011b lsls r3, r3, #4 - 8004450: 693a ldr r2, [r7, #16] - 8004452: 4313 orrs r3, r2 - 8004454: 613b str r3, [r7, #16] + 80044d0: 68bb ldr r3, [r7, #8] + 80044d2: 011b lsls r3, r3, #4 + 80044d4: 693a ldr r2, [r7, #16] + 80044d6: 4313 orrs r3, r2 + 80044d8: 613b str r3, [r7, #16] /* Write to TIMx CCMR1 and CCER registers */ TIMx->CCMR1 = tmpccmr1 ; - 8004456: 68fb ldr r3, [r7, #12] - 8004458: 697a ldr r2, [r7, #20] - 800445a: 619a str r2, [r3, #24] + 80044da: 68fb ldr r3, [r7, #12] + 80044dc: 697a ldr r2, [r7, #20] + 80044de: 619a str r2, [r3, #24] TIMx->CCER = tmpccer; - 800445c: 68fb ldr r3, [r7, #12] - 800445e: 693a ldr r2, [r7, #16] - 8004460: 621a str r2, [r3, #32] + 80044e0: 68fb ldr r3, [r7, #12] + 80044e2: 693a ldr r2, [r7, #16] + 80044e4: 621a str r2, [r3, #32] } - 8004462: bf00 nop - 8004464: 371c adds r7, #28 - 8004466: 46bd mov sp, r7 - 8004468: f85d 7b04 ldr.w r7, [sp], #4 - 800446c: 4770 bx lr + 80044e6: bf00 nop + 80044e8: 371c adds r7, #28 + 80044ea: 46bd mov sp, r7 + 80044ec: f85d 7b04 ldr.w r7, [sp], #4 + 80044f0: 4770 bx lr -0800446e : +080044f2 : * @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) { - 800446e: b480 push {r7} - 8004470: b085 sub sp, #20 - 8004472: af00 add r7, sp, #0 - 8004474: 6078 str r0, [r7, #4] - 8004476: 6039 str r1, [r7, #0] + 80044f2: b480 push {r7} + 80044f4: b085 sub sp, #20 + 80044f6: af00 add r7, sp, #0 + 80044f8: 6078 str r0, [r7, #4] + 80044fa: 6039 str r1, [r7, #0] uint32_t tmpsmcr; /* Get the TIMx SMCR register value */ tmpsmcr = TIMx->SMCR; - 8004478: 687b ldr r3, [r7, #4] - 800447a: 689b ldr r3, [r3, #8] - 800447c: 60fb str r3, [r7, #12] + 80044fc: 687b ldr r3, [r7, #4] + 80044fe: 689b ldr r3, [r3, #8] + 8004500: 60fb str r3, [r7, #12] /* Reset the TS Bits */ tmpsmcr &= ~TIM_SMCR_TS; - 800447e: 68fb ldr r3, [r7, #12] - 8004480: f023 0370 bic.w r3, r3, #112 ; 0x70 - 8004484: 60fb str r3, [r7, #12] + 8004502: 68fb ldr r3, [r7, #12] + 8004504: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8004508: 60fb str r3, [r7, #12] /* Set the Input Trigger source and the slave mode*/ tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); - 8004486: 683a ldr r2, [r7, #0] - 8004488: 68fb ldr r3, [r7, #12] - 800448a: 4313 orrs r3, r2 - 800448c: f043 0307 orr.w r3, r3, #7 - 8004490: 60fb str r3, [r7, #12] + 800450a: 683a ldr r2, [r7, #0] + 800450c: 68fb ldr r3, [r7, #12] + 800450e: 4313 orrs r3, r2 + 8004510: f043 0307 orr.w r3, r3, #7 + 8004514: 60fb str r3, [r7, #12] /* Write to TIMx SMCR */ TIMx->SMCR = tmpsmcr; - 8004492: 687b ldr r3, [r7, #4] - 8004494: 68fa ldr r2, [r7, #12] - 8004496: 609a str r2, [r3, #8] + 8004516: 687b ldr r3, [r7, #4] + 8004518: 68fa ldr r2, [r7, #12] + 800451a: 609a str r2, [r3, #8] } - 8004498: bf00 nop - 800449a: 3714 adds r7, #20 - 800449c: 46bd mov sp, r7 - 800449e: f85d 7b04 ldr.w r7, [sp], #4 - 80044a2: 4770 bx lr + 800451c: bf00 nop + 800451e: 3714 adds r7, #20 + 8004520: 46bd mov sp, r7 + 8004522: f85d 7b04 ldr.w r7, [sp], #4 + 8004526: 4770 bx lr -080044a4 : +08004528 : * 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) { - 80044a4: b480 push {r7} - 80044a6: b087 sub sp, #28 - 80044a8: af00 add r7, sp, #0 - 80044aa: 60f8 str r0, [r7, #12] - 80044ac: 60b9 str r1, [r7, #8] - 80044ae: 607a str r2, [r7, #4] - 80044b0: 603b str r3, [r7, #0] + 8004528: b480 push {r7} + 800452a: b087 sub sp, #28 + 800452c: af00 add r7, sp, #0 + 800452e: 60f8 str r0, [r7, #12] + 8004530: 60b9 str r1, [r7, #8] + 8004532: 607a str r2, [r7, #4] + 8004534: 603b str r3, [r7, #0] uint32_t tmpsmcr; tmpsmcr = TIMx->SMCR; - 80044b2: 68fb ldr r3, [r7, #12] - 80044b4: 689b ldr r3, [r3, #8] - 80044b6: 617b str r3, [r7, #20] + 8004536: 68fb ldr r3, [r7, #12] + 8004538: 689b ldr r3, [r3, #8] + 800453a: 617b str r3, [r7, #20] /* Reset the ETR Bits */ tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - 80044b8: 697b ldr r3, [r7, #20] - 80044ba: f423 437f bic.w r3, r3, #65280 ; 0xff00 - 80044be: 617b str r3, [r7, #20] + 800453c: 697b ldr r3, [r7, #20] + 800453e: f423 437f bic.w r3, r3, #65280 ; 0xff00 + 8004542: 617b str r3, [r7, #20] /* Set the Prescaler, the Filter value and the Polarity */ tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); - 80044c0: 683b ldr r3, [r7, #0] - 80044c2: 021a lsls r2, r3, #8 - 80044c4: 687b ldr r3, [r7, #4] - 80044c6: 431a orrs r2, r3 - 80044c8: 68bb ldr r3, [r7, #8] - 80044ca: 4313 orrs r3, r2 - 80044cc: 697a ldr r2, [r7, #20] - 80044ce: 4313 orrs r3, r2 - 80044d0: 617b str r3, [r7, #20] + 8004544: 683b ldr r3, [r7, #0] + 8004546: 021a lsls r2, r3, #8 + 8004548: 687b ldr r3, [r7, #4] + 800454a: 431a orrs r2, r3 + 800454c: 68bb ldr r3, [r7, #8] + 800454e: 4313 orrs r3, r2 + 8004550: 697a ldr r2, [r7, #20] + 8004552: 4313 orrs r3, r2 + 8004554: 617b str r3, [r7, #20] /* Write to TIMx SMCR */ TIMx->SMCR = tmpsmcr; - 80044d2: 68fb ldr r3, [r7, #12] - 80044d4: 697a ldr r2, [r7, #20] - 80044d6: 609a str r2, [r3, #8] + 8004556: 68fb ldr r3, [r7, #12] + 8004558: 697a ldr r2, [r7, #20] + 800455a: 609a str r2, [r3, #8] } - 80044d8: bf00 nop - 80044da: 371c adds r7, #28 - 80044dc: 46bd mov sp, r7 - 80044de: f85d 7b04 ldr.w r7, [sp], #4 - 80044e2: 4770 bx lr + 800455c: bf00 nop + 800455e: 371c adds r7, #28 + 8004560: 46bd mov sp, r7 + 8004562: f85d 7b04 ldr.w r7, [sp], #4 + 8004566: 4770 bx lr -080044e4 : +08004568 : * @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) { - 80044e4: b480 push {r7} - 80044e6: b087 sub sp, #28 - 80044e8: af00 add r7, sp, #0 - 80044ea: 60f8 str r0, [r7, #12] - 80044ec: 60b9 str r1, [r7, #8] - 80044ee: 607a str r2, [r7, #4] + 8004568: b480 push {r7} + 800456a: b087 sub sp, #28 + 800456c: af00 add r7, sp, #0 + 800456e: 60f8 str r0, [r7, #12] + 8004570: 60b9 str r1, [r7, #8] + 8004572: 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 */ - 80044f0: 68bb ldr r3, [r7, #8] - 80044f2: f003 031f and.w r3, r3, #31 - 80044f6: 2201 movs r2, #1 - 80044f8: fa02 f303 lsl.w r3, r2, r3 - 80044fc: 617b str r3, [r7, #20] + 8004574: 68bb ldr r3, [r7, #8] + 8004576: f003 031f and.w r3, r3, #31 + 800457a: 2201 movs r2, #1 + 800457c: fa02 f303 lsl.w r3, r2, r3 + 8004580: 617b str r3, [r7, #20] /* Reset the CCxE Bit */ TIMx->CCER &= ~tmp; - 80044fe: 68fb ldr r3, [r7, #12] - 8004500: 6a1a ldr r2, [r3, #32] - 8004502: 697b ldr r3, [r7, #20] - 8004504: 43db mvns r3, r3 - 8004506: 401a ands r2, r3 - 8004508: 68fb ldr r3, [r7, #12] - 800450a: 621a str r2, [r3, #32] + 8004582: 68fb ldr r3, [r7, #12] + 8004584: 6a1a ldr r2, [r3, #32] + 8004586: 697b ldr r3, [r7, #20] + 8004588: 43db mvns r3, r3 + 800458a: 401a ands r2, r3 + 800458c: 68fb ldr r3, [r7, #12] + 800458e: 621a str r2, [r3, #32] /* Set or reset the CCxE Bit */ TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ - 800450c: 68fb ldr r3, [r7, #12] - 800450e: 6a1a ldr r2, [r3, #32] - 8004510: 68bb ldr r3, [r7, #8] - 8004512: f003 031f and.w r3, r3, #31 - 8004516: 6879 ldr r1, [r7, #4] - 8004518: fa01 f303 lsl.w r3, r1, r3 - 800451c: 431a orrs r2, r3 - 800451e: 68fb ldr r3, [r7, #12] - 8004520: 621a str r2, [r3, #32] + 8004590: 68fb ldr r3, [r7, #12] + 8004592: 6a1a ldr r2, [r3, #32] + 8004594: 68bb ldr r3, [r7, #8] + 8004596: f003 031f and.w r3, r3, #31 + 800459a: 6879 ldr r1, [r7, #4] + 800459c: fa01 f303 lsl.w r3, r1, r3 + 80045a0: 431a orrs r2, r3 + 80045a2: 68fb ldr r3, [r7, #12] + 80045a4: 621a str r2, [r3, #32] } - 8004522: bf00 nop - 8004524: 371c adds r7, #28 - 8004526: 46bd mov sp, r7 - 8004528: f85d 7b04 ldr.w r7, [sp], #4 - 800452c: 4770 bx lr + 80045a6: bf00 nop + 80045a8: 371c adds r7, #28 + 80045aa: 46bd mov sp, r7 + 80045ac: f85d 7b04 ldr.w r7, [sp], #4 + 80045b0: 4770 bx lr ... -08004530 : +080045b4 : * mode. * @retval HAL status */ HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, TIM_MasterConfigTypeDef *sMasterConfig) { - 8004530: b480 push {r7} - 8004532: b085 sub sp, #20 - 8004534: af00 add r7, sp, #0 - 8004536: 6078 str r0, [r7, #4] - 8004538: 6039 str r1, [r7, #0] + 80045b4: b480 push {r7} + 80045b6: b085 sub sp, #20 + 80045b8: af00 add r7, sp, #0 + 80045ba: 6078 str r0, [r7, #4] + 80045bc: 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); - 800453a: 687b ldr r3, [r7, #4] - 800453c: f893 303c ldrb.w r3, [r3, #60] ; 0x3c - 8004540: 2b01 cmp r3, #1 - 8004542: d101 bne.n 8004548 - 8004544: 2302 movs r3, #2 - 8004546: e045 b.n 80045d4 - 8004548: 687b ldr r3, [r7, #4] - 800454a: 2201 movs r2, #1 - 800454c: f883 203c strb.w r2, [r3, #60] ; 0x3c + 80045be: 687b ldr r3, [r7, #4] + 80045c0: f893 303c ldrb.w r3, [r3, #60] ; 0x3c + 80045c4: 2b01 cmp r3, #1 + 80045c6: d101 bne.n 80045cc + 80045c8: 2302 movs r3, #2 + 80045ca: e045 b.n 8004658 + 80045cc: 687b ldr r3, [r7, #4] + 80045ce: 2201 movs r2, #1 + 80045d0: f883 203c strb.w r2, [r3, #60] ; 0x3c /* Change the handler state */ htim->State = HAL_TIM_STATE_BUSY; - 8004550: 687b ldr r3, [r7, #4] - 8004552: 2202 movs r2, #2 - 8004554: f883 203d strb.w r2, [r3, #61] ; 0x3d + 80045d4: 687b ldr r3, [r7, #4] + 80045d6: 2202 movs r2, #2 + 80045d8: f883 203d strb.w r2, [r3, #61] ; 0x3d /* Get the TIMx CR2 register value */ tmpcr2 = htim->Instance->CR2; - 8004558: 687b ldr r3, [r7, #4] - 800455a: 681b ldr r3, [r3, #0] - 800455c: 685b ldr r3, [r3, #4] - 800455e: 60fb str r3, [r7, #12] + 80045dc: 687b ldr r3, [r7, #4] + 80045de: 681b ldr r3, [r3, #0] + 80045e0: 685b ldr r3, [r3, #4] + 80045e2: 60fb str r3, [r7, #12] /* Get the TIMx SMCR register value */ tmpsmcr = htim->Instance->SMCR; - 8004560: 687b ldr r3, [r7, #4] - 8004562: 681b ldr r3, [r3, #0] - 8004564: 689b ldr r3, [r3, #8] - 8004566: 60bb str r3, [r7, #8] + 80045e4: 687b ldr r3, [r7, #4] + 80045e6: 681b ldr r3, [r3, #0] + 80045e8: 689b ldr r3, [r3, #8] + 80045ea: 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)) - 8004568: 687b ldr r3, [r7, #4] - 800456a: 681b ldr r3, [r3, #0] - 800456c: 4a1c ldr r2, [pc, #112] ; (80045e0 ) - 800456e: 4293 cmp r3, r2 - 8004570: d004 beq.n 800457c - 8004572: 687b ldr r3, [r7, #4] - 8004574: 681b ldr r3, [r3, #0] - 8004576: 4a1b ldr r2, [pc, #108] ; (80045e4 ) - 8004578: 4293 cmp r3, r2 - 800457a: d108 bne.n 800458e + 80045ec: 687b ldr r3, [r7, #4] + 80045ee: 681b ldr r3, [r3, #0] + 80045f0: 4a1c ldr r2, [pc, #112] ; (8004664 ) + 80045f2: 4293 cmp r3, r2 + 80045f4: d004 beq.n 8004600 + 80045f6: 687b ldr r3, [r7, #4] + 80045f8: 681b ldr r3, [r3, #0] + 80045fa: 4a1b ldr r2, [pc, #108] ; (8004668 ) + 80045fc: 4293 cmp r3, r2 + 80045fe: d108 bne.n 8004612 { /* Check the parameters */ assert_param(IS_TIM_TRGO2_SOURCE(sMasterConfig->MasterOutputTrigger2)); /* Clear the MMS2 bits */ tmpcr2 &= ~TIM_CR2_MMS2; - 800457c: 68fb ldr r3, [r7, #12] - 800457e: f423 0370 bic.w r3, r3, #15728640 ; 0xf00000 - 8004582: 60fb str r3, [r7, #12] + 8004600: 68fb ldr r3, [r7, #12] + 8004602: f423 0370 bic.w r3, r3, #15728640 ; 0xf00000 + 8004606: 60fb str r3, [r7, #12] /* Select the TRGO2 source*/ tmpcr2 |= sMasterConfig->MasterOutputTrigger2; - 8004584: 683b ldr r3, [r7, #0] - 8004586: 685b ldr r3, [r3, #4] - 8004588: 68fa ldr r2, [r7, #12] - 800458a: 4313 orrs r3, r2 - 800458c: 60fb str r3, [r7, #12] + 8004608: 683b ldr r3, [r7, #0] + 800460a: 685b ldr r3, [r3, #4] + 800460c: 68fa ldr r2, [r7, #12] + 800460e: 4313 orrs r3, r2 + 8004610: 60fb str r3, [r7, #12] } /* Reset the MMS Bits */ tmpcr2 &= ~TIM_CR2_MMS; - 800458e: 68fb ldr r3, [r7, #12] - 8004590: f023 0370 bic.w r3, r3, #112 ; 0x70 - 8004594: 60fb str r3, [r7, #12] + 8004612: 68fb ldr r3, [r7, #12] + 8004614: f023 0370 bic.w r3, r3, #112 ; 0x70 + 8004618: 60fb str r3, [r7, #12] /* Select the TRGO source */ tmpcr2 |= sMasterConfig->MasterOutputTrigger; - 8004596: 683b ldr r3, [r7, #0] - 8004598: 681b ldr r3, [r3, #0] - 800459a: 68fa ldr r2, [r7, #12] - 800459c: 4313 orrs r3, r2 - 800459e: 60fb str r3, [r7, #12] + 800461a: 683b ldr r3, [r7, #0] + 800461c: 681b ldr r3, [r3, #0] + 800461e: 68fa ldr r2, [r7, #12] + 8004620: 4313 orrs r3, r2 + 8004622: 60fb str r3, [r7, #12] /* Reset the MSM Bit */ tmpsmcr &= ~TIM_SMCR_MSM; - 80045a0: 68bb ldr r3, [r7, #8] - 80045a2: f023 0380 bic.w r3, r3, #128 ; 0x80 - 80045a6: 60bb str r3, [r7, #8] + 8004624: 68bb ldr r3, [r7, #8] + 8004626: f023 0380 bic.w r3, r3, #128 ; 0x80 + 800462a: 60bb str r3, [r7, #8] /* Set master mode */ tmpsmcr |= sMasterConfig->MasterSlaveMode; - 80045a8: 683b ldr r3, [r7, #0] - 80045aa: 689b ldr r3, [r3, #8] - 80045ac: 68ba ldr r2, [r7, #8] - 80045ae: 4313 orrs r3, r2 - 80045b0: 60bb str r3, [r7, #8] + 800462c: 683b ldr r3, [r7, #0] + 800462e: 689b ldr r3, [r3, #8] + 8004630: 68ba ldr r2, [r7, #8] + 8004632: 4313 orrs r3, r2 + 8004634: 60bb str r3, [r7, #8] /* Update TIMx CR2 */ htim->Instance->CR2 = tmpcr2; - 80045b2: 687b ldr r3, [r7, #4] - 80045b4: 681b ldr r3, [r3, #0] - 80045b6: 68fa ldr r2, [r7, #12] - 80045b8: 605a str r2, [r3, #4] + 8004636: 687b ldr r3, [r7, #4] + 8004638: 681b ldr r3, [r3, #0] + 800463a: 68fa ldr r2, [r7, #12] + 800463c: 605a str r2, [r3, #4] /* Update TIMx SMCR */ htim->Instance->SMCR = tmpsmcr; - 80045ba: 687b ldr r3, [r7, #4] - 80045bc: 681b ldr r3, [r3, #0] - 80045be: 68ba ldr r2, [r7, #8] - 80045c0: 609a str r2, [r3, #8] + 800463e: 687b ldr r3, [r7, #4] + 8004640: 681b ldr r3, [r3, #0] + 8004642: 68ba ldr r2, [r7, #8] + 8004644: 609a str r2, [r3, #8] /* Change the htim state */ htim->State = HAL_TIM_STATE_READY; - 80045c2: 687b ldr r3, [r7, #4] - 80045c4: 2201 movs r2, #1 - 80045c6: f883 203d strb.w r2, [r3, #61] ; 0x3d + 8004646: 687b ldr r3, [r7, #4] + 8004648: 2201 movs r2, #1 + 800464a: f883 203d strb.w r2, [r3, #61] ; 0x3d __HAL_UNLOCK(htim); - 80045ca: 687b ldr r3, [r7, #4] - 80045cc: 2200 movs r2, #0 - 80045ce: f883 203c strb.w r2, [r3, #60] ; 0x3c + 800464e: 687b ldr r3, [r7, #4] + 8004650: 2200 movs r2, #0 + 8004652: f883 203c strb.w r2, [r3, #60] ; 0x3c return HAL_OK; - 80045d2: 2300 movs r3, #0 + 8004656: 2300 movs r3, #0 } - 80045d4: 4618 mov r0, r3 - 80045d6: 3714 adds r7, #20 - 80045d8: 46bd mov sp, r7 - 80045da: f85d 7b04 ldr.w r7, [sp], #4 - 80045de: 4770 bx lr - 80045e0: 40010000 .word 0x40010000 - 80045e4: 40010400 .word 0x40010400 - -080045e8 : + 8004658: 4618 mov r0, r3 + 800465a: 3714 adds r7, #20 + 800465c: 46bd mov sp, r7 + 800465e: f85d 7b04 ldr.w r7, [sp], #4 + 8004662: 4770 bx lr + 8004664: 40010000 .word 0x40010000 + 8004668: 40010400 .word 0x40010400 + +0800466c : * @brief Hall commutation changed callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) { - 80045e8: b480 push {r7} - 80045ea: b083 sub sp, #12 - 80045ec: af00 add r7, sp, #0 - 80045ee: 6078 str r0, [r7, #4] + 800466c: b480 push {r7} + 800466e: b083 sub sp, #12 + 8004670: af00 add r7, sp, #0 + 8004672: 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 */ } - 80045f0: bf00 nop - 80045f2: 370c adds r7, #12 - 80045f4: 46bd mov sp, r7 - 80045f6: f85d 7b04 ldr.w r7, [sp], #4 - 80045fa: 4770 bx lr + 8004674: bf00 nop + 8004676: 370c adds r7, #12 + 8004678: 46bd mov sp, r7 + 800467a: f85d 7b04 ldr.w r7, [sp], #4 + 800467e: 4770 bx lr -080045fc : +08004680 : * @brief Hall Break detection callback in non-blocking mode * @param htim TIM handle * @retval None */ __weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) { - 80045fc: b480 push {r7} - 80045fe: b083 sub sp, #12 - 8004600: af00 add r7, sp, #0 - 8004602: 6078 str r0, [r7, #4] + 8004680: b480 push {r7} + 8004682: b083 sub sp, #12 + 8004684: af00 add r7, sp, #0 + 8004686: 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 */ } - 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 + 8004688: bf00 nop + 800468a: 370c adds r7, #12 + 800468c: 46bd mov sp, r7 + 800468e: f85d 7b04 ldr.w r7, [sp], #4 + 8004692: 4770 bx lr -08004610 : +08004694 : * @brief Hall Break2 detection callback in non blocking mode * @param htim: TIM handle * @retval None */ __weak void HAL_TIMEx_Break2Callback(TIM_HandleTypeDef *htim) { - 8004610: b480 push {r7} - 8004612: b083 sub sp, #12 - 8004614: af00 add r7, sp, #0 - 8004616: 6078 str r0, [r7, #4] + 8004694: b480 push {r7} + 8004696: b083 sub sp, #12 + 8004698: af00 add r7, sp, #0 + 800469a: 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 */ } - 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 + 800469c: bf00 nop + 800469e: 370c adds r7, #12 + 80046a0: 46bd mov sp, r7 + 80046a2: f85d 7b04 ldr.w r7, [sp], #4 + 80046a6: 4770 bx lr -08004624 : +080046a8 : * 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) { - 8004624: b580 push {r7, lr} - 8004626: b082 sub sp, #8 - 8004628: af00 add r7, sp, #0 - 800462a: 6078 str r0, [r7, #4] + 80046a8: b580 push {r7, lr} + 80046aa: b082 sub sp, #8 + 80046ac: af00 add r7, sp, #0 + 80046ae: 6078 str r0, [r7, #4] /* Check the UART handle allocation */ if (huart == NULL) - 800462c: 687b ldr r3, [r7, #4] - 800462e: 2b00 cmp r3, #0 - 8004630: d101 bne.n 8004636 + 80046b0: 687b ldr r3, [r7, #4] + 80046b2: 2b00 cmp r3, #0 + 80046b4: d101 bne.n 80046ba { return HAL_ERROR; - 8004632: 2301 movs r3, #1 - 8004634: e040 b.n 80046b8 + 80046b6: 2301 movs r3, #1 + 80046b8: e040 b.n 800473c { /* Check the parameters */ assert_param(IS_UART_INSTANCE(huart->Instance)); } if (huart->gState == HAL_UART_STATE_RESET) - 8004636: 687b ldr r3, [r7, #4] - 8004638: 6f5b ldr r3, [r3, #116] ; 0x74 - 800463a: 2b00 cmp r3, #0 - 800463c: d106 bne.n 800464c + 80046ba: 687b ldr r3, [r7, #4] + 80046bc: 6f5b ldr r3, [r3, #116] ; 0x74 + 80046be: 2b00 cmp r3, #0 + 80046c0: d106 bne.n 80046d0 { /* Allocate lock resource and initialize it */ huart->Lock = HAL_UNLOCKED; - 800463e: 687b ldr r3, [r7, #4] - 8004640: 2200 movs r2, #0 - 8004642: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 80046c2: 687b ldr r3, [r7, #4] + 80046c4: 2200 movs r2, #0 + 80046c6: 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); - 8004646: 6878 ldr r0, [r7, #4] - 8004648: f7fd fa38 bl 8001abc + 80046ca: 6878 ldr r0, [r7, #4] + 80046cc: f7fd fa38 bl 8001b40 #endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ } huart->gState = HAL_UART_STATE_BUSY; - 800464c: 687b ldr r3, [r7, #4] - 800464e: 2224 movs r2, #36 ; 0x24 - 8004650: 675a str r2, [r3, #116] ; 0x74 + 80046d0: 687b ldr r3, [r7, #4] + 80046d2: 2224 movs r2, #36 ; 0x24 + 80046d4: 675a str r2, [r3, #116] ; 0x74 /* Disable the Peripheral */ __HAL_UART_DISABLE(huart); - 8004652: 687b ldr r3, [r7, #4] - 8004654: 681b ldr r3, [r3, #0] - 8004656: 681a ldr r2, [r3, #0] - 8004658: 687b ldr r3, [r7, #4] - 800465a: 681b ldr r3, [r3, #0] - 800465c: f022 0201 bic.w r2, r2, #1 - 8004660: 601a str r2, [r3, #0] + 80046d6: 687b ldr r3, [r7, #4] + 80046d8: 681b ldr r3, [r3, #0] + 80046da: 681a ldr r2, [r3, #0] + 80046dc: 687b ldr r3, [r7, #4] + 80046de: 681b ldr r3, [r3, #0] + 80046e0: f022 0201 bic.w r2, r2, #1 + 80046e4: 601a str r2, [r3, #0] /* Set the UART Communication parameters */ if (UART_SetConfig(huart) == HAL_ERROR) - 8004662: 6878 ldr r0, [r7, #4] - 8004664: f000 fa90 bl 8004b88 - 8004668: 4603 mov r3, r0 - 800466a: 2b01 cmp r3, #1 - 800466c: d101 bne.n 8004672 + 80046e6: 6878 ldr r0, [r7, #4] + 80046e8: f000 fa90 bl 8004c0c + 80046ec: 4603 mov r3, r0 + 80046ee: 2b01 cmp r3, #1 + 80046f0: d101 bne.n 80046f6 { return HAL_ERROR; - 800466e: 2301 movs r3, #1 - 8004670: e022 b.n 80046b8 + 80046f2: 2301 movs r3, #1 + 80046f4: e022 b.n 800473c } if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT) - 8004672: 687b ldr r3, [r7, #4] - 8004674: 6a5b ldr r3, [r3, #36] ; 0x24 - 8004676: 2b00 cmp r3, #0 - 8004678: d002 beq.n 8004680 + 80046f6: 687b ldr r3, [r7, #4] + 80046f8: 6a5b ldr r3, [r3, #36] ; 0x24 + 80046fa: 2b00 cmp r3, #0 + 80046fc: d002 beq.n 8004704 { UART_AdvFeatureConfig(huart); - 800467a: 6878 ldr r0, [r7, #4] - 800467c: f000 fd28 bl 80050d0 + 80046fe: 6878 ldr r0, [r7, #4] + 8004700: f000 fd28 bl 8005154 } /* 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)); - 8004680: 687b ldr r3, [r7, #4] - 8004682: 681b ldr r3, [r3, #0] - 8004684: 685a ldr r2, [r3, #4] - 8004686: 687b ldr r3, [r7, #4] - 8004688: 681b ldr r3, [r3, #0] - 800468a: f422 4290 bic.w r2, r2, #18432 ; 0x4800 - 800468e: 605a str r2, [r3, #4] + 8004704: 687b ldr r3, [r7, #4] + 8004706: 681b ldr r3, [r3, #0] + 8004708: 685a ldr r2, [r3, #4] + 800470a: 687b ldr r3, [r7, #4] + 800470c: 681b ldr r3, [r3, #0] + 800470e: f422 4290 bic.w r2, r2, #18432 ; 0x4800 + 8004712: 605a str r2, [r3, #4] CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - 8004690: 687b ldr r3, [r7, #4] - 8004692: 681b ldr r3, [r3, #0] - 8004694: 689a ldr r2, [r3, #8] - 8004696: 687b ldr r3, [r7, #4] - 8004698: 681b ldr r3, [r3, #0] - 800469a: f022 022a bic.w r2, r2, #42 ; 0x2a - 800469e: 609a str r2, [r3, #8] + 8004714: 687b ldr r3, [r7, #4] + 8004716: 681b ldr r3, [r3, #0] + 8004718: 689a ldr r2, [r3, #8] + 800471a: 687b ldr r3, [r7, #4] + 800471c: 681b ldr r3, [r3, #0] + 800471e: f022 022a bic.w r2, r2, #42 ; 0x2a + 8004722: 609a str r2, [r3, #8] /* Enable the Peripheral */ __HAL_UART_ENABLE(huart); - 80046a0: 687b ldr r3, [r7, #4] - 80046a2: 681b ldr r3, [r3, #0] - 80046a4: 681a ldr r2, [r3, #0] - 80046a6: 687b ldr r3, [r7, #4] - 80046a8: 681b ldr r3, [r3, #0] - 80046aa: f042 0201 orr.w r2, r2, #1 - 80046ae: 601a str r2, [r3, #0] + 8004724: 687b ldr r3, [r7, #4] + 8004726: 681b ldr r3, [r3, #0] + 8004728: 681a ldr r2, [r3, #0] + 800472a: 687b ldr r3, [r7, #4] + 800472c: 681b ldr r3, [r3, #0] + 800472e: f042 0201 orr.w r2, r2, #1 + 8004732: 601a str r2, [r3, #0] /* TEACK and/or REACK to check before moving huart->gState and huart->RxState to Ready */ return (UART_CheckIdleState(huart)); - 80046b0: 6878 ldr r0, [r7, #4] - 80046b2: f000 fdaf bl 8005214 - 80046b6: 4603 mov r3, r0 + 8004734: 6878 ldr r0, [r7, #4] + 8004736: f000 fdaf bl 8005298 + 800473a: 4603 mov r3, r0 } - 80046b8: 4618 mov r0, r3 - 80046ba: 3708 adds r7, #8 - 80046bc: 46bd mov sp, r7 - 80046be: bd80 pop {r7, pc} + 800473c: 4618 mov r0, r3 + 800473e: 3708 adds r7, #8 + 8004740: 46bd mov sp, r7 + 8004742: bd80 pop {r7, pc} -080046c0 : +08004744 : * @param Size Amount of data to be sent. * @param Timeout Timeout duration. * @retval HAL status */ HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) { - 80046c0: b580 push {r7, lr} - 80046c2: b08a sub sp, #40 ; 0x28 - 80046c4: af02 add r7, sp, #8 - 80046c6: 60f8 str r0, [r7, #12] - 80046c8: 60b9 str r1, [r7, #8] - 80046ca: 603b str r3, [r7, #0] - 80046cc: 4613 mov r3, r2 - 80046ce: 80fb strh r3, [r7, #6] + 8004744: b580 push {r7, lr} + 8004746: b08a sub sp, #40 ; 0x28 + 8004748: af02 add r7, sp, #8 + 800474a: 60f8 str r0, [r7, #12] + 800474c: 60b9 str r1, [r7, #8] + 800474e: 603b str r3, [r7, #0] + 8004750: 4613 mov r3, r2 + 8004752: 80fb strh r3, [r7, #6] uint8_t *pdata8bits; uint16_t *pdata16bits; uint32_t tickstart; /* Check that a Tx process is not already ongoing */ if (huart->gState == HAL_UART_STATE_READY) - 80046d0: 68fb ldr r3, [r7, #12] - 80046d2: 6f5b ldr r3, [r3, #116] ; 0x74 - 80046d4: 2b20 cmp r3, #32 - 80046d6: d17f bne.n 80047d8 + 8004754: 68fb ldr r3, [r7, #12] + 8004756: 6f5b ldr r3, [r3, #116] ; 0x74 + 8004758: 2b20 cmp r3, #32 + 800475a: d17f bne.n 800485c { if ((pData == NULL) || (Size == 0U)) - 80046d8: 68bb ldr r3, [r7, #8] - 80046da: 2b00 cmp r3, #0 - 80046dc: d002 beq.n 80046e4 - 80046de: 88fb ldrh r3, [r7, #6] - 80046e0: 2b00 cmp r3, #0 - 80046e2: d101 bne.n 80046e8 + 800475c: 68bb ldr r3, [r7, #8] + 800475e: 2b00 cmp r3, #0 + 8004760: d002 beq.n 8004768 + 8004762: 88fb ldrh r3, [r7, #6] + 8004764: 2b00 cmp r3, #0 + 8004766: d101 bne.n 800476c { return HAL_ERROR; - 80046e4: 2301 movs r3, #1 - 80046e6: e078 b.n 80047da + 8004768: 2301 movs r3, #1 + 800476a: e078 b.n 800485e } /* Process Locked */ __HAL_LOCK(huart); - 80046e8: 68fb ldr r3, [r7, #12] - 80046ea: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 - 80046ee: 2b01 cmp r3, #1 - 80046f0: d101 bne.n 80046f6 - 80046f2: 2302 movs r3, #2 - 80046f4: e071 b.n 80047da - 80046f6: 68fb ldr r3, [r7, #12] - 80046f8: 2201 movs r2, #1 - 80046fa: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 800476c: 68fb ldr r3, [r7, #12] + 800476e: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 + 8004772: 2b01 cmp r3, #1 + 8004774: d101 bne.n 800477a + 8004776: 2302 movs r3, #2 + 8004778: e071 b.n 800485e + 800477a: 68fb ldr r3, [r7, #12] + 800477c: 2201 movs r2, #1 + 800477e: f883 2070 strb.w r2, [r3, #112] ; 0x70 huart->ErrorCode = HAL_UART_ERROR_NONE; - 80046fe: 68fb ldr r3, [r7, #12] - 8004700: 2200 movs r2, #0 - 8004702: 67da str r2, [r3, #124] ; 0x7c + 8004782: 68fb ldr r3, [r7, #12] + 8004784: 2200 movs r2, #0 + 8004786: 67da str r2, [r3, #124] ; 0x7c huart->gState = HAL_UART_STATE_BUSY_TX; - 8004704: 68fb ldr r3, [r7, #12] - 8004706: 2221 movs r2, #33 ; 0x21 - 8004708: 675a str r2, [r3, #116] ; 0x74 + 8004788: 68fb ldr r3, [r7, #12] + 800478a: 2221 movs r2, #33 ; 0x21 + 800478c: 675a str r2, [r3, #116] ; 0x74 /* Init tickstart for timeout managment*/ tickstart = HAL_GetTick(); - 800470a: f7fd fb1f bl 8001d4c - 800470e: 6178 str r0, [r7, #20] + 800478e: f7fd fb1f bl 8001dd0 + 8004792: 6178 str r0, [r7, #20] huart->TxXferSize = Size; - 8004710: 68fb ldr r3, [r7, #12] - 8004712: 88fa ldrh r2, [r7, #6] - 8004714: f8a3 2050 strh.w r2, [r3, #80] ; 0x50 + 8004794: 68fb ldr r3, [r7, #12] + 8004796: 88fa ldrh r2, [r7, #6] + 8004798: f8a3 2050 strh.w r2, [r3, #80] ; 0x50 huart->TxXferCount = Size; - 8004718: 68fb ldr r3, [r7, #12] - 800471a: 88fa ldrh r2, [r7, #6] - 800471c: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 800479c: 68fb ldr r3, [r7, #12] + 800479e: 88fa ldrh r2, [r7, #6] + 80047a0: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - 8004720: 68fb ldr r3, [r7, #12] - 8004722: 689b ldr r3, [r3, #8] - 8004724: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004728: d108 bne.n 800473c - 800472a: 68fb ldr r3, [r7, #12] - 800472c: 691b ldr r3, [r3, #16] - 800472e: 2b00 cmp r3, #0 - 8004730: d104 bne.n 800473c + 80047a4: 68fb ldr r3, [r7, #12] + 80047a6: 689b ldr r3, [r3, #8] + 80047a8: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 80047ac: d108 bne.n 80047c0 + 80047ae: 68fb ldr r3, [r7, #12] + 80047b0: 691b ldr r3, [r3, #16] + 80047b2: 2b00 cmp r3, #0 + 80047b4: d104 bne.n 80047c0 { pdata8bits = NULL; - 8004732: 2300 movs r3, #0 - 8004734: 61fb str r3, [r7, #28] + 80047b6: 2300 movs r3, #0 + 80047b8: 61fb str r3, [r7, #28] pdata16bits = (uint16_t *) pData; - 8004736: 68bb ldr r3, [r7, #8] - 8004738: 61bb str r3, [r7, #24] - 800473a: e003 b.n 8004744 + 80047ba: 68bb ldr r3, [r7, #8] + 80047bc: 61bb str r3, [r7, #24] + 80047be: e003 b.n 80047c8 } else { pdata8bits = pData; - 800473c: 68bb ldr r3, [r7, #8] - 800473e: 61fb str r3, [r7, #28] + 80047c0: 68bb ldr r3, [r7, #8] + 80047c2: 61fb str r3, [r7, #28] pdata16bits = NULL; - 8004740: 2300 movs r3, #0 - 8004742: 61bb str r3, [r7, #24] + 80047c4: 2300 movs r3, #0 + 80047c6: 61bb str r3, [r7, #24] } while (huart->TxXferCount > 0U) - 8004744: e02c b.n 80047a0 + 80047c8: e02c b.n 8004824 { if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - 8004746: 683b ldr r3, [r7, #0] - 8004748: 9300 str r3, [sp, #0] - 800474a: 697b ldr r3, [r7, #20] - 800474c: 2200 movs r2, #0 - 800474e: 2180 movs r1, #128 ; 0x80 - 8004750: 68f8 ldr r0, [r7, #12] - 8004752: f000 fd8e bl 8005272 - 8004756: 4603 mov r3, r0 - 8004758: 2b00 cmp r3, #0 - 800475a: d001 beq.n 8004760 + 80047ca: 683b ldr r3, [r7, #0] + 80047cc: 9300 str r3, [sp, #0] + 80047ce: 697b ldr r3, [r7, #20] + 80047d0: 2200 movs r2, #0 + 80047d2: 2180 movs r1, #128 ; 0x80 + 80047d4: 68f8 ldr r0, [r7, #12] + 80047d6: f000 fd8e bl 80052f6 + 80047da: 4603 mov r3, r0 + 80047dc: 2b00 cmp r3, #0 + 80047de: d001 beq.n 80047e4 { return HAL_TIMEOUT; - 800475c: 2303 movs r3, #3 - 800475e: e03c b.n 80047da + 80047e0: 2303 movs r3, #3 + 80047e2: e03c b.n 800485e } if (pdata8bits == NULL) - 8004760: 69fb ldr r3, [r7, #28] - 8004762: 2b00 cmp r3, #0 - 8004764: d10b bne.n 800477e + 80047e4: 69fb ldr r3, [r7, #28] + 80047e6: 2b00 cmp r3, #0 + 80047e8: d10b bne.n 8004802 { huart->Instance->TDR = (uint16_t)(*pdata16bits & 0x01FFU); - 8004766: 69bb ldr r3, [r7, #24] - 8004768: 881b ldrh r3, [r3, #0] - 800476a: 461a mov r2, r3 - 800476c: 68fb ldr r3, [r7, #12] - 800476e: 681b ldr r3, [r3, #0] - 8004770: f3c2 0208 ubfx r2, r2, #0, #9 - 8004774: 629a str r2, [r3, #40] ; 0x28 + 80047ea: 69bb ldr r3, [r7, #24] + 80047ec: 881b ldrh r3, [r3, #0] + 80047ee: 461a mov r2, r3 + 80047f0: 68fb ldr r3, [r7, #12] + 80047f2: 681b ldr r3, [r3, #0] + 80047f4: f3c2 0208 ubfx r2, r2, #0, #9 + 80047f8: 629a str r2, [r3, #40] ; 0x28 pdata16bits++; - 8004776: 69bb ldr r3, [r7, #24] - 8004778: 3302 adds r3, #2 - 800477a: 61bb str r3, [r7, #24] - 800477c: e007 b.n 800478e + 80047fa: 69bb ldr r3, [r7, #24] + 80047fc: 3302 adds r3, #2 + 80047fe: 61bb str r3, [r7, #24] + 8004800: e007 b.n 8004812 } else { huart->Instance->TDR = (uint8_t)(*pdata8bits & 0xFFU); - 800477e: 69fb ldr r3, [r7, #28] - 8004780: 781a ldrb r2, [r3, #0] - 8004782: 68fb ldr r3, [r7, #12] - 8004784: 681b ldr r3, [r3, #0] - 8004786: 629a str r2, [r3, #40] ; 0x28 + 8004802: 69fb ldr r3, [r7, #28] + 8004804: 781a ldrb r2, [r3, #0] + 8004806: 68fb ldr r3, [r7, #12] + 8004808: 681b ldr r3, [r3, #0] + 800480a: 629a str r2, [r3, #40] ; 0x28 pdata8bits++; - 8004788: 69fb ldr r3, [r7, #28] - 800478a: 3301 adds r3, #1 - 800478c: 61fb str r3, [r7, #28] + 800480c: 69fb ldr r3, [r7, #28] + 800480e: 3301 adds r3, #1 + 8004810: 61fb str r3, [r7, #28] } huart->TxXferCount--; - 800478e: 68fb ldr r3, [r7, #12] - 8004790: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 - 8004794: b29b uxth r3, r3 - 8004796: 3b01 subs r3, #1 - 8004798: b29a uxth r2, r3 - 800479a: 68fb ldr r3, [r7, #12] - 800479c: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 8004812: 68fb ldr r3, [r7, #12] + 8004814: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 + 8004818: b29b uxth r3, r3 + 800481a: 3b01 subs r3, #1 + 800481c: b29a uxth r2, r3 + 800481e: 68fb ldr r3, [r7, #12] + 8004820: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 while (huart->TxXferCount > 0U) - 80047a0: 68fb ldr r3, [r7, #12] - 80047a2: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 - 80047a6: b29b uxth r3, r3 - 80047a8: 2b00 cmp r3, #0 - 80047aa: d1cc bne.n 8004746 + 8004824: 68fb ldr r3, [r7, #12] + 8004826: f8b3 3052 ldrh.w r3, [r3, #82] ; 0x52 + 800482a: b29b uxth r3, r3 + 800482c: 2b00 cmp r3, #0 + 800482e: d1cc bne.n 80047ca } if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - 80047ac: 683b ldr r3, [r7, #0] - 80047ae: 9300 str r3, [sp, #0] - 80047b0: 697b ldr r3, [r7, #20] - 80047b2: 2200 movs r2, #0 - 80047b4: 2140 movs r1, #64 ; 0x40 - 80047b6: 68f8 ldr r0, [r7, #12] - 80047b8: f000 fd5b bl 8005272 - 80047bc: 4603 mov r3, r0 - 80047be: 2b00 cmp r3, #0 - 80047c0: d001 beq.n 80047c6 + 8004830: 683b ldr r3, [r7, #0] + 8004832: 9300 str r3, [sp, #0] + 8004834: 697b ldr r3, [r7, #20] + 8004836: 2200 movs r2, #0 + 8004838: 2140 movs r1, #64 ; 0x40 + 800483a: 68f8 ldr r0, [r7, #12] + 800483c: f000 fd5b bl 80052f6 + 8004840: 4603 mov r3, r0 + 8004842: 2b00 cmp r3, #0 + 8004844: d001 beq.n 800484a { return HAL_TIMEOUT; - 80047c2: 2303 movs r3, #3 - 80047c4: e009 b.n 80047da + 8004846: 2303 movs r3, #3 + 8004848: e009 b.n 800485e } /* At end of Tx process, restore huart->gState to Ready */ huart->gState = HAL_UART_STATE_READY; - 80047c6: 68fb ldr r3, [r7, #12] - 80047c8: 2220 movs r2, #32 - 80047ca: 675a str r2, [r3, #116] ; 0x74 + 800484a: 68fb ldr r3, [r7, #12] + 800484c: 2220 movs r2, #32 + 800484e: 675a str r2, [r3, #116] ; 0x74 /* Process Unlocked */ __HAL_UNLOCK(huart); - 80047cc: 68fb ldr r3, [r7, #12] - 80047ce: 2200 movs r2, #0 - 80047d0: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004850: 68fb ldr r3, [r7, #12] + 8004852: 2200 movs r2, #0 + 8004854: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_OK; - 80047d4: 2300 movs r3, #0 - 80047d6: e000 b.n 80047da + 8004858: 2300 movs r3, #0 + 800485a: e000 b.n 800485e } else { return HAL_BUSY; - 80047d8: 2302 movs r3, #2 + 800485c: 2302 movs r3, #2 } } - 80047da: 4618 mov r0, r3 - 80047dc: 3720 adds r7, #32 - 80047de: 46bd mov sp, r7 - 80047e0: bd80 pop {r7, pc} + 800485e: 4618 mov r0, r3 + 8004860: 3720 adds r7, #32 + 8004862: 46bd mov sp, r7 + 8004864: bd80 pop {r7, pc} ... -080047e4 : +08004868 : * @param pData Pointer to data buffer. * @param Size Amount of data to be received. * @retval HAL status */ HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) { - 80047e4: b480 push {r7} - 80047e6: b085 sub sp, #20 - 80047e8: af00 add r7, sp, #0 - 80047ea: 60f8 str r0, [r7, #12] - 80047ec: 60b9 str r1, [r7, #8] - 80047ee: 4613 mov r3, r2 - 80047f0: 80fb strh r3, [r7, #6] + 8004868: b480 push {r7} + 800486a: b085 sub sp, #20 + 800486c: af00 add r7, sp, #0 + 800486e: 60f8 str r0, [r7, #12] + 8004870: 60b9 str r1, [r7, #8] + 8004872: 4613 mov r3, r2 + 8004874: 80fb strh r3, [r7, #6] /* Check that a Rx process is not already ongoing */ if (huart->RxState == HAL_UART_STATE_READY) - 80047f2: 68fb ldr r3, [r7, #12] - 80047f4: 6f9b ldr r3, [r3, #120] ; 0x78 - 80047f6: 2b20 cmp r3, #32 - 80047f8: f040 808a bne.w 8004910 + 8004876: 68fb ldr r3, [r7, #12] + 8004878: 6f9b ldr r3, [r3, #120] ; 0x78 + 800487a: 2b20 cmp r3, #32 + 800487c: f040 808a bne.w 8004994 { if ((pData == NULL) || (Size == 0U)) - 80047fc: 68bb ldr r3, [r7, #8] - 80047fe: 2b00 cmp r3, #0 - 8004800: d002 beq.n 8004808 - 8004802: 88fb ldrh r3, [r7, #6] - 8004804: 2b00 cmp r3, #0 - 8004806: d101 bne.n 800480c + 8004880: 68bb ldr r3, [r7, #8] + 8004882: 2b00 cmp r3, #0 + 8004884: d002 beq.n 800488c + 8004886: 88fb ldrh r3, [r7, #6] + 8004888: 2b00 cmp r3, #0 + 800488a: d101 bne.n 8004890 { return HAL_ERROR; - 8004808: 2301 movs r3, #1 - 800480a: e082 b.n 8004912 + 800488c: 2301 movs r3, #1 + 800488e: e082 b.n 8004996 } /* Process Locked */ __HAL_LOCK(huart); - 800480c: 68fb ldr r3, [r7, #12] - 800480e: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 - 8004812: 2b01 cmp r3, #1 - 8004814: d101 bne.n 800481a - 8004816: 2302 movs r3, #2 - 8004818: e07b b.n 8004912 - 800481a: 68fb ldr r3, [r7, #12] - 800481c: 2201 movs r2, #1 - 800481e: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004890: 68fb ldr r3, [r7, #12] + 8004892: f893 3070 ldrb.w r3, [r3, #112] ; 0x70 + 8004896: 2b01 cmp r3, #1 + 8004898: d101 bne.n 800489e + 800489a: 2302 movs r3, #2 + 800489c: e07b b.n 8004996 + 800489e: 68fb ldr r3, [r7, #12] + 80048a0: 2201 movs r2, #1 + 80048a2: f883 2070 strb.w r2, [r3, #112] ; 0x70 huart->pRxBuffPtr = pData; - 8004822: 68fb ldr r3, [r7, #12] - 8004824: 68ba ldr r2, [r7, #8] - 8004826: 655a str r2, [r3, #84] ; 0x54 + 80048a6: 68fb ldr r3, [r7, #12] + 80048a8: 68ba ldr r2, [r7, #8] + 80048aa: 655a str r2, [r3, #84] ; 0x54 huart->RxXferSize = Size; - 8004828: 68fb ldr r3, [r7, #12] - 800482a: 88fa ldrh r2, [r7, #6] - 800482c: f8a3 2058 strh.w r2, [r3, #88] ; 0x58 + 80048ac: 68fb ldr r3, [r7, #12] + 80048ae: 88fa ldrh r2, [r7, #6] + 80048b0: f8a3 2058 strh.w r2, [r3, #88] ; 0x58 huart->RxXferCount = Size; - 8004830: 68fb ldr r3, [r7, #12] - 8004832: 88fa ldrh r2, [r7, #6] - 8004834: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 80048b4: 68fb ldr r3, [r7, #12] + 80048b6: 88fa ldrh r2, [r7, #6] + 80048b8: f8a3 205a strh.w r2, [r3, #90] ; 0x5a huart->RxISR = NULL; - 8004838: 68fb ldr r3, [r7, #12] - 800483a: 2200 movs r2, #0 - 800483c: 661a str r2, [r3, #96] ; 0x60 + 80048bc: 68fb ldr r3, [r7, #12] + 80048be: 2200 movs r2, #0 + 80048c0: 661a str r2, [r3, #96] ; 0x60 /* Computation of UART mask to apply to RDR register */ UART_MASK_COMPUTATION(huart); - 800483e: 68fb ldr r3, [r7, #12] - 8004840: 689b ldr r3, [r3, #8] - 8004842: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004846: d10e bne.n 8004866 - 8004848: 68fb ldr r3, [r7, #12] - 800484a: 691b ldr r3, [r3, #16] - 800484c: 2b00 cmp r3, #0 - 800484e: d105 bne.n 800485c - 8004850: 68fb ldr r3, [r7, #12] - 8004852: f240 12ff movw r2, #511 ; 0x1ff - 8004856: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 800485a: e02d b.n 80048b8 - 800485c: 68fb ldr r3, [r7, #12] - 800485e: 22ff movs r2, #255 ; 0xff - 8004860: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 8004864: e028 b.n 80048b8 - 8004866: 68fb ldr r3, [r7, #12] - 8004868: 689b ldr r3, [r3, #8] - 800486a: 2b00 cmp r3, #0 - 800486c: d10d bne.n 800488a - 800486e: 68fb ldr r3, [r7, #12] - 8004870: 691b ldr r3, [r3, #16] - 8004872: 2b00 cmp r3, #0 - 8004874: d104 bne.n 8004880 - 8004876: 68fb ldr r3, [r7, #12] - 8004878: 22ff movs r2, #255 ; 0xff - 800487a: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 800487e: e01b b.n 80048b8 - 8004880: 68fb ldr r3, [r7, #12] - 8004882: 227f movs r2, #127 ; 0x7f - 8004884: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 8004888: e016 b.n 80048b8 - 800488a: 68fb ldr r3, [r7, #12] - 800488c: 689b ldr r3, [r3, #8] - 800488e: f1b3 5f80 cmp.w r3, #268435456 ; 0x10000000 - 8004892: d10d bne.n 80048b0 - 8004894: 68fb ldr r3, [r7, #12] - 8004896: 691b ldr r3, [r3, #16] - 8004898: 2b00 cmp r3, #0 - 800489a: d104 bne.n 80048a6 - 800489c: 68fb ldr r3, [r7, #12] - 800489e: 227f movs r2, #127 ; 0x7f - 80048a0: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80048a4: e008 b.n 80048b8 - 80048a6: 68fb ldr r3, [r7, #12] - 80048a8: 223f movs r2, #63 ; 0x3f - 80048aa: f8a3 205c strh.w r2, [r3, #92] ; 0x5c - 80048ae: e003 b.n 80048b8 - 80048b0: 68fb ldr r3, [r7, #12] - 80048b2: 2200 movs r2, #0 - 80048b4: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80048c2: 68fb ldr r3, [r7, #12] + 80048c4: 689b ldr r3, [r3, #8] + 80048c6: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 80048ca: d10e bne.n 80048ea + 80048cc: 68fb ldr r3, [r7, #12] + 80048ce: 691b ldr r3, [r3, #16] + 80048d0: 2b00 cmp r3, #0 + 80048d2: d105 bne.n 80048e0 + 80048d4: 68fb ldr r3, [r7, #12] + 80048d6: f240 12ff movw r2, #511 ; 0x1ff + 80048da: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80048de: e02d b.n 800493c + 80048e0: 68fb ldr r3, [r7, #12] + 80048e2: 22ff movs r2, #255 ; 0xff + 80048e4: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 80048e8: e028 b.n 800493c + 80048ea: 68fb ldr r3, [r7, #12] + 80048ec: 689b ldr r3, [r3, #8] + 80048ee: 2b00 cmp r3, #0 + 80048f0: d10d bne.n 800490e + 80048f2: 68fb ldr r3, [r7, #12] + 80048f4: 691b ldr r3, [r3, #16] + 80048f6: 2b00 cmp r3, #0 + 80048f8: d104 bne.n 8004904 + 80048fa: 68fb ldr r3, [r7, #12] + 80048fc: 22ff movs r2, #255 ; 0xff + 80048fe: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 8004902: e01b b.n 800493c + 8004904: 68fb ldr r3, [r7, #12] + 8004906: 227f movs r2, #127 ; 0x7f + 8004908: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 800490c: e016 b.n 800493c + 800490e: 68fb ldr r3, [r7, #12] + 8004910: 689b ldr r3, [r3, #8] + 8004912: f1b3 5f80 cmp.w r3, #268435456 ; 0x10000000 + 8004916: d10d bne.n 8004934 + 8004918: 68fb ldr r3, [r7, #12] + 800491a: 691b ldr r3, [r3, #16] + 800491c: 2b00 cmp r3, #0 + 800491e: d104 bne.n 800492a + 8004920: 68fb ldr r3, [r7, #12] + 8004922: 227f movs r2, #127 ; 0x7f + 8004924: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 8004928: e008 b.n 800493c + 800492a: 68fb ldr r3, [r7, #12] + 800492c: 223f movs r2, #63 ; 0x3f + 800492e: f8a3 205c strh.w r2, [r3, #92] ; 0x5c + 8004932: e003 b.n 800493c + 8004934: 68fb ldr r3, [r7, #12] + 8004936: 2200 movs r2, #0 + 8004938: f8a3 205c strh.w r2, [r3, #92] ; 0x5c huart->ErrorCode = HAL_UART_ERROR_NONE; - 80048b8: 68fb ldr r3, [r7, #12] - 80048ba: 2200 movs r2, #0 - 80048bc: 67da str r2, [r3, #124] ; 0x7c + 800493c: 68fb ldr r3, [r7, #12] + 800493e: 2200 movs r2, #0 + 8004940: 67da str r2, [r3, #124] ; 0x7c huart->RxState = HAL_UART_STATE_BUSY_RX; - 80048be: 68fb ldr r3, [r7, #12] - 80048c0: 2222 movs r2, #34 ; 0x22 - 80048c2: 679a str r2, [r3, #120] ; 0x78 + 8004942: 68fb ldr r3, [r7, #12] + 8004944: 2222 movs r2, #34 ; 0x22 + 8004946: 679a str r2, [r3, #120] ; 0x78 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - 80048c4: 68fb ldr r3, [r7, #12] - 80048c6: 681b ldr r3, [r3, #0] - 80048c8: 689a ldr r2, [r3, #8] - 80048ca: 68fb ldr r3, [r7, #12] - 80048cc: 681b ldr r3, [r3, #0] - 80048ce: f042 0201 orr.w r2, r2, #1 - 80048d2: 609a str r2, [r3, #8] + 8004948: 68fb ldr r3, [r7, #12] + 800494a: 681b ldr r3, [r3, #0] + 800494c: 689a ldr r2, [r3, #8] + 800494e: 68fb ldr r3, [r7, #12] + 8004950: 681b ldr r3, [r3, #0] + 8004952: f042 0201 orr.w r2, r2, #1 + 8004956: 609a str r2, [r3, #8] /* Set the Rx ISR function pointer according to the data word length */ if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - 80048d4: 68fb ldr r3, [r7, #12] - 80048d6: 689b ldr r3, [r3, #8] - 80048d8: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 80048dc: d107 bne.n 80048ee - 80048de: 68fb ldr r3, [r7, #12] - 80048e0: 691b ldr r3, [r3, #16] - 80048e2: 2b00 cmp r3, #0 - 80048e4: d103 bne.n 80048ee + 8004958: 68fb ldr r3, [r7, #12] + 800495a: 689b ldr r3, [r3, #8] + 800495c: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004960: d107 bne.n 8004972 + 8004962: 68fb ldr r3, [r7, #12] + 8004964: 691b ldr r3, [r3, #16] + 8004966: 2b00 cmp r3, #0 + 8004968: d103 bne.n 8004972 { huart->RxISR = UART_RxISR_16BIT; - 80048e6: 68fb ldr r3, [r7, #12] - 80048e8: 4a0d ldr r2, [pc, #52] ; (8004920 ) - 80048ea: 661a str r2, [r3, #96] ; 0x60 - 80048ec: e002 b.n 80048f4 + 800496a: 68fb ldr r3, [r7, #12] + 800496c: 4a0d ldr r2, [pc, #52] ; (80049a4 ) + 800496e: 661a str r2, [r3, #96] ; 0x60 + 8004970: e002 b.n 8004978 } else { huart->RxISR = UART_RxISR_8BIT; - 80048ee: 68fb ldr r3, [r7, #12] - 80048f0: 4a0c ldr r2, [pc, #48] ; (8004924 ) - 80048f2: 661a str r2, [r3, #96] ; 0x60 + 8004972: 68fb ldr r3, [r7, #12] + 8004974: 4a0c ldr r2, [pc, #48] ; (80049a8 ) + 8004976: 661a str r2, [r3, #96] ; 0x60 } /* Process Unlocked */ __HAL_UNLOCK(huart); - 80048f4: 68fb ldr r3, [r7, #12] - 80048f6: 2200 movs r2, #0 - 80048f8: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8004978: 68fb ldr r3, [r7, #12] + 800497a: 2200 movs r2, #0 + 800497c: f883 2070 strb.w r2, [r3, #112] ; 0x70 /* Enable the UART Parity Error interrupt and Data Register Not Empty interrupt */ SET_BIT(huart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); - 80048fc: 68fb ldr r3, [r7, #12] - 80048fe: 681b ldr r3, [r3, #0] - 8004900: 681a ldr r2, [r3, #0] - 8004902: 68fb ldr r3, [r7, #12] - 8004904: 681b ldr r3, [r3, #0] - 8004906: f442 7290 orr.w r2, r2, #288 ; 0x120 - 800490a: 601a str r2, [r3, #0] + 8004980: 68fb ldr r3, [r7, #12] + 8004982: 681b ldr r3, [r3, #0] + 8004984: 681a ldr r2, [r3, #0] + 8004986: 68fb ldr r3, [r7, #12] + 8004988: 681b ldr r3, [r3, #0] + 800498a: f442 7290 orr.w r2, r2, #288 ; 0x120 + 800498e: 601a str r2, [r3, #0] return HAL_OK; - 800490c: 2300 movs r3, #0 - 800490e: e000 b.n 8004912 + 8004990: 2300 movs r3, #0 + 8004992: e000 b.n 8004996 } else { return HAL_BUSY; - 8004910: 2302 movs r3, #2 + 8004994: 2302 movs r3, #2 } } - 8004912: 4618 mov r0, r3 - 8004914: 3714 adds r7, #20 - 8004916: 46bd mov sp, r7 - 8004918: f85d 7b04 ldr.w r7, [sp], #4 - 800491c: 4770 bx lr - 800491e: bf00 nop - 8004920: 08005447 .word 0x08005447 - 8004924: 080053a1 .word 0x080053a1 - -08004928 : + 8004996: 4618 mov r0, r3 + 8004998: 3714 adds r7, #20 + 800499a: 46bd mov sp, r7 + 800499c: f85d 7b04 ldr.w r7, [sp], #4 + 80049a0: 4770 bx lr + 80049a2: bf00 nop + 80049a4: 080054cb .word 0x080054cb + 80049a8: 08005425 .word 0x08005425 + +080049ac : * @brief Handle UART interrupt request. * @param huart UART handle. * @retval None */ void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) { - 8004928: b580 push {r7, lr} - 800492a: b088 sub sp, #32 - 800492c: af00 add r7, sp, #0 - 800492e: 6078 str r0, [r7, #4] + 80049ac: b580 push {r7, lr} + 80049ae: b088 sub sp, #32 + 80049b0: af00 add r7, sp, #0 + 80049b2: 6078 str r0, [r7, #4] uint32_t isrflags = READ_REG(huart->Instance->ISR); - 8004930: 687b ldr r3, [r7, #4] - 8004932: 681b ldr r3, [r3, #0] - 8004934: 69db ldr r3, [r3, #28] - 8004936: 61fb str r3, [r7, #28] + 80049b4: 687b ldr r3, [r7, #4] + 80049b6: 681b ldr r3, [r3, #0] + 80049b8: 69db ldr r3, [r3, #28] + 80049ba: 61fb str r3, [r7, #28] uint32_t cr1its = READ_REG(huart->Instance->CR1); - 8004938: 687b ldr r3, [r7, #4] - 800493a: 681b ldr r3, [r3, #0] - 800493c: 681b ldr r3, [r3, #0] - 800493e: 61bb str r3, [r7, #24] + 80049bc: 687b ldr r3, [r7, #4] + 80049be: 681b ldr r3, [r3, #0] + 80049c0: 681b ldr r3, [r3, #0] + 80049c2: 61bb str r3, [r7, #24] uint32_t cr3its = READ_REG(huart->Instance->CR3); - 8004940: 687b ldr r3, [r7, #4] - 8004942: 681b ldr r3, [r3, #0] - 8004944: 689b ldr r3, [r3, #8] - 8004946: 617b str r3, [r7, #20] + 80049c4: 687b ldr r3, [r7, #4] + 80049c6: 681b ldr r3, [r3, #0] + 80049c8: 689b ldr r3, [r3, #8] + 80049ca: 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)); - 8004948: 69fb ldr r3, [r7, #28] - 800494a: f003 030f and.w r3, r3, #15 - 800494e: 613b str r3, [r7, #16] + 80049cc: 69fb ldr r3, [r7, #28] + 80049ce: f003 030f and.w r3, r3, #15 + 80049d2: 613b str r3, [r7, #16] if (errorflags == 0U) - 8004950: 693b ldr r3, [r7, #16] - 8004952: 2b00 cmp r3, #0 - 8004954: d113 bne.n 800497e + 80049d4: 693b ldr r3, [r7, #16] + 80049d6: 2b00 cmp r3, #0 + 80049d8: d113 bne.n 8004a02 { /* UART in mode Receiver ---------------------------------------------------*/ if (((isrflags & USART_ISR_RXNE) != 0U) - 8004956: 69fb ldr r3, [r7, #28] - 8004958: f003 0320 and.w r3, r3, #32 - 800495c: 2b00 cmp r3, #0 - 800495e: d00e beq.n 800497e + 80049da: 69fb ldr r3, [r7, #28] + 80049dc: f003 0320 and.w r3, r3, #32 + 80049e0: 2b00 cmp r3, #0 + 80049e2: d00e beq.n 8004a02 && ((cr1its & USART_CR1_RXNEIE) != 0U)) - 8004960: 69bb ldr r3, [r7, #24] - 8004962: f003 0320 and.w r3, r3, #32 - 8004966: 2b00 cmp r3, #0 - 8004968: d009 beq.n 800497e + 80049e4: 69bb ldr r3, [r7, #24] + 80049e6: f003 0320 and.w r3, r3, #32 + 80049ea: 2b00 cmp r3, #0 + 80049ec: d009 beq.n 8004a02 { if (huart->RxISR != NULL) - 800496a: 687b ldr r3, [r7, #4] - 800496c: 6e1b ldr r3, [r3, #96] ; 0x60 - 800496e: 2b00 cmp r3, #0 - 8004970: f000 80eb beq.w 8004b4a + 80049ee: 687b ldr r3, [r7, #4] + 80049f0: 6e1b ldr r3, [r3, #96] ; 0x60 + 80049f2: 2b00 cmp r3, #0 + 80049f4: f000 80eb beq.w 8004bce { huart->RxISR(huart); - 8004974: 687b ldr r3, [r7, #4] - 8004976: 6e1b ldr r3, [r3, #96] ; 0x60 - 8004978: 6878 ldr r0, [r7, #4] - 800497a: 4798 blx r3 + 80049f8: 687b ldr r3, [r7, #4] + 80049fa: 6e1b ldr r3, [r3, #96] ; 0x60 + 80049fc: 6878 ldr r0, [r7, #4] + 80049fe: 4798 blx r3 } return; - 800497c: e0e5 b.n 8004b4a + 8004a00: e0e5 b.n 8004bce } } /* If some errors occur */ if ((errorflags != 0U) - 800497e: 693b ldr r3, [r7, #16] - 8004980: 2b00 cmp r3, #0 - 8004982: f000 80c0 beq.w 8004b06 + 8004a02: 693b ldr r3, [r7, #16] + 8004a04: 2b00 cmp r3, #0 + 8004a06: f000 80c0 beq.w 8004b8a && (((cr3its & USART_CR3_EIE) != 0U) - 8004986: 697b ldr r3, [r7, #20] - 8004988: f003 0301 and.w r3, r3, #1 - 800498c: 2b00 cmp r3, #0 - 800498e: d105 bne.n 800499c + 8004a0a: 697b ldr r3, [r7, #20] + 8004a0c: f003 0301 and.w r3, r3, #1 + 8004a10: 2b00 cmp r3, #0 + 8004a12: d105 bne.n 8004a20 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != 0U))) - 8004990: 69bb ldr r3, [r7, #24] - 8004992: f403 7390 and.w r3, r3, #288 ; 0x120 - 8004996: 2b00 cmp r3, #0 - 8004998: f000 80b5 beq.w 8004b06 + 8004a14: 69bb ldr r3, [r7, #24] + 8004a16: f403 7390 and.w r3, r3, #288 ; 0x120 + 8004a1a: 2b00 cmp r3, #0 + 8004a1c: f000 80b5 beq.w 8004b8a { /* UART parity error interrupt occurred -------------------------------------*/ if (((isrflags & USART_ISR_PE) != 0U) && ((cr1its & USART_CR1_PEIE) != 0U)) - 800499c: 69fb ldr r3, [r7, #28] - 800499e: f003 0301 and.w r3, r3, #1 - 80049a2: 2b00 cmp r3, #0 - 80049a4: d00e beq.n 80049c4 - 80049a6: 69bb ldr r3, [r7, #24] - 80049a8: f403 7380 and.w r3, r3, #256 ; 0x100 - 80049ac: 2b00 cmp r3, #0 - 80049ae: d009 beq.n 80049c4 + 8004a20: 69fb ldr r3, [r7, #28] + 8004a22: f003 0301 and.w r3, r3, #1 + 8004a26: 2b00 cmp r3, #0 + 8004a28: d00e beq.n 8004a48 + 8004a2a: 69bb ldr r3, [r7, #24] + 8004a2c: f403 7380 and.w r3, r3, #256 ; 0x100 + 8004a30: 2b00 cmp r3, #0 + 8004a32: d009 beq.n 8004a48 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_PEF); - 80049b0: 687b ldr r3, [r7, #4] - 80049b2: 681b ldr r3, [r3, #0] - 80049b4: 2201 movs r2, #1 - 80049b6: 621a str r2, [r3, #32] + 8004a34: 687b ldr r3, [r7, #4] + 8004a36: 681b ldr r3, [r3, #0] + 8004a38: 2201 movs r2, #1 + 8004a3a: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_PE; - 80049b8: 687b ldr r3, [r7, #4] - 80049ba: 6fdb ldr r3, [r3, #124] ; 0x7c - 80049bc: f043 0201 orr.w r2, r3, #1 - 80049c0: 687b ldr r3, [r7, #4] - 80049c2: 67da str r2, [r3, #124] ; 0x7c + 8004a3c: 687b ldr r3, [r7, #4] + 8004a3e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004a40: f043 0201 orr.w r2, r3, #1 + 8004a44: 687b ldr r3, [r7, #4] + 8004a46: 67da str r2, [r3, #124] ; 0x7c } /* UART frame error interrupt occurred --------------------------------------*/ if (((isrflags & USART_ISR_FE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) - 80049c4: 69fb ldr r3, [r7, #28] - 80049c6: f003 0302 and.w r3, r3, #2 - 80049ca: 2b00 cmp r3, #0 - 80049cc: d00e beq.n 80049ec - 80049ce: 697b ldr r3, [r7, #20] - 80049d0: f003 0301 and.w r3, r3, #1 - 80049d4: 2b00 cmp r3, #0 - 80049d6: d009 beq.n 80049ec + 8004a48: 69fb ldr r3, [r7, #28] + 8004a4a: f003 0302 and.w r3, r3, #2 + 8004a4e: 2b00 cmp r3, #0 + 8004a50: d00e beq.n 8004a70 + 8004a52: 697b ldr r3, [r7, #20] + 8004a54: f003 0301 and.w r3, r3, #1 + 8004a58: 2b00 cmp r3, #0 + 8004a5a: d009 beq.n 8004a70 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_FEF); - 80049d8: 687b ldr r3, [r7, #4] - 80049da: 681b ldr r3, [r3, #0] - 80049dc: 2202 movs r2, #2 - 80049de: 621a str r2, [r3, #32] + 8004a5c: 687b ldr r3, [r7, #4] + 8004a5e: 681b ldr r3, [r3, #0] + 8004a60: 2202 movs r2, #2 + 8004a62: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_FE; - 80049e0: 687b ldr r3, [r7, #4] - 80049e2: 6fdb ldr r3, [r3, #124] ; 0x7c - 80049e4: f043 0204 orr.w r2, r3, #4 - 80049e8: 687b ldr r3, [r7, #4] - 80049ea: 67da str r2, [r3, #124] ; 0x7c + 8004a64: 687b ldr r3, [r7, #4] + 8004a66: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004a68: f043 0204 orr.w r2, r3, #4 + 8004a6c: 687b ldr r3, [r7, #4] + 8004a6e: 67da str r2, [r3, #124] ; 0x7c } /* UART noise error interrupt occurred --------------------------------------*/ if (((isrflags & USART_ISR_NE) != 0U) && ((cr3its & USART_CR3_EIE) != 0U)) - 80049ec: 69fb ldr r3, [r7, #28] - 80049ee: f003 0304 and.w r3, r3, #4 - 80049f2: 2b00 cmp r3, #0 - 80049f4: d00e beq.n 8004a14 - 80049f6: 697b ldr r3, [r7, #20] - 80049f8: f003 0301 and.w r3, r3, #1 - 80049fc: 2b00 cmp r3, #0 - 80049fe: d009 beq.n 8004a14 + 8004a70: 69fb ldr r3, [r7, #28] + 8004a72: f003 0304 and.w r3, r3, #4 + 8004a76: 2b00 cmp r3, #0 + 8004a78: d00e beq.n 8004a98 + 8004a7a: 697b ldr r3, [r7, #20] + 8004a7c: f003 0301 and.w r3, r3, #1 + 8004a80: 2b00 cmp r3, #0 + 8004a82: d009 beq.n 8004a98 { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_NEF); - 8004a00: 687b ldr r3, [r7, #4] - 8004a02: 681b ldr r3, [r3, #0] - 8004a04: 2204 movs r2, #4 - 8004a06: 621a str r2, [r3, #32] + 8004a84: 687b ldr r3, [r7, #4] + 8004a86: 681b ldr r3, [r3, #0] + 8004a88: 2204 movs r2, #4 + 8004a8a: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_NE; - 8004a08: 687b ldr r3, [r7, #4] - 8004a0a: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004a0c: f043 0202 orr.w r2, r3, #2 - 8004a10: 687b ldr r3, [r7, #4] - 8004a12: 67da str r2, [r3, #124] ; 0x7c + 8004a8c: 687b ldr r3, [r7, #4] + 8004a8e: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004a90: f043 0202 orr.w r2, r3, #2 + 8004a94: 687b ldr r3, [r7, #4] + 8004a96: 67da str r2, [r3, #124] ; 0x7c } /* UART Over-Run interrupt occurred -----------------------------------------*/ if (((isrflags & USART_ISR_ORE) != 0U) - 8004a14: 69fb ldr r3, [r7, #28] - 8004a16: f003 0308 and.w r3, r3, #8 - 8004a1a: 2b00 cmp r3, #0 - 8004a1c: d013 beq.n 8004a46 + 8004a98: 69fb ldr r3, [r7, #28] + 8004a9a: f003 0308 and.w r3, r3, #8 + 8004a9e: 2b00 cmp r3, #0 + 8004aa0: d013 beq.n 8004aca && (((cr1its & USART_CR1_RXNEIE) != 0U) || - 8004a1e: 69bb ldr r3, [r7, #24] - 8004a20: f003 0320 and.w r3, r3, #32 - 8004a24: 2b00 cmp r3, #0 - 8004a26: d104 bne.n 8004a32 + 8004aa2: 69bb ldr r3, [r7, #24] + 8004aa4: f003 0320 and.w r3, r3, #32 + 8004aa8: 2b00 cmp r3, #0 + 8004aaa: d104 bne.n 8004ab6 ((cr3its & USART_CR3_EIE) != 0U))) - 8004a28: 697b ldr r3, [r7, #20] - 8004a2a: f003 0301 and.w r3, r3, #1 + 8004aac: 697b ldr r3, [r7, #20] + 8004aae: f003 0301 and.w r3, r3, #1 && (((cr1its & USART_CR1_RXNEIE) != 0U) || - 8004a2e: 2b00 cmp r3, #0 - 8004a30: d009 beq.n 8004a46 + 8004ab2: 2b00 cmp r3, #0 + 8004ab4: d009 beq.n 8004aca { __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_OREF); - 8004a32: 687b ldr r3, [r7, #4] - 8004a34: 681b ldr r3, [r3, #0] - 8004a36: 2208 movs r2, #8 - 8004a38: 621a str r2, [r3, #32] + 8004ab6: 687b ldr r3, [r7, #4] + 8004ab8: 681b ldr r3, [r3, #0] + 8004aba: 2208 movs r2, #8 + 8004abc: 621a str r2, [r3, #32] huart->ErrorCode |= HAL_UART_ERROR_ORE; - 8004a3a: 687b ldr r3, [r7, #4] - 8004a3c: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004a3e: f043 0208 orr.w r2, r3, #8 - 8004a42: 687b ldr r3, [r7, #4] - 8004a44: 67da str r2, [r3, #124] ; 0x7c + 8004abe: 687b ldr r3, [r7, #4] + 8004ac0: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004ac2: f043 0208 orr.w r2, r3, #8 + 8004ac6: 687b ldr r3, [r7, #4] + 8004ac8: 67da str r2, [r3, #124] ; 0x7c } /* Call UART Error Call back function if need be --------------------------*/ if (huart->ErrorCode != HAL_UART_ERROR_NONE) - 8004a46: 687b ldr r3, [r7, #4] - 8004a48: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004a4a: 2b00 cmp r3, #0 - 8004a4c: d07f beq.n 8004b4e + 8004aca: 687b ldr r3, [r7, #4] + 8004acc: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004ace: 2b00 cmp r3, #0 + 8004ad0: d07f beq.n 8004bd2 { /* UART in mode Receiver ---------------------------------------------------*/ if (((isrflags & USART_ISR_RXNE) != 0U) - 8004a4e: 69fb ldr r3, [r7, #28] - 8004a50: f003 0320 and.w r3, r3, #32 - 8004a54: 2b00 cmp r3, #0 - 8004a56: d00c beq.n 8004a72 + 8004ad2: 69fb ldr r3, [r7, #28] + 8004ad4: f003 0320 and.w r3, r3, #32 + 8004ad8: 2b00 cmp r3, #0 + 8004ada: d00c beq.n 8004af6 && ((cr1its & USART_CR1_RXNEIE) != 0U)) - 8004a58: 69bb ldr r3, [r7, #24] - 8004a5a: f003 0320 and.w r3, r3, #32 - 8004a5e: 2b00 cmp r3, #0 - 8004a60: d007 beq.n 8004a72 + 8004adc: 69bb ldr r3, [r7, #24] + 8004ade: f003 0320 and.w r3, r3, #32 + 8004ae2: 2b00 cmp r3, #0 + 8004ae4: d007 beq.n 8004af6 { if (huart->RxISR != NULL) - 8004a62: 687b ldr r3, [r7, #4] - 8004a64: 6e1b ldr r3, [r3, #96] ; 0x60 - 8004a66: 2b00 cmp r3, #0 - 8004a68: d003 beq.n 8004a72 + 8004ae6: 687b ldr r3, [r7, #4] + 8004ae8: 6e1b ldr r3, [r3, #96] ; 0x60 + 8004aea: 2b00 cmp r3, #0 + 8004aec: d003 beq.n 8004af6 { huart->RxISR(huart); - 8004a6a: 687b ldr r3, [r7, #4] - 8004a6c: 6e1b ldr r3, [r3, #96] ; 0x60 - 8004a6e: 6878 ldr r0, [r7, #4] - 8004a70: 4798 blx r3 + 8004aee: 687b ldr r3, [r7, #4] + 8004af0: 6e1b ldr r3, [r3, #96] ; 0x60 + 8004af2: 6878 ldr r0, [r7, #4] + 8004af4: 4798 blx r3 } } /* If Overrun error occurs, or if any error occurs in DMA mode reception, consider error as blocking */ errorcode = huart->ErrorCode; - 8004a72: 687b ldr r3, [r7, #4] - 8004a74: 6fdb ldr r3, [r3, #124] ; 0x7c - 8004a76: 60fb str r3, [r7, #12] + 8004af6: 687b ldr r3, [r7, #4] + 8004af8: 6fdb ldr r3, [r3, #124] ; 0x7c + 8004afa: 60fb str r3, [r7, #12] if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || - 8004a78: 687b ldr r3, [r7, #4] - 8004a7a: 681b ldr r3, [r3, #0] - 8004a7c: 689b ldr r3, [r3, #8] - 8004a7e: f003 0340 and.w r3, r3, #64 ; 0x40 - 8004a82: 2b40 cmp r3, #64 ; 0x40 - 8004a84: d004 beq.n 8004a90 + 8004afc: 687b ldr r3, [r7, #4] + 8004afe: 681b ldr r3, [r3, #0] + 8004b00: 689b ldr r3, [r3, #8] + 8004b02: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004b06: 2b40 cmp r3, #64 ; 0x40 + 8004b08: d004 beq.n 8004b14 ((errorcode & HAL_UART_ERROR_ORE) != 0U)) - 8004a86: 68fb ldr r3, [r7, #12] - 8004a88: f003 0308 and.w r3, r3, #8 + 8004b0a: 68fb ldr r3, [r7, #12] + 8004b0c: f003 0308 and.w r3, r3, #8 if ((HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) || - 8004a8c: 2b00 cmp r3, #0 - 8004a8e: d031 beq.n 8004af4 + 8004b10: 2b00 cmp r3, #0 + 8004b12: d031 beq.n 8004b78 { /* 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); - 8004a90: 6878 ldr r0, [r7, #4] - 8004a92: f000 fc36 bl 8005302 + 8004b14: 6878 ldr r0, [r7, #4] + 8004b16: f000 fc36 bl 8005386 /* Disable the UART DMA Rx request if enabled */ if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004a96: 687b ldr r3, [r7, #4] - 8004a98: 681b ldr r3, [r3, #0] - 8004a9a: 689b ldr r3, [r3, #8] - 8004a9c: f003 0340 and.w r3, r3, #64 ; 0x40 - 8004aa0: 2b40 cmp r3, #64 ; 0x40 - 8004aa2: d123 bne.n 8004aec + 8004b1a: 687b ldr r3, [r7, #4] + 8004b1c: 681b ldr r3, [r3, #0] + 8004b1e: 689b ldr r3, [r3, #8] + 8004b20: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004b24: 2b40 cmp r3, #64 ; 0x40 + 8004b26: d123 bne.n 8004b70 { CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - 8004aa4: 687b ldr r3, [r7, #4] - 8004aa6: 681b ldr r3, [r3, #0] - 8004aa8: 689a ldr r2, [r3, #8] - 8004aaa: 687b ldr r3, [r7, #4] - 8004aac: 681b ldr r3, [r3, #0] - 8004aae: f022 0240 bic.w r2, r2, #64 ; 0x40 - 8004ab2: 609a str r2, [r3, #8] + 8004b28: 687b ldr r3, [r7, #4] + 8004b2a: 681b ldr r3, [r3, #0] + 8004b2c: 689a ldr r2, [r3, #8] + 8004b2e: 687b ldr r3, [r7, #4] + 8004b30: 681b ldr r3, [r3, #0] + 8004b32: f022 0240 bic.w r2, r2, #64 ; 0x40 + 8004b36: 609a str r2, [r3, #8] /* Abort the UART DMA Rx channel */ if (huart->hdmarx != NULL) - 8004ab4: 687b ldr r3, [r7, #4] - 8004ab6: 6edb ldr r3, [r3, #108] ; 0x6c - 8004ab8: 2b00 cmp r3, #0 - 8004aba: d013 beq.n 8004ae4 + 8004b38: 687b ldr r3, [r7, #4] + 8004b3a: 6edb ldr r3, [r3, #108] ; 0x6c + 8004b3c: 2b00 cmp r3, #0 + 8004b3e: d013 beq.n 8004b68 { /* Set the UART DMA Abort callback : will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; - 8004abc: 687b ldr r3, [r7, #4] - 8004abe: 6edb ldr r3, [r3, #108] ; 0x6c - 8004ac0: 4a26 ldr r2, [pc, #152] ; (8004b5c ) - 8004ac2: 651a str r2, [r3, #80] ; 0x50 + 8004b40: 687b ldr r3, [r7, #4] + 8004b42: 6edb ldr r3, [r3, #108] ; 0x6c + 8004b44: 4a26 ldr r2, [pc, #152] ; (8004be0 ) + 8004b46: 651a str r2, [r3, #80] ; 0x50 /* Abort DMA RX */ if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - 8004ac4: 687b ldr r3, [r7, #4] - 8004ac6: 6edb ldr r3, [r3, #108] ; 0x6c - 8004ac8: 4618 mov r0, r3 - 8004aca: f7fd fa5c bl 8001f86 - 8004ace: 4603 mov r3, r0 - 8004ad0: 2b00 cmp r3, #0 - 8004ad2: d016 beq.n 8004b02 + 8004b48: 687b ldr r3, [r7, #4] + 8004b4a: 6edb ldr r3, [r3, #108] ; 0x6c + 8004b4c: 4618 mov r0, r3 + 8004b4e: f7fd fa5c bl 800200a + 8004b52: 4603 mov r3, r0 + 8004b54: 2b00 cmp r3, #0 + 8004b56: d016 beq.n 8004b86 { /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ huart->hdmarx->XferAbortCallback(huart->hdmarx); - 8004ad4: 687b ldr r3, [r7, #4] - 8004ad6: 6edb ldr r3, [r3, #108] ; 0x6c - 8004ad8: 6d1b ldr r3, [r3, #80] ; 0x50 - 8004ada: 687a ldr r2, [r7, #4] - 8004adc: 6ed2 ldr r2, [r2, #108] ; 0x6c - 8004ade: 4610 mov r0, r2 - 8004ae0: 4798 blx r3 + 8004b58: 687b ldr r3, [r7, #4] + 8004b5a: 6edb ldr r3, [r3, #108] ; 0x6c + 8004b5c: 6d1b ldr r3, [r3, #80] ; 0x50 + 8004b5e: 687a ldr r2, [r7, #4] + 8004b60: 6ed2 ldr r2, [r2, #108] ; 0x6c + 8004b62: 4610 mov r0, r2 + 8004b64: 4798 blx r3 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004ae2: e00e b.n 8004b02 + 8004b66: e00e b.n 8004b86 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004ae4: 6878 ldr r0, [r7, #4] - 8004ae6: f000 f845 bl 8004b74 + 8004b68: 6878 ldr r0, [r7, #4] + 8004b6a: f000 f845 bl 8004bf8 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004aea: e00a b.n 8004b02 + 8004b6e: e00a b.n 8004b86 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004aec: 6878 ldr r0, [r7, #4] - 8004aee: f000 f841 bl 8004b74 + 8004b70: 6878 ldr r0, [r7, #4] + 8004b72: f000 f841 bl 8004bf8 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004af2: e006 b.n 8004b02 + 8004b76: e006 b.n 8004b86 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered error callback*/ huart->ErrorCallback(huart); #else /*Call legacy weak error callback*/ HAL_UART_ErrorCallback(huart); - 8004af4: 6878 ldr r0, [r7, #4] - 8004af6: f000 f83d bl 8004b74 + 8004b78: 6878 ldr r0, [r7, #4] + 8004b7a: f000 f83d bl 8004bf8 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ huart->ErrorCode = HAL_UART_ERROR_NONE; - 8004afa: 687b ldr r3, [r7, #4] - 8004afc: 2200 movs r2, #0 - 8004afe: 67da str r2, [r3, #124] ; 0x7c + 8004b7e: 687b ldr r3, [r7, #4] + 8004b80: 2200 movs r2, #0 + 8004b82: 67da str r2, [r3, #124] ; 0x7c } } return; - 8004b00: e025 b.n 8004b4e + 8004b84: e025 b.n 8004bd2 if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - 8004b02: bf00 nop + 8004b86: bf00 nop return; - 8004b04: e023 b.n 8004b4e + 8004b88: e023 b.n 8004bd2 } /* End if some error occurs */ /* UART in mode Transmitter ------------------------------------------------*/ if (((isrflags & USART_ISR_TXE) != 0U) - 8004b06: 69fb ldr r3, [r7, #28] - 8004b08: f003 0380 and.w r3, r3, #128 ; 0x80 - 8004b0c: 2b00 cmp r3, #0 - 8004b0e: d00d beq.n 8004b2c + 8004b8a: 69fb ldr r3, [r7, #28] + 8004b8c: f003 0380 and.w r3, r3, #128 ; 0x80 + 8004b90: 2b00 cmp r3, #0 + 8004b92: d00d beq.n 8004bb0 && ((cr1its & USART_CR1_TXEIE) != 0U)) - 8004b10: 69bb ldr r3, [r7, #24] - 8004b12: f003 0380 and.w r3, r3, #128 ; 0x80 - 8004b16: 2b00 cmp r3, #0 - 8004b18: d008 beq.n 8004b2c + 8004b94: 69bb ldr r3, [r7, #24] + 8004b96: f003 0380 and.w r3, r3, #128 ; 0x80 + 8004b9a: 2b00 cmp r3, #0 + 8004b9c: d008 beq.n 8004bb0 { if (huart->TxISR != NULL) - 8004b1a: 687b ldr r3, [r7, #4] - 8004b1c: 6e5b ldr r3, [r3, #100] ; 0x64 - 8004b1e: 2b00 cmp r3, #0 - 8004b20: d017 beq.n 8004b52 + 8004b9e: 687b ldr r3, [r7, #4] + 8004ba0: 6e5b ldr r3, [r3, #100] ; 0x64 + 8004ba2: 2b00 cmp r3, #0 + 8004ba4: d017 beq.n 8004bd6 { huart->TxISR(huart); - 8004b22: 687b ldr r3, [r7, #4] - 8004b24: 6e5b ldr r3, [r3, #100] ; 0x64 - 8004b26: 6878 ldr r0, [r7, #4] - 8004b28: 4798 blx r3 + 8004ba6: 687b ldr r3, [r7, #4] + 8004ba8: 6e5b ldr r3, [r3, #100] ; 0x64 + 8004baa: 6878 ldr r0, [r7, #4] + 8004bac: 4798 blx r3 } return; - 8004b2a: e012 b.n 8004b52 + 8004bae: e012 b.n 8004bd6 } /* UART in mode Transmitter (transmission end) -----------------------------*/ if (((isrflags & USART_ISR_TC) != 0U) && ((cr1its & USART_CR1_TCIE) != 0U)) - 8004b2c: 69fb ldr r3, [r7, #28] - 8004b2e: f003 0340 and.w r3, r3, #64 ; 0x40 - 8004b32: 2b00 cmp r3, #0 - 8004b34: d00e beq.n 8004b54 - 8004b36: 69bb ldr r3, [r7, #24] - 8004b38: f003 0340 and.w r3, r3, #64 ; 0x40 - 8004b3c: 2b00 cmp r3, #0 - 8004b3e: d009 beq.n 8004b54 + 8004bb0: 69fb ldr r3, [r7, #28] + 8004bb2: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004bb6: 2b00 cmp r3, #0 + 8004bb8: d00e beq.n 8004bd8 + 8004bba: 69bb ldr r3, [r7, #24] + 8004bbc: f003 0340 and.w r3, r3, #64 ; 0x40 + 8004bc0: 2b00 cmp r3, #0 + 8004bc2: d009 beq.n 8004bd8 { UART_EndTransmit_IT(huart); - 8004b40: 6878 ldr r0, [r7, #4] - 8004b42: f000 fc14 bl 800536e + 8004bc4: 6878 ldr r0, [r7, #4] + 8004bc6: f000 fc14 bl 80053f2 return; - 8004b46: bf00 nop - 8004b48: e004 b.n 8004b54 + 8004bca: bf00 nop + 8004bcc: e004 b.n 8004bd8 return; - 8004b4a: bf00 nop - 8004b4c: e002 b.n 8004b54 + 8004bce: bf00 nop + 8004bd0: e002 b.n 8004bd8 return; - 8004b4e: bf00 nop - 8004b50: e000 b.n 8004b54 + 8004bd2: bf00 nop + 8004bd4: e000 b.n 8004bd8 return; - 8004b52: bf00 nop + 8004bd6: bf00 nop } } - 8004b54: 3720 adds r7, #32 - 8004b56: 46bd mov sp, r7 - 8004b58: bd80 pop {r7, pc} - 8004b5a: bf00 nop - 8004b5c: 08005343 .word 0x08005343 + 8004bd8: 3720 adds r7, #32 + 8004bda: 46bd mov sp, r7 + 8004bdc: bd80 pop {r7, pc} + 8004bde: bf00 nop + 8004be0: 080053c7 .word 0x080053c7 -08004b60 : +08004be4 : * @brief Tx Transfer completed callback. * @param huart UART handle. * @retval None */ __weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) { - 8004b60: b480 push {r7} - 8004b62: b083 sub sp, #12 - 8004b64: af00 add r7, sp, #0 - 8004b66: 6078 str r0, [r7, #4] + 8004be4: b480 push {r7} + 8004be6: b083 sub sp, #12 + 8004be8: af00 add r7, sp, #0 + 8004bea: 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. */ } - 8004b68: bf00 nop - 8004b6a: 370c adds r7, #12 - 8004b6c: 46bd mov sp, r7 - 8004b6e: f85d 7b04 ldr.w r7, [sp], #4 - 8004b72: 4770 bx lr + 8004bec: bf00 nop + 8004bee: 370c adds r7, #12 + 8004bf0: 46bd mov sp, r7 + 8004bf2: f85d 7b04 ldr.w r7, [sp], #4 + 8004bf6: 4770 bx lr -08004b74 : +08004bf8 : * @brief UART error callback. * @param huart UART handle. * @retval None */ __weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) { - 8004b74: b480 push {r7} - 8004b76: b083 sub sp, #12 - 8004b78: af00 add r7, sp, #0 - 8004b7a: 6078 str r0, [r7, #4] + 8004bf8: b480 push {r7} + 8004bfa: b083 sub sp, #12 + 8004bfc: af00 add r7, sp, #0 + 8004bfe: 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. */ } - 8004b7c: bf00 nop - 8004b7e: 370c adds r7, #12 - 8004b80: 46bd mov sp, r7 - 8004b82: f85d 7b04 ldr.w r7, [sp], #4 - 8004b86: 4770 bx lr + 8004c00: bf00 nop + 8004c02: 370c adds r7, #12 + 8004c04: 46bd mov sp, r7 + 8004c06: f85d 7b04 ldr.w r7, [sp], #4 + 8004c0a: 4770 bx lr -08004b88 : +08004c0c : * @brief Configure the UART peripheral. * @param huart UART handle. * @retval HAL status */ HAL_StatusTypeDef UART_SetConfig(UART_HandleTypeDef *huart) { - 8004b88: b580 push {r7, lr} - 8004b8a: b088 sub sp, #32 - 8004b8c: af00 add r7, sp, #0 - 8004b8e: 6078 str r0, [r7, #4] + 8004c0c: b580 push {r7, lr} + 8004c0e: b088 sub sp, #32 + 8004c10: af00 add r7, sp, #0 + 8004c12: 6078 str r0, [r7, #4] uint32_t tmpreg; uint16_t brrtemp; UART_ClockSourceTypeDef clocksource; uint32_t usartdiv = 0x00000000U; - 8004b90: 2300 movs r3, #0 - 8004b92: 61bb str r3, [r7, #24] + 8004c14: 2300 movs r3, #0 + 8004c16: 61bb str r3, [r7, #24] HAL_StatusTypeDef ret = HAL_OK; - 8004b94: 2300 movs r3, #0 - 8004b96: 75fb strb r3, [r7, #23] + 8004c18: 2300 movs r3, #0 + 8004c1a: 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 ; - 8004b98: 687b ldr r3, [r7, #4] - 8004b9a: 689a ldr r2, [r3, #8] - 8004b9c: 687b ldr r3, [r7, #4] - 8004b9e: 691b ldr r3, [r3, #16] - 8004ba0: 431a orrs r2, r3 - 8004ba2: 687b ldr r3, [r7, #4] - 8004ba4: 695b ldr r3, [r3, #20] - 8004ba6: 431a orrs r2, r3 - 8004ba8: 687b ldr r3, [r7, #4] - 8004baa: 69db ldr r3, [r3, #28] - 8004bac: 4313 orrs r3, r2 - 8004bae: 613b str r3, [r7, #16] + 8004c1c: 687b ldr r3, [r7, #4] + 8004c1e: 689a ldr r2, [r3, #8] + 8004c20: 687b ldr r3, [r7, #4] + 8004c22: 691b ldr r3, [r3, #16] + 8004c24: 431a orrs r2, r3 + 8004c26: 687b ldr r3, [r7, #4] + 8004c28: 695b ldr r3, [r3, #20] + 8004c2a: 431a orrs r2, r3 + 8004c2c: 687b ldr r3, [r7, #4] + 8004c2e: 69db ldr r3, [r3, #28] + 8004c30: 4313 orrs r3, r2 + 8004c32: 613b str r3, [r7, #16] MODIFY_REG(huart->Instance->CR1, USART_CR1_FIELDS, tmpreg); - 8004bb0: 687b ldr r3, [r7, #4] - 8004bb2: 681b ldr r3, [r3, #0] - 8004bb4: 681a ldr r2, [r3, #0] - 8004bb6: 4bb1 ldr r3, [pc, #708] ; (8004e7c ) - 8004bb8: 4013 ands r3, r2 - 8004bba: 687a ldr r2, [r7, #4] - 8004bbc: 6812 ldr r2, [r2, #0] - 8004bbe: 6939 ldr r1, [r7, #16] - 8004bc0: 430b orrs r3, r1 - 8004bc2: 6013 str r3, [r2, #0] + 8004c34: 687b ldr r3, [r7, #4] + 8004c36: 681b ldr r3, [r3, #0] + 8004c38: 681a ldr r2, [r3, #0] + 8004c3a: 4bb1 ldr r3, [pc, #708] ; (8004f00 ) + 8004c3c: 4013 ands r3, r2 + 8004c3e: 687a ldr r2, [r7, #4] + 8004c40: 6812 ldr r2, [r2, #0] + 8004c42: 6939 ldr r1, [r7, #16] + 8004c44: 430b orrs r3, r1 + 8004c46: 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); - 8004bc4: 687b ldr r3, [r7, #4] - 8004bc6: 681b ldr r3, [r3, #0] - 8004bc8: 685b ldr r3, [r3, #4] - 8004bca: f423 5140 bic.w r1, r3, #12288 ; 0x3000 - 8004bce: 687b ldr r3, [r7, #4] - 8004bd0: 68da ldr r2, [r3, #12] - 8004bd2: 687b ldr r3, [r7, #4] - 8004bd4: 681b ldr r3, [r3, #0] - 8004bd6: 430a orrs r2, r1 - 8004bd8: 605a str r2, [r3, #4] + 8004c48: 687b ldr r3, [r7, #4] + 8004c4a: 681b ldr r3, [r3, #0] + 8004c4c: 685b ldr r3, [r3, #4] + 8004c4e: f423 5140 bic.w r1, r3, #12288 ; 0x3000 + 8004c52: 687b ldr r3, [r7, #4] + 8004c54: 68da ldr r2, [r3, #12] + 8004c56: 687b ldr r3, [r7, #4] + 8004c58: 681b ldr r3, [r3, #0] + 8004c5a: 430a orrs r2, r1 + 8004c5c: 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; - 8004bda: 687b ldr r3, [r7, #4] - 8004bdc: 699b ldr r3, [r3, #24] - 8004bde: 613b str r3, [r7, #16] + 8004c5e: 687b ldr r3, [r7, #4] + 8004c60: 699b ldr r3, [r3, #24] + 8004c62: 613b str r3, [r7, #16] tmpreg |= huart->Init.OneBitSampling; - 8004be0: 687b ldr r3, [r7, #4] - 8004be2: 6a1b ldr r3, [r3, #32] - 8004be4: 693a ldr r2, [r7, #16] - 8004be6: 4313 orrs r3, r2 - 8004be8: 613b str r3, [r7, #16] + 8004c64: 687b ldr r3, [r7, #4] + 8004c66: 6a1b ldr r3, [r3, #32] + 8004c68: 693a ldr r2, [r7, #16] + 8004c6a: 4313 orrs r3, r2 + 8004c6c: 613b str r3, [r7, #16] MODIFY_REG(huart->Instance->CR3, USART_CR3_FIELDS, tmpreg); - 8004bea: 687b ldr r3, [r7, #4] - 8004bec: 681b ldr r3, [r3, #0] - 8004bee: 689b ldr r3, [r3, #8] - 8004bf0: f423 6130 bic.w r1, r3, #2816 ; 0xb00 - 8004bf4: 687b ldr r3, [r7, #4] - 8004bf6: 681b ldr r3, [r3, #0] - 8004bf8: 693a ldr r2, [r7, #16] - 8004bfa: 430a orrs r2, r1 - 8004bfc: 609a str r2, [r3, #8] + 8004c6e: 687b ldr r3, [r7, #4] + 8004c70: 681b ldr r3, [r3, #0] + 8004c72: 689b ldr r3, [r3, #8] + 8004c74: f423 6130 bic.w r1, r3, #2816 ; 0xb00 + 8004c78: 687b ldr r3, [r7, #4] + 8004c7a: 681b ldr r3, [r3, #0] + 8004c7c: 693a ldr r2, [r7, #16] + 8004c7e: 430a orrs r2, r1 + 8004c80: 609a str r2, [r3, #8] /*-------------------------- USART BRR Configuration -----------------------*/ UART_GETCLOCKSOURCE(huart, clocksource); - 8004bfe: 687b ldr r3, [r7, #4] - 8004c00: 681b ldr r3, [r3, #0] - 8004c02: 4a9f ldr r2, [pc, #636] ; (8004e80 ) - 8004c04: 4293 cmp r3, r2 - 8004c06: d121 bne.n 8004c4c - 8004c08: 4b9e ldr r3, [pc, #632] ; (8004e84 ) - 8004c0a: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004c0e: f003 0303 and.w r3, r3, #3 - 8004c12: 2b03 cmp r3, #3 - 8004c14: d816 bhi.n 8004c44 - 8004c16: a201 add r2, pc, #4 ; (adr r2, 8004c1c ) - 8004c18: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004c1c: 08004c2d .word 0x08004c2d - 8004c20: 08004c39 .word 0x08004c39 - 8004c24: 08004c33 .word 0x08004c33 - 8004c28: 08004c3f .word 0x08004c3f - 8004c2c: 2301 movs r3, #1 - 8004c2e: 77fb strb r3, [r7, #31] - 8004c30: e151 b.n 8004ed6 - 8004c32: 2302 movs r3, #2 - 8004c34: 77fb strb r3, [r7, #31] - 8004c36: e14e b.n 8004ed6 - 8004c38: 2304 movs r3, #4 - 8004c3a: 77fb strb r3, [r7, #31] - 8004c3c: e14b b.n 8004ed6 - 8004c3e: 2308 movs r3, #8 - 8004c40: 77fb strb r3, [r7, #31] - 8004c42: e148 b.n 8004ed6 - 8004c44: 2310 movs r3, #16 - 8004c46: 77fb strb r3, [r7, #31] - 8004c48: bf00 nop - 8004c4a: e144 b.n 8004ed6 - 8004c4c: 687b ldr r3, [r7, #4] - 8004c4e: 681b ldr r3, [r3, #0] - 8004c50: 4a8d ldr r2, [pc, #564] ; (8004e88 ) - 8004c52: 4293 cmp r3, r2 - 8004c54: d134 bne.n 8004cc0 - 8004c56: 4b8b ldr r3, [pc, #556] ; (8004e84 ) - 8004c58: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004c5c: f003 030c and.w r3, r3, #12 - 8004c60: 2b0c cmp r3, #12 - 8004c62: d829 bhi.n 8004cb8 - 8004c64: a201 add r2, pc, #4 ; (adr r2, 8004c6c ) - 8004c66: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004c6a: bf00 nop - 8004c6c: 08004ca1 .word 0x08004ca1 - 8004c70: 08004cb9 .word 0x08004cb9 - 8004c74: 08004cb9 .word 0x08004cb9 - 8004c78: 08004cb9 .word 0x08004cb9 - 8004c7c: 08004cad .word 0x08004cad - 8004c80: 08004cb9 .word 0x08004cb9 - 8004c84: 08004cb9 .word 0x08004cb9 - 8004c88: 08004cb9 .word 0x08004cb9 - 8004c8c: 08004ca7 .word 0x08004ca7 - 8004c90: 08004cb9 .word 0x08004cb9 - 8004c94: 08004cb9 .word 0x08004cb9 - 8004c98: 08004cb9 .word 0x08004cb9 - 8004c9c: 08004cb3 .word 0x08004cb3 - 8004ca0: 2300 movs r3, #0 - 8004ca2: 77fb strb r3, [r7, #31] - 8004ca4: e117 b.n 8004ed6 - 8004ca6: 2302 movs r3, #2 - 8004ca8: 77fb strb r3, [r7, #31] - 8004caa: e114 b.n 8004ed6 - 8004cac: 2304 movs r3, #4 - 8004cae: 77fb strb r3, [r7, #31] - 8004cb0: e111 b.n 8004ed6 - 8004cb2: 2308 movs r3, #8 - 8004cb4: 77fb strb r3, [r7, #31] - 8004cb6: e10e b.n 8004ed6 - 8004cb8: 2310 movs r3, #16 - 8004cba: 77fb strb r3, [r7, #31] - 8004cbc: bf00 nop - 8004cbe: e10a b.n 8004ed6 - 8004cc0: 687b ldr r3, [r7, #4] - 8004cc2: 681b ldr r3, [r3, #0] - 8004cc4: 4a71 ldr r2, [pc, #452] ; (8004e8c ) - 8004cc6: 4293 cmp r3, r2 - 8004cc8: d120 bne.n 8004d0c - 8004cca: 4b6e ldr r3, [pc, #440] ; (8004e84 ) - 8004ccc: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004cd0: f003 0330 and.w r3, r3, #48 ; 0x30 - 8004cd4: 2b10 cmp r3, #16 - 8004cd6: d00f beq.n 8004cf8 - 8004cd8: 2b10 cmp r3, #16 - 8004cda: d802 bhi.n 8004ce2 - 8004cdc: 2b00 cmp r3, #0 - 8004cde: d005 beq.n 8004cec - 8004ce0: e010 b.n 8004d04 - 8004ce2: 2b20 cmp r3, #32 - 8004ce4: d005 beq.n 8004cf2 - 8004ce6: 2b30 cmp r3, #48 ; 0x30 - 8004ce8: d009 beq.n 8004cfe - 8004cea: e00b b.n 8004d04 - 8004cec: 2300 movs r3, #0 - 8004cee: 77fb strb r3, [r7, #31] - 8004cf0: e0f1 b.n 8004ed6 - 8004cf2: 2302 movs r3, #2 - 8004cf4: 77fb strb r3, [r7, #31] - 8004cf6: e0ee b.n 8004ed6 - 8004cf8: 2304 movs r3, #4 - 8004cfa: 77fb strb r3, [r7, #31] - 8004cfc: e0eb b.n 8004ed6 - 8004cfe: 2308 movs r3, #8 - 8004d00: 77fb strb r3, [r7, #31] - 8004d02: e0e8 b.n 8004ed6 - 8004d04: 2310 movs r3, #16 - 8004d06: 77fb strb r3, [r7, #31] - 8004d08: bf00 nop - 8004d0a: e0e4 b.n 8004ed6 - 8004d0c: 687b ldr r3, [r7, #4] - 8004d0e: 681b ldr r3, [r3, #0] - 8004d10: 4a5f ldr r2, [pc, #380] ; (8004e90 ) - 8004d12: 4293 cmp r3, r2 - 8004d14: d120 bne.n 8004d58 - 8004d16: 4b5b ldr r3, [pc, #364] ; (8004e84 ) - 8004d18: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004d1c: f003 03c0 and.w r3, r3, #192 ; 0xc0 - 8004d20: 2b40 cmp r3, #64 ; 0x40 - 8004d22: d00f beq.n 8004d44 - 8004d24: 2b40 cmp r3, #64 ; 0x40 - 8004d26: d802 bhi.n 8004d2e - 8004d28: 2b00 cmp r3, #0 - 8004d2a: d005 beq.n 8004d38 - 8004d2c: e010 b.n 8004d50 - 8004d2e: 2b80 cmp r3, #128 ; 0x80 - 8004d30: d005 beq.n 8004d3e - 8004d32: 2bc0 cmp r3, #192 ; 0xc0 - 8004d34: d009 beq.n 8004d4a - 8004d36: e00b b.n 8004d50 - 8004d38: 2300 movs r3, #0 - 8004d3a: 77fb strb r3, [r7, #31] - 8004d3c: e0cb b.n 8004ed6 - 8004d3e: 2302 movs r3, #2 - 8004d40: 77fb strb r3, [r7, #31] - 8004d42: e0c8 b.n 8004ed6 - 8004d44: 2304 movs r3, #4 - 8004d46: 77fb strb r3, [r7, #31] - 8004d48: e0c5 b.n 8004ed6 - 8004d4a: 2308 movs r3, #8 - 8004d4c: 77fb strb r3, [r7, #31] - 8004d4e: e0c2 b.n 8004ed6 - 8004d50: 2310 movs r3, #16 - 8004d52: 77fb strb r3, [r7, #31] - 8004d54: bf00 nop - 8004d56: e0be b.n 8004ed6 - 8004d58: 687b ldr r3, [r7, #4] - 8004d5a: 681b ldr r3, [r3, #0] - 8004d5c: 4a4d ldr r2, [pc, #308] ; (8004e94 ) - 8004d5e: 4293 cmp r3, r2 - 8004d60: d124 bne.n 8004dac - 8004d62: 4b48 ldr r3, [pc, #288] ; (8004e84 ) - 8004d64: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004d68: f403 7340 and.w r3, r3, #768 ; 0x300 - 8004d6c: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 8004d70: d012 beq.n 8004d98 - 8004d72: f5b3 7f80 cmp.w r3, #256 ; 0x100 - 8004d76: d802 bhi.n 8004d7e - 8004d78: 2b00 cmp r3, #0 - 8004d7a: d007 beq.n 8004d8c - 8004d7c: e012 b.n 8004da4 - 8004d7e: f5b3 7f00 cmp.w r3, #512 ; 0x200 - 8004d82: d006 beq.n 8004d92 - 8004d84: f5b3 7f40 cmp.w r3, #768 ; 0x300 - 8004d88: d009 beq.n 8004d9e - 8004d8a: e00b b.n 8004da4 - 8004d8c: 2300 movs r3, #0 - 8004d8e: 77fb strb r3, [r7, #31] - 8004d90: e0a1 b.n 8004ed6 - 8004d92: 2302 movs r3, #2 - 8004d94: 77fb strb r3, [r7, #31] - 8004d96: e09e b.n 8004ed6 - 8004d98: 2304 movs r3, #4 - 8004d9a: 77fb strb r3, [r7, #31] - 8004d9c: e09b b.n 8004ed6 - 8004d9e: 2308 movs r3, #8 - 8004da0: 77fb strb r3, [r7, #31] - 8004da2: e098 b.n 8004ed6 - 8004da4: 2310 movs r3, #16 - 8004da6: 77fb strb r3, [r7, #31] - 8004da8: bf00 nop - 8004daa: e094 b.n 8004ed6 - 8004dac: 687b ldr r3, [r7, #4] - 8004dae: 681b ldr r3, [r3, #0] - 8004db0: 4a39 ldr r2, [pc, #228] ; (8004e98 ) - 8004db2: 4293 cmp r3, r2 - 8004db4: d124 bne.n 8004e00 - 8004db6: 4b33 ldr r3, [pc, #204] ; (8004e84 ) - 8004db8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004dbc: f403 6340 and.w r3, r3, #3072 ; 0xc00 - 8004dc0: f5b3 6f80 cmp.w r3, #1024 ; 0x400 - 8004dc4: d012 beq.n 8004dec - 8004dc6: f5b3 6f80 cmp.w r3, #1024 ; 0x400 - 8004dca: d802 bhi.n 8004dd2 - 8004dcc: 2b00 cmp r3, #0 - 8004dce: d007 beq.n 8004de0 - 8004dd0: e012 b.n 8004df8 - 8004dd2: f5b3 6f00 cmp.w r3, #2048 ; 0x800 - 8004dd6: d006 beq.n 8004de6 - 8004dd8: f5b3 6f40 cmp.w r3, #3072 ; 0xc00 - 8004ddc: d009 beq.n 8004df2 - 8004dde: e00b b.n 8004df8 - 8004de0: 2301 movs r3, #1 - 8004de2: 77fb strb r3, [r7, #31] - 8004de4: e077 b.n 8004ed6 - 8004de6: 2302 movs r3, #2 - 8004de8: 77fb strb r3, [r7, #31] - 8004dea: e074 b.n 8004ed6 - 8004dec: 2304 movs r3, #4 - 8004dee: 77fb strb r3, [r7, #31] - 8004df0: e071 b.n 8004ed6 - 8004df2: 2308 movs r3, #8 - 8004df4: 77fb strb r3, [r7, #31] - 8004df6: e06e b.n 8004ed6 - 8004df8: 2310 movs r3, #16 - 8004dfa: 77fb strb r3, [r7, #31] - 8004dfc: bf00 nop - 8004dfe: e06a b.n 8004ed6 - 8004e00: 687b ldr r3, [r7, #4] - 8004e02: 681b ldr r3, [r3, #0] - 8004e04: 4a25 ldr r2, [pc, #148] ; (8004e9c ) - 8004e06: 4293 cmp r3, r2 - 8004e08: d124 bne.n 8004e54 - 8004e0a: 4b1e ldr r3, [pc, #120] ; (8004e84 ) - 8004e0c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004e10: f403 5340 and.w r3, r3, #12288 ; 0x3000 - 8004e14: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004e18: d012 beq.n 8004e40 - 8004e1a: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 - 8004e1e: d802 bhi.n 8004e26 - 8004e20: 2b00 cmp r3, #0 - 8004e22: d007 beq.n 8004e34 - 8004e24: e012 b.n 8004e4c - 8004e26: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 - 8004e2a: d006 beq.n 8004e3a - 8004e2c: f5b3 5f40 cmp.w r3, #12288 ; 0x3000 - 8004e30: d009 beq.n 8004e46 - 8004e32: e00b b.n 8004e4c - 8004e34: 2300 movs r3, #0 - 8004e36: 77fb strb r3, [r7, #31] - 8004e38: e04d b.n 8004ed6 - 8004e3a: 2302 movs r3, #2 - 8004e3c: 77fb strb r3, [r7, #31] - 8004e3e: e04a b.n 8004ed6 - 8004e40: 2304 movs r3, #4 - 8004e42: 77fb strb r3, [r7, #31] - 8004e44: e047 b.n 8004ed6 - 8004e46: 2308 movs r3, #8 - 8004e48: 77fb strb r3, [r7, #31] - 8004e4a: e044 b.n 8004ed6 - 8004e4c: 2310 movs r3, #16 - 8004e4e: 77fb strb r3, [r7, #31] - 8004e50: bf00 nop - 8004e52: e040 b.n 8004ed6 - 8004e54: 687b ldr r3, [r7, #4] - 8004e56: 681b ldr r3, [r3, #0] - 8004e58: 4a11 ldr r2, [pc, #68] ; (8004ea0 ) - 8004e5a: 4293 cmp r3, r2 - 8004e5c: d139 bne.n 8004ed2 - 8004e5e: 4b09 ldr r3, [pc, #36] ; (8004e84 ) - 8004e60: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 - 8004e64: f403 4340 and.w r3, r3, #49152 ; 0xc000 - 8004e68: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 - 8004e6c: d027 beq.n 8004ebe - 8004e6e: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 - 8004e72: d817 bhi.n 8004ea4 - 8004e74: 2b00 cmp r3, #0 - 8004e76: d01c beq.n 8004eb2 - 8004e78: e027 b.n 8004eca - 8004e7a: bf00 nop - 8004e7c: efff69f3 .word 0xefff69f3 - 8004e80: 40011000 .word 0x40011000 - 8004e84: 40023800 .word 0x40023800 - 8004e88: 40004400 .word 0x40004400 - 8004e8c: 40004800 .word 0x40004800 - 8004e90: 40004c00 .word 0x40004c00 - 8004e94: 40005000 .word 0x40005000 - 8004e98: 40011400 .word 0x40011400 - 8004e9c: 40007800 .word 0x40007800 - 8004ea0: 40007c00 .word 0x40007c00 - 8004ea4: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 - 8004ea8: d006 beq.n 8004eb8 - 8004eaa: f5b3 4f40 cmp.w r3, #49152 ; 0xc000 - 8004eae: d009 beq.n 8004ec4 - 8004eb0: e00b b.n 8004eca - 8004eb2: 2300 movs r3, #0 - 8004eb4: 77fb strb r3, [r7, #31] - 8004eb6: e00e b.n 8004ed6 - 8004eb8: 2302 movs r3, #2 + 8004c82: 687b ldr r3, [r7, #4] + 8004c84: 681b ldr r3, [r3, #0] + 8004c86: 4a9f ldr r2, [pc, #636] ; (8004f04 ) + 8004c88: 4293 cmp r3, r2 + 8004c8a: d121 bne.n 8004cd0 + 8004c8c: 4b9e ldr r3, [pc, #632] ; (8004f08 ) + 8004c8e: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004c92: f003 0303 and.w r3, r3, #3 + 8004c96: 2b03 cmp r3, #3 + 8004c98: d816 bhi.n 8004cc8 + 8004c9a: a201 add r2, pc, #4 ; (adr r2, 8004ca0 ) + 8004c9c: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004ca0: 08004cb1 .word 0x08004cb1 + 8004ca4: 08004cbd .word 0x08004cbd + 8004ca8: 08004cb7 .word 0x08004cb7 + 8004cac: 08004cc3 .word 0x08004cc3 + 8004cb0: 2301 movs r3, #1 + 8004cb2: 77fb strb r3, [r7, #31] + 8004cb4: e151 b.n 8004f5a + 8004cb6: 2302 movs r3, #2 + 8004cb8: 77fb strb r3, [r7, #31] + 8004cba: e14e b.n 8004f5a + 8004cbc: 2304 movs r3, #4 + 8004cbe: 77fb strb r3, [r7, #31] + 8004cc0: e14b b.n 8004f5a + 8004cc2: 2308 movs r3, #8 + 8004cc4: 77fb strb r3, [r7, #31] + 8004cc6: e148 b.n 8004f5a + 8004cc8: 2310 movs r3, #16 + 8004cca: 77fb strb r3, [r7, #31] + 8004ccc: bf00 nop + 8004cce: e144 b.n 8004f5a + 8004cd0: 687b ldr r3, [r7, #4] + 8004cd2: 681b ldr r3, [r3, #0] + 8004cd4: 4a8d ldr r2, [pc, #564] ; (8004f0c ) + 8004cd6: 4293 cmp r3, r2 + 8004cd8: d134 bne.n 8004d44 + 8004cda: 4b8b ldr r3, [pc, #556] ; (8004f08 ) + 8004cdc: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004ce0: f003 030c and.w r3, r3, #12 + 8004ce4: 2b0c cmp r3, #12 + 8004ce6: d829 bhi.n 8004d3c + 8004ce8: a201 add r2, pc, #4 ; (adr r2, 8004cf0 ) + 8004cea: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004cee: bf00 nop + 8004cf0: 08004d25 .word 0x08004d25 + 8004cf4: 08004d3d .word 0x08004d3d + 8004cf8: 08004d3d .word 0x08004d3d + 8004cfc: 08004d3d .word 0x08004d3d + 8004d00: 08004d31 .word 0x08004d31 + 8004d04: 08004d3d .word 0x08004d3d + 8004d08: 08004d3d .word 0x08004d3d + 8004d0c: 08004d3d .word 0x08004d3d + 8004d10: 08004d2b .word 0x08004d2b + 8004d14: 08004d3d .word 0x08004d3d + 8004d18: 08004d3d .word 0x08004d3d + 8004d1c: 08004d3d .word 0x08004d3d + 8004d20: 08004d37 .word 0x08004d37 + 8004d24: 2300 movs r3, #0 + 8004d26: 77fb strb r3, [r7, #31] + 8004d28: e117 b.n 8004f5a + 8004d2a: 2302 movs r3, #2 + 8004d2c: 77fb strb r3, [r7, #31] + 8004d2e: e114 b.n 8004f5a + 8004d30: 2304 movs r3, #4 + 8004d32: 77fb strb r3, [r7, #31] + 8004d34: e111 b.n 8004f5a + 8004d36: 2308 movs r3, #8 + 8004d38: 77fb strb r3, [r7, #31] + 8004d3a: e10e b.n 8004f5a + 8004d3c: 2310 movs r3, #16 + 8004d3e: 77fb strb r3, [r7, #31] + 8004d40: bf00 nop + 8004d42: e10a b.n 8004f5a + 8004d44: 687b ldr r3, [r7, #4] + 8004d46: 681b ldr r3, [r3, #0] + 8004d48: 4a71 ldr r2, [pc, #452] ; (8004f10 ) + 8004d4a: 4293 cmp r3, r2 + 8004d4c: d120 bne.n 8004d90 + 8004d4e: 4b6e ldr r3, [pc, #440] ; (8004f08 ) + 8004d50: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004d54: f003 0330 and.w r3, r3, #48 ; 0x30 + 8004d58: 2b10 cmp r3, #16 + 8004d5a: d00f beq.n 8004d7c + 8004d5c: 2b10 cmp r3, #16 + 8004d5e: d802 bhi.n 8004d66 + 8004d60: 2b00 cmp r3, #0 + 8004d62: d005 beq.n 8004d70 + 8004d64: e010 b.n 8004d88 + 8004d66: 2b20 cmp r3, #32 + 8004d68: d005 beq.n 8004d76 + 8004d6a: 2b30 cmp r3, #48 ; 0x30 + 8004d6c: d009 beq.n 8004d82 + 8004d6e: e00b b.n 8004d88 + 8004d70: 2300 movs r3, #0 + 8004d72: 77fb strb r3, [r7, #31] + 8004d74: e0f1 b.n 8004f5a + 8004d76: 2302 movs r3, #2 + 8004d78: 77fb strb r3, [r7, #31] + 8004d7a: e0ee b.n 8004f5a + 8004d7c: 2304 movs r3, #4 + 8004d7e: 77fb strb r3, [r7, #31] + 8004d80: e0eb b.n 8004f5a + 8004d82: 2308 movs r3, #8 + 8004d84: 77fb strb r3, [r7, #31] + 8004d86: e0e8 b.n 8004f5a + 8004d88: 2310 movs r3, #16 + 8004d8a: 77fb strb r3, [r7, #31] + 8004d8c: bf00 nop + 8004d8e: e0e4 b.n 8004f5a + 8004d90: 687b ldr r3, [r7, #4] + 8004d92: 681b ldr r3, [r3, #0] + 8004d94: 4a5f ldr r2, [pc, #380] ; (8004f14 ) + 8004d96: 4293 cmp r3, r2 + 8004d98: d120 bne.n 8004ddc + 8004d9a: 4b5b ldr r3, [pc, #364] ; (8004f08 ) + 8004d9c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004da0: f003 03c0 and.w r3, r3, #192 ; 0xc0 + 8004da4: 2b40 cmp r3, #64 ; 0x40 + 8004da6: d00f beq.n 8004dc8 + 8004da8: 2b40 cmp r3, #64 ; 0x40 + 8004daa: d802 bhi.n 8004db2 + 8004dac: 2b00 cmp r3, #0 + 8004dae: d005 beq.n 8004dbc + 8004db0: e010 b.n 8004dd4 + 8004db2: 2b80 cmp r3, #128 ; 0x80 + 8004db4: d005 beq.n 8004dc2 + 8004db6: 2bc0 cmp r3, #192 ; 0xc0 + 8004db8: d009 beq.n 8004dce + 8004dba: e00b b.n 8004dd4 + 8004dbc: 2300 movs r3, #0 + 8004dbe: 77fb strb r3, [r7, #31] + 8004dc0: e0cb b.n 8004f5a + 8004dc2: 2302 movs r3, #2 + 8004dc4: 77fb strb r3, [r7, #31] + 8004dc6: e0c8 b.n 8004f5a + 8004dc8: 2304 movs r3, #4 + 8004dca: 77fb strb r3, [r7, #31] + 8004dcc: e0c5 b.n 8004f5a + 8004dce: 2308 movs r3, #8 + 8004dd0: 77fb strb r3, [r7, #31] + 8004dd2: e0c2 b.n 8004f5a + 8004dd4: 2310 movs r3, #16 + 8004dd6: 77fb strb r3, [r7, #31] + 8004dd8: bf00 nop + 8004dda: e0be b.n 8004f5a + 8004ddc: 687b ldr r3, [r7, #4] + 8004dde: 681b ldr r3, [r3, #0] + 8004de0: 4a4d ldr r2, [pc, #308] ; (8004f18 ) + 8004de2: 4293 cmp r3, r2 + 8004de4: d124 bne.n 8004e30 + 8004de6: 4b48 ldr r3, [pc, #288] ; (8004f08 ) + 8004de8: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004dec: f403 7340 and.w r3, r3, #768 ; 0x300 + 8004df0: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8004df4: d012 beq.n 8004e1c + 8004df6: f5b3 7f80 cmp.w r3, #256 ; 0x100 + 8004dfa: d802 bhi.n 8004e02 + 8004dfc: 2b00 cmp r3, #0 + 8004dfe: d007 beq.n 8004e10 + 8004e00: e012 b.n 8004e28 + 8004e02: f5b3 7f00 cmp.w r3, #512 ; 0x200 + 8004e06: d006 beq.n 8004e16 + 8004e08: f5b3 7f40 cmp.w r3, #768 ; 0x300 + 8004e0c: d009 beq.n 8004e22 + 8004e0e: e00b b.n 8004e28 + 8004e10: 2300 movs r3, #0 + 8004e12: 77fb strb r3, [r7, #31] + 8004e14: e0a1 b.n 8004f5a + 8004e16: 2302 movs r3, #2 + 8004e18: 77fb strb r3, [r7, #31] + 8004e1a: e09e b.n 8004f5a + 8004e1c: 2304 movs r3, #4 + 8004e1e: 77fb strb r3, [r7, #31] + 8004e20: e09b b.n 8004f5a + 8004e22: 2308 movs r3, #8 + 8004e24: 77fb strb r3, [r7, #31] + 8004e26: e098 b.n 8004f5a + 8004e28: 2310 movs r3, #16 + 8004e2a: 77fb strb r3, [r7, #31] + 8004e2c: bf00 nop + 8004e2e: e094 b.n 8004f5a + 8004e30: 687b ldr r3, [r7, #4] + 8004e32: 681b ldr r3, [r3, #0] + 8004e34: 4a39 ldr r2, [pc, #228] ; (8004f1c ) + 8004e36: 4293 cmp r3, r2 + 8004e38: d124 bne.n 8004e84 + 8004e3a: 4b33 ldr r3, [pc, #204] ; (8004f08 ) + 8004e3c: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004e40: f403 6340 and.w r3, r3, #3072 ; 0xc00 + 8004e44: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004e48: d012 beq.n 8004e70 + 8004e4a: f5b3 6f80 cmp.w r3, #1024 ; 0x400 + 8004e4e: d802 bhi.n 8004e56 + 8004e50: 2b00 cmp r3, #0 + 8004e52: d007 beq.n 8004e64 + 8004e54: e012 b.n 8004e7c + 8004e56: f5b3 6f00 cmp.w r3, #2048 ; 0x800 + 8004e5a: d006 beq.n 8004e6a + 8004e5c: f5b3 6f40 cmp.w r3, #3072 ; 0xc00 + 8004e60: d009 beq.n 8004e76 + 8004e62: e00b b.n 8004e7c + 8004e64: 2301 movs r3, #1 + 8004e66: 77fb strb r3, [r7, #31] + 8004e68: e077 b.n 8004f5a + 8004e6a: 2302 movs r3, #2 + 8004e6c: 77fb strb r3, [r7, #31] + 8004e6e: e074 b.n 8004f5a + 8004e70: 2304 movs r3, #4 + 8004e72: 77fb strb r3, [r7, #31] + 8004e74: e071 b.n 8004f5a + 8004e76: 2308 movs r3, #8 + 8004e78: 77fb strb r3, [r7, #31] + 8004e7a: e06e b.n 8004f5a + 8004e7c: 2310 movs r3, #16 + 8004e7e: 77fb strb r3, [r7, #31] + 8004e80: bf00 nop + 8004e82: e06a b.n 8004f5a + 8004e84: 687b ldr r3, [r7, #4] + 8004e86: 681b ldr r3, [r3, #0] + 8004e88: 4a25 ldr r2, [pc, #148] ; (8004f20 ) + 8004e8a: 4293 cmp r3, r2 + 8004e8c: d124 bne.n 8004ed8 + 8004e8e: 4b1e ldr r3, [pc, #120] ; (8004f08 ) + 8004e90: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004e94: f403 5340 and.w r3, r3, #12288 ; 0x3000 + 8004e98: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004e9c: d012 beq.n 8004ec4 + 8004e9e: f5b3 5f80 cmp.w r3, #4096 ; 0x1000 + 8004ea2: d802 bhi.n 8004eaa + 8004ea4: 2b00 cmp r3, #0 + 8004ea6: d007 beq.n 8004eb8 + 8004ea8: e012 b.n 8004ed0 + 8004eaa: f5b3 5f00 cmp.w r3, #8192 ; 0x2000 + 8004eae: d006 beq.n 8004ebe + 8004eb0: f5b3 5f40 cmp.w r3, #12288 ; 0x3000 + 8004eb4: d009 beq.n 8004eca + 8004eb6: e00b b.n 8004ed0 + 8004eb8: 2300 movs r3, #0 8004eba: 77fb strb r3, [r7, #31] - 8004ebc: e00b b.n 8004ed6 - 8004ebe: 2304 movs r3, #4 + 8004ebc: e04d b.n 8004f5a + 8004ebe: 2302 movs r3, #2 8004ec0: 77fb strb r3, [r7, #31] - 8004ec2: e008 b.n 8004ed6 - 8004ec4: 2308 movs r3, #8 + 8004ec2: e04a b.n 8004f5a + 8004ec4: 2304 movs r3, #4 8004ec6: 77fb strb r3, [r7, #31] - 8004ec8: e005 b.n 8004ed6 - 8004eca: 2310 movs r3, #16 + 8004ec8: e047 b.n 8004f5a + 8004eca: 2308 movs r3, #8 8004ecc: 77fb strb r3, [r7, #31] - 8004ece: bf00 nop - 8004ed0: e001 b.n 8004ed6 - 8004ed2: 2310 movs r3, #16 - 8004ed4: 77fb strb r3, [r7, #31] + 8004ece: e044 b.n 8004f5a + 8004ed0: 2310 movs r3, #16 + 8004ed2: 77fb strb r3, [r7, #31] + 8004ed4: bf00 nop + 8004ed6: e040 b.n 8004f5a + 8004ed8: 687b ldr r3, [r7, #4] + 8004eda: 681b ldr r3, [r3, #0] + 8004edc: 4a11 ldr r2, [pc, #68] ; (8004f24 ) + 8004ede: 4293 cmp r3, r2 + 8004ee0: d139 bne.n 8004f56 + 8004ee2: 4b09 ldr r3, [pc, #36] ; (8004f08 ) + 8004ee4: f8d3 3090 ldr.w r3, [r3, #144] ; 0x90 + 8004ee8: f403 4340 and.w r3, r3, #49152 ; 0xc000 + 8004eec: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 8004ef0: d027 beq.n 8004f42 + 8004ef2: f5b3 4f80 cmp.w r3, #16384 ; 0x4000 + 8004ef6: d817 bhi.n 8004f28 + 8004ef8: 2b00 cmp r3, #0 + 8004efa: d01c beq.n 8004f36 + 8004efc: e027 b.n 8004f4e + 8004efe: bf00 nop + 8004f00: efff69f3 .word 0xefff69f3 + 8004f04: 40011000 .word 0x40011000 + 8004f08: 40023800 .word 0x40023800 + 8004f0c: 40004400 .word 0x40004400 + 8004f10: 40004800 .word 0x40004800 + 8004f14: 40004c00 .word 0x40004c00 + 8004f18: 40005000 .word 0x40005000 + 8004f1c: 40011400 .word 0x40011400 + 8004f20: 40007800 .word 0x40007800 + 8004f24: 40007c00 .word 0x40007c00 + 8004f28: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 8004f2c: d006 beq.n 8004f3c + 8004f2e: f5b3 4f40 cmp.w r3, #49152 ; 0xc000 + 8004f32: d009 beq.n 8004f48 + 8004f34: e00b b.n 8004f4e + 8004f36: 2300 movs r3, #0 + 8004f38: 77fb strb r3, [r7, #31] + 8004f3a: e00e b.n 8004f5a + 8004f3c: 2302 movs r3, #2 + 8004f3e: 77fb strb r3, [r7, #31] + 8004f40: e00b b.n 8004f5a + 8004f42: 2304 movs r3, #4 + 8004f44: 77fb strb r3, [r7, #31] + 8004f46: e008 b.n 8004f5a + 8004f48: 2308 movs r3, #8 + 8004f4a: 77fb strb r3, [r7, #31] + 8004f4c: e005 b.n 8004f5a + 8004f4e: 2310 movs r3, #16 + 8004f50: 77fb strb r3, [r7, #31] + 8004f52: bf00 nop + 8004f54: e001 b.n 8004f5a + 8004f56: 2310 movs r3, #16 + 8004f58: 77fb strb r3, [r7, #31] if (huart->Init.OverSampling == UART_OVERSAMPLING_8) - 8004ed6: 687b ldr r3, [r7, #4] - 8004ed8: 69db ldr r3, [r3, #28] - 8004eda: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 - 8004ede: d17c bne.n 8004fda + 8004f5a: 687b ldr r3, [r7, #4] + 8004f5c: 69db ldr r3, [r3, #28] + 8004f5e: f5b3 4f00 cmp.w r3, #32768 ; 0x8000 + 8004f62: d17c bne.n 800505e { switch (clocksource) - 8004ee0: 7ffb ldrb r3, [r7, #31] - 8004ee2: 2b08 cmp r3, #8 - 8004ee4: d859 bhi.n 8004f9a - 8004ee6: a201 add r2, pc, #4 ; (adr r2, 8004eec ) - 8004ee8: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004eec: 08004f11 .word 0x08004f11 - 8004ef0: 08004f2f .word 0x08004f2f - 8004ef4: 08004f4d .word 0x08004f4d - 8004ef8: 08004f9b .word 0x08004f9b - 8004efc: 08004f65 .word 0x08004f65 - 8004f00: 08004f9b .word 0x08004f9b - 8004f04: 08004f9b .word 0x08004f9b - 8004f08: 08004f9b .word 0x08004f9b - 8004f0c: 08004f83 .word 0x08004f83 + 8004f64: 7ffb ldrb r3, [r7, #31] + 8004f66: 2b08 cmp r3, #8 + 8004f68: d859 bhi.n 800501e + 8004f6a: a201 add r2, pc, #4 ; (adr r2, 8004f70 ) + 8004f6c: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 8004f70: 08004f95 .word 0x08004f95 + 8004f74: 08004fb3 .word 0x08004fb3 + 8004f78: 08004fd1 .word 0x08004fd1 + 8004f7c: 0800501f .word 0x0800501f + 8004f80: 08004fe9 .word 0x08004fe9 + 8004f84: 0800501f .word 0x0800501f + 8004f88: 0800501f .word 0x0800501f + 8004f8c: 0800501f .word 0x0800501f + 8004f90: 08005007 .word 0x08005007 { case UART_CLOCKSOURCE_PCLK1: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); - 8004f10: f7fd fe50 bl 8002bb4 - 8004f14: 4603 mov r3, r0 - 8004f16: 005a lsls r2, r3, #1 - 8004f18: 687b ldr r3, [r7, #4] - 8004f1a: 685b ldr r3, [r3, #4] - 8004f1c: 085b lsrs r3, r3, #1 - 8004f1e: 441a add r2, r3 - 8004f20: 687b ldr r3, [r7, #4] - 8004f22: 685b ldr r3, [r3, #4] - 8004f24: fbb2 f3f3 udiv r3, r2, r3 - 8004f28: b29b uxth r3, r3 - 8004f2a: 61bb str r3, [r7, #24] + 8004f94: f7fd fe50 bl 8002c38 + 8004f98: 4603 mov r3, r0 + 8004f9a: 005a lsls r2, r3, #1 + 8004f9c: 687b ldr r3, [r7, #4] + 8004f9e: 685b ldr r3, [r3, #4] + 8004fa0: 085b lsrs r3, r3, #1 + 8004fa2: 441a add r2, r3 + 8004fa4: 687b ldr r3, [r7, #4] + 8004fa6: 685b ldr r3, [r3, #4] + 8004fa8: fbb2 f3f3 udiv r3, r2, r3 + 8004fac: b29b uxth r3, r3 + 8004fae: 61bb str r3, [r7, #24] break; - 8004f2c: e038 b.n 8004fa0 + 8004fb0: e038 b.n 8005024 case UART_CLOCKSOURCE_PCLK2: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); - 8004f2e: f7fd fe55 bl 8002bdc - 8004f32: 4603 mov r3, r0 - 8004f34: 005a lsls r2, r3, #1 - 8004f36: 687b ldr r3, [r7, #4] - 8004f38: 685b ldr r3, [r3, #4] - 8004f3a: 085b lsrs r3, r3, #1 - 8004f3c: 441a add r2, r3 - 8004f3e: 687b ldr r3, [r7, #4] - 8004f40: 685b ldr r3, [r3, #4] - 8004f42: fbb2 f3f3 udiv r3, r2, r3 - 8004f46: b29b uxth r3, r3 - 8004f48: 61bb str r3, [r7, #24] + 8004fb2: f7fd fe55 bl 8002c60 + 8004fb6: 4603 mov r3, r0 + 8004fb8: 005a lsls r2, r3, #1 + 8004fba: 687b ldr r3, [r7, #4] + 8004fbc: 685b ldr r3, [r3, #4] + 8004fbe: 085b lsrs r3, r3, #1 + 8004fc0: 441a add r2, r3 + 8004fc2: 687b ldr r3, [r7, #4] + 8004fc4: 685b ldr r3, [r3, #4] + 8004fc6: fbb2 f3f3 udiv r3, r2, r3 + 8004fca: b29b uxth r3, r3 + 8004fcc: 61bb str r3, [r7, #24] break; - 8004f4a: e029 b.n 8004fa0 + 8004fce: e029 b.n 8005024 case UART_CLOCKSOURCE_HSI: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HSI_VALUE, huart->Init.BaudRate)); - 8004f4c: 687b ldr r3, [r7, #4] - 8004f4e: 685b ldr r3, [r3, #4] - 8004f50: 085a lsrs r2, r3, #1 - 8004f52: 4b5d ldr r3, [pc, #372] ; (80050c8 ) - 8004f54: 4413 add r3, r2 - 8004f56: 687a ldr r2, [r7, #4] - 8004f58: 6852 ldr r2, [r2, #4] - 8004f5a: fbb3 f3f2 udiv r3, r3, r2 - 8004f5e: b29b uxth r3, r3 - 8004f60: 61bb str r3, [r7, #24] + 8004fd0: 687b ldr r3, [r7, #4] + 8004fd2: 685b ldr r3, [r3, #4] + 8004fd4: 085a lsrs r2, r3, #1 + 8004fd6: 4b5d ldr r3, [pc, #372] ; (800514c ) + 8004fd8: 4413 add r3, r2 + 8004fda: 687a ldr r2, [r7, #4] + 8004fdc: 6852 ldr r2, [r2, #4] + 8004fde: fbb3 f3f2 udiv r3, r3, r2 + 8004fe2: b29b uxth r3, r3 + 8004fe4: 61bb str r3, [r7, #24] break; - 8004f62: e01d b.n 8004fa0 + 8004fe6: e01d b.n 8005024 case UART_CLOCKSOURCE_SYSCLK: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); - 8004f64: f7fd fd68 bl 8002a38 - 8004f68: 4603 mov r3, r0 - 8004f6a: 005a lsls r2, r3, #1 - 8004f6c: 687b ldr r3, [r7, #4] - 8004f6e: 685b ldr r3, [r3, #4] - 8004f70: 085b lsrs r3, r3, #1 - 8004f72: 441a add r2, r3 - 8004f74: 687b ldr r3, [r7, #4] - 8004f76: 685b ldr r3, [r3, #4] - 8004f78: fbb2 f3f3 udiv r3, r2, r3 - 8004f7c: b29b uxth r3, r3 - 8004f7e: 61bb str r3, [r7, #24] + 8004fe8: f7fd fd68 bl 8002abc + 8004fec: 4603 mov r3, r0 + 8004fee: 005a lsls r2, r3, #1 + 8004ff0: 687b ldr r3, [r7, #4] + 8004ff2: 685b ldr r3, [r3, #4] + 8004ff4: 085b lsrs r3, r3, #1 + 8004ff6: 441a add r2, r3 + 8004ff8: 687b ldr r3, [r7, #4] + 8004ffa: 685b ldr r3, [r3, #4] + 8004ffc: fbb2 f3f3 udiv r3, r2, r3 + 8005000: b29b uxth r3, r3 + 8005002: 61bb str r3, [r7, #24] break; - 8004f80: e00e b.n 8004fa0 + 8005004: e00e b.n 8005024 case UART_CLOCKSOURCE_LSE: usartdiv = (uint16_t)(UART_DIV_SAMPLING8(LSE_VALUE, huart->Init.BaudRate)); - 8004f82: 687b ldr r3, [r7, #4] - 8004f84: 685b ldr r3, [r3, #4] - 8004f86: 085b lsrs r3, r3, #1 - 8004f88: f503 3280 add.w r2, r3, #65536 ; 0x10000 - 8004f8c: 687b ldr r3, [r7, #4] - 8004f8e: 685b ldr r3, [r3, #4] - 8004f90: fbb2 f3f3 udiv r3, r2, r3 - 8004f94: b29b uxth r3, r3 - 8004f96: 61bb str r3, [r7, #24] + 8005006: 687b ldr r3, [r7, #4] + 8005008: 685b ldr r3, [r3, #4] + 800500a: 085b lsrs r3, r3, #1 + 800500c: f503 3280 add.w r2, r3, #65536 ; 0x10000 + 8005010: 687b ldr r3, [r7, #4] + 8005012: 685b ldr r3, [r3, #4] + 8005014: fbb2 f3f3 udiv r3, r2, r3 + 8005018: b29b uxth r3, r3 + 800501a: 61bb str r3, [r7, #24] break; - 8004f98: e002 b.n 8004fa0 + 800501c: e002 b.n 8005024 case UART_CLOCKSOURCE_UNDEFINED: default: ret = HAL_ERROR; - 8004f9a: 2301 movs r3, #1 - 8004f9c: 75fb strb r3, [r7, #23] + 800501e: 2301 movs r3, #1 + 8005020: 75fb strb r3, [r7, #23] break; - 8004f9e: bf00 nop + 8005022: bf00 nop } /* USARTDIV must be greater than or equal to 0d16 */ if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) - 8004fa0: 69bb ldr r3, [r7, #24] - 8004fa2: 2b0f cmp r3, #15 - 8004fa4: d916 bls.n 8004fd4 - 8004fa6: 69bb ldr r3, [r7, #24] - 8004fa8: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 8004fac: d212 bcs.n 8004fd4 + 8005024: 69bb ldr r3, [r7, #24] + 8005026: 2b0f cmp r3, #15 + 8005028: d916 bls.n 8005058 + 800502a: 69bb ldr r3, [r7, #24] + 800502c: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8005030: d212 bcs.n 8005058 { brrtemp = (uint16_t)(usartdiv & 0xFFF0U); - 8004fae: 69bb ldr r3, [r7, #24] - 8004fb0: b29b uxth r3, r3 - 8004fb2: f023 030f bic.w r3, r3, #15 - 8004fb6: 81fb strh r3, [r7, #14] + 8005032: 69bb ldr r3, [r7, #24] + 8005034: b29b uxth r3, r3 + 8005036: f023 030f bic.w r3, r3, #15 + 800503a: 81fb strh r3, [r7, #14] brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U); - 8004fb8: 69bb ldr r3, [r7, #24] - 8004fba: 085b lsrs r3, r3, #1 - 8004fbc: b29b uxth r3, r3 - 8004fbe: f003 0307 and.w r3, r3, #7 - 8004fc2: b29a uxth r2, r3 - 8004fc4: 89fb ldrh r3, [r7, #14] - 8004fc6: 4313 orrs r3, r2 - 8004fc8: 81fb strh r3, [r7, #14] + 800503c: 69bb ldr r3, [r7, #24] + 800503e: 085b lsrs r3, r3, #1 + 8005040: b29b uxth r3, r3 + 8005042: f003 0307 and.w r3, r3, #7 + 8005046: b29a uxth r2, r3 + 8005048: 89fb ldrh r3, [r7, #14] + 800504a: 4313 orrs r3, r2 + 800504c: 81fb strh r3, [r7, #14] huart->Instance->BRR = brrtemp; - 8004fca: 687b ldr r3, [r7, #4] - 8004fcc: 681b ldr r3, [r3, #0] - 8004fce: 89fa ldrh r2, [r7, #14] - 8004fd0: 60da str r2, [r3, #12] - 8004fd2: e06e b.n 80050b2 + 800504e: 687b ldr r3, [r7, #4] + 8005050: 681b ldr r3, [r3, #0] + 8005052: 89fa ldrh r2, [r7, #14] + 8005054: 60da str r2, [r3, #12] + 8005056: e06e b.n 8005136 } else { ret = HAL_ERROR; - 8004fd4: 2301 movs r3, #1 - 8004fd6: 75fb strb r3, [r7, #23] - 8004fd8: e06b b.n 80050b2 + 8005058: 2301 movs r3, #1 + 800505a: 75fb strb r3, [r7, #23] + 800505c: e06b b.n 8005136 } } else { switch (clocksource) - 8004fda: 7ffb ldrb r3, [r7, #31] - 8004fdc: 2b08 cmp r3, #8 - 8004fde: d857 bhi.n 8005090 - 8004fe0: a201 add r2, pc, #4 ; (adr r2, 8004fe8 ) - 8004fe2: f852 f023 ldr.w pc, [r2, r3, lsl #2] - 8004fe6: bf00 nop - 8004fe8: 0800500d .word 0x0800500d - 8004fec: 08005029 .word 0x08005029 - 8004ff0: 08005045 .word 0x08005045 - 8004ff4: 08005091 .word 0x08005091 - 8004ff8: 0800505d .word 0x0800505d - 8004ffc: 08005091 .word 0x08005091 - 8005000: 08005091 .word 0x08005091 - 8005004: 08005091 .word 0x08005091 - 8005008: 08005079 .word 0x08005079 + 800505e: 7ffb ldrb r3, [r7, #31] + 8005060: 2b08 cmp r3, #8 + 8005062: d857 bhi.n 8005114 + 8005064: a201 add r2, pc, #4 ; (adr r2, 800506c ) + 8005066: f852 f023 ldr.w pc, [r2, r3, lsl #2] + 800506a: bf00 nop + 800506c: 08005091 .word 0x08005091 + 8005070: 080050ad .word 0x080050ad + 8005074: 080050c9 .word 0x080050c9 + 8005078: 08005115 .word 0x08005115 + 800507c: 080050e1 .word 0x080050e1 + 8005080: 08005115 .word 0x08005115 + 8005084: 08005115 .word 0x08005115 + 8005088: 08005115 .word 0x08005115 + 800508c: 080050fd .word 0x080050fd { case UART_CLOCKSOURCE_PCLK1: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK1Freq(), huart->Init.BaudRate)); - 800500c: f7fd fdd2 bl 8002bb4 - 8005010: 4602 mov r2, r0 - 8005012: 687b ldr r3, [r7, #4] - 8005014: 685b ldr r3, [r3, #4] - 8005016: 085b lsrs r3, r3, #1 - 8005018: 441a add r2, r3 - 800501a: 687b ldr r3, [r7, #4] - 800501c: 685b ldr r3, [r3, #4] - 800501e: fbb2 f3f3 udiv r3, r2, r3 - 8005022: b29b uxth r3, r3 - 8005024: 61bb str r3, [r7, #24] + 8005090: f7fd fdd2 bl 8002c38 + 8005094: 4602 mov r2, r0 + 8005096: 687b ldr r3, [r7, #4] + 8005098: 685b ldr r3, [r3, #4] + 800509a: 085b lsrs r3, r3, #1 + 800509c: 441a add r2, r3 + 800509e: 687b ldr r3, [r7, #4] + 80050a0: 685b ldr r3, [r3, #4] + 80050a2: fbb2 f3f3 udiv r3, r2, r3 + 80050a6: b29b uxth r3, r3 + 80050a8: 61bb str r3, [r7, #24] break; - 8005026: e036 b.n 8005096 + 80050aa: e036 b.n 800511a case UART_CLOCKSOURCE_PCLK2: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetPCLK2Freq(), huart->Init.BaudRate)); - 8005028: f7fd fdd8 bl 8002bdc - 800502c: 4602 mov r2, r0 - 800502e: 687b ldr r3, [r7, #4] - 8005030: 685b ldr r3, [r3, #4] - 8005032: 085b lsrs r3, r3, #1 - 8005034: 441a add r2, r3 - 8005036: 687b ldr r3, [r7, #4] - 8005038: 685b ldr r3, [r3, #4] - 800503a: fbb2 f3f3 udiv r3, r2, r3 - 800503e: b29b uxth r3, r3 - 8005040: 61bb str r3, [r7, #24] + 80050ac: f7fd fdd8 bl 8002c60 + 80050b0: 4602 mov r2, r0 + 80050b2: 687b ldr r3, [r7, #4] + 80050b4: 685b ldr r3, [r3, #4] + 80050b6: 085b lsrs r3, r3, #1 + 80050b8: 441a add r2, r3 + 80050ba: 687b ldr r3, [r7, #4] + 80050bc: 685b ldr r3, [r3, #4] + 80050be: fbb2 f3f3 udiv r3, r2, r3 + 80050c2: b29b uxth r3, r3 + 80050c4: 61bb str r3, [r7, #24] break; - 8005042: e028 b.n 8005096 + 80050c6: e028 b.n 800511a case UART_CLOCKSOURCE_HSI: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HSI_VALUE, huart->Init.BaudRate)); - 8005044: 687b ldr r3, [r7, #4] - 8005046: 685b ldr r3, [r3, #4] - 8005048: 085a lsrs r2, r3, #1 - 800504a: 4b20 ldr r3, [pc, #128] ; (80050cc ) - 800504c: 4413 add r3, r2 - 800504e: 687a ldr r2, [r7, #4] - 8005050: 6852 ldr r2, [r2, #4] - 8005052: fbb3 f3f2 udiv r3, r3, r2 - 8005056: b29b uxth r3, r3 - 8005058: 61bb str r3, [r7, #24] + 80050c8: 687b ldr r3, [r7, #4] + 80050ca: 685b ldr r3, [r3, #4] + 80050cc: 085a lsrs r2, r3, #1 + 80050ce: 4b20 ldr r3, [pc, #128] ; (8005150 ) + 80050d0: 4413 add r3, r2 + 80050d2: 687a ldr r2, [r7, #4] + 80050d4: 6852 ldr r2, [r2, #4] + 80050d6: fbb3 f3f2 udiv r3, r3, r2 + 80050da: b29b uxth r3, r3 + 80050dc: 61bb str r3, [r7, #24] break; - 800505a: e01c b.n 8005096 + 80050de: e01c b.n 800511a case UART_CLOCKSOURCE_SYSCLK: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(HAL_RCC_GetSysClockFreq(), huart->Init.BaudRate)); - 800505c: f7fd fcec bl 8002a38 - 8005060: 4602 mov r2, r0 - 8005062: 687b ldr r3, [r7, #4] - 8005064: 685b ldr r3, [r3, #4] - 8005066: 085b lsrs r3, r3, #1 - 8005068: 441a add r2, r3 - 800506a: 687b ldr r3, [r7, #4] - 800506c: 685b ldr r3, [r3, #4] - 800506e: fbb2 f3f3 udiv r3, r2, r3 - 8005072: b29b uxth r3, r3 - 8005074: 61bb str r3, [r7, #24] + 80050e0: f7fd fcec bl 8002abc + 80050e4: 4602 mov r2, r0 + 80050e6: 687b ldr r3, [r7, #4] + 80050e8: 685b ldr r3, [r3, #4] + 80050ea: 085b lsrs r3, r3, #1 + 80050ec: 441a add r2, r3 + 80050ee: 687b ldr r3, [r7, #4] + 80050f0: 685b ldr r3, [r3, #4] + 80050f2: fbb2 f3f3 udiv r3, r2, r3 + 80050f6: b29b uxth r3, r3 + 80050f8: 61bb str r3, [r7, #24] break; - 8005076: e00e b.n 8005096 + 80050fa: e00e b.n 800511a case UART_CLOCKSOURCE_LSE: usartdiv = (uint16_t)(UART_DIV_SAMPLING16(LSE_VALUE, huart->Init.BaudRate)); - 8005078: 687b ldr r3, [r7, #4] - 800507a: 685b ldr r3, [r3, #4] - 800507c: 085b lsrs r3, r3, #1 - 800507e: f503 4200 add.w r2, r3, #32768 ; 0x8000 - 8005082: 687b ldr r3, [r7, #4] - 8005084: 685b ldr r3, [r3, #4] - 8005086: fbb2 f3f3 udiv r3, r2, r3 - 800508a: b29b uxth r3, r3 - 800508c: 61bb str r3, [r7, #24] + 80050fc: 687b ldr r3, [r7, #4] + 80050fe: 685b ldr r3, [r3, #4] + 8005100: 085b lsrs r3, r3, #1 + 8005102: f503 4200 add.w r2, r3, #32768 ; 0x8000 + 8005106: 687b ldr r3, [r7, #4] + 8005108: 685b ldr r3, [r3, #4] + 800510a: fbb2 f3f3 udiv r3, r2, r3 + 800510e: b29b uxth r3, r3 + 8005110: 61bb str r3, [r7, #24] break; - 800508e: e002 b.n 8005096 + 8005112: e002 b.n 800511a case UART_CLOCKSOURCE_UNDEFINED: default: ret = HAL_ERROR; - 8005090: 2301 movs r3, #1 - 8005092: 75fb strb r3, [r7, #23] + 8005114: 2301 movs r3, #1 + 8005116: 75fb strb r3, [r7, #23] break; - 8005094: bf00 nop + 8005118: bf00 nop } /* USARTDIV must be greater than or equal to 0d16 */ if ((usartdiv >= UART_BRR_MIN) && (usartdiv <= UART_BRR_MAX)) - 8005096: 69bb ldr r3, [r7, #24] - 8005098: 2b0f cmp r3, #15 - 800509a: d908 bls.n 80050ae - 800509c: 69bb ldr r3, [r7, #24] - 800509e: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 - 80050a2: d204 bcs.n 80050ae + 800511a: 69bb ldr r3, [r7, #24] + 800511c: 2b0f cmp r3, #15 + 800511e: d908 bls.n 8005132 + 8005120: 69bb ldr r3, [r7, #24] + 8005122: f5b3 3f80 cmp.w r3, #65536 ; 0x10000 + 8005126: d204 bcs.n 8005132 { huart->Instance->BRR = usartdiv; - 80050a4: 687b ldr r3, [r7, #4] - 80050a6: 681b ldr r3, [r3, #0] - 80050a8: 69ba ldr r2, [r7, #24] - 80050aa: 60da str r2, [r3, #12] - 80050ac: e001 b.n 80050b2 + 8005128: 687b ldr r3, [r7, #4] + 800512a: 681b ldr r3, [r3, #0] + 800512c: 69ba ldr r2, [r7, #24] + 800512e: 60da str r2, [r3, #12] + 8005130: e001 b.n 8005136 } else { ret = HAL_ERROR; - 80050ae: 2301 movs r3, #1 - 80050b0: 75fb strb r3, [r7, #23] + 8005132: 2301 movs r3, #1 + 8005134: 75fb strb r3, [r7, #23] } } /* Clear ISR function pointers */ huart->RxISR = NULL; - 80050b2: 687b ldr r3, [r7, #4] - 80050b4: 2200 movs r2, #0 - 80050b6: 661a str r2, [r3, #96] ; 0x60 + 8005136: 687b ldr r3, [r7, #4] + 8005138: 2200 movs r2, #0 + 800513a: 661a str r2, [r3, #96] ; 0x60 huart->TxISR = NULL; - 80050b8: 687b ldr r3, [r7, #4] - 80050ba: 2200 movs r2, #0 - 80050bc: 665a str r2, [r3, #100] ; 0x64 + 800513c: 687b ldr r3, [r7, #4] + 800513e: 2200 movs r2, #0 + 8005140: 665a str r2, [r3, #100] ; 0x64 return ret; - 80050be: 7dfb ldrb r3, [r7, #23] + 8005142: 7dfb ldrb r3, [r7, #23] } - 80050c0: 4618 mov r0, r3 - 80050c2: 3720 adds r7, #32 - 80050c4: 46bd mov sp, r7 - 80050c6: bd80 pop {r7, pc} - 80050c8: 01e84800 .word 0x01e84800 - 80050cc: 00f42400 .word 0x00f42400 - -080050d0 : + 8005144: 4618 mov r0, r3 + 8005146: 3720 adds r7, #32 + 8005148: 46bd mov sp, r7 + 800514a: bd80 pop {r7, pc} + 800514c: 01e84800 .word 0x01e84800 + 8005150: 00f42400 .word 0x00f42400 + +08005154 : * @brief Configure the UART peripheral advanced features. * @param huart UART handle. * @retval None */ void UART_AdvFeatureConfig(UART_HandleTypeDef *huart) { - 80050d0: b480 push {r7} - 80050d2: b083 sub sp, #12 - 80050d4: af00 add r7, sp, #0 - 80050d6: 6078 str r0, [r7, #4] + 8005154: b480 push {r7} + 8005156: b083 sub sp, #12 + 8005158: af00 add r7, sp, #0 + 800515a: 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)) - 80050d8: 687b ldr r3, [r7, #4] - 80050da: 6a5b ldr r3, [r3, #36] ; 0x24 - 80050dc: f003 0301 and.w r3, r3, #1 - 80050e0: 2b00 cmp r3, #0 - 80050e2: d00a beq.n 80050fa + 800515c: 687b ldr r3, [r7, #4] + 800515e: 6a5b ldr r3, [r3, #36] ; 0x24 + 8005160: f003 0301 and.w r3, r3, #1 + 8005164: 2b00 cmp r3, #0 + 8005166: d00a beq.n 800517e { assert_param(IS_UART_ADVFEATURE_TXINV(huart->AdvancedInit.TxPinLevelInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_TXINV, huart->AdvancedInit.TxPinLevelInvert); - 80050e4: 687b ldr r3, [r7, #4] - 80050e6: 681b ldr r3, [r3, #0] - 80050e8: 685b ldr r3, [r3, #4] - 80050ea: f423 3100 bic.w r1, r3, #131072 ; 0x20000 - 80050ee: 687b ldr r3, [r7, #4] - 80050f0: 6a9a ldr r2, [r3, #40] ; 0x28 - 80050f2: 687b ldr r3, [r7, #4] - 80050f4: 681b ldr r3, [r3, #0] - 80050f6: 430a orrs r2, r1 - 80050f8: 605a str r2, [r3, #4] + 8005168: 687b ldr r3, [r7, #4] + 800516a: 681b ldr r3, [r3, #0] + 800516c: 685b ldr r3, [r3, #4] + 800516e: f423 3100 bic.w r1, r3, #131072 ; 0x20000 + 8005172: 687b ldr r3, [r7, #4] + 8005174: 6a9a ldr r2, [r3, #40] ; 0x28 + 8005176: 687b ldr r3, [r7, #4] + 8005178: 681b ldr r3, [r3, #0] + 800517a: 430a orrs r2, r1 + 800517c: 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)) - 80050fa: 687b ldr r3, [r7, #4] - 80050fc: 6a5b ldr r3, [r3, #36] ; 0x24 - 80050fe: f003 0302 and.w r3, r3, #2 - 8005102: 2b00 cmp r3, #0 - 8005104: d00a beq.n 800511c + 800517e: 687b ldr r3, [r7, #4] + 8005180: 6a5b ldr r3, [r3, #36] ; 0x24 + 8005182: f003 0302 and.w r3, r3, #2 + 8005186: 2b00 cmp r3, #0 + 8005188: d00a beq.n 80051a0 { assert_param(IS_UART_ADVFEATURE_RXINV(huart->AdvancedInit.RxPinLevelInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_RXINV, huart->AdvancedInit.RxPinLevelInvert); - 8005106: 687b ldr r3, [r7, #4] - 8005108: 681b ldr r3, [r3, #0] - 800510a: 685b ldr r3, [r3, #4] - 800510c: f423 3180 bic.w r1, r3, #65536 ; 0x10000 - 8005110: 687b ldr r3, [r7, #4] - 8005112: 6ada ldr r2, [r3, #44] ; 0x2c - 8005114: 687b ldr r3, [r7, #4] - 8005116: 681b ldr r3, [r3, #0] - 8005118: 430a orrs r2, r1 - 800511a: 605a str r2, [r3, #4] + 800518a: 687b ldr r3, [r7, #4] + 800518c: 681b ldr r3, [r3, #0] + 800518e: 685b ldr r3, [r3, #4] + 8005190: f423 3180 bic.w r1, r3, #65536 ; 0x10000 + 8005194: 687b ldr r3, [r7, #4] + 8005196: 6ada ldr r2, [r3, #44] ; 0x2c + 8005198: 687b ldr r3, [r7, #4] + 800519a: 681b ldr r3, [r3, #0] + 800519c: 430a orrs r2, r1 + 800519e: 605a str r2, [r3, #4] } /* if required, configure data inversion */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_DATAINVERT_INIT)) - 800511c: 687b ldr r3, [r7, #4] - 800511e: 6a5b ldr r3, [r3, #36] ; 0x24 - 8005120: f003 0304 and.w r3, r3, #4 - 8005124: 2b00 cmp r3, #0 - 8005126: d00a beq.n 800513e + 80051a0: 687b ldr r3, [r7, #4] + 80051a2: 6a5b ldr r3, [r3, #36] ; 0x24 + 80051a4: f003 0304 and.w r3, r3, #4 + 80051a8: 2b00 cmp r3, #0 + 80051aa: d00a beq.n 80051c2 { assert_param(IS_UART_ADVFEATURE_DATAINV(huart->AdvancedInit.DataInvert)); MODIFY_REG(huart->Instance->CR2, USART_CR2_DATAINV, huart->AdvancedInit.DataInvert); - 8005128: 687b ldr r3, [r7, #4] - 800512a: 681b ldr r3, [r3, #0] - 800512c: 685b ldr r3, [r3, #4] - 800512e: f423 2180 bic.w r1, r3, #262144 ; 0x40000 - 8005132: 687b ldr r3, [r7, #4] - 8005134: 6b1a ldr r2, [r3, #48] ; 0x30 - 8005136: 687b ldr r3, [r7, #4] - 8005138: 681b ldr r3, [r3, #0] - 800513a: 430a orrs r2, r1 - 800513c: 605a str r2, [r3, #4] + 80051ac: 687b ldr r3, [r7, #4] + 80051ae: 681b ldr r3, [r3, #0] + 80051b0: 685b ldr r3, [r3, #4] + 80051b2: f423 2180 bic.w r1, r3, #262144 ; 0x40000 + 80051b6: 687b ldr r3, [r7, #4] + 80051b8: 6b1a ldr r2, [r3, #48] ; 0x30 + 80051ba: 687b ldr r3, [r7, #4] + 80051bc: 681b ldr r3, [r3, #0] + 80051be: 430a orrs r2, r1 + 80051c0: 605a str r2, [r3, #4] } /* if required, configure RX/TX pins swap */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_SWAP_INIT)) - 800513e: 687b ldr r3, [r7, #4] - 8005140: 6a5b ldr r3, [r3, #36] ; 0x24 - 8005142: f003 0308 and.w r3, r3, #8 - 8005146: 2b00 cmp r3, #0 - 8005148: d00a beq.n 8005160 + 80051c2: 687b ldr r3, [r7, #4] + 80051c4: 6a5b ldr r3, [r3, #36] ; 0x24 + 80051c6: f003 0308 and.w r3, r3, #8 + 80051ca: 2b00 cmp r3, #0 + 80051cc: d00a beq.n 80051e4 { assert_param(IS_UART_ADVFEATURE_SWAP(huart->AdvancedInit.Swap)); MODIFY_REG(huart->Instance->CR2, USART_CR2_SWAP, huart->AdvancedInit.Swap); - 800514a: 687b ldr r3, [r7, #4] - 800514c: 681b ldr r3, [r3, #0] - 800514e: 685b ldr r3, [r3, #4] - 8005150: f423 4100 bic.w r1, r3, #32768 ; 0x8000 - 8005154: 687b ldr r3, [r7, #4] - 8005156: 6b5a ldr r2, [r3, #52] ; 0x34 - 8005158: 687b ldr r3, [r7, #4] - 800515a: 681b ldr r3, [r3, #0] - 800515c: 430a orrs r2, r1 - 800515e: 605a str r2, [r3, #4] + 80051ce: 687b ldr r3, [r7, #4] + 80051d0: 681b ldr r3, [r3, #0] + 80051d2: 685b ldr r3, [r3, #4] + 80051d4: f423 4100 bic.w r1, r3, #32768 ; 0x8000 + 80051d8: 687b ldr r3, [r7, #4] + 80051da: 6b5a ldr r2, [r3, #52] ; 0x34 + 80051dc: 687b ldr r3, [r7, #4] + 80051de: 681b ldr r3, [r3, #0] + 80051e0: 430a orrs r2, r1 + 80051e2: 605a str r2, [r3, #4] } /* if required, configure RX overrun detection disabling */ if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXOVERRUNDISABLE_INIT)) - 8005160: 687b ldr r3, [r7, #4] - 8005162: 6a5b ldr r3, [r3, #36] ; 0x24 - 8005164: f003 0310 and.w r3, r3, #16 - 8005168: 2b00 cmp r3, #0 - 800516a: d00a beq.n 8005182 + 80051e4: 687b ldr r3, [r7, #4] + 80051e6: 6a5b ldr r3, [r3, #36] ; 0x24 + 80051e8: f003 0310 and.w r3, r3, #16 + 80051ec: 2b00 cmp r3, #0 + 80051ee: d00a beq.n 8005206 { assert_param(IS_UART_OVERRUN(huart->AdvancedInit.OverrunDisable)); MODIFY_REG(huart->Instance->CR3, USART_CR3_OVRDIS, huart->AdvancedInit.OverrunDisable); - 800516c: 687b ldr r3, [r7, #4] - 800516e: 681b ldr r3, [r3, #0] - 8005170: 689b ldr r3, [r3, #8] - 8005172: f423 5180 bic.w r1, r3, #4096 ; 0x1000 - 8005176: 687b ldr r3, [r7, #4] - 8005178: 6b9a ldr r2, [r3, #56] ; 0x38 - 800517a: 687b ldr r3, [r7, #4] - 800517c: 681b ldr r3, [r3, #0] - 800517e: 430a orrs r2, r1 - 8005180: 609a str r2, [r3, #8] + 80051f0: 687b ldr r3, [r7, #4] + 80051f2: 681b ldr r3, [r3, #0] + 80051f4: 689b ldr r3, [r3, #8] + 80051f6: f423 5180 bic.w r1, r3, #4096 ; 0x1000 + 80051fa: 687b ldr r3, [r7, #4] + 80051fc: 6b9a ldr r2, [r3, #56] ; 0x38 + 80051fe: 687b ldr r3, [r7, #4] + 8005200: 681b ldr r3, [r3, #0] + 8005202: 430a orrs r2, r1 + 8005204: 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)) - 8005182: 687b ldr r3, [r7, #4] - 8005184: 6a5b ldr r3, [r3, #36] ; 0x24 - 8005186: f003 0320 and.w r3, r3, #32 - 800518a: 2b00 cmp r3, #0 - 800518c: d00a beq.n 80051a4 + 8005206: 687b ldr r3, [r7, #4] + 8005208: 6a5b ldr r3, [r3, #36] ; 0x24 + 800520a: f003 0320 and.w r3, r3, #32 + 800520e: 2b00 cmp r3, #0 + 8005210: d00a beq.n 8005228 { assert_param(IS_UART_ADVFEATURE_DMAONRXERROR(huart->AdvancedInit.DMADisableonRxError)); MODIFY_REG(huart->Instance->CR3, USART_CR3_DDRE, huart->AdvancedInit.DMADisableonRxError); - 800518e: 687b ldr r3, [r7, #4] - 8005190: 681b ldr r3, [r3, #0] - 8005192: 689b ldr r3, [r3, #8] - 8005194: f423 5100 bic.w r1, r3, #8192 ; 0x2000 - 8005198: 687b ldr r3, [r7, #4] - 800519a: 6bda ldr r2, [r3, #60] ; 0x3c - 800519c: 687b ldr r3, [r7, #4] - 800519e: 681b ldr r3, [r3, #0] - 80051a0: 430a orrs r2, r1 - 80051a2: 609a str r2, [r3, #8] + 8005212: 687b ldr r3, [r7, #4] + 8005214: 681b ldr r3, [r3, #0] + 8005216: 689b ldr r3, [r3, #8] + 8005218: f423 5100 bic.w r1, r3, #8192 ; 0x2000 + 800521c: 687b ldr r3, [r7, #4] + 800521e: 6bda ldr r2, [r3, #60] ; 0x3c + 8005220: 687b ldr r3, [r7, #4] + 8005222: 681b ldr r3, [r3, #0] + 8005224: 430a orrs r2, r1 + 8005226: 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)) - 80051a4: 687b ldr r3, [r7, #4] - 80051a6: 6a5b ldr r3, [r3, #36] ; 0x24 - 80051a8: f003 0340 and.w r3, r3, #64 ; 0x40 - 80051ac: 2b00 cmp r3, #0 - 80051ae: d01a beq.n 80051e6 + 8005228: 687b ldr r3, [r7, #4] + 800522a: 6a5b ldr r3, [r3, #36] ; 0x24 + 800522c: f003 0340 and.w r3, r3, #64 ; 0x40 + 8005230: 2b00 cmp r3, #0 + 8005232: d01a beq.n 800526a { 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); - 80051b0: 687b ldr r3, [r7, #4] - 80051b2: 681b ldr r3, [r3, #0] - 80051b4: 685b ldr r3, [r3, #4] - 80051b6: f423 1180 bic.w r1, r3, #1048576 ; 0x100000 - 80051ba: 687b ldr r3, [r7, #4] - 80051bc: 6c1a ldr r2, [r3, #64] ; 0x40 - 80051be: 687b ldr r3, [r7, #4] - 80051c0: 681b ldr r3, [r3, #0] - 80051c2: 430a orrs r2, r1 - 80051c4: 605a str r2, [r3, #4] + 8005234: 687b ldr r3, [r7, #4] + 8005236: 681b ldr r3, [r3, #0] + 8005238: 685b ldr r3, [r3, #4] + 800523a: f423 1180 bic.w r1, r3, #1048576 ; 0x100000 + 800523e: 687b ldr r3, [r7, #4] + 8005240: 6c1a ldr r2, [r3, #64] ; 0x40 + 8005242: 687b ldr r3, [r7, #4] + 8005244: 681b ldr r3, [r3, #0] + 8005246: 430a orrs r2, r1 + 8005248: 605a str r2, [r3, #4] /* set auto Baudrate detection parameters if detection is enabled */ if (huart->AdvancedInit.AutoBaudRateEnable == UART_ADVFEATURE_AUTOBAUDRATE_ENABLE) - 80051c6: 687b ldr r3, [r7, #4] - 80051c8: 6c1b ldr r3, [r3, #64] ; 0x40 - 80051ca: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 - 80051ce: d10a bne.n 80051e6 + 800524a: 687b ldr r3, [r7, #4] + 800524c: 6c1b ldr r3, [r3, #64] ; 0x40 + 800524e: f5b3 1f80 cmp.w r3, #1048576 ; 0x100000 + 8005252: d10a bne.n 800526a { assert_param(IS_UART_ADVFEATURE_AUTOBAUDRATEMODE(huart->AdvancedInit.AutoBaudRateMode)); MODIFY_REG(huart->Instance->CR2, USART_CR2_ABRMODE, huart->AdvancedInit.AutoBaudRateMode); - 80051d0: 687b ldr r3, [r7, #4] - 80051d2: 681b ldr r3, [r3, #0] - 80051d4: 685b ldr r3, [r3, #4] - 80051d6: f423 01c0 bic.w r1, r3, #6291456 ; 0x600000 - 80051da: 687b ldr r3, [r7, #4] - 80051dc: 6c5a ldr r2, [r3, #68] ; 0x44 - 80051de: 687b ldr r3, [r7, #4] - 80051e0: 681b ldr r3, [r3, #0] - 80051e2: 430a orrs r2, r1 - 80051e4: 605a str r2, [r3, #4] + 8005254: 687b ldr r3, [r7, #4] + 8005256: 681b ldr r3, [r3, #0] + 8005258: 685b ldr r3, [r3, #4] + 800525a: f423 01c0 bic.w r1, r3, #6291456 ; 0x600000 + 800525e: 687b ldr r3, [r7, #4] + 8005260: 6c5a ldr r2, [r3, #68] ; 0x44 + 8005262: 687b ldr r3, [r7, #4] + 8005264: 681b ldr r3, [r3, #0] + 8005266: 430a orrs r2, r1 + 8005268: 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)) - 80051e6: 687b ldr r3, [r7, #4] - 80051e8: 6a5b ldr r3, [r3, #36] ; 0x24 - 80051ea: f003 0380 and.w r3, r3, #128 ; 0x80 - 80051ee: 2b00 cmp r3, #0 - 80051f0: d00a beq.n 8005208 + 800526a: 687b ldr r3, [r7, #4] + 800526c: 6a5b ldr r3, [r3, #36] ; 0x24 + 800526e: f003 0380 and.w r3, r3, #128 ; 0x80 + 8005272: 2b00 cmp r3, #0 + 8005274: d00a beq.n 800528c { assert_param(IS_UART_ADVFEATURE_MSBFIRST(huart->AdvancedInit.MSBFirst)); MODIFY_REG(huart->Instance->CR2, USART_CR2_MSBFIRST, huart->AdvancedInit.MSBFirst); - 80051f2: 687b ldr r3, [r7, #4] - 80051f4: 681b ldr r3, [r3, #0] - 80051f6: 685b ldr r3, [r3, #4] - 80051f8: f423 2100 bic.w r1, r3, #524288 ; 0x80000 - 80051fc: 687b ldr r3, [r7, #4] - 80051fe: 6c9a ldr r2, [r3, #72] ; 0x48 - 8005200: 687b ldr r3, [r7, #4] - 8005202: 681b ldr r3, [r3, #0] - 8005204: 430a orrs r2, r1 - 8005206: 605a str r2, [r3, #4] + 8005276: 687b ldr r3, [r7, #4] + 8005278: 681b ldr r3, [r3, #0] + 800527a: 685b ldr r3, [r3, #4] + 800527c: f423 2100 bic.w r1, r3, #524288 ; 0x80000 + 8005280: 687b ldr r3, [r7, #4] + 8005282: 6c9a ldr r2, [r3, #72] ; 0x48 + 8005284: 687b ldr r3, [r7, #4] + 8005286: 681b ldr r3, [r3, #0] + 8005288: 430a orrs r2, r1 + 800528a: 605a str r2, [r3, #4] } } - 8005208: bf00 nop - 800520a: 370c adds r7, #12 - 800520c: 46bd mov sp, r7 - 800520e: f85d 7b04 ldr.w r7, [sp], #4 - 8005212: 4770 bx lr + 800528c: bf00 nop + 800528e: 370c adds r7, #12 + 8005290: 46bd mov sp, r7 + 8005292: f85d 7b04 ldr.w r7, [sp], #4 + 8005296: 4770 bx lr -08005214 : +08005298 : * @brief Check the UART Idle State. * @param huart UART handle. * @retval HAL status */ HAL_StatusTypeDef UART_CheckIdleState(UART_HandleTypeDef *huart) { - 8005214: b580 push {r7, lr} - 8005216: b086 sub sp, #24 - 8005218: af02 add r7, sp, #8 - 800521a: 6078 str r0, [r7, #4] + 8005298: b580 push {r7, lr} + 800529a: b086 sub sp, #24 + 800529c: af02 add r7, sp, #8 + 800529e: 6078 str r0, [r7, #4] uint32_t tickstart; /* Initialize the UART ErrorCode */ huart->ErrorCode = HAL_UART_ERROR_NONE; - 800521c: 687b ldr r3, [r7, #4] - 800521e: 2200 movs r2, #0 - 8005220: 67da str r2, [r3, #124] ; 0x7c + 80052a0: 687b ldr r3, [r7, #4] + 80052a2: 2200 movs r2, #0 + 80052a4: 67da str r2, [r3, #124] ; 0x7c /* Init tickstart for timeout managment*/ tickstart = HAL_GetTick(); - 8005222: f7fc fd93 bl 8001d4c - 8005226: 60f8 str r0, [r7, #12] + 80052a6: f7fc fd93 bl 8001dd0 + 80052aa: 60f8 str r0, [r7, #12] /* Check if the Transmitter is enabled */ if ((huart->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE) - 8005228: 687b ldr r3, [r7, #4] - 800522a: 681b ldr r3, [r3, #0] - 800522c: 681b ldr r3, [r3, #0] - 800522e: f003 0308 and.w r3, r3, #8 - 8005232: 2b08 cmp r3, #8 - 8005234: d10e bne.n 8005254 + 80052ac: 687b ldr r3, [r7, #4] + 80052ae: 681b ldr r3, [r3, #0] + 80052b0: 681b ldr r3, [r3, #0] + 80052b2: f003 0308 and.w r3, r3, #8 + 80052b6: 2b08 cmp r3, #8 + 80052b8: d10e bne.n 80052d8 { /* Wait until TEACK flag is set */ if (UART_WaitOnFlagUntilTimeout(huart, USART_ISR_TEACK, RESET, tickstart, HAL_UART_TIMEOUT_VALUE) != HAL_OK) - 8005236: f06f 437e mvn.w r3, #4261412864 ; 0xfe000000 - 800523a: 9300 str r3, [sp, #0] - 800523c: 68fb ldr r3, [r7, #12] - 800523e: 2200 movs r2, #0 - 8005240: f44f 1100 mov.w r1, #2097152 ; 0x200000 - 8005244: 6878 ldr r0, [r7, #4] - 8005246: f000 f814 bl 8005272 - 800524a: 4603 mov r3, r0 - 800524c: 2b00 cmp r3, #0 - 800524e: d001 beq.n 8005254 + 80052ba: f06f 437e mvn.w r3, #4261412864 ; 0xfe000000 + 80052be: 9300 str r3, [sp, #0] + 80052c0: 68fb ldr r3, [r7, #12] + 80052c2: 2200 movs r2, #0 + 80052c4: f44f 1100 mov.w r1, #2097152 ; 0x200000 + 80052c8: 6878 ldr r0, [r7, #4] + 80052ca: f000 f814 bl 80052f6 + 80052ce: 4603 mov r3, r0 + 80052d0: 2b00 cmp r3, #0 + 80052d2: d001 beq.n 80052d8 { /* Timeout occurred */ return HAL_TIMEOUT; - 8005250: 2303 movs r3, #3 - 8005252: e00a b.n 800526a + 80052d4: 2303 movs r3, #3 + 80052d6: e00a b.n 80052ee } } /* Initialize the UART State */ huart->gState = HAL_UART_STATE_READY; - 8005254: 687b ldr r3, [r7, #4] - 8005256: 2220 movs r2, #32 - 8005258: 675a str r2, [r3, #116] ; 0x74 + 80052d8: 687b ldr r3, [r7, #4] + 80052da: 2220 movs r2, #32 + 80052dc: 675a str r2, [r3, #116] ; 0x74 huart->RxState = HAL_UART_STATE_READY; - 800525a: 687b ldr r3, [r7, #4] - 800525c: 2220 movs r2, #32 - 800525e: 679a str r2, [r3, #120] ; 0x78 + 80052de: 687b ldr r3, [r7, #4] + 80052e0: 2220 movs r2, #32 + 80052e2: 679a str r2, [r3, #120] ; 0x78 /* Process Unlocked */ __HAL_UNLOCK(huart); - 8005260: 687b ldr r3, [r7, #4] - 8005262: 2200 movs r2, #0 - 8005264: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 80052e4: 687b ldr r3, [r7, #4] + 80052e6: 2200 movs r2, #0 + 80052e8: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_OK; - 8005268: 2300 movs r3, #0 + 80052ec: 2300 movs r3, #0 } - 800526a: 4618 mov r0, r3 - 800526c: 3710 adds r7, #16 - 800526e: 46bd mov sp, r7 - 8005270: bd80 pop {r7, pc} + 80052ee: 4618 mov r0, r3 + 80052f0: 3710 adds r7, #16 + 80052f2: 46bd mov sp, r7 + 80052f4: bd80 pop {r7, pc} -08005272 : +080052f6 : * @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) { - 8005272: b580 push {r7, lr} - 8005274: b084 sub sp, #16 - 8005276: af00 add r7, sp, #0 - 8005278: 60f8 str r0, [r7, #12] - 800527a: 60b9 str r1, [r7, #8] - 800527c: 603b str r3, [r7, #0] - 800527e: 4613 mov r3, r2 - 8005280: 71fb strb r3, [r7, #7] + 80052f6: b580 push {r7, lr} + 80052f8: b084 sub sp, #16 + 80052fa: af00 add r7, sp, #0 + 80052fc: 60f8 str r0, [r7, #12] + 80052fe: 60b9 str r1, [r7, #8] + 8005300: 603b str r3, [r7, #0] + 8005302: 4613 mov r3, r2 + 8005304: 71fb strb r3, [r7, #7] /* Wait until flag is set */ while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - 8005282: e02a b.n 80052da + 8005306: e02a b.n 800535e { /* Check for the Timeout */ if (Timeout != HAL_MAX_DELAY) - 8005284: 69bb ldr r3, [r7, #24] - 8005286: f1b3 3fff cmp.w r3, #4294967295 ; 0xffffffff - 800528a: d026 beq.n 80052da + 8005308: 69bb ldr r3, [r7, #24] + 800530a: f1b3 3fff cmp.w r3, #4294967295 ; 0xffffffff + 800530e: d026 beq.n 800535e { if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - 800528c: f7fc fd5e bl 8001d4c - 8005290: 4602 mov r2, r0 - 8005292: 683b ldr r3, [r7, #0] - 8005294: 1ad3 subs r3, r2, r3 - 8005296: 69ba ldr r2, [r7, #24] - 8005298: 429a cmp r2, r3 - 800529a: d302 bcc.n 80052a2 - 800529c: 69bb ldr r3, [r7, #24] - 800529e: 2b00 cmp r3, #0 - 80052a0: d11b bne.n 80052da + 8005310: f7fc fd5e bl 8001dd0 + 8005314: 4602 mov r2, r0 + 8005316: 683b ldr r3, [r7, #0] + 8005318: 1ad3 subs r3, r2, r3 + 800531a: 69ba ldr r2, [r7, #24] + 800531c: 429a cmp r2, r3 + 800531e: d302 bcc.n 8005326 + 8005320: 69bb ldr r3, [r7, #24] + 8005322: 2b00 cmp r3, #0 + 8005324: d11b bne.n 800535e { /* 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)); - 80052a2: 68fb ldr r3, [r7, #12] - 80052a4: 681b ldr r3, [r3, #0] - 80052a6: 681a ldr r2, [r3, #0] - 80052a8: 68fb ldr r3, [r7, #12] - 80052aa: 681b ldr r3, [r3, #0] - 80052ac: f422 72d0 bic.w r2, r2, #416 ; 0x1a0 - 80052b0: 601a str r2, [r3, #0] + 8005326: 68fb ldr r3, [r7, #12] + 8005328: 681b ldr r3, [r3, #0] + 800532a: 681a ldr r2, [r3, #0] + 800532c: 68fb ldr r3, [r7, #12] + 800532e: 681b ldr r3, [r3, #0] + 8005330: f422 72d0 bic.w r2, r2, #416 ; 0x1a0 + 8005334: 601a str r2, [r3, #0] CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 80052b2: 68fb ldr r3, [r7, #12] - 80052b4: 681b ldr r3, [r3, #0] - 80052b6: 689a ldr r2, [r3, #8] - 80052b8: 68fb ldr r3, [r7, #12] - 80052ba: 681b ldr r3, [r3, #0] - 80052bc: f022 0201 bic.w r2, r2, #1 - 80052c0: 609a str r2, [r3, #8] + 8005336: 68fb ldr r3, [r7, #12] + 8005338: 681b ldr r3, [r3, #0] + 800533a: 689a ldr r2, [r3, #8] + 800533c: 68fb ldr r3, [r7, #12] + 800533e: 681b ldr r3, [r3, #0] + 8005340: f022 0201 bic.w r2, r2, #1 + 8005344: 609a str r2, [r3, #8] huart->gState = HAL_UART_STATE_READY; - 80052c2: 68fb ldr r3, [r7, #12] - 80052c4: 2220 movs r2, #32 - 80052c6: 675a str r2, [r3, #116] ; 0x74 + 8005346: 68fb ldr r3, [r7, #12] + 8005348: 2220 movs r2, #32 + 800534a: 675a str r2, [r3, #116] ; 0x74 huart->RxState = HAL_UART_STATE_READY; - 80052c8: 68fb ldr r3, [r7, #12] - 80052ca: 2220 movs r2, #32 - 80052cc: 679a str r2, [r3, #120] ; 0x78 + 800534c: 68fb ldr r3, [r7, #12] + 800534e: 2220 movs r2, #32 + 8005350: 679a str r2, [r3, #120] ; 0x78 /* Process Unlocked */ __HAL_UNLOCK(huart); - 80052ce: 68fb ldr r3, [r7, #12] - 80052d0: 2200 movs r2, #0 - 80052d2: f883 2070 strb.w r2, [r3, #112] ; 0x70 + 8005352: 68fb ldr r3, [r7, #12] + 8005354: 2200 movs r2, #0 + 8005356: f883 2070 strb.w r2, [r3, #112] ; 0x70 return HAL_TIMEOUT; - 80052d6: 2303 movs r3, #3 - 80052d8: e00f b.n 80052fa + 800535a: 2303 movs r3, #3 + 800535c: e00f b.n 800537e while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - 80052da: 68fb ldr r3, [r7, #12] - 80052dc: 681b ldr r3, [r3, #0] - 80052de: 69da ldr r2, [r3, #28] - 80052e0: 68bb ldr r3, [r7, #8] - 80052e2: 4013 ands r3, r2 - 80052e4: 68ba ldr r2, [r7, #8] - 80052e6: 429a cmp r2, r3 - 80052e8: bf0c ite eq - 80052ea: 2301 moveq r3, #1 - 80052ec: 2300 movne r3, #0 - 80052ee: b2db uxtb r3, r3 - 80052f0: 461a mov r2, r3 - 80052f2: 79fb ldrb r3, [r7, #7] - 80052f4: 429a cmp r2, r3 - 80052f6: d0c5 beq.n 8005284 + 800535e: 68fb ldr r3, [r7, #12] + 8005360: 681b ldr r3, [r3, #0] + 8005362: 69da ldr r2, [r3, #28] + 8005364: 68bb ldr r3, [r7, #8] + 8005366: 4013 ands r3, r2 + 8005368: 68ba ldr r2, [r7, #8] + 800536a: 429a cmp r2, r3 + 800536c: bf0c ite eq + 800536e: 2301 moveq r3, #1 + 8005370: 2300 movne r3, #0 + 8005372: b2db uxtb r3, r3 + 8005374: 461a mov r2, r3 + 8005376: 79fb ldrb r3, [r7, #7] + 8005378: 429a cmp r2, r3 + 800537a: d0c5 beq.n 8005308 } } } return HAL_OK; - 80052f8: 2300 movs r3, #0 + 800537c: 2300 movs r3, #0 } - 80052fa: 4618 mov r0, r3 - 80052fc: 3710 adds r7, #16 - 80052fe: 46bd mov sp, r7 - 8005300: bd80 pop {r7, pc} + 800537e: 4618 mov r0, r3 + 8005380: 3710 adds r7, #16 + 8005382: 46bd mov sp, r7 + 8005384: bd80 pop {r7, pc} -08005302 : +08005386 : * @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) { - 8005302: b480 push {r7} - 8005304: b083 sub sp, #12 - 8005306: af00 add r7, sp, #0 - 8005308: 6078 str r0, [r7, #4] + 8005386: b480 push {r7} + 8005388: b083 sub sp, #12 + 800538a: af00 add r7, sp, #0 + 800538c: 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)); - 800530a: 687b ldr r3, [r7, #4] - 800530c: 681b ldr r3, [r3, #0] - 800530e: 681a ldr r2, [r3, #0] - 8005310: 687b ldr r3, [r7, #4] - 8005312: 681b ldr r3, [r3, #0] - 8005314: f422 7290 bic.w r2, r2, #288 ; 0x120 - 8005318: 601a str r2, [r3, #0] + 800538e: 687b ldr r3, [r7, #4] + 8005390: 681b ldr r3, [r3, #0] + 8005392: 681a ldr r2, [r3, #0] + 8005394: 687b ldr r3, [r7, #4] + 8005396: 681b ldr r3, [r3, #0] + 8005398: f422 7290 bic.w r2, r2, #288 ; 0x120 + 800539c: 601a str r2, [r3, #0] CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 800531a: 687b ldr r3, [r7, #4] - 800531c: 681b ldr r3, [r3, #0] - 800531e: 689a ldr r2, [r3, #8] - 8005320: 687b ldr r3, [r7, #4] - 8005322: 681b ldr r3, [r3, #0] - 8005324: f022 0201 bic.w r2, r2, #1 - 8005328: 609a str r2, [r3, #8] + 800539e: 687b ldr r3, [r7, #4] + 80053a0: 681b ldr r3, [r3, #0] + 80053a2: 689a ldr r2, [r3, #8] + 80053a4: 687b ldr r3, [r7, #4] + 80053a6: 681b ldr r3, [r3, #0] + 80053a8: f022 0201 bic.w r2, r2, #1 + 80053ac: 609a str r2, [r3, #8] /* At end of Rx process, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 800532a: 687b ldr r3, [r7, #4] - 800532c: 2220 movs r2, #32 - 800532e: 679a str r2, [r3, #120] ; 0x78 + 80053ae: 687b ldr r3, [r7, #4] + 80053b0: 2220 movs r2, #32 + 80053b2: 679a str r2, [r3, #120] ; 0x78 /* Reset RxIsr function pointer */ huart->RxISR = NULL; - 8005330: 687b ldr r3, [r7, #4] - 8005332: 2200 movs r2, #0 - 8005334: 661a str r2, [r3, #96] ; 0x60 + 80053b4: 687b ldr r3, [r7, #4] + 80053b6: 2200 movs r2, #0 + 80053b8: 661a str r2, [r3, #96] ; 0x60 } - 8005336: bf00 nop - 8005338: 370c adds r7, #12 - 800533a: 46bd mov sp, r7 - 800533c: f85d 7b04 ldr.w r7, [sp], #4 - 8005340: 4770 bx lr + 80053ba: bf00 nop + 80053bc: 370c adds r7, #12 + 80053be: 46bd mov sp, r7 + 80053c0: f85d 7b04 ldr.w r7, [sp], #4 + 80053c4: 4770 bx lr -08005342 : +080053c6 : * (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) { - 8005342: b580 push {r7, lr} - 8005344: b084 sub sp, #16 - 8005346: af00 add r7, sp, #0 - 8005348: 6078 str r0, [r7, #4] + 80053c6: b580 push {r7, lr} + 80053c8: b084 sub sp, #16 + 80053ca: af00 add r7, sp, #0 + 80053cc: 6078 str r0, [r7, #4] UART_HandleTypeDef *huart = (UART_HandleTypeDef *)(hdma->Parent); - 800534a: 687b ldr r3, [r7, #4] - 800534c: 6b9b ldr r3, [r3, #56] ; 0x38 - 800534e: 60fb str r3, [r7, #12] + 80053ce: 687b ldr r3, [r7, #4] + 80053d0: 6b9b ldr r3, [r3, #56] ; 0x38 + 80053d2: 60fb str r3, [r7, #12] huart->RxXferCount = 0U; - 8005350: 68fb ldr r3, [r7, #12] - 8005352: 2200 movs r2, #0 - 8005354: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 80053d4: 68fb ldr r3, [r7, #12] + 80053d6: 2200 movs r2, #0 + 80053d8: f8a3 205a strh.w r2, [r3, #90] ; 0x5a huart->TxXferCount = 0U; - 8005358: 68fb ldr r3, [r7, #12] - 800535a: 2200 movs r2, #0 - 800535c: f8a3 2052 strh.w r2, [r3, #82] ; 0x52 + 80053dc: 68fb ldr r3, [r7, #12] + 80053de: 2200 movs r2, #0 + 80053e0: 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); - 8005360: 68f8 ldr r0, [r7, #12] - 8005362: f7ff fc07 bl 8004b74 + 80053e4: 68f8 ldr r0, [r7, #12] + 80053e6: f7ff fc07 bl 8004bf8 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ } - 8005366: bf00 nop - 8005368: 3710 adds r7, #16 - 800536a: 46bd mov sp, r7 - 800536c: bd80 pop {r7, pc} + 80053ea: bf00 nop + 80053ec: 3710 adds r7, #16 + 80053ee: 46bd mov sp, r7 + 80053f0: bd80 pop {r7, pc} -0800536e : +080053f2 : * @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) { - 800536e: b580 push {r7, lr} - 8005370: b082 sub sp, #8 - 8005372: af00 add r7, sp, #0 - 8005374: 6078 str r0, [r7, #4] + 80053f2: b580 push {r7, lr} + 80053f4: b082 sub sp, #8 + 80053f6: af00 add r7, sp, #0 + 80053f8: 6078 str r0, [r7, #4] /* Disable the UART Transmit Complete Interrupt */ CLEAR_BIT(huart->Instance->CR1, USART_CR1_TCIE); - 8005376: 687b ldr r3, [r7, #4] - 8005378: 681b ldr r3, [r3, #0] - 800537a: 681a ldr r2, [r3, #0] - 800537c: 687b ldr r3, [r7, #4] - 800537e: 681b ldr r3, [r3, #0] - 8005380: f022 0240 bic.w r2, r2, #64 ; 0x40 - 8005384: 601a str r2, [r3, #0] + 80053fa: 687b ldr r3, [r7, #4] + 80053fc: 681b ldr r3, [r3, #0] + 80053fe: 681a ldr r2, [r3, #0] + 8005400: 687b ldr r3, [r7, #4] + 8005402: 681b ldr r3, [r3, #0] + 8005404: f022 0240 bic.w r2, r2, #64 ; 0x40 + 8005408: 601a str r2, [r3, #0] /* Tx process is ended, restore huart->gState to Ready */ huart->gState = HAL_UART_STATE_READY; - 8005386: 687b ldr r3, [r7, #4] - 8005388: 2220 movs r2, #32 - 800538a: 675a str r2, [r3, #116] ; 0x74 + 800540a: 687b ldr r3, [r7, #4] + 800540c: 2220 movs r2, #32 + 800540e: 675a str r2, [r3, #116] ; 0x74 /* Cleat TxISR function pointer */ huart->TxISR = NULL; - 800538c: 687b ldr r3, [r7, #4] - 800538e: 2200 movs r2, #0 - 8005390: 665a str r2, [r3, #100] ; 0x64 + 8005410: 687b ldr r3, [r7, #4] + 8005412: 2200 movs r2, #0 + 8005414: 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); - 8005392: 6878 ldr r0, [r7, #4] - 8005394: f7ff fbe4 bl 8004b60 + 8005416: 6878 ldr r0, [r7, #4] + 8005418: f7ff fbe4 bl 8004be4 #endif /* USE_HAL_UART_REGISTER_CALLBACKS */ } - 8005398: bf00 nop - 800539a: 3708 adds r7, #8 - 800539c: 46bd mov sp, r7 - 800539e: bd80 pop {r7, pc} + 800541c: bf00 nop + 800541e: 3708 adds r7, #8 + 8005420: 46bd mov sp, r7 + 8005422: bd80 pop {r7, pc} -080053a0 : +08005424 : * @brief RX interrrupt handler for 7 or 8 bits data word length . * @param huart UART handle. * @retval None */ static void UART_RxISR_8BIT(UART_HandleTypeDef *huart) { - 80053a0: b580 push {r7, lr} - 80053a2: b084 sub sp, #16 - 80053a4: af00 add r7, sp, #0 - 80053a6: 6078 str r0, [r7, #4] + 8005424: b580 push {r7, lr} + 8005426: b084 sub sp, #16 + 8005428: af00 add r7, sp, #0 + 800542a: 6078 str r0, [r7, #4] uint16_t uhMask = huart->Mask; - 80053a8: 687b ldr r3, [r7, #4] - 80053aa: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c - 80053ae: 81fb strh r3, [r7, #14] + 800542c: 687b ldr r3, [r7, #4] + 800542e: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c + 8005432: 81fb strh r3, [r7, #14] uint16_t uhdata; /* Check that a Rx process is ongoing */ if (huart->RxState == HAL_UART_STATE_BUSY_RX) - 80053b0: 687b ldr r3, [r7, #4] - 80053b2: 6f9b ldr r3, [r3, #120] ; 0x78 - 80053b4: 2b22 cmp r3, #34 ; 0x22 - 80053b6: d13a bne.n 800542e + 8005434: 687b ldr r3, [r7, #4] + 8005436: 6f9b ldr r3, [r3, #120] ; 0x78 + 8005438: 2b22 cmp r3, #34 ; 0x22 + 800543a: d13a bne.n 80054b2 { uhdata = (uint16_t) READ_REG(huart->Instance->RDR); - 80053b8: 687b ldr r3, [r7, #4] - 80053ba: 681b ldr r3, [r3, #0] - 80053bc: 6a5b ldr r3, [r3, #36] ; 0x24 - 80053be: 81bb strh r3, [r7, #12] + 800543c: 687b ldr r3, [r7, #4] + 800543e: 681b ldr r3, [r3, #0] + 8005440: 6a5b ldr r3, [r3, #36] ; 0x24 + 8005442: 81bb strh r3, [r7, #12] *huart->pRxBuffPtr = (uint8_t)(uhdata & (uint8_t)uhMask); - 80053c0: 89bb ldrh r3, [r7, #12] - 80053c2: b2d9 uxtb r1, r3 - 80053c4: 89fb ldrh r3, [r7, #14] - 80053c6: b2da uxtb r2, r3 - 80053c8: 687b ldr r3, [r7, #4] - 80053ca: 6d5b ldr r3, [r3, #84] ; 0x54 - 80053cc: 400a ands r2, r1 - 80053ce: b2d2 uxtb r2, r2 - 80053d0: 701a strb r2, [r3, #0] + 8005444: 89bb ldrh r3, [r7, #12] + 8005446: b2d9 uxtb r1, r3 + 8005448: 89fb ldrh r3, [r7, #14] + 800544a: b2da uxtb r2, r3 + 800544c: 687b ldr r3, [r7, #4] + 800544e: 6d5b ldr r3, [r3, #84] ; 0x54 + 8005450: 400a ands r2, r1 + 8005452: b2d2 uxtb r2, r2 + 8005454: 701a strb r2, [r3, #0] huart->pRxBuffPtr++; - 80053d2: 687b ldr r3, [r7, #4] - 80053d4: 6d5b ldr r3, [r3, #84] ; 0x54 - 80053d6: 1c5a adds r2, r3, #1 - 80053d8: 687b ldr r3, [r7, #4] - 80053da: 655a str r2, [r3, #84] ; 0x54 + 8005456: 687b ldr r3, [r7, #4] + 8005458: 6d5b ldr r3, [r3, #84] ; 0x54 + 800545a: 1c5a adds r2, r3, #1 + 800545c: 687b ldr r3, [r7, #4] + 800545e: 655a str r2, [r3, #84] ; 0x54 huart->RxXferCount--; - 80053dc: 687b ldr r3, [r7, #4] - 80053de: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 80053e2: b29b uxth r3, r3 - 80053e4: 3b01 subs r3, #1 - 80053e6: b29a uxth r2, r3 - 80053e8: 687b ldr r3, [r7, #4] - 80053ea: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 8005460: 687b ldr r3, [r7, #4] + 8005462: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 8005466: b29b uxth r3, r3 + 8005468: 3b01 subs r3, #1 + 800546a: b29a uxth r2, r3 + 800546c: 687b ldr r3, [r7, #4] + 800546e: f8a3 205a strh.w r2, [r3, #90] ; 0x5a if (huart->RxXferCount == 0U) - 80053ee: 687b ldr r3, [r7, #4] - 80053f0: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 80053f4: b29b uxth r3, r3 - 80053f6: 2b00 cmp r3, #0 - 80053f8: d121 bne.n 800543e + 8005472: 687b ldr r3, [r7, #4] + 8005474: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 8005478: b29b uxth r3, r3 + 800547a: 2b00 cmp r3, #0 + 800547c: d121 bne.n 80054c2 { /* Disable the UART Parity Error Interrupt and RXNE interrupts */ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - 80053fa: 687b ldr r3, [r7, #4] - 80053fc: 681b ldr r3, [r3, #0] - 80053fe: 681a ldr r2, [r3, #0] - 8005400: 687b ldr r3, [r7, #4] - 8005402: 681b ldr r3, [r3, #0] - 8005404: f422 7290 bic.w r2, r2, #288 ; 0x120 - 8005408: 601a str r2, [r3, #0] + 800547e: 687b ldr r3, [r7, #4] + 8005480: 681b ldr r3, [r3, #0] + 8005482: 681a ldr r2, [r3, #0] + 8005484: 687b ldr r3, [r7, #4] + 8005486: 681b ldr r3, [r3, #0] + 8005488: f422 7290 bic.w r2, r2, #288 ; 0x120 + 800548c: 601a str r2, [r3, #0] /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 800540a: 687b ldr r3, [r7, #4] - 800540c: 681b ldr r3, [r3, #0] - 800540e: 689a ldr r2, [r3, #8] - 8005410: 687b ldr r3, [r7, #4] - 8005412: 681b ldr r3, [r3, #0] - 8005414: f022 0201 bic.w r2, r2, #1 - 8005418: 609a str r2, [r3, #8] + 800548e: 687b ldr r3, [r7, #4] + 8005490: 681b ldr r3, [r3, #0] + 8005492: 689a ldr r2, [r3, #8] + 8005494: 687b ldr r3, [r7, #4] + 8005496: 681b ldr r3, [r3, #0] + 8005498: f022 0201 bic.w r2, r2, #1 + 800549c: 609a str r2, [r3, #8] /* Rx process is completed, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 800541a: 687b ldr r3, [r7, #4] - 800541c: 2220 movs r2, #32 - 800541e: 679a str r2, [r3, #120] ; 0x78 + 800549e: 687b ldr r3, [r7, #4] + 80054a0: 2220 movs r2, #32 + 80054a2: 679a str r2, [r3, #120] ; 0x78 /* Clear RxISR function pointer */ huart->RxISR = NULL; - 8005420: 687b ldr r3, [r7, #4] - 8005422: 2200 movs r2, #0 - 8005424: 661a str r2, [r3, #96] ; 0x60 + 80054a4: 687b ldr r3, [r7, #4] + 80054a6: 2200 movs r2, #0 + 80054a8: 661a str r2, [r3, #96] ; 0x60 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered Rx complete callback*/ huart->RxCpltCallback(huart); #else /*Call legacy weak Rx complete callback*/ HAL_UART_RxCpltCallback(huart); - 8005426: 6878 ldr r0, [r7, #4] - 8005428: f7fc f8ac bl 8001584 + 80054aa: 6878 ldr r0, [r7, #4] + 80054ac: f7fc f854 bl 8001558 else { /* Clear RXNE interrupt flag */ __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); } } - 800542c: e007 b.n 800543e + 80054b0: e007 b.n 80054c2 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); - 800542e: 687b ldr r3, [r7, #4] - 8005430: 681b ldr r3, [r3, #0] - 8005432: 699a ldr r2, [r3, #24] - 8005434: 687b ldr r3, [r7, #4] - 8005436: 681b ldr r3, [r3, #0] - 8005438: f042 0208 orr.w r2, r2, #8 - 800543c: 619a str r2, [r3, #24] + 80054b2: 687b ldr r3, [r7, #4] + 80054b4: 681b ldr r3, [r3, #0] + 80054b6: 699a ldr r2, [r3, #24] + 80054b8: 687b ldr r3, [r7, #4] + 80054ba: 681b ldr r3, [r3, #0] + 80054bc: f042 0208 orr.w r2, r2, #8 + 80054c0: 619a str r2, [r3, #24] } - 800543e: bf00 nop - 8005440: 3710 adds r7, #16 - 8005442: 46bd mov sp, r7 - 8005444: bd80 pop {r7, pc} + 80054c2: bf00 nop + 80054c4: 3710 adds r7, #16 + 80054c6: 46bd mov sp, r7 + 80054c8: bd80 pop {r7, pc} -08005446 : +080054ca : * interruptions have been enabled by HAL_UART_Receive_IT() * @param huart UART handle. * @retval None */ static void UART_RxISR_16BIT(UART_HandleTypeDef *huart) { - 8005446: b580 push {r7, lr} - 8005448: b084 sub sp, #16 - 800544a: af00 add r7, sp, #0 - 800544c: 6078 str r0, [r7, #4] + 80054ca: b580 push {r7, lr} + 80054cc: b084 sub sp, #16 + 80054ce: af00 add r7, sp, #0 + 80054d0: 6078 str r0, [r7, #4] uint16_t *tmp; uint16_t uhMask = huart->Mask; - 800544e: 687b ldr r3, [r7, #4] - 8005450: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c - 8005454: 81fb strh r3, [r7, #14] + 80054d2: 687b ldr r3, [r7, #4] + 80054d4: f8b3 305c ldrh.w r3, [r3, #92] ; 0x5c + 80054d8: 81fb strh r3, [r7, #14] uint16_t uhdata; /* Check that a Rx process is ongoing */ if (huart->RxState == HAL_UART_STATE_BUSY_RX) - 8005456: 687b ldr r3, [r7, #4] - 8005458: 6f9b ldr r3, [r3, #120] ; 0x78 - 800545a: 2b22 cmp r3, #34 ; 0x22 - 800545c: d13a bne.n 80054d4 + 80054da: 687b ldr r3, [r7, #4] + 80054dc: 6f9b ldr r3, [r3, #120] ; 0x78 + 80054de: 2b22 cmp r3, #34 ; 0x22 + 80054e0: d13a bne.n 8005558 { uhdata = (uint16_t) READ_REG(huart->Instance->RDR); - 800545e: 687b ldr r3, [r7, #4] - 8005460: 681b ldr r3, [r3, #0] - 8005462: 6a5b ldr r3, [r3, #36] ; 0x24 - 8005464: 81bb strh r3, [r7, #12] + 80054e2: 687b ldr r3, [r7, #4] + 80054e4: 681b ldr r3, [r3, #0] + 80054e6: 6a5b ldr r3, [r3, #36] ; 0x24 + 80054e8: 81bb strh r3, [r7, #12] tmp = (uint16_t *) huart->pRxBuffPtr ; - 8005466: 687b ldr r3, [r7, #4] - 8005468: 6d5b ldr r3, [r3, #84] ; 0x54 - 800546a: 60bb str r3, [r7, #8] + 80054ea: 687b ldr r3, [r7, #4] + 80054ec: 6d5b ldr r3, [r3, #84] ; 0x54 + 80054ee: 60bb str r3, [r7, #8] *tmp = (uint16_t)(uhdata & uhMask); - 800546c: 89ba ldrh r2, [r7, #12] - 800546e: 89fb ldrh r3, [r7, #14] - 8005470: 4013 ands r3, r2 - 8005472: b29a uxth r2, r3 - 8005474: 68bb ldr r3, [r7, #8] - 8005476: 801a strh r2, [r3, #0] + 80054f0: 89ba ldrh r2, [r7, #12] + 80054f2: 89fb ldrh r3, [r7, #14] + 80054f4: 4013 ands r3, r2 + 80054f6: b29a uxth r2, r3 + 80054f8: 68bb ldr r3, [r7, #8] + 80054fa: 801a strh r2, [r3, #0] huart->pRxBuffPtr += 2U; - 8005478: 687b ldr r3, [r7, #4] - 800547a: 6d5b ldr r3, [r3, #84] ; 0x54 - 800547c: 1c9a adds r2, r3, #2 - 800547e: 687b ldr r3, [r7, #4] - 8005480: 655a str r2, [r3, #84] ; 0x54 + 80054fc: 687b ldr r3, [r7, #4] + 80054fe: 6d5b ldr r3, [r3, #84] ; 0x54 + 8005500: 1c9a adds r2, r3, #2 + 8005502: 687b ldr r3, [r7, #4] + 8005504: 655a str r2, [r3, #84] ; 0x54 huart->RxXferCount--; - 8005482: 687b ldr r3, [r7, #4] - 8005484: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 8005488: b29b uxth r3, r3 - 800548a: 3b01 subs r3, #1 - 800548c: b29a uxth r2, r3 - 800548e: 687b ldr r3, [r7, #4] - 8005490: f8a3 205a strh.w r2, [r3, #90] ; 0x5a + 8005506: 687b ldr r3, [r7, #4] + 8005508: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 800550c: b29b uxth r3, r3 + 800550e: 3b01 subs r3, #1 + 8005510: b29a uxth r2, r3 + 8005512: 687b ldr r3, [r7, #4] + 8005514: f8a3 205a strh.w r2, [r3, #90] ; 0x5a if (huart->RxXferCount == 0U) - 8005494: 687b ldr r3, [r7, #4] - 8005496: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a - 800549a: b29b uxth r3, r3 - 800549c: 2b00 cmp r3, #0 - 800549e: d121 bne.n 80054e4 + 8005518: 687b ldr r3, [r7, #4] + 800551a: f8b3 305a ldrh.w r3, [r3, #90] ; 0x5a + 800551e: b29b uxth r3, r3 + 8005520: 2b00 cmp r3, #0 + 8005522: d121 bne.n 8005568 { /* Disable the UART Parity Error Interrupt and RXNE interrupt*/ CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - 80054a0: 687b ldr r3, [r7, #4] - 80054a2: 681b ldr r3, [r3, #0] - 80054a4: 681a ldr r2, [r3, #0] - 80054a6: 687b ldr r3, [r7, #4] - 80054a8: 681b ldr r3, [r3, #0] - 80054aa: f422 7290 bic.w r2, r2, #288 ; 0x120 - 80054ae: 601a str r2, [r3, #0] + 8005524: 687b ldr r3, [r7, #4] + 8005526: 681b ldr r3, [r3, #0] + 8005528: 681a ldr r2, [r3, #0] + 800552a: 687b ldr r3, [r7, #4] + 800552c: 681b ldr r3, [r3, #0] + 800552e: f422 7290 bic.w r2, r2, #288 ; 0x120 + 8005532: 601a str r2, [r3, #0] /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - 80054b0: 687b ldr r3, [r7, #4] - 80054b2: 681b ldr r3, [r3, #0] - 80054b4: 689a ldr r2, [r3, #8] - 80054b6: 687b ldr r3, [r7, #4] - 80054b8: 681b ldr r3, [r3, #0] - 80054ba: f022 0201 bic.w r2, r2, #1 - 80054be: 609a str r2, [r3, #8] + 8005534: 687b ldr r3, [r7, #4] + 8005536: 681b ldr r3, [r3, #0] + 8005538: 689a ldr r2, [r3, #8] + 800553a: 687b ldr r3, [r7, #4] + 800553c: 681b ldr r3, [r3, #0] + 800553e: f022 0201 bic.w r2, r2, #1 + 8005542: 609a str r2, [r3, #8] /* Rx process is completed, restore huart->RxState to Ready */ huart->RxState = HAL_UART_STATE_READY; - 80054c0: 687b ldr r3, [r7, #4] - 80054c2: 2220 movs r2, #32 - 80054c4: 679a str r2, [r3, #120] ; 0x78 + 8005544: 687b ldr r3, [r7, #4] + 8005546: 2220 movs r2, #32 + 8005548: 679a str r2, [r3, #120] ; 0x78 /* Clear RxISR function pointer */ huart->RxISR = NULL; - 80054c6: 687b ldr r3, [r7, #4] - 80054c8: 2200 movs r2, #0 - 80054ca: 661a str r2, [r3, #96] ; 0x60 + 800554a: 687b ldr r3, [r7, #4] + 800554c: 2200 movs r2, #0 + 800554e: 661a str r2, [r3, #96] ; 0x60 #if (USE_HAL_UART_REGISTER_CALLBACKS == 1) /*Call registered Rx complete callback*/ huart->RxCpltCallback(huart); #else /*Call legacy weak Rx complete callback*/ HAL_UART_RxCpltCallback(huart); - 80054cc: 6878 ldr r0, [r7, #4] - 80054ce: f7fc f859 bl 8001584 + 8005550: 6878 ldr r0, [r7, #4] + 8005552: f7fc f801 bl 8001558 else { /* Clear RXNE interrupt flag */ __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); } } - 80054d2: e007 b.n 80054e4 + 8005556: e007 b.n 8005568 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST); - 80054d4: 687b ldr r3, [r7, #4] - 80054d6: 681b ldr r3, [r3, #0] - 80054d8: 699a ldr r2, [r3, #24] - 80054da: 687b ldr r3, [r7, #4] - 80054dc: 681b ldr r3, [r3, #0] - 80054de: f042 0208 orr.w r2, r2, #8 - 80054e2: 619a str r2, [r3, #24] + 8005558: 687b ldr r3, [r7, #4] + 800555a: 681b ldr r3, [r3, #0] + 800555c: 699a ldr r2, [r3, #24] + 800555e: 687b ldr r3, [r7, #4] + 8005560: 681b ldr r3, [r3, #0] + 8005562: f042 0208 orr.w r2, r2, #8 + 8005566: 619a str r2, [r3, #24] } - 80054e4: bf00 nop - 80054e6: 3710 adds r7, #16 - 80054e8: 46bd mov sp, r7 - 80054ea: bd80 pop {r7, pc} - -080054ec <__libc_init_array>: - 80054ec: b570 push {r4, r5, r6, lr} - 80054ee: 4e0d ldr r6, [pc, #52] ; (8005524 <__libc_init_array+0x38>) - 80054f0: 4c0d ldr r4, [pc, #52] ; (8005528 <__libc_init_array+0x3c>) - 80054f2: 1ba4 subs r4, r4, r6 - 80054f4: 10a4 asrs r4, r4, #2 - 80054f6: 2500 movs r5, #0 - 80054f8: 42a5 cmp r5, r4 - 80054fa: d109 bne.n 8005510 <__libc_init_array+0x24> - 80054fc: 4e0b ldr r6, [pc, #44] ; (800552c <__libc_init_array+0x40>) - 80054fe: 4c0c ldr r4, [pc, #48] ; (8005530 <__libc_init_array+0x44>) - 8005500: f000 f820 bl 8005544 <_init> - 8005504: 1ba4 subs r4, r4, r6 - 8005506: 10a4 asrs r4, r4, #2 - 8005508: 2500 movs r5, #0 - 800550a: 42a5 cmp r5, r4 - 800550c: d105 bne.n 800551a <__libc_init_array+0x2e> - 800550e: bd70 pop {r4, r5, r6, pc} - 8005510: f856 3025 ldr.w r3, [r6, r5, lsl #2] - 8005514: 4798 blx r3 - 8005516: 3501 adds r5, #1 - 8005518: e7ee b.n 80054f8 <__libc_init_array+0xc> - 800551a: f856 3025 ldr.w r3, [r6, r5, lsl #2] - 800551e: 4798 blx r3 - 8005520: 3501 adds r5, #1 - 8005522: e7f2 b.n 800550a <__libc_init_array+0x1e> - 8005524: 0800557c .word 0x0800557c - 8005528: 0800557c .word 0x0800557c - 800552c: 0800557c .word 0x0800557c - 8005530: 08005584 .word 0x08005584 - -08005534 : - 8005534: 4402 add r2, r0 - 8005536: 4603 mov r3, r0 - 8005538: 4293 cmp r3, r2 - 800553a: d100 bne.n 800553e - 800553c: 4770 bx lr - 800553e: f803 1b01 strb.w r1, [r3], #1 - 8005542: e7f9 b.n 8005538 - -08005544 <_init>: - 8005544: b5f8 push {r3, r4, r5, r6, r7, lr} - 8005546: bf00 nop - 8005548: bcf8 pop {r3, r4, r5, r6, r7} - 800554a: bc08 pop {r3} - 800554c: 469e mov lr, r3 - 800554e: 4770 bx lr - -08005550 <_fini>: - 8005550: b5f8 push {r3, r4, r5, r6, r7, lr} - 8005552: bf00 nop - 8005554: bcf8 pop {r3, r4, r5, r6, r7} - 8005556: bc08 pop {r3} - 8005558: 469e mov lr, r3 - 800555a: 4770 bx lr + 8005568: bf00 nop + 800556a: 3710 adds r7, #16 + 800556c: 46bd mov sp, r7 + 800556e: bd80 pop {r7, pc} + +08005570 <__libc_init_array>: + 8005570: b570 push {r4, r5, r6, lr} + 8005572: 4e0d ldr r6, [pc, #52] ; (80055a8 <__libc_init_array+0x38>) + 8005574: 4c0d ldr r4, [pc, #52] ; (80055ac <__libc_init_array+0x3c>) + 8005576: 1ba4 subs r4, r4, r6 + 8005578: 10a4 asrs r4, r4, #2 + 800557a: 2500 movs r5, #0 + 800557c: 42a5 cmp r5, r4 + 800557e: d109 bne.n 8005594 <__libc_init_array+0x24> + 8005580: 4e0b ldr r6, [pc, #44] ; (80055b0 <__libc_init_array+0x40>) + 8005582: 4c0c ldr r4, [pc, #48] ; (80055b4 <__libc_init_array+0x44>) + 8005584: f000 f820 bl 80055c8 <_init> + 8005588: 1ba4 subs r4, r4, r6 + 800558a: 10a4 asrs r4, r4, #2 + 800558c: 2500 movs r5, #0 + 800558e: 42a5 cmp r5, r4 + 8005590: d105 bne.n 800559e <__libc_init_array+0x2e> + 8005592: bd70 pop {r4, r5, r6, pc} + 8005594: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 8005598: 4798 blx r3 + 800559a: 3501 adds r5, #1 + 800559c: e7ee b.n 800557c <__libc_init_array+0xc> + 800559e: f856 3025 ldr.w r3, [r6, r5, lsl #2] + 80055a2: 4798 blx r3 + 80055a4: 3501 adds r5, #1 + 80055a6: e7f2 b.n 800558e <__libc_init_array+0x1e> + 80055a8: 08005600 .word 0x08005600 + 80055ac: 08005600 .word 0x08005600 + 80055b0: 08005600 .word 0x08005600 + 80055b4: 08005608 .word 0x08005608 + +080055b8 : + 80055b8: 4402 add r2, r0 + 80055ba: 4603 mov r3, r0 + 80055bc: 4293 cmp r3, r2 + 80055be: d100 bne.n 80055c2 + 80055c0: 4770 bx lr + 80055c2: f803 1b01 strb.w r1, [r3], #1 + 80055c6: e7f9 b.n 80055bc + +080055c8 <_init>: + 80055c8: b5f8 push {r3, r4, r5, r6, r7, lr} + 80055ca: bf00 nop + 80055cc: bcf8 pop {r3, r4, r5, r6, r7} + 80055ce: bc08 pop {r3} + 80055d0: 469e mov lr, r3 + 80055d2: 4770 bx lr + +080055d4 <_fini>: + 80055d4: b5f8 push {r3, r4, r5, r6, r7, lr} + 80055d6: bf00 nop + 80055d8: bcf8 pop {r3, r4, r5, r6, r7} + 80055da: bc08 pop {r3} + 80055dc: 469e mov lr, r3 + 80055de: 4770 bx lr diff --git a/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.cfg b/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.cfg deleted file mode 100644 index 12d525f..0000000 --- a/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.cfg +++ /dev/null @@ -1,40 +0,0 @@ -# This is an genericBoard board with a single STM32F767ZITx chip -# -# Generated by STM32CubeIDE -# Take care that such file, as generated, may be overridden without any early notice. Please have a look to debug launch configuration setup(s) - -source [find interface/stlink.cfg] - -set WORKAREASIZE 0x8000 - -transport select "hla_swd" - -set CHIPNAME STM32F767ZITx -set BOARDNAME genericBoard - -# Enable debug when in low power modes -set ENABLE_LOW_POWER 1 - -# Stop Watchdog counters when halt -set STOP_WATCHDOG 1 - -# STlink Debug clock frequency -set CLOCK_FREQ 8000 - -# Reset configuration -# use hardware reset, connect under reset -# connect_assert_srst needed if low power mode application running (WFI...) -reset_config srst_only srst_nogate connect_assert_srst -set CONNECT_UNDER_RESET 1 -set CORE_RESET 0 - - - -# BCTM CPU variables - - - -source [find target/stm32f7x.cfg] - - - diff --git a/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.launch b/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.launch deleted file mode 100644 index 4430a2d..0000000 --- a/utils/pid_tuning/otto_pid_tuning/otto_controller_source Debug.launch +++ /dev/null @@ -1,96 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/utils/pid_tuning/pid_tuning.py b/utils/pid_tuning/pid_tuning.py index ccf9180..21af19a 100644 --- a/utils/pid_tuning/pid_tuning.py +++ b/utils/pid_tuning/pid_tuning.py @@ -7,12 +7,20 @@ ser = serial.Serial( bytesize=serial.EIGHTBITS, rtscts=False) pid_select = float(input("Enter 1 for left tuning, 2 for right tuning, 3 for cross tuning: ")) -pid_setpoint = float(input("Enter the setpoint: ")) +if (pid_select == 3): + pid_lin_vel = float(input("Enter the linear velocity setpoint: ")) + pid_ang_vel = float(input("Enter the angular velocity setpoint: ")) + pid_fixed_setpoint = 0 +else: + pid_fixed_setpoint = float(input("Enter the setpoint: ")) + pid_lin_vel = 0 + pid_ang_vel = 0 kp = float(input("Enter kp: ")) ki = float(input("Enter ki: ")) kd = float(input("Enter kd: ")) -msg_output = struct.pack('