之前有个应用想控制一个真空泵来着,需要略微的调速并且保持稳定,正好本次拿到了这个小开发板,就准备试试,好的话以后可以使用它干点商品,话不多说,说一下大体思路,
基于STM32生态良好的开发工具包,cube里提供了很多范例,所以快速开发还得是借用cube的快速配置,使用cube样例程序包里的定时器输入捕获程序使用TIM1作为采样频率计进行采样hall信号,获得pid的current参数,使用TIM PWM out程序作为PWM输出部分,给无刷驱动版提供PWM(PS:由于样例程序PWM信号只有100Hz,所以手动调整了样例程序使其达到1000Hz)
至于TIM14,设置成一秒100次中断(使用cube快速设置分频和重装值)每次中断进行pid的输出来修正电机。
void TimerUpdate_Callback(void)
{
aa++;
if(pid_motor.target>0){
PID_Execute(&pid_motor);
DutyCycle-=pid_motor.out;
if(DutyCycle>100)DutyCycle=100;
if(DutyCycle<0)DutyCycle=0;
Configure_DutyCycle(DutyCycle);
}else{
PID_Reset(&pid_motor);
Configure_DutyCycle(0);
}
}本次控制的是一个无刷电机,所以就可以通过PWM控制并且反馈信号可以取的无刷电机的hall传感器来进行pid调速(实际上只是PI,调参数太麻了,调不动了,只是调电机不带负载那酸爽你懂得)
话不多说,上图和代码吧
可以看到tim3的输出通道接在了电机驱动板的pwm in,tim1的输入捕获通道接在了电机的一路hall,按键里面设置了十组转速,可以通过按键进行循环调速。
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file Examples_LL/TIM/TIM_PWMOutput_Init/Src/main.c
* @author MCD Application Team
* @brief This example describes how to use a timer peripheral to generate a
* PWM output signal and update PWM duty cycle.
* Peripheral initialization done using LL initialization function.
******************************************************************************
* @attention
*
* Copyright (c) 2022 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"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
typedef struct{
double kp;
double ki;
double kd;
double current;
double target;
double ival;
double ilim;
double error;
double last_error;
double out;
} PID_DataTypeDef;
void PID_Execute(PID_DataTypeDef * pid);
void PID_Reset(PID_DataTypeDef * pid);
void PID_Execute(PID_DataTypeDef * pid){
pid->error = pid->current - pid->target;
pid->ival += pid->error;
// Anti-windup integral processing
if(pid->ival > 0){
if(pid->ival > pid->ilim) pid->ival = pid->ilim;
}
else{
if(pid->ival < -(pid->ilim)) pid->ival = -(pid->ilim);
}
pid->out = (
pid->kp * pid->error
+ pid->ki * pid->ival
+ pid->kd * (pid->error - pid->last_error)
);
pid->last_error = pid->error;
}
void PID_Reset(PID_DataTypeDef * pid){
pid->error = 0;
pid->last_error = 0;
pid->ival = 0;
}
PID_DataTypeDef pid_motor;
uint32_t DutyCycle=0;
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* Number of output compare modes */
#define TIM_DUTY_CYCLES_NB 11
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim14;
UART_HandleTypeDef huart2;
/* USER CODE BEGIN PV */
/* Duty cycles: D = T/P * 100% */
/* where T is the pulse duration and P the period of the PWM signal */
static uint32_t aDutyCycle[TIM_DUTY_CYCLES_NB] = {
0, /* 0% */
70, /* 10% */
71, /* 20% */
72, /* 30% */
73, /* 40% */
74, /* 50% */
75, /* 60% */
76, /* 70% */
77, /* 80% */
78, /* 90% */
79, /* 100% */
};
/* Duty cycle index */
static uint8_t iDutyCycle = 0;
/* Measured duty cycle */
__IO uint32_t uwMeasuredDutyCycle = 0;
/* Measured frequency */
__IO uint32_t uwMeasuredFrequency = 0;
/* TIM2 Clock */
static uint32_t TimOutClock = 1;
uint32_t timxPrescaler = 0;
uint32_t timxPeriod = 0;
uint32_t aa=0;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_TIM3_Init(void);
static void MX_USART2_UART_Init(void);
static void MX_TIM1_Init(void);
static void MX_TIM14_Init(void);
/* USER CODE BEGIN PFP */
__STATIC_INLINE void Configure_DutyCycle(uint32_t D);
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
// PID controllers
pid_motor.kp = 0.4;
pid_motor.ki = 0.007;
pid_motor.kd = 0;
pid_motor.ilim = 2000;
/* 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 */
/* - Set the pre-scaler value to have TIM3 counter clock equal to 10 kHz */
/* - Set the auto-reload value to have a counter frequency of 100 Hz */
/* TIM3CLK = SystemCoreClock / (APB prescaler & multiplier) */
TimOutClock = SystemCoreClock/1;
timxPrescaler = __LL_TIM_CALC_PSC(SystemCoreClock, 10000);
timxPeriod = __LL_TIM_CALC_ARR(TimOutClock, timxPrescaler, 1000);
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_TIM3_Init();
MX_USART2_UART_Init();
MX_TIM1_Init();
MX_TIM14_Init();
/* USER CODE BEGIN 2 */
/**************************/
/* TIM1 interrupts set-up */
/**************************/
/* Enable the capture/compare interrupt for channel 1 */
LL_TIM_EnableIT_CC1(TIM1);
/***********************/
/* Start input capture */
/***********************/
/* Enable input channel 1 */
LL_TIM_CC_EnableChannel(TIM1, LL_TIM_CHANNEL_CH1);
/* Enable counter */
LL_TIM_EnableCounter(TIM1);//----
/**************************/
/* TIM14 interrupts set-up */
/**************************/
/* Enable the capture/compare interrupt for channel 1 */
LL_TIM_ClearFlag_UPDATE(TIM14);
/* Enable the update interrupt */
LL_TIM_EnableIT_UPDATE(TIM14);
/* Enable counter */
LL_TIM_EnableCounter(TIM14);
/**************************/
/* TIM3 interrupts set-up */
/**************************/
/* Enable the capture/compare interrupt for channel 1 */
LL_TIM_EnableIT_CC1(TIM3);
/**********************************/
/* Start output signal generation */
/**********************************/
/* Enable output channel 1 */
LL_TIM_CC_EnableChannel(TIM3, LL_TIM_CHANNEL_CH1);
/* Enable counter */
LL_TIM_EnableCounter(TIM3);
/* Force update generation */
LL_TIM_GenerateEvent_UPDATE(TIM3);
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
uint8_t a=0;
uint8_t b[4];
while (1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
LL_FLASH_SetLatency(LL_FLASH_LATENCY_1);
/* HSI configuration and activation */
LL_RCC_HSI_Enable();
while(LL_RCC_HSI_IsReady() != 1)
{
}
LL_RCC_HSI_SetCalibTrimming(64);
LL_RCC_SetHSIDiv(LL_RCC_HSI_DIV_1);
/* Set AHB prescaler*/
LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1);
/* Sysclk activation on the HSI */
LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_HSI);
while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_HSI)
{
}
/* Set APB1 prescaler*/
LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1);
/* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
LL_SetSystemCoreClock(48000000);
/* Update the time base */
if (HAL_InitTick (TICK_INT_PRIORITY) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief TIM1 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM1_Init(void)
{
/* USER CODE BEGIN TIM1_Init 0 */
/* USER CODE END TIM1_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_IC_InitTypeDef sConfigIC = {0};
/* USER CODE BEGIN TIM1_Init 1 */
/* USER CODE END TIM1_Init 1 */
htim1.Instance = TIM1;
htim1.Init.Prescaler = 2000;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 65535;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Init.RepetitionCounter = 0;
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_IC_Init(&htim1) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
sConfigIC.ICSelection = TIM_ICSELECTION_DIRECTTI;
sConfigIC.ICPrescaler = TIM_ICPSC_DIV1;
sConfigIC.ICFilter = 0;
if (HAL_TIM_IC_ConfigChannel(&htim1, &sConfigIC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM1_Init 2 */
/* USER CODE END TIM1_Init 2 */
}
/**
* @brief TIM3 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM3_Init(void)
{
/* USER CODE BEGIN TIM3_Init 0 */
/* USER CODE END TIM3_Init 0 */
LL_TIM_InitTypeDef TIM_InitStruct = {0};
LL_TIM_OC_InitTypeDef TIM_OC_InitStruct = {0};
LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
/* Peripheral clock enable */
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM3);
/* TIM3 interrupt Init */
NVIC_SetPriority(TIM3_IRQn, 0);
NVIC_EnableIRQ(TIM3_IRQn);
/* USER CODE BEGIN TIM3_Init 1 */
/* USER CODE END TIM3_Init 1 */
TIM_InitStruct.Prescaler = timxPrescaler;
TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
TIM_InitStruct.Autoreload = timxPeriod;
TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
LL_TIM_Init(TIM3, &TIM_InitStruct);
LL_TIM_EnableARRPreload(TIM3);
LL_TIM_OC_EnablePreload(TIM3, LL_TIM_CHANNEL_CH1);
TIM_OC_InitStruct.OCMode = LL_TIM_OCMODE_PWM1;
TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
TIM_OC_InitStruct.CompareValue = ((timxPeriod + 1 ) / 2);
TIM_OC_InitStruct.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
LL_TIM_OC_Init(TIM3, LL_TIM_CHANNEL_CH1, &TIM_OC_InitStruct);
LL_TIM_OC_DisableFast(TIM3, LL_TIM_CHANNEL_CH1);
LL_TIM_SetTriggerOutput(TIM3, LL_TIM_TRGO_RESET);
LL_TIM_DisableMasterSlaveMode(TIM3);
/* USER CODE BEGIN TIM3_Init 2 */
/* USER CODE END TIM3_Init 2 */
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
/**TIM3 GPIO Configuration
PA6 ------> TIM3_CH1
*/
GPIO_InitStruct.Pin = TIM3_CH1_Pin;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_DOWN;
GPIO_InitStruct.Alternate = LL_GPIO_AF_1;
LL_GPIO_Init(TIM3_CH1_GPIO_Port, &GPIO_InitStruct);
}
/**
* @brief TIM14 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM14_Init(void)
{
/* USER CODE BEGIN TIM14_Init 0 */
/* USER CODE END TIM14_Init 0 */
/* USER CODE BEGIN TIM14_Init 1 */
/* USER CODE END TIM14_Init 1 */
htim14.Instance = TIM14;
htim14.Init.Prescaler = 4799;
htim14.Init.CounterMode = TIM_COUNTERMODE_UP;
htim14.Init.Period = 99;
htim14.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim14.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim14) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM14_Init 2 */
/* USER CODE END TIM14_Init 2 */
}
/**
* @brief USART2 Initialization Function
* @param None
* @retval None
*/
static void MX_USART2_UART_Init(void)
{
/* USER CODE BEGIN USART2_Init 0 */
/* USER CODE END USART2_Init 0 */
/* USER CODE BEGIN USART2_Init 1 */
/* USER CODE END USART2_Init 1 */
huart2.Instance = USART2;
huart2.Init.BaudRate = 115200;
huart2.Init.WordLength = UART_WORDLENGTH_8B;
huart2.Init.StopBits = UART_STOPBITS_1;
huart2.Init.Parity = UART_PARITY_NONE;
huart2.Init.Mode = UART_MODE_TX_RX;
huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart2.Init.OverSampling = UART_OVERSAMPLING_16;
huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart2.Init.ClockPrescaler = UART_PRESCALER_DIV1;
huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART2_Init 2 */
/* USER CODE END USART2_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
LL_EXTI_InitTypeDef EXTI_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */
/* GPIO Ports Clock Enable */
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOC);
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
/**/
LL_EXTI_SetEXTISource(LL_EXTI_CONFIG_PORTC, LL_EXTI_CONFIG_LINE13);
/**/
EXTI_InitStruct.Line_0_31 = LL_EXTI_LINE_13;
EXTI_InitStruct.LineCommand = ENABLE;
EXTI_InitStruct.Mode = LL_EXTI_MODE_IT;
EXTI_InitStruct.Trigger = LL_EXTI_TRIGGER_FALLING;
LL_EXTI_Init(&EXTI_InitStruct);
/**/
LL_GPIO_SetPinPull(USER_BUTTON_GPIO_Port, USER_BUTTON_Pin, LL_GPIO_PULL_UP);
/**/
LL_GPIO_SetPinMode(USER_BUTTON_GPIO_Port, USER_BUTTON_Pin, LL_GPIO_MODE_INPUT);
/* EXTI interrupt init*/
NVIC_SetPriority(EXTI4_15_IRQn, 0);
NVIC_EnableIRQ(EXTI4_15_IRQn);
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}
/* USER CODE BEGIN 4 */
/**
* @brief Changes the duty cycle of the PWM signal.
* D = (T/P)*100
* where T is the pulse duration and P is the PWM signal period
* @param D Duty cycle
* @retval None
*/
__STATIC_INLINE void Configure_DutyCycle(uint32_t D)
{
uint32_t P; /* Pulse duration */
uint32_t T; /* PWM signal period */
/* PWM signal period is determined by the value of the auto-reload register */
T = LL_TIM_GetAutoReload(TIM3) + 1;
/* Pulse duration is determined by the value of the compare register. */
/* Its value is calculated in order to match the requested duty cycle. */
P = (D*T)/100;
LL_TIM_OC_SetCompareCH1(TIM3, P);
}
/******************************************************************************/
/* USER IRQ HANDLER TREATMENT */
/******************************************************************************/
/**
* @brief User button interrupt processing
* @note When the user key button is pressed the PWM duty cycle is updated.
* @param None
* @retval None
*/
void UserButton_Callback(void)
{
/* Set new duty cycle */
//iDutyCycle = (iDutyCycle + 1) % TIM_DUTY_CYCLES_NB;
iDutyCycle++;
if(iDutyCycle==11)iDutyCycle=0;
pid_motor.target=aDutyCycle[iDutyCycle];
}
/**
* @brief Timer capture/compare interrupt processing
* @param None
* @retval None
*/
void TimerCaptureCompare_Callback(void)
{
uint32_t CNT, ARR;
CNT = LL_TIM_GetCounter(TIM3);
ARR = LL_TIM_GetAutoReload(TIM3);
if (LL_TIM_OC_GetCompareCH1(TIM3) > ARR )
{
/* If capture/compare setting is greater than autoreload, there is a counter overflow and counter restarts from 0.
Need to add full period to counter value (ARR+1) */
CNT = CNT + ARR + 1;
}
uwMeasuredDutyCycle = (CNT * 100) / ( ARR + 1 );
}
/**
* @brief Timer capture/compare interrupt processing
* @note TIM1 input capture module is used to capture the value of the counter
* after a transition is detected by the corresponding input channel.
* @param None
* @retval None
*/
void TimerCaptureCompare_Callback_1(void)
{
/* Capture index */
static uint16_t uhCaptureIndex = 0;
/* Captured Values */
static uint32_t uwICValue1 = 0;
static uint32_t uwICValue2 = 0;
static uint32_t uwDiffCapture = 0;
uint32_t TIM1CLK;
uint32_t PSC;
uint32_t IC1PSC;
uint32_t IC1Polarity;
if(uhCaptureIndex == 0)
{
/* Get the 1st Input Capture value */
uwICValue1 = LL_TIM_IC_GetCaptureCH1(TIM1);
uhCaptureIndex = 1;
}
else if(uhCaptureIndex == 1)
{
/* Get the 2nd Input Capture value */
uwICValue2 = LL_TIM_IC_GetCaptureCH1(TIM1);
/* Capture computation */
if (uwICValue2 > uwICValue1)
{
uwDiffCapture = (uwICValue2 - uwICValue1);
}
else if (uwICValue2 < uwICValue1)
{
uwDiffCapture = ((TIM1_ARR_MAX - uwICValue1) + uwICValue2) + 1;
}
else
{
/* If capture values are equal, we have reached the limit of frequency */
/* measures. */
//LED_Blinking(LED_BLINK_ERROR);
}
/* The signal frequency is calculated as follows: */
/* Frequency = (TIM1*IC1PSC) / (Capture*(PSC+1)*IC1Polarity) */
/* where: */
/* Capture is the difference between two consecutive captures */
/* TIM1CLK is the timer counter clock frequency */
/* PSC is the timer prescaler value */
/* IC1PSC is the input capture prescaler value */
/* IC1Polarity value depends on the capture sensitivity: */
/* 1 if the input is sensitive to rising or falling edges */
/* 2 if the input is sensitive to both rising and falling edges */
/* Retrieve actual TIM1 counter clock frequency */
TIM1CLK = SystemCoreClock;
/* Retrieve actual TIM1 prescaler value */
PSC = LL_TIM_GetPrescaler(TIM1);
/* Retrieve actual IC1 prescaler ratio */
IC1PSC = __LL_TIM_GET_ICPSC_RATIO(LL_TIM_IC_GetPrescaler(TIM1, LL_TIM_CHANNEL_CH1));
/* Retrieve actual IC1 polarity setting */
if (LL_TIM_IC_GetPolarity(TIM1, LL_TIM_CHANNEL_CH1) == LL_TIM_IC_POLARITY_BOTHEDGE)
IC1Polarity = 2;
else
IC1Polarity = 1;
/* Calculate input signal frequency */
uwMeasuredFrequency = (TIM1CLK *IC1PSC) / (uwDiffCapture*(PSC+1)*IC1Polarity);
pid_motor.current=uwMeasuredFrequency;
/* reset capture index */
uhCaptureIndex = 0;
}
}//-------
void TimerUpdate_Callback(void)
{
aa++;
if(pid_motor.target>0){
PID_Execute(&pid_motor);
DutyCycle-=pid_motor.out;
if(DutyCycle>100)DutyCycle=100;
if(DutyCycle<0)DutyCycle=0;
Configure_DutyCycle(DutyCycle);
}else{
PID_Reset(&pid_motor);
Configure_DutyCycle(0);
}
}
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* Infinite loop */
while (1)
{
}
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */
我要赚赏金
