当前位置: 首页 > news >正文

PID控制电机

电调是c620,电机是M3508

源码看的中科大开源的,b站评论有链接

准备工作

首先明白pid控制电机恒速转动是通过控制电流,也就是PID计算函数的计算结果是电流

其次,明确工作流程

1.CAN接收电调反馈报文得到当前的转速

2.根据当前转速计算pid得到电流

3.CAN发送电调接收报文控制电流,进而控制转速

所需函数

首先肯定是pid结构体的定义和初始化以及计算

typedef struct {int16_t Kp, Ki, Kd;        // PID参数int16_t setpoint;         // 目标转速int16_t current;          // 当前转速int32_t integral;         // 积分项int16_t prev_error;       // 上一次误差int16_t output_limit;     // 输出限幅int32_t integral_limit;   // 积分限幅
} PID_HandleTypeDef;PID_HandleTypeDef pid_motor;
void PID_Init(void) {pid_motor.Kp = 100;       // 调整后的比例系数pid_motor.Ki = 5;         // 调整后的积分系数pid_motor.Kd = 10;        // 调整后的微分系数pid_motor.setpoint = 100; // 目标转速pid_motor.current = 0;pid_motor.integral = 0;pid_motor.prev_error = 0;pid_motor.output_limit = 10000;  // 电流限幅pid_motor.integral_limit = 5000; // 积分限幅
}
int16_t PID_Calculate(PID_HandleTypeDef *pid, int16_t current_speed) {int16_t error = pid->setpoint - current_speed;int32_t derivative;int32_t output;// 积分项计算与限幅pid->integral += error;if (pid->integral > pid->integral_limit) pid->integral = pid->integral_limit;if (pid->integral < -pid->integral_limit) pid->integral = -pid->integral_limit;// 微分项计算derivative = error - pid->prev_error;pid->prev_error = error;// 输出计算与限幅output = (pid->Kp * error) + (pid->Ki * pid->integral) + (pid->Kd * derivative);if (output > pid->output_limit) output = pid->output_limit;if (output < -pid->output_limit) output = -pid->output_limit;return (int16_t)output;
}

其次是CAN通信的发送和接收

//CAN的使能中断
void CAN_Init(CAN_HandleTypeDef *hcan) {HAL_CAN_Start(hcan);__HAL_CAN_ENABLE_IT(hcan, CAN_IT_RX_FIFO1_MSG_PENDING);}
// CAN发送函数
void Motor_SendCurrent(CAN_HandleTypeDef *hcan, int16_t current) {CAN_TxHeaderTypeDef tx_header;uint8_t tx_data[8] = {0};uint32_t tx_mailbox;tx_header.StdId = 0x200;tx_header.IDE = CAN_ID_STD;tx_header.RTR = CAN_RTR_DATA;tx_header.DLC = 8;// 正确的小端有符号格式tx_data[0] = current & 0xFF;        // 低字节tx_data[1] = (current >> 8) & 0xFF; // 高字节HAL_CAN_AddTxMessage(hcan, &tx_header, tx_data, &tx_mailbox);
}
//配置滤波器
HAL_StatusTypeDef CAN_Filter_Mask_Config(CAN_HandleTypeDef *hcan, uint32_t FilterBank, uint32_t FIFO, uint8_t IsExtended, uint32_t ID, uint32_t Mask)
{CAN_FilterTypeDef sFilterConfig;// 基本配置sFilterConfig.FilterBank = FilterBank;sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;      // 掩码模式sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;    // 32位滤波sFilterConfig.FilterFIFOAssignment = FIFO;sFilterConfig.FilterActivation = CAN_FILTER_ENABLE;   // 启用滤波器// 标准帧配置if (IsExtended == 0) {// 标准帧ID(11位)sFilterConfig.FilterIdHigh = (ID & 0x7FF) << 5;   // 标准ID放入高16位sFilterConfig.FilterIdLow = 0;                    // 低16位不用sFilterConfig.FilterMaskIdHigh = (Mask << 5);     // 掩码高16位sFilterConfig.FilterMaskIdLow = 0;                // 掩码低16位}// 扩展帧配置else {// 扩展帧ID(29位)sFilterConfig.FilterIdHigh = (ID >> 13);          // 高16位sFilterConfig.FilterIdLow = ((ID & 0x1FFF) << 3) | CAN_ID_EXT;  // 低16位+扩展帧标志sFilterConfig.FilterMaskIdHigh = (Mask >> 13);    // 掩码高16位sFilterConfig.FilterMaskIdLow = (Mask & 0x1FFF) << 3;  // 掩码低16位}// 应用配置return HAL_CAN_ConfigFilter(hcan, &sFilterConfig);
}
// CAN接收回调void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) {CAN_RxHeaderTypeDef header;uint8_t data[8];HAL_CAN_GetRxMessage(hcan, CAN_FILTER_FIFO1, &header, data);if (header.StdId == 0x201) {// 小端格式解析 (data[2]是低字节)int16_t speed = (data[3] << 8) | data[2];pid_motor.current = speed;}
}

其次是定时器的中断,pid除了有关计算的以外,还需要采样时间,这里使用定时器

void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {if (htim->Instance == TIM2) {// 计算PID输出int16_t current_cmd = PID_Calculate(&pid_motor, pid_motor.current);// 发送电流指令Motor_SendCurrent(&hcan1, current_cmd);}
}

整体代码

/* USER CODE BEGIN Header */
/********************************************************************************* @file           : main.c* @brief          : Main program body******************************************************************************* @attention** Copyright (c) 2025 STMicroelectronics.* All rights reserved.** This software is licensed under terms that can be found in the LICENSE file* in the root directory of this software component.* If no LICENSE file comes with this software, it is provided AS-IS.********************************************************************************/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "can.h"
#include "dma.h"
#include "tim.h"
#include "usart.h"
#include "gpio.h"
#include "stdio.h"/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes *//* USER CODE END Includes *//* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD *//* USER CODE END PTD *//* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD *//* USER CODE END PD *//* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM *//* USER CODE END PM *//* Private variables ---------------------------------------------------------*//* USER CODE BEGIN PV *//* USER CODE END PV *//* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP *//* USER CODE END PFP *//* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 *///定义PID结构体
typedef struct {int16_t Kp, Ki, Kd;        // PID参数int16_t setpoint;         // 目标转速int16_t current;          // 当前转速int32_t integral;         // 积分项int16_t prev_error;       // 上一次误差int16_t output_limit;     // 输出限幅int32_t integral_limit;   // 积分限幅
} PID_HandleTypeDef;PID_HandleTypeDef pid_motor;//CAN的使能中断
void CAN_Init(CAN_HandleTypeDef *hcan) {HAL_CAN_Start(hcan);__HAL_CAN_ENABLE_IT(hcan, CAN_IT_RX_FIFO1_MSG_PENDING);}// CAN发送函数
void Motor_SendCurrent(CAN_HandleTypeDef *hcan, int16_t current) {CAN_TxHeaderTypeDef tx_header;uint8_t tx_data[8] = {0};uint32_t tx_mailbox;tx_header.StdId = 0x200;tx_header.IDE = CAN_ID_STD;tx_header.RTR = CAN_RTR_DATA;tx_header.DLC = 8;// 正确的小端有符号格式tx_data[0] = current & 0xFF;        // 低字节tx_data[1] = (current >> 8) & 0xFF; // 高字节HAL_CAN_AddTxMessage(hcan, &tx_header, tx_data, &tx_mailbox);
}
// 初始化PID
void PID_Init(void) {pid_motor.Kp = 100;       // 调整后的比例系数pid_motor.Ki = 5;         // 调整后的积分系数pid_motor.Kd = 10;        // 调整后的微分系数pid_motor.setpoint = 100; // 目标转速pid_motor.current = 0;pid_motor.integral = 0;pid_motor.prev_error = 0;pid_motor.output_limit = 10000;  // 电流限幅pid_motor.integral_limit = 5000; // 积分限幅
}// PID计算函数
int16_t PID_Calculate(PID_HandleTypeDef *pid, int16_t current_speed) {int16_t error = pid->setpoint - current_speed;int32_t derivative;int32_t output;// 积分项计算与限幅pid->integral += error;if (pid->integral > pid->integral_limit) pid->integral = pid->integral_limit;if (pid->integral < -pid->integral_limit) pid->integral = -pid->integral_limit;// 微分项计算derivative = error - pid->prev_error;pid->prev_error = error;// 输出计算与限幅output = (pid->Kp * error) + (pid->Ki * pid->integral) + (pid->Kd * derivative);if (output > pid->output_limit) output = pid->output_limit;if (output < -pid->output_limit) output = -pid->output_limit;return (int16_t)output;
}// CAN接收回调void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) {CAN_RxHeaderTypeDef header;uint8_t data[8];HAL_CAN_GetRxMessage(hcan, CAN_FILTER_FIFO1, &header, data);if (header.StdId == 0x201) {// 小端格式解析 (data[2]是低字节)int16_t speed = (data[3] << 8) | data[2];pid_motor.current = speed;}
}void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {if (htim->Instance == TIM2) {// 计算PID输出int16_t current_cmd = PID_Calculate(&pid_motor, pid_motor.current);// 发送电流指令Motor_SendCurrent(&hcan1, current_cmd);}
}//void CAN_Init(CAN_HandleTypeDef *hcan)
//{
//  HAL_CAN_Start(hcan);
//  __HAL_CAN_ENABLE_IT(hcan, CAN_IT_RX_FIFO1_MSG_PENDING);
//}//typedef struct{
//	int E_P,E_I,E_D;
//}Error;
当前的E和上一次的E
//Error N_E,L_E;
依次表示当前转速,目标转速和电流
//uint16_t N_Value=0,T_Value=1000,C_Value;
PID的三个参数
//uint16_t K_P=100,K_I=0,K_D=0;
接收数组
//uint8_t CAN1_0x200_Tx_Data[8];
Error的设置,在CAN的接收回调里使用
//void E_Set(uint16_t N_Value,uint16_t T_Value)
//{
//	//赋值
//	N_E.E_P=T_Value-N_Value;
//	N_E.E_I=N_E.E_P+L_E.E_I;
//	N_E.E_D=N_E.E_P-L_E.E_P;
//	//更换
//	L_E.E_P=N_E.E_P;
//	L_E.E_I=N_E.E_I;
//	L_E.E_D=N_E.E_D;
//	
//}
发送数组
//uint8_t CAN_Send_Data(CAN_HandleTypeDef *hcan, uint16_t ID, uint8_t *Data, uint16_t Length)
//{
//  CAN_TxHeaderTypeDef tx_header;
//  uint32_t used_mailbox;
// 
//  // 检测关键传参
//  assert_param(hcan != NULL);
// 
//  tx_header.StdId = ID;
//  tx_header.ExtId = 0;
//  tx_header.IDE = 0;
//  tx_header.RTR = 0;
//  tx_header.DLC = Length;
// 
//  return (HAL_CAN_AddTxMessage(hcan, &tx_header, Data, &used_mailbox));
//}
//配置滤波器
HAL_StatusTypeDef CAN_Filter_Mask_Config(CAN_HandleTypeDef *hcan, uint32_t FilterBank, uint32_t FIFO, uint8_t IsExtended, uint32_t ID, uint32_t Mask)
{CAN_FilterTypeDef sFilterConfig;// 基本配置sFilterConfig.FilterBank = FilterBank;sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;      // 掩码模式sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;    // 32位滤波sFilterConfig.FilterFIFOAssignment = FIFO;sFilterConfig.FilterActivation = CAN_FILTER_ENABLE;   // 启用滤波器// 标准帧配置if (IsExtended == 0) {// 标准帧ID(11位)sFilterConfig.FilterIdHigh = (ID & 0x7FF) << 5;   // 标准ID放入高16位sFilterConfig.FilterIdLow = 0;                    // 低16位不用sFilterConfig.FilterMaskIdHigh = (Mask << 5);     // 掩码高16位sFilterConfig.FilterMaskIdLow = 0;                // 掩码低16位}// 扩展帧配置else {// 扩展帧ID(29位)sFilterConfig.FilterIdHigh = (ID >> 13);          // 高16位sFilterConfig.FilterIdLow = ((ID & 0x1FFF) << 3) | CAN_ID_EXT;  // 低16位+扩展帧标志sFilterConfig.FilterMaskIdHigh = (Mask >> 13);    // 掩码高16位sFilterConfig.FilterMaskIdLow = (Mask & 0x1FFF) << 3;  // 掩码低16位}// 应用配置return HAL_CAN_ConfigFilter(hcan, &sFilterConfig);
}
// //接受回调函数
//void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan)
//{
//  CAN_RxHeaderTypeDef header;
//  uint8_t data[8];
//  HAL_CAN_GetRxMessage(hcan, CAN_FILTER_FIFO1, &header, data);
//	//2和3对应转速的高低八位
//	N_Value=(data[2]<<8)|data[3];
//	E_Set(N_Value,T_Value);
//	
//}/* USER CODE END 0 *//*** @brief  The application entry point.* @retval int*/
int main(void)
{/* USER CODE BEGIN 1 *//* USER CODE END 1 *//* MCU Configuration--------------------------------------------------------*//* Reset of all peripherals, Initializes the Flash interface and the Systick. */HAL_Init();/* USER CODE BEGIN Init *//* USER CODE END Init *//* Configure the system clock */SystemClock_Config();/* USER CODE BEGIN SysInit *//* USER CODE END SysInit *//* Initialize all configured peripherals */MX_GPIO_Init();MX_DMA_Init();MX_CAN1_Init();MX_USART1_UART_Init();MX_TIM2_Init();/* USER CODE BEGIN 2 */// 修正滤波器配置CAN_Filter_Mask_Config(&hcan1, 10, CAN_FILTER_FIFO1, 0, 0x201 << 5, 0x7FF << 5);PID_Init();CAN_Init(&hcan1);HAL_TIM_Base_Start_IT(&htim2);/* USER CODE END 2 *//* Infinite loop *//* USER CODE BEGIN WHILE */while (1){/* USER CODE END WHILE *//* USER CODE BEGIN 3 */}/* USER CODE END 3 */
}/*** @brief System Clock Configuration* @retval None*/
void SystemClock_Config(void)
{RCC_OscInitTypeDef RCC_OscInitStruct = {0};RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};/** Configure the main internal regulator output voltage*/__HAL_RCC_PWR_CLK_ENABLE();__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);/** Initializes the RCC Oscillators according to the specified parameters* in the RCC_OscInitTypeDef structure.*/RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;RCC_OscInitStruct.HSEState = RCC_HSE_ON;RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;RCC_OscInitStruct.PLL.PLLM = 4;RCC_OscInitStruct.PLL.PLLN = 168;RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;RCC_OscInitStruct.PLL.PLLQ = 4;if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK){Error_Handler();}/** Initializes the CPU, AHB and APB buses clocks*/RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK){Error_Handler();}
}/* USER CODE BEGIN 4 *//* USER CODE END 4 *//*** @brief  This function is executed in case of error occurrence.* @retval None*/
void Error_Handler(void)
{/* USER CODE BEGIN Error_Handler_Debug *//* User can add his own implementation to report the HAL error return state */__disable_irq();while (1){}/* USER CODE END Error_Handler_Debug */
}#ifdef  USE_FULL_ASSERT
/*** @brief  Reports the name of the source file and the source line number*         where the assert_param error has occurred.* @param  file: pointer to the source file name* @param  line: assert_param error line source number* @retval None*/
void assert_failed(uint8_t *file, uint32_t line)
{/* USER CODE BEGIN 6 *//* User can add his own implementation to report the file name and line number,ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) *//* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

源码的解读

我只会c的语言基础,这个源码也是看的云里雾里,只是大致理解

alg_pid.cpp里是pid的初始化,和部分结构体内部变量的get和set函数,void Class_PID::TIM_Adjust_PeriodElapsedCallback()是pid计算函数

/* USER CODE BEGIN Header */
/********************************************************************************* @file           : main.c* @brief          : Main program body******************************************************************************* @attention** Copyright (c) 2023 STMicroelectronics.* All rights reserved.** This software is licensed under terms that can be found in the LICENSE file* in the root directory of this software component.* If no LICENSE file comes with this software, it is provided AS-IS.********************************************************************************/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "can.h"
#include "dma.h"
#include "usart.h"
#include "gpio.h"/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */#include "drv_bsp.h"
#include "drv_can.h"#include "alg_pid.h"#include "dvc_serialplot.h"/* USER CODE END Includes *//* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD *//* USER CODE END PTD *//* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD *//* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM *//* USER CODE END PM *//* Private variables ---------------------------------------------------------*//* USER CODE BEGIN PV */Class_Serialplot serialplot;
Class_PID pid_omega;int16_t Rx_Encoder, Rx_Omega, Rx_Torque, Rx_Temperature;
float Now_Omega, Target_Omega = 50.0f * PI;
uint32_t Counter = 0;
int32_t Output;static char Variable_Assignment_List[][SERIALPLOT_RX_VARIABLE_ASSIGNMENT_MAX_LENGTH] = {//电机调PID"po","io","do",
};/* USER CODE END PV *//* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP *//* USER CODE END PFP *//* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 *//*** @brief CAN报文回调函数** @param Rx_Buffer CAN接收的信息结构体
接收了电调反馈报文的全部内容 Buffer是缓冲区就是个数组*/
void CAN_Motor_Call_Back(Struct_CAN_Rx_Buffer *Rx_Buffer)
{uint8_t *Rx_Data = Rx_Buffer->Data;switch (Rx_Buffer->Header.StdId){//相比第七次培训修改了CANID适配case (0x201):{Rx_Encoder = (Rx_Data[0] << 8) | Rx_Data[1];Rx_Omega = (Rx_Data[2] << 8) | Rx_Data[3];Rx_Torque = (Rx_Data[4] << 8) | Rx_Data[5];Rx_Temperature = Rx_Data[6];}break;}
}/*** @brief HAL库UART接收DMA空闲中断** @param huart UART编号* @param Size 长度
串口显示,并通过电脑进行pid的设置*/
void UART_Serialplot_Call_Back(uint8_t *Buffer, uint16_t Length)
{serialplot.UART_RxCpltCallback(Buffer);switch (serialplot.Get_Variable_Index()){// 电机调PIDcase(0):{pid_omega.Set_K_P(serialplot.Get_Variable_Value());}break;case(1):{pid_omega.Set_K_I(serialplot.Get_Variable_Value());}break;case(2):{pid_omega.Set_K_D(serialplot.Get_Variable_Value());}break;}
}/* USER CODE END 0 *//*** @brief  The application entry point.* @retval int*/
int main(void)
{/* USER CODE BEGIN 1 *//* USER CODE END 1 *//* MCU Configuration--------------------------------------------------------*//* Reset of all peripherals, Initializes the Flash interface and the Systick. */HAL_Init();/* USER CODE BEGIN Init *//* USER CODE END Init *//* Configure the system clock */SystemClock_Config();/* USER CODE BEGIN SysInit *//* USER CODE END SysInit *//* Initialize all configured peripherals */MX_GPIO_Init();MX_DMA_Init();MX_CAN1_Init();MX_USART2_UART_Init();/* USER CODE BEGIN 2 */BSP_Init(BSP_DC24_LU_ON | BSP_DC24_LD_ON | BSP_DC24_RU_ON | BSP_DC24_RD_ON);CAN_Init(&hcan1, CAN_Motor_Call_Back);//相比第七次培训修改了接收字典列表指针UART_Init(&huart2, UART_Serialplot_Call_Back, SERIALPLOT_RX_VARIABLE_ASSIGNMENT_MAX_LENGTH);//相比第七次培训修改了CANID适配, 另外ID和掩码改成0表示所有包均接收不进行过滤CAN_Filter_Mask_Config(&hcan1, CAN_FILTER(0) | CAN_FIFO_1 | CAN_STDID | CAN_DATA_TYPE, 0, 0);pid_omega.Init(0.0f, 0.0f, 0.0f, 0.0f, 2500.0f, 2500.0f);serialplot.Init(&huart2, 3, (char **)Variable_Assignment_List);/* USER CODE END 2 *//* Infinite loop *//* USER CODE BEGIN WHILE */while (1){//如果计时到2000ms就换一个目标值Counter++;if(Counter >= 2000){Counter = 0;if(Target_Omega == 50.0f * PI){Target_Omega = 100.0f * PI;}else if(Target_Omega == 100.0f * PI){Target_Omega = 50.0f * PI;}}//串口绘图显示内容Now_Omega = Rx_Omega * 2.0f * PI / 60.0f;serialplot.Set_Data(2, &Now_Omega, &Target_Omega);//相比第七次培训修改了函数名, 以便适配新的开发库serialplot.TIM_Write_PeriodElapsedCallback();TIM_UART_PeriodElapsedCallback();//PID相关计算内容pid_omega.Set_Target(Target_Omega);pid_omega.Set_Now(Now_Omega);pid_omega.TIM_Adjust_PeriodElapsedCallback();Output = pid_omega.Get_Out();//输出数据到电机CAN1_0x200_Tx_Data[0] = Output >> 8;CAN1_0x200_Tx_Data[1] = Output;CAN_Send_Data(&hcan1, 0x200, CAN1_0x200_Tx_Data, 8);//延时1msHAL_Delay(0);/* USER CODE END WHILE *//* USER CODE BEGIN 3 */}/* USER CODE END 3 */
}/*** @brief System Clock Configuration* @retval None*/
void SystemClock_Config(void)
{RCC_OscInitTypeDef RCC_OscInitStruct = {0};RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};/** Configure the main internal regulator output voltage*/__HAL_RCC_PWR_CLK_ENABLE();__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);/** Initializes the RCC Oscillators according to the specified parameters* in the RCC_OscInitTypeDef structure.*/RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;RCC_OscInitStruct.HSEState = RCC_HSE_ON;RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;RCC_OscInitStruct.PLL.PLLM = 6;RCC_OscInitStruct.PLL.PLLN = 180;RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;RCC_OscInitStruct.PLL.PLLQ = 4;if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK){Error_Handler();}/** Activate the Over-Drive mode*/if (HAL_PWREx_EnableOverDrive() != HAL_OK){Error_Handler();}/** Initializes the CPU, AHB and APB buses clocks*/RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK){Error_Handler();}
}/* USER CODE BEGIN 4 *//* USER CODE END 4 *//*** @brief  This function is executed in case of error occurrence.* @retval None*/
void Error_Handler(void)
{/* USER CODE BEGIN Error_Handler_Debug *//* User can add his own implementation to report the HAL error return state */__disable_irq();while (1){}/* USER CODE END Error_Handler_Debug */
}#ifdef USE_FULL_ASSERT
/*** @brief  Reports the name of the source file and the source line number*         where the assert_param error has occurred.* @param  file: pointer to the source file name* @param  line: assert_param error line source number* @retval None*/
void assert_failed(uint8_t *file, uint32_t line)
{/* USER CODE BEGIN 6 *//* User can add his own implementation to report the file name and line number,ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) *//* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

相关文章:

  • springboot入门之路(二)
  • 技术赋能教师专业发展:从理论到实践的深度剖析
  • createInnerAudioContext播放不完整?
  • 榕壹云外卖跑腿系统:基于Spring Boot的开源生活服务平台技术解析
  • STM32 GPIO 寄存器开发
  • OCCT基础类库介绍:Modeling Algorithm - Topological Tools
  • 今天我想清楚了
  • 无需公网IP:Termux+手机+内网穿透实现Minecraft远程多人联机
  • 基于大数据技术的在UGC数据分析与路线推荐的研究
  • ArcGIS中利用泰森多边形法分析站点与流域占比
  • VTK知识学习(54)- 交互与Widget(五)
  • ES 索引加载 vs BulkLoad
  • function ‘as_cholmod_sparse‘ not provided by package ‘Matrix‘
  • FreeCAD创作参数化凹形和水波纹式雨水箅子
  • 意法STM32F103C8T6 单片机ARM Cortex-M3 国民MCU 电机控制到物联网专用
  • Windows系统提示“mfc140u.dll丢失”?详细修复指南,一键恢复程序运行!
  • 智能制造——解读 51页制造业数据治理主数据管理系统建设方案【附全文阅读】
  • 从零Gazebo中实现Cartographer算法建图(新目录)
  • 如何使用 mkimage 工具生成 uImage 文件(RISC-V 环境)
  • 使用 Rust Clippy 的详细方案
  • 门户网站建设意见/发软文是什么意思
  • 如何查看百度蜘蛛来过网站/北京网站制作400办理多少钱
  • wordpress 友言/徐州关键词优化排名
  • 东软实训网站开发/免费的网站申请
  • phpweb手机网站程序/seo网站排名优化服务
  • 网站注册搜索引擎的目的/网站关键字优化公司