• BLDC的列子2


    1.三相采样电流的采集以u相为举例。

    采集下桥臂I-V的电压。在除以采样电阻。就可以得到采样电流。但由于I-V的电压比较小。

    需要一个放大电路把电压放大ADC才采集的到。

    放大后的电压是AMP_IU.用ADC去采集这个电压。从而算出I_V的电压。 

    在电机停止的时候也会有微小的电压。并且包括1.25V的抬升电压。所以实际的电压如下计算:

     先求电机停止时的偏置电压,在求运行时的电压。

    I = (运行时的电压 - 偏置电压)/0.12 

     2.电源电压

     

    运放是一个射极跟随器所以VBUS等于A点的电压 。当用ADC采集VBUS的电压就知道A点的电压。从而可以计算出POWER的电压(分压公式)。因为POWER是电机的供电电压。当比较相差很大时就可以判断有故障发生。

    3.板子温度的采集

    板子上有一个热敏电阻随温度的变化而变化。

    跟电源电压一样运放是射极跟随器。VTEMP点的电压等于A点的电压。VCC等于3. 3v。可以求出R106的阻值。

    上面实际温度的公式是根据热敏电阻的手册可以查出的。

     上面的有些参数需要查手册如下:Rt就是通过上面分压计算得到。

     4.速度环

    当只有一对极时。旋转一圈有180度的高电平与180度的低电平(如图:霍尔1,2,3)。

    当我们求出高电平的时间(t)=高电平的计数值*PWM的频率(不是定时器的频率)。

    总的时间:2t(因为高电平与低电平相等) T=2(Cnt/fpwm) 单位s/圈。

    倒数就是:圈每秒 T=fpwm/2*Cnt   如果转为RPM乘上60即可。

    如果是两对极 T=fpwm/4*Cnt   霍尔1,2,3会经历两次的N-S。多对极依次

     速度环的框图:

     

     dome:速度-电流PID

    高级定时器T1(开启更新中断55us进入一次),定时器6(计时作用防止堵转)。ADC采集温度,电源电源电压,三相采样电流(力矩)。开启DMA。各采集50次求平均值。减小误差。

    高级定时器.h 与定时器6.h 一起

    1. #ifndef __BLDC_TIM_H
    2. #define __BLDC_TIM_H
    3. #include "./SYSTEM/sys/sys.h"
    4. /******************************************************************************************/
    5. /* 高级定时器 定义 */
    6. extern TIM_HandleTypeDef g_atimx_handle; /* 定时器x句柄 */
    7. /* TIMX PWM 定义
    8. * 注意: 通过修改这几个宏定义, 可以支持TIM1/TIM8定时器
    9. */
    10. #define ATIM_TIMX_PWM_CH1_GPIO_PORT GPIOA
    11. #define ATIM_TIMX_PWM_CH1_GPIO_PIN GPIO_PIN_8
    12. #define ATIM_TIMX_PWM_CH1_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0) /* PA口时钟使能 */
    13. #define ATIM_TIMX_PWM_CH2_GPIO_PORT GPIOA
    14. #define ATIM_TIMX_PWM_CH2_GPIO_PIN GPIO_PIN_9
    15. #define ATIM_TIMX_PWM_CH2_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0) /* PA口时钟使能 */
    16. #define ATIM_TIMX_PWM_CH3_GPIO_PORT GPIOA
    17. #define ATIM_TIMX_PWM_CH3_GPIO_PIN GPIO_PIN_10
    18. #define ATIM_TIMX_PWM_CH3_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0) /* PA口时钟使能 */
    19. /* 互补通道IO */
    20. #define M1_LOW_SIDE_U_PORT GPIOB
    21. #define M1_LOW_SIDE_U_PIN GPIO_PIN_13
    22. #define M1_LOW_SIDE_U_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0) /* PB口时钟使能 */
    23. #define M1_LOW_SIDE_V_PORT GPIOB
    24. #define M1_LOW_SIDE_V_PIN GPIO_PIN_14
    25. #define M1_LOW_SIDE_V_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0) /* PB口时钟使能 */
    26. #define M1_LOW_SIDE_W_PORT GPIOB
    27. #define M1_LOW_SIDE_W_PIN GPIO_PIN_15
    28. #define M1_LOW_SIDE_W_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0) /* PB口时钟使能 */
    29. #define ATIM_TIMX_PWM_CHY_GPIO_AF GPIO_AF1_TIM1
    30. #define ATIM_TIMX_PWM TIM1
    31. #define ATIM_TIMX_PWM_IRQn TIM1_UP_TIM10_IRQn
    32. #define ATIM_TIMX_PWM_IRQHandler TIM1_UP_TIM10_IRQHandler
    33. #define ATIM_TIMX_PWM_CH1 TIM_CHANNEL_1 /* 通道1 */
    34. #define ATIM_TIMX_PWM_CH2 TIM_CHANNEL_2 /* 通道2 */
    35. #define ATIM_TIMX_PWM_CH3 TIM_CHANNEL_3 /* 通道3 */
    36. #define ATIM_TIMX_PWM_CHY_CLK_ENABLE() do{ __HAL_RCC_TIM1_CLK_ENABLE(); }while(0) /* TIM1 时钟使能 */
    37. /******************************************************************************************/
    38. /* 基本定时器 定义 */
    39. /* TIMX 中断定义
    40. * 默认是针对TIM6
    41. */
    42. #define BTIM_TIMX_INT TIM6
    43. #define BTIM_TIMX_INT_IRQn TIM6_DAC_IRQn
    44. #define BTIM_TIMX_INT_IRQHandler TIM6_DAC_IRQHandler
    45. #define BTIM_TIMX_INT_CLK_ENABLE() do{ __HAL_RCC_TIM6_CLK_ENABLE(); }while(0) /* TIM6 时钟使能 */
    46. extern TIM_HandleTypeDef g_atimx_handle; /* 定时器x句柄 */
    47. /******************************************************************************************/
    48. void atim_timx_oc_chy_init(uint16_t arr, uint16_t psc); /* 高级定时器 PWM初始化函数 */
    49. void btim_timx_int_init(uint16_t arr, uint16_t psc); /* 基本定时器中断初始化 */
    50. #endif

    高级定时器.c与定时器6.c 一起 

    1. #include "./BSP/TIMER/bldc_tim.h"
    2. #include "./BSP/LED/led.h"
    3. #include "./BSP/BLDC/bldc.h"
    4. #include "./BSP/PID/pid.h"
    5. #include "./SYSTEM/delay/delay.h"
    6. #include "./BSP/ADC/adc.h"
    7. #include "./DEBUG/debug.h"
    8. /******************************** 定时器配置句柄 定义 ***********************************/
    9. TIM_HandleTypeDef g_atimx_handle; /* 定时器x句柄 */
    10. TIM_OC_InitTypeDef g_atimx_oc_chy_handle; /* 定时器输出句柄 */
    11. /******************************** 定义全局变量 ************************************/
    12. extern _bldc_obj g_bldc_motor1;
    13. extern PID_TypeDef g_speed_pid; /* 位置PID参数结构体 */
    14. /******************************************************************************************/
    15. /**
    16. * @brief 高级定时器TIMX PWM 初始化函数
    17. * @note
    18. * 高级定时器的时钟来自APB2, 而PCLK2 = 168Mhz, 我们设置PPRE2不分频, 因此
    19. * 高级定时器时钟 = 168Mhz
    20. * 定时器溢出时间计算方法: Tout = ((arr + 1) * (psc + 1)) / Ft us.
    21. * Ft=定时器工作频率,单位:Mhz
    22. *
    23. * @param arr: 自动重装值
    24. * @param psc: 时钟预分频数
    25. * @retval 无
    26. */
    27. void atim_timx_oc_chy_init(uint16_t arr, uint16_t psc)
    28. {
    29. ATIM_TIMX_PWM_CHY_CLK_ENABLE(); /* TIMX 时钟使能 */
    30. g_atimx_handle.Instance = ATIM_TIMX_PWM; /* 定时器x */
    31. g_atimx_handle.Init.Prescaler = psc; /* 定时器分频 */
    32. g_atimx_handle.Init.CounterMode = TIM_COUNTERMODE_UP; /* 向上计数模式 */
    33. g_atimx_handle.Init.Period = arr; /* 自动重装载值 */
    34. g_atimx_handle.Init.ClockDivision=TIM_CLOCKDIVISION_DIV1; /* 分频因子 */
    35. g_atimx_handle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; /*使能TIMx_ARR进行缓冲*/
    36. g_atimx_handle.Init.RepetitionCounter = 0; /* 开始时不计数*/
    37. HAL_TIM_PWM_Init(&g_atimx_handle); /* 初始化PWM */
    38. g_atimx_oc_chy_handle.OCMode = TIM_OCMODE_PWM1; /* 模式选择PWM1 */
    39. g_atimx_oc_chy_handle.Pulse = 0;
    40. g_atimx_oc_chy_handle.OCPolarity = TIM_OCPOLARITY_HIGH; /* 输出比较极性为高 */
    41. g_atimx_oc_chy_handle.OCNPolarity = TIM_OCNPOLARITY_HIGH;
    42. g_atimx_oc_chy_handle.OCFastMode = TIM_OCFAST_DISABLE;
    43. g_atimx_oc_chy_handle.OCIdleState = TIM_OCIDLESTATE_RESET;
    44. g_atimx_oc_chy_handle.OCNIdleState = TIM_OCNIDLESTATE_RESET;
    45. HAL_TIM_PWM_ConfigChannel(&g_atimx_handle, &g_atimx_oc_chy_handle, ATIM_TIMX_PWM_CH1); /* 配置TIMx通道y */
    46. HAL_TIM_PWM_ConfigChannel(&g_atimx_handle, &g_atimx_oc_chy_handle, ATIM_TIMX_PWM_CH2); /* 配置TIMx通道y */
    47. HAL_TIM_PWM_ConfigChannel(&g_atimx_handle, &g_atimx_oc_chy_handle, ATIM_TIMX_PWM_CH3); /* 配置TIMx通道y */
    48. /* 开启定时器通道1输出PWM */
    49. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_1);
    50. /* 开启定时器通道2输出PWM */
    51. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_2);
    52. /* 开启定时器通道3输出PWM */
    53. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_3);
    54. HAL_NVIC_SetPriority(TIM1_UP_TIM10_IRQn, 2, 2);
    55. HAL_NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn);
    56. HAL_TIM_Base_Start_IT(&g_atimx_handle); /* 启动高级定时器1 */
    57. }
    58. /**
    59. * @brief 定时器底层驱动,时钟使能,引脚配置
    60. 此函数会被HAL_TIM_PWM_Init()调用
    61. * @param htim:定时器句柄
    62. * @retval 无
    63. */
    64. void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim)
    65. {
    66. if (htim->Instance == ATIM_TIMX_PWM)
    67. {
    68. GPIO_InitTypeDef gpio_init_struct;
    69. ATIM_TIMX_PWM_CHY_CLK_ENABLE(); /* 开启通道y的IO时钟 */
    70. /* 三个上桥臂对应IO时钟使能 */
    71. ATIM_TIMX_PWM_CH1_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    72. ATIM_TIMX_PWM_CH2_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    73. ATIM_TIMX_PWM_CH3_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    74. /* 三个下桥臂对应IO时钟使能 */
    75. M1_LOW_SIDE_U_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    76. M1_LOW_SIDE_V_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    77. M1_LOW_SIDE_W_GPIO_CLK_ENABLE(); /* IO时钟使能 */
    78. /* UVW_LOW的IO初始化 */
    79. gpio_init_struct.Pin = M1_LOW_SIDE_U_PIN;
    80. gpio_init_struct.Pull = GPIO_NOPULL;
    81. gpio_init_struct.Speed = GPIO_SPEED_HIGH;
    82. gpio_init_struct.Mode = GPIO_MODE_OUTPUT_PP; /* 推挽输出模式 */
    83. HAL_GPIO_Init(M1_LOW_SIDE_U_PORT, &gpio_init_struct);
    84. gpio_init_struct.Pin = M1_LOW_SIDE_V_PIN;
    85. HAL_GPIO_Init(M1_LOW_SIDE_V_PORT, &gpio_init_struct);
    86. gpio_init_struct.Pin = M1_LOW_SIDE_W_PIN;
    87. HAL_GPIO_Init(M1_LOW_SIDE_W_PORT, &gpio_init_struct);
    88. /*定时器IO初始化*/
    89. gpio_init_struct.Pin = ATIM_TIMX_PWM_CH1_GPIO_PIN; /* 通道y的IO口 */
    90. gpio_init_struct.Mode = GPIO_MODE_AF_PP; /* 复用推挽输出 */
    91. gpio_init_struct.Pull = GPIO_NOPULL; /* 上拉 */
    92. gpio_init_struct.Speed = GPIO_SPEED_FREQ_HIGH; /* 高速 */
    93. gpio_init_struct.Alternate = ATIM_TIMX_PWM_CHY_GPIO_AF; /* 端口复用 */
    94. HAL_GPIO_Init(ATIM_TIMX_PWM_CH1_GPIO_PORT, &gpio_init_struct);
    95. gpio_init_struct.Pin = ATIM_TIMX_PWM_CH2_GPIO_PIN;
    96. HAL_GPIO_Init(ATIM_TIMX_PWM_CH2_GPIO_PORT, &gpio_init_struct);
    97. gpio_init_struct.Pin = ATIM_TIMX_PWM_CH3_GPIO_PIN;
    98. HAL_GPIO_Init(ATIM_TIMX_PWM_CH3_GPIO_PORT, &gpio_init_struct);
    99. }
    100. }
    101. /**
    102. * @brief 高级定时器TIMX中断服务函数
    103. * @param 无
    104. * @retval 无
    105. */
    106. void ATIM_TIMX_PWM_IRQHandler(void)
    107. {
    108. HAL_TIM_IRQHandler(&g_atimx_handle);
    109. }
    110. /******************************************基本定时器初始化**********************************************************/
    111. TIM_HandleTypeDef timx_handler; /* 定时器参数句柄 */
    112. /**
    113. * @brief 基本定时器TIMX定时中断初始化函数
    114. * @note
    115. * 基本定时器的时钟来自APB1,当PPRE1 ≥ 2分频的时候
    116. * 基本定时器的时钟为APB1时钟的2倍, 而APB1为42 所以定时器时钟 = 84MHZ
    117. * 定时器溢出时间计算方法: Tout = ((arr + 1) * (psc + 1)) / Ft us.
    118. * Ft=定时器工作频率,单位:Mhz
    119. *
    120. * @param arr: 自动重装值。
    121. * @param psc: 时钟预分频数
    122. * @retval 无
    123. */
    124. void btim_timx_int_init(uint16_t arr, uint16_t psc)
    125. {
    126. timx_handler.Instance = BTIM_TIMX_INT; /* 基本定时器X */
    127. timx_handler.Init.Prescaler = psc; /* 设置预分频器 */
    128. timx_handler.Init.CounterMode = TIM_COUNTERMODE_UP; /* 向上计数器 */
    129. timx_handler.Init.Period = arr; /* 自动装载值 */
    130. timx_handler.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; /* 时钟分频因子 */
    131. HAL_TIM_Base_Init(&timx_handler);
    132. HAL_TIM_Base_Start_IT(&timx_handler); /* 使能通用定时器x和及其更新中断:TIM_IT_UPDATE */
    133. __HAL_TIM_CLEAR_IT(&timx_handler,TIM_IT_UPDATE); /* 清除更新中断标志位 */
    134. }
    135. /**
    136. * @brief 定时器底册驱动,开启时钟,设置中断优先级
    137. 此函数会被HAL_TIM_Base_Init()函数调用
    138. * @param 无
    139. * @retval 无
    140. */
    141. void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim)
    142. {
    143. if (htim->Instance == BTIM_TIMX_INT)
    144. {
    145. BTIM_TIMX_INT_CLK_ENABLE(); /* 使能TIM时钟*/
    146. HAL_NVIC_SetPriority(BTIM_TIMX_INT_IRQn, 1, 3); /* 抢占1,子优先级3,组2 */
    147. HAL_NVIC_EnableIRQ(BTIM_TIMX_INT_IRQn); /* 开启ITM3中断 */
    148. }
    149. }
    150. /**
    151. * @brief 基本定时器TIMX中断服务函数
    152. * @param 无
    153. * @retval 无
    154. */
    155. void BTIM_TIMX_INT_IRQHandler(void)
    156. {
    157. HAL_TIM_IRQHandler(&timx_handler); /*定时器回调函数*/
    158. }
    159. /***********************************************定时器中断回调函数***********************************************/
    160. static uint8_t pid_s_count = 0; /* 速度环运行标志 */
    161. static uint8_t pid_c_count = 0; /* 电流环运行标志 */
    162. static uint8_t cf_count = 0; /* 定时器时间记录 */
    163. int32_t temp_pwm1 = 0; /* 存放速度环的PID计算结果 */
    164. int32_t temp_pwm2 = 0; /* 存放电流环的PID计算结果 */
    165. /* 将PID期望值进行一阶滤波后存放至以下变量 */
    166. int32_t motor_pwm_s = 0;
    167. int32_t motor_pwm_c = 0;
    168. int32_t motor_pwm_sl= 0;
    169. /* 停机状态下电流采集使用 */
    170. #define ADC_AMP_OFFSET_TIMES 50
    171. uint16_t adc_amp_offset[3][ADC_AMP_OFFSET_TIMES+1];
    172. uint8_t adc_amp_offset_p = 0;
    173. int16_t adc_amp[3];
    174. volatile uint16_t adc_val_m1[ADC_CH_NUM];
    175. int16_t adc_amp_un[3];
    176. float adc_amp_bus = 0.0f;
    177. float debug_data_temp = 0.0f;
    178. float *user_setpoint = (float*)(&g_speed_pid.SetPoint); /* 目标值赋值 */
    179. uint8_t clc = 0; /* 等待时间进入堵塞控制时间 */
    180. /**
    181. * @brief 定时器中断回调
    182. * @param 无
    183. * @retval 无
    184. */
    185. void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
    186. {
    187. uint8_t i;
    188. uint8_t bldc_dir=0;
    189. static uint8_t times_count=0; /* 定时器时间记录 */
    190. int16_t temp_speed=0; /* 临时速度存储 */
    191. if(htim->Instance == ATIM_TIMX_PWM) /* 55us */
    192. {
    193. if(g_bldc_motor1.run_flag == RUN)
    194. {
    195. /******************************* 三相电流计算 *******************************/
    196. for(i=0; i<3; i++)
    197. {
    198. adc_val_m1[i] = g_adc_val[i+2]; /* UVW三相ADC通道 */
    199. adc_amp[i] = adc_val_m1[i] - adc_amp_offset[i][ADC_AMP_OFFSET_TIMES];
    200. if(adc_amp[i] >= 0) /* 去除反电动势引起的负电流数据 */
    201. adc_amp_un[i] = adc_amp[i];
    202. }
    203. /* 运算母线电流(母线电流为任意两个有开关动作的相电流之和)*/
    204. if(g_bldc_motor1.step_sta == 0x05)
    205. {
    206. adc_amp_bus = (adc_amp_un[0] + adc_amp_un[1])*ADC2CURT; /* UV */
    207. }
    208. else if(g_bldc_motor1.step_sta == 0x01)
    209. {
    210. adc_amp_bus = (adc_amp_un[0] + adc_amp_un[2])*ADC2CURT; /* UW */
    211. }
    212. else if(g_bldc_motor1.step_sta == 0x03)
    213. {
    214. adc_amp_bus = (adc_amp_un[1]+ adc_amp_un[2])*ADC2CURT; /* VW */
    215. }
    216. else if(g_bldc_motor1.step_sta == 0x02)
    217. {
    218. adc_amp_bus = (adc_amp_un[0]+ adc_amp_un[1])*ADC2CURT; /* UV */
    219. }
    220. else if(g_bldc_motor1.step_sta == 0x06)
    221. {
    222. adc_amp_bus= (adc_amp_un[0]+ adc_amp_un[2])*ADC2CURT; /* WU */
    223. }
    224. else if(g_bldc_motor1.step_sta == 0x04)
    225. {
    226. adc_amp_bus= (adc_amp_un[2]+ adc_amp_un[1])*ADC2CURT; /* WV */
    227. }
    228. /******************************* 六步换向 *******************************/
    229. if(g_bldc_motor1.dir == CW)
    230. {
    231. g_bldc_motor1.step_sta = hallsensor_get_state(MOTOR_1);
    232. }
    233. else
    234. {
    235. g_bldc_motor1.step_sta = 7 - hallsensor_get_state(MOTOR_1);
    236. }
    237. if((g_bldc_motor1.step_sta <= 6)&&(g_bldc_motor1.step_sta >= 1))
    238. {
    239. pfunclist_m1[g_bldc_motor1.step_sta-1]();
    240. }
    241. else /* 编码器错误、接触不良、断开等情况 */
    242. {
    243. stop_motor1();
    244. g_bldc_motor1.run_flag = STOP;
    245. }
    246. /******************************* 速度计算 *******************************/
    247. g_bldc_motor1.count_j++; /* 计算速度专用计数值 */
    248. g_bldc_motor1.hall_sta_edge = uemf_edge(g_bldc_motor1.hall_single_sta);
    249. if(g_bldc_motor1.hall_sta_edge == 0) /* 统计单个霍尔信号的高电平时间 */
    250. {
    251. /* 计算速度 */
    252. if(g_bldc_motor1.dir == CW)
    253. temp_speed = (SPEED_COEFF/g_bldc_motor1.count_j);
    254. else
    255. temp_speed = -(SPEED_COEFF/g_bldc_motor1.count_j);
    256. FirstOrderRC_LPF(g_bldc_motor1.speed,temp_speed,0.2379);
    257. g_bldc_motor1.no_single = 0;
    258. g_bldc_motor1.count_j = 0;
    259. }
    260. if(g_bldc_motor1.hall_sta_edge == 1)
    261. {
    262. g_bldc_motor1.no_single = 0;
    263. g_bldc_motor1.count_j = 0;
    264. }
    265. if(g_bldc_motor1.hall_sta_edge == 2) /* 霍尔值一直不变代表未换向 */
    266. {
    267. g_bldc_motor1.no_single++; /* 不换相时间累计 超时则判定速度为0 */
    268. if(g_bldc_motor1.no_single > 15000)
    269. {
    270. g_bldc_motor1.no_single = 0;
    271. g_bldc_motor1.speed = 0; /* 超时换向 判定为停止 速度为0 */
    272. }
    273. }
    274. /******************************* 位置记录以及堵转标记 *******************************/
    275. if(g_bldc_motor1.step_last != g_bldc_motor1.step_sta)
    276. {
    277. g_bldc_motor1.hall_keep_t = 0;
    278. bldc_dir = check_hall_dir(&g_bldc_motor1);
    279. if(bldc_dir == CCW)
    280. {
    281. g_bldc_motor1.pos -= 1;
    282. }
    283. else if(bldc_dir == CW)
    284. {
    285. g_bldc_motor1.pos += 1;
    286. }
    287. g_bldc_motor1.step_last = g_bldc_motor1.step_sta;
    288. }
    289. else if(g_bldc_motor1.run_flag == RUN) /* 运行且霍尔保持时 */
    290. {
    291. g_bldc_motor1.hall_keep_t++; /* 换向一次所需计数值(时间) 单位1/18k */
    292. if(g_bldc_motor1.hall_keep_t > 15000) /* 堵转 */
    293. {
    294. g_bldc_motor1.hall_keep_t = 0;
    295. #if LOCK_TAC
    296. stop_motor1();
    297. g_bldc_motor1.run_flag = STOP;; /* 标记停机 */
    298. g_bldc_motor1.pwm_duty = 0;
    299. #endif
    300. g_bldc_motor1.locked_rotor = 1; /* 标记堵转 */
    301. }
    302. }
    303. /******************************* PID控制 *******************************/
    304. if(g_bldc_motor1.run_flag == RUN) /* 进入PID闭环控制 */
    305. {
    306. pid_c_count++;
    307. pid_s_count++;
    308. if(pid_s_count > 2)
    309. {
    310. /******************************* PID计算 *******************************/
    311. temp_pwm1 = increment_pid_ctrl(&g_speed_pid,g_bldc_motor1.speed); /* 速度环PID的控制 */
    312. FirstOrderRC_LPF(motor_pwm_s,temp_pwm1,0.085); /* 一阶 */
    313. if(motor_pwm_s < 0)
    314. {
    315. motor_pwm_sl = -motor_pwm_s;
    316. }
    317. else
    318. {
    319. motor_pwm_sl = motor_pwm_s;
    320. }
    321. *user_setpoint = debug_data_temp; /* 重新保持上位机指令要求 */
    322. pid_s_count = 0;
    323. }
    324. if(pid_c_count > 1) /* 电流环 */
    325. {
    326. /* 换向尖峰电流大于设定的电流值将导致PID调节转至电流环调节 速度环无法起作用,转速无法调节 */
    327. if(adc_amp_bus > (g_current_pid.SetPoint - 20))
    328. {
    329. cf_count++; /* 滤除换向尖峰电流的影响 */
    330. if(cf_count > 4)
    331. {
    332. cf_count = 0;
    333. temp_pwm2 = increment_pid_ctrl(&g_current_pid,adc_amp_bus); /* 电流环PID计算 */
    334. FirstOrderRC_LPF(motor_pwm_c,temp_pwm2,0.085);/* 一阶数字滤波 滤波系数0.08 */
    335. }
    336. }
    337. else
    338. {
    339. cf_count = 0;
    340. temp_pwm2 = increment_pid_ctrl(&g_current_pid,adc_amp_bus);
    341. FirstOrderRC_LPF(motor_pwm_c,temp_pwm2,0.085);
    342. }
    343. pid_c_count = 0;
    344. }
    345. /* 电流环输出值大于速度环输出则使用速度环调节 */
    346. if(motor_pwm_c > motor_pwm_sl)
    347. {
    348. g_bldc_motor1.pwm_duty = motor_pwm_sl;
    349. if(motor_pwm_s < 0) /* 正反转积分控制 */
    350. g_current_pid.Ui = -g_speed_pid.Ui; /* 速度环积分给电流环 */
    351. else
    352. g_current_pid.Ui = g_speed_pid.Ui;
    353. }
    354. else /* 速度环输出值大于电流环输出则使用电流环调节 */
    355. {
    356. g_bldc_motor1.pwm_duty = motor_pwm_c;
    357. if(motor_pwm_s < 0)
    358. g_speed_pid.Ui = -g_current_pid.Ui;/* 电流环积分给速度环 */
    359. else
    360. g_speed_pid.Ui = g_current_pid.Ui;
    361. }
    362. }
    363. }
    364. }
    365. if(htim->Instance == TIM6)
    366. {
    367. /******************************* 采集电机停机状态下的偏置电压 *******************************/
    368. times_count++;
    369. if(g_bldc_motor1.run_flag == STOP)
    370. {
    371. uint8_t i;
    372. uint32_t avg[3] = {0,0,0};
    373. adc_amp_offset[0][adc_amp_offset_p] = g_adc_val[2]; /* 得到还未开始运动时三相的基准电压 */
    374. adc_amp_offset[1][adc_amp_offset_p] = g_adc_val[3];
    375. adc_amp_offset[2][adc_amp_offset_p] = g_adc_val[4];
    376. adc_amp_offset_p++;
    377. NUM_CLEAR(adc_amp_offset_p,ADC_AMP_OFFSET_TIMES); /* 最大采集ADC_AMP_OFFSET_TIMES次,超过即从0开始继续采集 */
    378. for(i = 0; i < ADC_AMP_OFFSET_TIMES; i++) /* 将采集的每个通道值累加 */
    379. {
    380. avg[0] += adc_amp_offset[0][i];
    381. avg[1] += adc_amp_offset[1][i];
    382. avg[2] += adc_amp_offset[2][i];
    383. }
    384. for(i = 0; i < 3; i++) /* 取平均即软件滤波 */
    385. {
    386. avg[i] /= ADC_AMP_OFFSET_TIMES;
    387. adc_amp_offset[i][ADC_AMP_OFFSET_TIMES] = avg[i]; /* 得到还未开始运动时的基准电压 */
    388. }
    389. }
    390. /******************************* 定时判断电机是否发生堵塞 *******************************/
    391. if(times_count == SMAPLSE_PID_SPEED)
    392. {
    393. #if (LOCK_TAC == 2)
    394. if(g_bldc_motor1.locked_rotor == 1) /* 堵转处理,当到达一定速度后可进入闭环控制 */
    395. {
    396. clc++;
    397. if(clc > 50) /* 延迟2s后重新启动 */
    398. {
    399. #if DEBUG_ENABLE /*开启调试*/
    400. debug_send_motorstate(RUN_STATE); /* 电机运行*/
    401. #endif
    402. clc = 0;
    403. pid_init();
    404. stop_motor1();
    405. g_speed_pid.SetPoint = 400.0; /* 400PRM */
    406. g_bldc_motor1.pwm_duty = 500; /* 加速启动速度 */
    407. g_bldc_motor1.run_flag = RUN; /* 开启运行 */
    408. start_motor1(); /* 运行电机 */
    409. g_bldc_motor1.locked_rotor = 0;
    410. }
    411. }
    412. #endif
    413. times_count = 0;
    414. }
    415. }
    416. }

     霍尔传感器.h

    1. #ifndef __BLDC_H
    2. #define __BLDC_H
    3. #include "./SYSTEM/sys/sys.h"
    4. /******************************************************************************************/
    5. typedef struct
    6. {
    7. __IO uint8_t run_flag; /* 运行标志 */
    8. __IO uint8_t locked_rotor; /* 堵转标记 */
    9. __IO uint8_t step_sta; /* 本次霍尔状态 */
    10. __IO uint8_t hall_single_sta;/* 单个霍尔状态 */
    11. __IO uint8_t hall_sta_edge; /* 单个霍尔状态跳变 */
    12. __IO uint8_t step_last; /* 上次霍尔状态 */
    13. __IO uint8_t dir; /* 电机旋转方向 */
    14. __IO int32_t pos; /* 电机位置 */
    15. __IO int32_t speed; /* 电机速度 */
    16. __IO int16_t current; /* 电机速度 */
    17. __IO uint16_t pwm_duty; /* 电机占空比 */
    18. __IO uint32_t hall_keep_t; /* 霍尔保持时间 */
    19. __IO uint32_t hall_pul_num; /* 霍尔传感器脉冲数 */
    20. __IO uint32_t lock_time; /* 电机堵转时间 */
    21. __IO uint32_t no_single;
    22. __IO uint32_t count_j;
    23. __IO uint64_t sum_pos;
    24. } _bldc_obj;
    25. /******************************************************************************************/
    26. #define MOTOR_1 1
    27. #define MOTOR_2 2
    28. extern _bldc_obj g_bldc_motor1;
    29. /********************************************************************************************/
    30. /*刹车引脚*/
    31. #define SHUTDOWN_PIN GPIO_PIN_10
    32. #define SHUTDOWN_PIN_GPIO GPIOF
    33. #define SHUTDOWN_PIN_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOF_CLK_ENABLE(); }while(0) /* PF口时钟使能 */
    34. #define SHUTDOWN2_PIN GPIO_PIN_2
    35. #define SHUTDOWN2_PIN_GPIO GPIOF
    36. #define SHUTDOWN2_PIN_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOF_CLK_ENABLE(); }while(0) /* PF口时钟使能 */
    37. #define SHUTDOWN_EN HAL_GPIO_WritePin(SHUTDOWN_PIN_GPIO,SHUTDOWN_PIN,GPIO_PIN_SET);
    38. #define SHUTDOWN_OFF HAL_GPIO_WritePin(SHUTDOWN_PIN_GPIO,SHUTDOWN_PIN,GPIO_PIN_RESET);
    39. #define SHUTDOWN2_EN HAL_GPIO_WritePin(SHUTDOWN2_PIN_GPIO,SHUTDOWN2_PIN,GPIO_PIN_SET);
    40. #define SHUTDOWN2_OFF HAL_GPIO_WritePin(SHUTDOWN2_PIN_GPIO,SHUTDOWN2_PIN,GPIO_PIN_RESET);
    41. /******************************************************************************************/
    42. /*霍尔传感器接口一*/
    43. #define HALL1_TIM_CH1_PIN GPIO_PIN_10 /* U */
    44. #define HALL1_TIM_CH1_GPIO GPIOH
    45. #define HALL1_U_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOH_CLK_ENABLE(); }while(0) /* PH口时钟使能 */
    46. #define HALL1_TIM_CH2_PIN GPIO_PIN_11 /* V */
    47. #define HALL1_TIM_CH2_GPIO GPIOH
    48. #define HALL1_V_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOH_CLK_ENABLE(); }while(0) /* PH口时钟使能 */
    49. #define HALL1_TIM_CH3_PIN GPIO_PIN_12 /* W */
    50. #define HALL1_TIM_CH3_GPIO GPIOH
    51. #define HALL1_W_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOH_CLK_ENABLE(); }while(0) /* PH口时钟使能 */
    52. /*霍尔传感器接口二*/
    53. #define HALL2_TIM_CH1_PIN GPIO_PIN_12 /* U */
    54. #define HALL2_TIM_CH1_GPIO GPIOD
    55. #define HALL2_U_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOD_CLK_ENABLE(); }while(0) /* PD口时钟使能 */
    56. #define HALL2_TIM_CH2_PIN GPIO_PIN_13 /* V */
    57. #define HALL2_TIM_CH2_GPIO GPIOD
    58. #define HALL2_V_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOD_CLK_ENABLE(); }while(0) /* PD口时钟使能 */
    59. #define HALL2_TIM_CH3_PIN GPIO_PIN_8 /* W */
    60. #define HALL2_TIM_CH3_GPIO GPIOB
    61. #define HALL2_W_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0) /* PB口时钟使能 */
    62. /********************************************************************************************/
    63. #define MAX_PWM_DUTY (((168000/18) - 1)*0.96)
    64. #define H_PWM_L_ON
    65. #ifndef H_PWM_L_ON
    66. #define H_PWM_L_PWM
    67. #endif
    68. #define CCW (1) /* 逆时针 */
    69. #define CW (2) /* 顺时针 */
    70. #define HALL_ERROR (0xF0) /* 霍尔错误标志 */
    71. #define RUN (1) /* 电机运动标志 */
    72. #define STOP (0) /* 电机停机标志 */
    73. #define LOCK_TAC 2 /* 堵转处理:2为开启,其他关闭 */
    74. #define SPEED_COEFF (uint32_t)((18000/4)*60) /* 旋转一圈变化4个信号,2对级永磁体特性,NSNS共4级数*/
    75. #define ADC2CURT (float)(3.3f/4.096f/0.12f)
    76. #define ADC2VBUS (float)(3.3f*25/4096)
    77. #define NUM_CLEAR(para,val) {if(para >= val){para=0;}}
    78. #define NUM_MAX_LIMIT(para,val) {if(para > val){para=val;}}
    79. #define NUM_MIN_LIMIT(para,val) {if(para < val){para=val;}}
    80. typedef void(*pctr) (void);
    81. void stop_motor1(void);
    82. void start_motor1(void);
    83. #define FirstOrderRC_LPF(Yn_1,Xn,a) Yn_1 = (1-a)*Yn_1 + a*Xn; /* Yn:out;Xn:in;a:系数 */
    84. /******************************************************************************************/
    85. /* 外部接口函数*/
    86. void bldc_init(uint16_t arr, uint16_t psc); /* BLDC初始化 */
    87. uint8_t check_hall_dir(_bldc_obj * obj); /* 检测电机旋转方向 */
    88. extern pctr pfunclist_m1[6]; /* 六步换相函数指针数组 */
    89. void bldc_ctrl(uint8_t motor_id,int32_t dir,float duty); /* bldc控制函数 */
    90. uint8_t uemf_edge(uint8_t val); /* 波形状态检测 */
    91. float get_temp(uint16_t para); /* 获取温度值 */
    92. void calc_adc_val(uint16_t * p); /* adc数据软件滤波函数 */
    93. void hall_gpio_init(void); /* 霍尔接口初始化 */
    94. uint32_t hallsensor_get_state(uint8_t motor_id); /* 获取霍尔状态 */
    95. /* 六步换相 */
    96. void m1_uhvl(void);
    97. void m1_uhwl(void);
    98. void m1_vhwl(void);
    99. void m1_vhul(void);
    100. void m1_whul(void);
    101. void m1_whvl(void);
    102. #endif

      霍尔传感器.C

    1. #include "./BSP/BLDC/bldc.h"
    2. #include "./BSP/TIMER/bldc_tim.h"
    3. #include "./BSP/ADC/adc.h"
    4. #include "math.h"
    5. _bldc_obj g_bldc_motor1 = {STOP,0,0,CCW,0,0,0,0,0,0}; /* 电机结构体 */
    6. const uint8_t hall_table_cw[6] = {6,2,3,1,5,4}; /* 顺时针旋转表 */
    7. const uint8_t hall_table_ccw[6] = {5,1,3,2,6,4}; /* 逆时针旋转表 */
    8. const uint8_t hall_cw_table[12] = {0x62,0x23,0x31,0x15,0x54,0x46,0x63,0x21,0x35,0x14,0x56,0x42}; /* 顺方向组合 */
    9. const uint8_t hall_ccw_table[12] = {0x45,0x51,0x13,0x32,0x26,0x64,0x41,0x53,0x12,0x36,0x24,0x65}; /* 逆方向组合 */
    10. /**
    11. * @brief 无刷电机初始化,包括定时器,霍尔接口以及SD引脚初始化
    12. * @param arr: 自动重装值
    13. * @param psc: 时钟预分频数
    14. * @retval 无
    15. */
    16. void bldc_init(uint16_t arr, uint16_t psc)
    17. {
    18. GPIO_InitTypeDef gpio_init_struct;
    19. SHUTDOWN_PIN_GPIO_CLK_ENABLE();
    20. SHUTDOWN2_PIN_GPIO_CLK_ENABLE();
    21. gpio_init_struct.Pin = SHUTDOWN_PIN;
    22. gpio_init_struct.Mode = GPIO_MODE_OUTPUT_PP;
    23. gpio_init_struct.Pull = GPIO_NOPULL;
    24. gpio_init_struct.Speed = GPIO_SPEED_FREQ_LOW;
    25. HAL_GPIO_Init(SHUTDOWN_PIN_GPIO, &gpio_init_struct);
    26. gpio_init_struct.Pin = SHUTDOWN2_PIN;
    27. HAL_GPIO_Init(SHUTDOWN2_PIN_GPIO, &gpio_init_struct);
    28. hall_gpio_init(); /* 霍尔接口初始化 */
    29. atim_timx_oc_chy_init(arr, psc);
    30. btim_timx_int_init(1000 - 1 , 84 - 1);
    31. }
    32. /**
    33. * @brief BLDC控制函数
    34. * @param dir :电机方向, Duty:PWM占空比
    35. * @retval 无
    36. */
    37. void bldc_ctrl(uint8_t motor_id,int32_t dir,float duty)
    38. {
    39. if(motor_id == MOTOR_1)
    40. {
    41. g_bldc_motor1.dir = dir; /* 方向 */
    42. g_bldc_motor1.pwm_duty = duty; /* 占空比 */
    43. }
    44. }
    45. /**
    46. * @brief 旋转方向检测函数
    47. * @param obj:电机控制句柄
    48. * @retval 旋转方向定义如下:
    49. * 正转,CW
    50. * 反转,CCW
    51. */
    52. uint8_t check_hall_dir(_bldc_obj * obj)
    53. {
    54. uint8_t temp,res = HALL_ERROR;
    55. if((obj->step_last <= 6)&&(obj->step_sta <= 6))
    56. {
    57. temp = ((obj->step_last & 0x0F) << 4)|(obj->step_sta & 0x0F);
    58. if((temp == hall_ccw_table[0])||(temp == hall_ccw_table[1])||\
    59. (temp == hall_ccw_table[2])||(temp == hall_ccw_table[3])||\
    60. (temp == hall_ccw_table[4])||(temp == hall_ccw_table[5]))
    61. {
    62. res = CCW;
    63. }
    64. else if((temp == hall_cw_table[0])||(temp == hall_cw_table[1])||\
    65. (temp == hall_cw_table[2])||(temp == hall_cw_table[3])||\
    66. (temp == hall_cw_table[4])||(temp == hall_cw_table[5]))
    67. {
    68. res = CW;
    69. }
    70. }
    71. return res;
    72. }
    73. /*****************************************************************************************/
    74. /*霍尔接口初始化*/
    75. /**
    76. * @brief 霍尔传感器定时器初始化
    77. * @param 无
    78. * @retval 无
    79. */
    80. void hall_gpio_init(void)
    81. {
    82. GPIO_InitTypeDef gpio_init_struct;
    83. HALL1_U_GPIO_CLK_ENABLE();
    84. HALL1_V_GPIO_CLK_ENABLE();
    85. HALL1_W_GPIO_CLK_ENABLE();
    86. HALL2_U_GPIO_CLK_ENABLE();
    87. HALL2_V_GPIO_CLK_ENABLE();
    88. HALL2_W_GPIO_CLK_ENABLE();
    89. /* 霍尔通道 1 引脚初始化 */
    90. gpio_init_struct.Pin = HALL1_TIM_CH1_PIN;
    91. gpio_init_struct.Mode = GPIO_MODE_INPUT;
    92. gpio_init_struct.Pull = GPIO_PULLUP;
    93. HAL_GPIO_Init(HALL1_TIM_CH1_GPIO, &gpio_init_struct);
    94. /* 霍尔通道 2 引脚初始化 */
    95. gpio_init_struct.Pin = HALL1_TIM_CH2_PIN;
    96. HAL_GPIO_Init(HALL1_TIM_CH2_GPIO, &gpio_init_struct);
    97. /* 霍尔通道 3 引脚初始化 */
    98. gpio_init_struct.Pin = HALL1_TIM_CH3_PIN;
    99. HAL_GPIO_Init(HALL1_TIM_CH3_GPIO, &gpio_init_struct);
    100. }
    101. /**
    102. * @brief 获取霍尔传感器引脚状态
    103. * @param 无
    104. * @retval 霍尔传感器引脚状态
    105. */
    106. uint32_t hallsensor_get_state(uint8_t motor_id)
    107. {
    108. __IO static uint32_t State ;
    109. State = 0;
    110. if(motor_id == MOTOR_1)
    111. {
    112. if(HAL_GPIO_ReadPin(HALL1_TIM_CH1_GPIO,HALL1_TIM_CH1_PIN) != GPIO_PIN_RESET) /* 霍尔传感器状态获取 */
    113. {
    114. State |= 0x01U;
    115. }
    116. if(HAL_GPIO_ReadPin(HALL1_TIM_CH2_GPIO,HALL1_TIM_CH2_PIN) != GPIO_PIN_RESET) /* 霍尔传感器状态获取 */
    117. {
    118. State |= 0x02U;
    119. }
    120. if(HAL_GPIO_ReadPin(HALL1_TIM_CH3_GPIO,HALL1_TIM_CH3_PIN) != GPIO_PIN_RESET) /* 霍尔传感器状态获取 */
    121. {
    122. State |= 0x04U;
    123. g_bldc_motor1.hall_single_sta=1;
    124. }
    125. else
    126. g_bldc_motor1.hall_single_sta=0;
    127. }
    128. return State;
    129. }
    130. /************************************* BLDC相关函数 *************************************/
    131. /* 关闭电机运转 */
    132. void stop_motor1(void)
    133. {
    134. /* 关闭半桥芯片输出 */
    135. SHUTDOWN_OFF;
    136. /* 关闭PWM输出 */
    137. HAL_TIM_PWM_Stop(&g_atimx_handle,TIM_CHANNEL_1);
    138. HAL_TIM_PWM_Stop(&g_atimx_handle,TIM_CHANNEL_2);
    139. HAL_TIM_PWM_Stop(&g_atimx_handle,TIM_CHANNEL_3);
    140. /* 上下桥臂全部关断 */
    141. g_atimx_handle.Instance->CCR2 = 0;
    142. g_atimx_handle.Instance->CCR1 = 0;
    143. g_atimx_handle.Instance->CCR3 = 0;
    144. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_RESET);
    145. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_RESET);
    146. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_RESET);
    147. }
    148. /* 开启电机运转 */
    149. void start_motor1(void)
    150. {
    151. SHUTDOWN_EN;
    152. /* 使能PWM输出 */
    153. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_1);
    154. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_2);
    155. HAL_TIM_PWM_Start(&g_atimx_handle,TIM_CHANNEL_3);
    156. }
    157. /*****************************************************************************************/
    158. /* 六步换向函数指针 */
    159. pctr pfunclist_m1[6] =
    160. {
    161. &m1_uhwl, &m1_vhul, &m1_vhwl,
    162. &m1_whvl, &m1_uhvl, &m1_whul
    163. };
    164. /* 上下桥臂的导通情况,共6种,也称为6步换向 */
    165. void m1_uhvl(void)
    166. {
    167. g_atimx_handle.Instance->CCR2 = 0;
    168. g_atimx_handle.Instance->CCR1 = g_bldc_motor1.pwm_duty; /* U相上桥臂PWM */
    169. g_atimx_handle.Instance->CCR3 = 0;
    170. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_SET); /* V相下桥臂导通 */
    171. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_RESET); /* U相下桥臂关闭 */
    172. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_RESET); /* W相下桥臂关闭 */
    173. }
    174. void m1_uhwl(void)
    175. {
    176. g_atimx_handle.Instance->CCR2 = 0;
    177. g_atimx_handle.Instance->CCR1 = g_bldc_motor1.pwm_duty;
    178. g_atimx_handle.Instance->CCR3 = 0;
    179. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_SET);
    180. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_RESET);
    181. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_RESET);
    182. }
    183. void m1_vhwl(void)
    184. {
    185. g_atimx_handle.Instance->CCR1=0;
    186. g_atimx_handle.Instance->CCR2 = g_bldc_motor1.pwm_duty;
    187. g_atimx_handle.Instance->CCR3=0;
    188. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_SET);
    189. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_RESET);
    190. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_RESET);
    191. }
    192. void m1_vhul(void)
    193. {
    194. g_atimx_handle.Instance->CCR1 = 0;
    195. g_atimx_handle.Instance->CCR2 = g_bldc_motor1.pwm_duty;
    196. g_atimx_handle.Instance->CCR3 = 0;
    197. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_SET);
    198. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_RESET);
    199. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_RESET);
    200. }
    201. void m1_whul(void)
    202. {
    203. g_atimx_handle.Instance->CCR2 = 0;
    204. g_atimx_handle.Instance->CCR3 = g_bldc_motor1.pwm_duty;
    205. g_atimx_handle.Instance->CCR1 = 0;
    206. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_SET);
    207. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_RESET);
    208. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_RESET);
    209. }
    210. void m1_whvl(void)
    211. {
    212. g_atimx_handle.Instance->CCR2 = 0;
    213. g_atimx_handle.Instance->CCR3 = g_bldc_motor1.pwm_duty;
    214. g_atimx_handle.Instance->CCR1 = 0;
    215. HAL_GPIO_WritePin(M1_LOW_SIDE_V_PORT,M1_LOW_SIDE_V_PIN,GPIO_PIN_SET);
    216. HAL_GPIO_WritePin(M1_LOW_SIDE_U_PORT,M1_LOW_SIDE_U_PIN,GPIO_PIN_RESET);
    217. HAL_GPIO_WritePin(M1_LOW_SIDE_W_PORT,M1_LOW_SIDE_W_PIN,GPIO_PIN_RESET);
    218. }
    219. /**
    220. * @brief 检测输入信号是否发生变化
    221. * @param val :输入信号
    222. * @note 测量速度使用,获取输入信号状态翻转情况,计算速度
    223. * @retval 0:计算高电平时间,1:计算低电平时间,2:信号未改变
    224. */
    225. uint8_t uemf_edge(uint8_t val)
    226. {
    227. /* 主要是检测val信号从0 - 1 在从 1 - 0的过程,即高电平所持续的过程 */
    228. static uint8_t oldval=0;
    229. if(oldval != val)
    230. {
    231. oldval = val;
    232. if(val == 0) return 0;
    233. else return 1;
    234. }
    235. return 2;
    236. }
    237. /************************************* 第二部分 电压电流温度采集 **********************************************/
    238. /*
    239. Rt = Rp *exp(B*(1/T1-1/T2))
    240. Rt 是热敏电阻在T1温度下的阻值;
    241. Rp是热敏电阻在T2常温下的标称阻值;
    242. exp是e的n次方,e是自然常数,就是自然对数的底数,近似等于 2.7182818;
    243. B值是热敏电阻的重要参数,教程中用到的热敏电阻B值为3380;
    244. 这里T1和T2指的是开尔文温度,T2是常温25℃,即(273.15+25)K
    245. T1就是所求的温度
    246. */
    247. const float Rp = 10000.0f; /* 10K */
    248. const float T2 = (273.15f + 25.0f); /* T2 */
    249. const float Bx = 3380.0f; /* B */
    250. const float Ka = 273.15f;
    251. /**
    252. * @brief 计算温度值
    253. * @param para: 温度采集对应ADC通道的值(已滤波)
    254. * @note 计算温度分为两步:
    255. 1.根据ADC采集到的值计算当前对应的Rt
    256. 2.根据Rt计算对应的温度值
    257. * @retval 温度值
    258. */
    259. float get_temp(uint16_t para)
    260. {
    261. float Rt;
    262. float temp;
    263. Rt = 3.3f / (para * 3.3f / 4096.0f / 4700.0f) - 4700.0f;
    264. /* like this R=5000, T2=273.15+25,B=3470, RT=5000*EXP(3470*(1/T1-1/(273.15+25)) */
    265. temp = Rt / Rp;
    266. temp = log(temp); /* ln(Rt/Rp) */
    267. temp /= Bx; /* ln(Rt/Rp)/B */
    268. temp += (1.0f / T2);
    269. temp = 1.0f / (temp);
    270. temp -= Ka;
    271. return temp;
    272. }
    273. extern uint16_t g_adc_value[ADC_CH_NUM * ADC_COLL];
    274. /**
    275. * @brief 计算ADC的平均值(滤波)
    276. * @param * p :存放ADC值的指针地址
    277. * @note 此函数对电压、温度、电流对应的ADC值进行滤波
    278. * @retval 无
    279. */
    280. void calc_adc_val(uint16_t * p)
    281. {
    282. uint32_t temp[ADC_CH_NUM] = {0,0,0}; /* 定义一个缓存数组 */
    283. int i,j; /* 循环采集ADC_COLL次数 */
    284. for(i=0;i/* 根据ADC通道数循环获取,并累加 */
    285. {
    286. for(j=0;j/* 将采集到的ADC值,各通道进行累加 */
    287. {
    288. temp[j] += g_adc_value[j+i*ADC_CH_NUM];
    289. }
    290. }
    291. for(j=0;j
    292. {
    293. temp[j] /= ADC_COLL; /* 获取平均值 */
    294. p[j] = temp[j]; /* 存到*p */
    295. }
    296. }

    ADC.h

    1. #ifndef __ADC_H
    2. #define __ADC_H
    3. #include "./SYSTEM/sys/sys.h"
    4. /******************************************************************************************/
    5. /* ADC及引脚 定义 */
    6. #define ADC_ADCX_CH0_GPIO_PORT GPIOB /* 电源电压采集引脚 */
    7. #define ADC_ADCX_CH0_GPIO_PIN GPIO_PIN_1
    8. #define ADC_ADCX_CH0_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0)
    9. #define ADC_ADCX_CH1_GPIO_PORT GPIOA /* 温度采集引脚 */
    10. #define ADC_ADCX_CH1_GPIO_PIN GPIO_PIN_0
    11. #define ADC_ADCX_CH1_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0)
    12. #define ADC_ADCX_CH2_GPIO_PORT GPIOB /* U相采集引脚 */
    13. #define ADC_ADCX_CH2_GPIO_PIN GPIO_PIN_0
    14. #define ADC_ADCX_CH2_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOB_CLK_ENABLE(); }while(0)
    15. #define ADC_ADCX_CH3_GPIO_PORT GPIOA /* V相采集引脚 */
    16. #define ADC_ADCX_CH3_GPIO_PIN GPIO_PIN_6
    17. #define ADC_ADCX_CH3_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0)
    18. #define ADC_ADCX_CH4_GPIO_PORT GPIOA /* W相采集引脚 */
    19. #define ADC_ADCX_CH4_GPIO_PIN GPIO_PIN_3
    20. #define ADC_ADCX_CH4_GPIO_CLK_ENABLE() do{ __HAL_RCC_GPIOA_CLK_ENABLE(); }while(0)
    21. #define ADC_ADCX ADC1
    22. #define ADC_ADCX_CH0 ADC_CHANNEL_9 /* 通道Y, 0 <= Y <= 17 */
    23. #define ADC_ADCX_CH1 ADC_CHANNEL_0
    24. #define ADC_ADCX_CH2 ADC_CHANNEL_8
    25. #define ADC_ADCX_CH3 ADC_CHANNEL_6
    26. #define ADC_ADCX_CH4 ADC_CHANNEL_3
    27. #define ADC_ADCX_CHY_CLK_ENABLE() do{ __HAL_RCC_ADC1_CLK_ENABLE(); }while(0) /* ADC1 时钟使能 */
    28. #define ADC_CH_NUM 5 /* 需要转换的通道数目 */
    29. #define ADC_COLL 50 /* 单采集次数 */
    30. #define ADC_SUM ADC_CH_NUM * ADC_COLL /* 总采集次数 */
    31. /* ADC单通道/多通道 DMA采集 DMA数据流相关 定义
    32. * 注意: 这里我们的通道还是使用上面的定义.
    33. */
    34. #define ADC_ADCX_DMASx DMA2_Stream4
    35. #define ADC_ADCX_DMASx_Chanel DMA_CHANNEL_0 /* ADC1_DMA请求源 */
    36. #define ADC_ADCX_DMASx_IRQn DMA2_Stream4_IRQn
    37. #define ADC_ADCX_DMASx_IRQHandler DMA2_Stream4_IRQHandler
    38. extern uint16_t g_adc_val[ADC_CH_NUM];
    39. /******************************************************************************************/
    40. void adc_init(void); /* ADC初始化 */
    41. uint32_t adc_get_result_average(uint8_t ch); /* 获得某个通道值 */
    42. void adc_nch_dma_init(void);
    43. #endif

     ADC.c

    1. #include "./BSP/ADC/adc.h"
    2. #include "./SYSTEM/delay/delay.h"
    3. #include "./BSP/DMA/dma.h"
    4. #include "./BSP/BLDC/bldc.h"
    5. #include "./BSP/TIMER/bldc_tim.h"
    6. /* 多通道ADC采集 DMA读取 */
    7. ADC_HandleTypeDef g_adc_nch_dma_handle; /* 与DMA关联的ADC句柄 */
    8. DMA_HandleTypeDef g_dma_nch_adc_handle; /* 与ADC关联的DMA句柄 */
    9. uint8_t g_adc_dma_sta = 0; /* DMA传输状态标志, 0,未完成; 1, 已完成 */
    10. uint16_t g_adc_value[ADC_CH_NUM * ADC_COLL] = {0}; /* 存储ADC原始值 */
    11. float g_adc_u_value[ADC_CH_NUM] = {0}; /* 存储ADC转换后的电压值 */
    12. /***************************************多通道ADC采集(DMA读取)程序*****************************************/
    13. /**
    14. * @brief ADC初始化
    15. * @param 无
    16. * @retval 无
    17. */
    18. void adc_init(void)
    19. {
    20. ADC_ChannelConfTypeDef sConfig = {0};
    21. g_adc_nch_dma_handle.Instance = ADC_ADCX;
    22. g_adc_nch_dma_handle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4; /* 4分频,ADCCLK = PCLK2/4 = 84/4 = 21Mhz */
    23. g_adc_nch_dma_handle.Init.Resolution = ADC_RESOLUTION_12B; /* 12位模式 */
    24. g_adc_nch_dma_handle.Init.ScanConvMode = ENABLE; /* 扫描模式 多通道使用 */
    25. g_adc_nch_dma_handle.Init.ContinuousConvMode = ENABLE; /* 连续转换模式,转换完成之后接着继续转换 */
    26. g_adc_nch_dma_handle.Init.DiscontinuousConvMode = DISABLE; /* 禁止不连续采样模式 */
    27. g_adc_nch_dma_handle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; /* 使用软件触发 */
    28. g_adc_nch_dma_handle.Init.ExternalTrigConv = ADC_SOFTWARE_START; /* 软件触发 */
    29. g_adc_nch_dma_handle.Init.DataAlign = ADC_DATAALIGN_RIGHT; /* 右对齐 */
    30. g_adc_nch_dma_handle.Init.NbrOfConversion = ADC_CH_NUM; /* 使用转换通道数,需根据实际转换通道去设置 */
    31. g_adc_nch_dma_handle.Init.DMAContinuousRequests = ENABLE; /* 开启DMA连续转换 */
    32. g_adc_nch_dma_handle.Init.EOCSelection = ADC_EOC_SEQ_CONV;
    33. HAL_ADC_Init(&g_adc_nch_dma_handle);
    34. /* 配置使用的ADC通道,采样序列里的第几个转换,增加或者减少通道需要修改这部分 */
    35. sConfig.Channel = ADC_ADCX_CH0; /* 电源电压采集 */
    36. sConfig.Rank = 1;
    37. sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
    38. HAL_ADC_ConfigChannel(&g_adc_nch_dma_handle, &sConfig);
    39. sConfig.Channel = ADC_ADCX_CH1; /* 温度采集 */
    40. sConfig.Rank = 2;
    41. HAL_ADC_ConfigChannel(&g_adc_nch_dma_handle, &sConfig);
    42. sConfig.Channel = ADC_ADCX_CH2; /* U相电压采集 */
    43. sConfig.Rank = 3;
    44. HAL_ADC_ConfigChannel(&g_adc_nch_dma_handle, &sConfig);
    45. sConfig.Channel = ADC_ADCX_CH3; /* V相电压采集 */
    46. sConfig.Rank = 4;
    47. HAL_ADC_ConfigChannel(&g_adc_nch_dma_handle, &sConfig);
    48. sConfig.Channel = ADC_ADCX_CH4; /* W相电压采集 */
    49. sConfig.Rank = 5;
    50. HAL_ADC_ConfigChannel(&g_adc_nch_dma_handle, &sConfig);
    51. }
    52. /**
    53. * @brief ADC DMA读取 初始化函数
    54. * @note 本函数还是使用adc_init对ADC进行大部分配置,有差异的地方再单独配置
    55. * @param par : 外设地址
    56. * @param mar : 存储器地址
    57. * @retval 无
    58. */
    59. void adc_nch_dma_init(void)
    60. {
    61. GPIO_InitTypeDef GPIO_InitStruct = {0};
    62. ADC_ADCX_CHY_CLK_ENABLE(); /* 使能ADCx时钟 */
    63. ADC_ADCX_CH0_GPIO_CLK_ENABLE(); /* 开启GPIO时钟 */
    64. ADC_ADCX_CH1_GPIO_CLK_ENABLE();
    65. ADC_ADCX_CH2_GPIO_CLK_ENABLE();
    66. ADC_ADCX_CH3_GPIO_CLK_ENABLE();
    67. ADC_ADCX_CH4_GPIO_CLK_ENABLE();
    68. /* AD采集引脚模式设置,模拟输入 */
    69. GPIO_InitStruct.Pin = ADC_ADCX_CH0_GPIO_PIN;
    70. GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
    71. GPIO_InitStruct.Pull = GPIO_NOPULL;
    72. HAL_GPIO_Init(ADC_ADCX_CH0_GPIO_PORT, &GPIO_InitStruct);
    73. GPIO_InitStruct.Pin = ADC_ADCX_CH1_GPIO_PIN;
    74. HAL_GPIO_Init(ADC_ADCX_CH1_GPIO_PORT, &GPIO_InitStruct);
    75. GPIO_InitStruct.Pin = ADC_ADCX_CH2_GPIO_PIN;
    76. HAL_GPIO_Init(ADC_ADCX_CH2_GPIO_PORT, &GPIO_InitStruct);
    77. GPIO_InitStruct.Pin = ADC_ADCX_CH3_GPIO_PIN;
    78. HAL_GPIO_Init(ADC_ADCX_CH3_GPIO_PORT, &GPIO_InitStruct);
    79. GPIO_InitStruct.Pin = ADC_ADCX_CH4_GPIO_PIN;
    80. HAL_GPIO_Init(ADC_ADCX_CH4_GPIO_PORT, &GPIO_InitStruct);
    81. adc_init();
    82. if ((uint32_t)ADC_ADCX_DMASx > (uint32_t)DMA2) /* 大于DMA1_Channel7, 则为DMA2的通道了 */
    83. {
    84. __HAL_RCC_DMA2_CLK_ENABLE(); /* DMA2时钟使能 */
    85. }
    86. else
    87. {
    88. __HAL_RCC_DMA1_CLK_ENABLE(); /* DMA1时钟使能 */
    89. }
    90. /* DMA配置 */
    91. g_dma_nch_adc_handle.Instance = ADC_ADCX_DMASx; /* 设置DMA通道 */
    92. g_dma_nch_adc_handle.Init.Channel = DMA_CHANNEL_0;
    93. g_dma_nch_adc_handle.Init.Direction = DMA_PERIPH_TO_MEMORY; /* DIR = 1 , 外设到存储器模式 */
    94. g_dma_nch_adc_handle.Init.PeriphInc = DMA_PINC_DISABLE; /* 外设非增量模式 */
    95. g_dma_nch_adc_handle.Init.MemInc = DMA_MINC_ENABLE; /* 存储器增量模式 */
    96. g_dma_nch_adc_handle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; /* 外设数据长度:16位 */
    97. g_dma_nch_adc_handle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; /* 存储器数据长度:16位 */
    98. g_dma_nch_adc_handle.Init.Mode = DMA_CIRCULAR; /* 外设流控模式 */
    99. g_dma_nch_adc_handle.Init.Priority = DMA_PRIORITY_MEDIUM; /* 中等优先级 */
    100. HAL_DMA_Init(&g_dma_nch_adc_handle);
    101. __HAL_LINKDMA(&g_adc_nch_dma_handle,DMA_Handle,g_dma_nch_adc_handle);
    102. HAL_NVIC_SetPriority(ADC_ADCX_DMASx_IRQn, 2, 1);
    103. HAL_NVIC_EnableIRQ(ADC_ADCX_DMASx_IRQn);
    104. HAL_ADC_Start_DMA(&g_adc_nch_dma_handle,(uint32_t *)g_adc_value,ADC_CH_NUM * ADC_COLL);
    105. }
    106. /**
    107. * @brief ADC DMA采集中断服务函数
    108. * @param 无
    109. * @retval 无
    110. */
    111. void ADC_ADCX_DMASx_IRQHandler(void)
    112. {
    113. HAL_DMA_IRQHandler(&g_dma_nch_adc_handle);
    114. }
    115. uint16_t g_adc_val[ADC_CH_NUM]; /* ADC平均值存放数组 */
    116. void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc)
    117. {
    118. if (hadc->Instance == ADC1) /* 大约2.6ms采集完成进入中断 */
    119. {
    120. HAL_ADC_Stop_DMA(&g_adc_nch_dma_handle); /* 关闭DMA转换 */
    121. calc_adc_val(g_adc_val); /* ADC数值转换 */
    122. HAL_ADC_Start_DMA(&g_adc_nch_dma_handle, (uint32_t *)&g_adc_value, (uint32_t)(ADC_SUM)); /* 再启动DMA转换 */
    123. }
    124. }
    125. /**
    126. * @brief 获取通道ch的转换值,取times次, 然后平均
    127. * @param ch : 通道号, 0~17
    128. * @retval 通道ch的times次转换结果平均值
    129. */
    130. uint32_t adc_get_result_average(uint8_t ch)
    131. {
    132. uint32_t temp_val = 0;
    133. uint16_t t;
    134. for (t = ch; t < ADC_SUM; t += ADC_CH_NUM ) /* 获取times次数据 */
    135. {
    136. temp_val += g_adc_value[t];
    137. }
    138. return temp_val / ADC_COLL; /* 返回平均值 */
    139. }

     pid.h

    1. #ifndef __PID_H
    2. #define __PID_H
    3. #include "./SYSTEM/sys/sys.h"
    4. /************************************ PID相关参数 ****************************************/
    5. #define C_KP 2.00f /* P参数 */
    6. #define C_KI 0.20f /* I参数 */
    7. #define C_KD 0.01f /* D参数 */
    8. #define S_KP 0.00800f /* P参数 */
    9. #define S_KI 0.00025f /* I参数 */
    10. #define S_KD 0.00020f /* D参数 */
    11. #define SMAPLSE_PID_SPEED 40 /* 采样率 单位ms */
    12. /*PID结构体*/
    13. typedef struct
    14. {
    15. __IO float SetPoint; /* 设定目标 */
    16. __IO float ActualValue; /* 实际值 */
    17. __IO float SumError; /* 误差累计 */
    18. __IO float Up; /* 比例项 */
    19. __IO float Ui; /* 积分项 */
    20. __IO float Ud; /* 微分项 */
    21. __IO float Proportion; /* 比例常数 P */
    22. __IO float Integral; /* 积分常数 I */
    23. __IO float Derivative; /* 微分常数 D */
    24. __IO float Error; /* Error[-1] */
    25. __IO float LastError; /* Error[-1] */
    26. __IO float PrevError; /* Error[-2] */
    27. __IO float IngMin;
    28. __IO float IngMax;
    29. __IO float OutMin;
    30. __IO float OutMax;
    31. } PID_TypeDef;
    32. #define LIMIT_OUT(var,max,min) {(var)=(var)>(max)?(max):(var);(var)=(var)<(min)?(min):(var);}
    33. extern PID_TypeDef g_current_pid; /* 电流PID参数结构体 */
    34. extern PID_TypeDef g_speed_pid; /* 速度PID参数结构体 */
    35. /*********************************** 函数声明 **************************************/
    36. void pid_init(void); /* PID初始化函数 */
    37. int32_t increment_pid_ctrl(PID_TypeDef *PID,float Feedback_value); /* PID控制算法 */
    38. #endif

    pid.c

    1. #include "./BSP/PID/pid.h"
    2. #include "./BSP/BLDC/bldc.h"
    3. PID_TypeDef g_current_pid; /* 电流PID参数结构体 */
    4. PID_TypeDef g_speed_pid; /* 速度PID参数结构体 */
    5. /**
    6. * @brief 初始化PID
    7. * @param 无
    8. * @retval 无
    9. */
    10. void pid_init(void)
    11. {
    12. /* 设定电流目标1500mA(空载最小电流400mA左右)较高的转速对应的电流较大,力矩较大,可适应较高的转速调节*/
    13. /* 【注意】如设置的转速对应的电流超过了电流设定值,将导致PID转至电流环调节,转速将无法继续提升 */
    14. g_current_pid.SetPoint = 1500.0;
    15. g_current_pid.ActualValue = 0.0; /* 设定目标Desired Value */
    16. g_current_pid.LastError = 0.0; /* Error[1] */
    17. g_current_pid.LastError = 0.0; /* Error[-1] */
    18. g_current_pid.PrevError = 0.0; /* Error[-2] */
    19. g_current_pid.Proportion = C_KP; /* 比例常数 Proportional Const */
    20. g_current_pid.Integral = C_KI; /* 积分常数 Integral Const */
    21. g_current_pid.Derivative = C_KD; /* 微分常数 Derivative Const */
    22. g_current_pid.IngMax = 9000; /* 积分限制 */
    23. g_current_pid.IngMin = 600;
    24. g_current_pid.OutMin = 600;
    25. g_current_pid.OutMax = 9000; /* 期望限制 */
    26. g_speed_pid.SetPoint = 0; /* 设定目标Desired Value */
    27. g_speed_pid.ActualValue = 0.0; /* 设定目标Desired Value */
    28. g_speed_pid.Ui = 0.0;
    29. g_speed_pid.Up = 0.0;
    30. g_speed_pid.Ud = 0.0;
    31. g_speed_pid.Error = 0.0; /* Error[1] */
    32. g_speed_pid.LastError = 0.0; /* Error[-1] */
    33. g_speed_pid.PrevError = 0.0; /* Error[-2] */
    34. g_speed_pid.Proportion = S_KP; /* 比例常数 Proportional Const */
    35. g_speed_pid.Integral = S_KI; /* 积分常数 Integral Const */
    36. g_speed_pid.Derivative = S_KD; /* 微分常数 Derivative Const */
    37. g_speed_pid.IngMax = 9000;
    38. g_speed_pid.IngMin = -9000;
    39. g_speed_pid.OutMax = 9000; /* 输出限制 */
    40. g_speed_pid.OutMin = -9000;
    41. }
    42. /**
    43. * @brief 位置式PID算法
    44. * @param *PID:PID结构体句柄所对应的目标值
    45. * @param Feedback_value : 实际值
    46. * @retval 目标控制量
    47. */
    48. int32_t increment_pid_ctrl(PID_TypeDef *PID,float Feedback_value)
    49. {
    50. PID->Error = (float)(PID->SetPoint - Feedback_value); /* 目标值与实际值的偏差值 */
    51. PID->Up = PID->Proportion * PID->Error;
    52. PID->Ui += (PID->Error * PID->Integral);
    53. LIMIT_OUT(PID->Ui,PID->IngMax,PID->IngMin); /* 积分限制 */
    54. PID->Ud = PID->Derivative * (PID->Error - PID->LastError);
    55. PID->ActualValue = PID->Up + PID->Ui + PID->Ud;
    56. LIMIT_OUT(PID->ActualValue,PID->OutMax,PID->OutMin); /* 输出限制 */
    57. PID->LastError = PID->Error; /* 存储上次误差,以便下次计算使用 */
    58. return ((int32_t)(PID->ActualValue)); /* 返回实际控制数值 */
    59. }

     main.c

    1. #include "./SYSTEM/sys/sys.h"
    2. #include "./SYSTEM/usart/usart.h"
    3. #include "./SYSTEM/delay/delay.h"
    4. #include "./BSP/LED/led.h"
    5. #include "./BSP/TIMER/bldc_tim.h"
    6. #include "./BSP/KEY/key.h"
    7. #include "./BSP/LCD/lcd.h"
    8. #include "./BSP/BLDC/bldc.h"
    9. #include "./BSP/PID/pid.h"
    10. #include "./DEBUG/debug.h"
    11. #include "./BSP/ADC/adc.h"
    12. extern float*user_setpoint;
    13. extern float debug_data_temp;
    14. extern int32_t motor_pwm_s;
    15. extern int32_t temp_pwm1;
    16. extern int16_t adc_amp_un[3];
    17. extern float adc_amp_bus;
    18. extern uint16_t g_adc_value[ADC_CH_NUM * ADC_COLL];
    19. extern uint8_t clc;
    20. void bldc_speed_stop(void); /* 清除电机状态并关闭电机 */
    21. int main(void)
    22. {
    23. uint8_t debug_cmd = 0; /* 存放上位机指令 */
    24. float current_lpf[4] = {0.0f}; /* 存放三相电流以及母线电流 */
    25. uint8_t key,t;
    26. char buf[32];
    27. float current[3] = {0.0f};
    28. int16_t speed_diplay = 0;
    29. float user_setpoint_temp = 0.0;
    30. HAL_Init(); /* 初始化HAL库 */
    31. sys_stm32_clock_init(336, 8, 2, 7); /* 设置时钟,168Mhz */
    32. delay_init(168); /* 延时初始化 */
    33. usart_init(115200); /* 串口初始化为115200 */
    34. led_init(); /* 初始化LED */
    35. key_init(); /* 初始化按键 */
    36. lcd_init(); /* 初始化LCD */
    37. bldc_init(168000/18-1,0); /* 18KHz */
    38. bldc_ctrl(MOTOR_1,CCW,0); /* 初始无刷电机接口1速度 */
    39. pid_init();
    40. g_point_color = WHITE;
    41. g_back_color = BLACK;
    42. adc_nch_dma_init();
    43. while (1)
    44. {
    45. t++;
    46. if(t % 20 == 0)
    47. {
    48. sprintf(buf,"PWM_Duty:%.1f%% ",(float)((g_bldc_motor1.pwm_duty/MAX_PWM_DUTY)*100)); /* 显示控制PWM占空比 */
    49. lcd_show_string(10,110,200,16,16,buf,g_point_color);
    50. user_setpoint_temp = (*user_setpoint);
    51. speed_diplay = g_bldc_motor1.speed;
    52. sprintf(buf,"SetSpeed:%4d ",(int16_t)user_setpoint_temp); /* 显示设置速度 */
    53. lcd_show_string(10,110,200,16,16,buf,g_point_color);
    54. sprintf(buf,"M1 speed:%4d ",speed_diplay); /* 显示转速 */
    55. lcd_show_string(10,130,200,16,16,buf,g_point_color);
    56. sprintf(buf,"M1 pos:%4d",g_bldc_motor1.pos); /* 显示位置变化 */
    57. lcd_show_string(10,150,200,16,16,buf,g_point_color);
    58. sprintf(buf,"PWM_Duty:%.1f%% ",(float)((g_bldc_motor1.pwm_duty/(float)MAX_PWM_DUTY)*100)); /* 显示控制PWM占空比 */
    59. lcd_show_string(10,170,200,16,16,buf,g_point_color);
    60. sprintf(buf,"Power:%.3fV ",g_adc_value[0]*ADC2VBUS);
    61. lcd_show_string(10,190,200,16,16,buf,g_point_color);
    62. sprintf(buf,"Temp:%.1fC ",get_temp(g_adc_value[1]));
    63. lcd_show_string(10,210,200,16,16,buf,g_point_color);
    64. LED0_TOGGLE(); /* LED0(红灯) 翻转 */
    65. /* 三相电流计算 */
    66. current[0] = adc_amp_un[0]* ADC2CURT;/*U*/
    67. current[1] = adc_amp_un[1]* ADC2CURT;/*V*/
    68. current[2] = adc_amp_un[2]* ADC2CURT;/*W*/
    69. /*一阶数字滤波 滤波系数0.1 用于显示*/
    70. FirstOrderRC_LPF(current_lpf[0],current[0],0.1f);
    71. FirstOrderRC_LPF(current_lpf[1],current[1],0.1f);
    72. FirstOrderRC_LPF(current_lpf[2],current[2],0.1f);
    73. FirstOrderRC_LPF(current_lpf[3],adc_amp_bus,0.1f);
    74. if(g_bldc_motor1.run_flag == STOP) /* 停机的电流显示 */
    75. {
    76. current_lpf[0]=0;
    77. current_lpf[1]=0;
    78. current_lpf[2]=0;
    79. current_lpf[3]=0;
    80. }
    81. }
    82. key = key_scan(0);
    83. if(key == KEY0_PRES) /* 按下KEY0目标速度值++ */
    84. {
    85. g_bldc_motor1.run_flag = RUN; /* 开启运行 */
    86. start_motor1(); /* 开启运行 */
    87. if(g_bldc_motor1.dir == CCW && *user_setpoint == 0) /* 切换方向条件*/
    88. {
    89. g_bldc_motor1.dir = CW;
    90. }
    91. *user_setpoint += 400; /* 逆时针旋转下递增 */
    92. if(*user_setpoint >= 3000) /* 最高不超过3000PRM */
    93. *user_setpoint = 3000;
    94. if(*user_setpoint == 0)
    95. {
    96. pid_init(); /* 初始化PID */
    97. g_bldc_motor1.run_flag = STOP; /* 标记停机 */
    98. stop_motor1(); /* 停机 */
    99. g_bldc_motor1.speed = 0;
    100. motor_pwm_s = 0;
    101. g_bldc_motor1.pwm_duty = 0;
    102. }
    103. debug_data_temp = *user_setpoint;
    104. }
    105. else if(key == KEY1_PRES) /* 按下KEY1目标速度值-- */
    106. {
    107. g_bldc_motor1.run_flag = RUN; /* 开启运行 */
    108. start_motor1(); /* 运行电机 */
    109. /* 切换方向条件 */
    110. if(g_bldc_motor1.dir == CW && *user_setpoint == 0)
    111. {
    112. g_bldc_motor1.dir = CCW;
    113. }
    114. *user_setpoint -= 400; /* 逆时针旋转下递增 */
    115. if(*user_setpoint <= -3000) /* 最高不超过300PRM */
    116. *user_setpoint = -3000;
    117. if(*user_setpoint == 0)
    118. {
    119. pid_init(); /* 初始化PID */
    120. g_bldc_motor1.run_flag = STOP; /* 标记停机 */
    121. stop_motor1(); /* 停机 */
    122. g_bldc_motor1.speed = 0;
    123. motor_pwm_s = 0;
    124. g_bldc_motor1.pwm_duty = 0;
    125. }
    126. debug_data_temp = *user_setpoint;
    127. }
    128. else if(key == KEY2_PRES) /* 按下KEY2关闭电机 */
    129. {
    130. bldc_speed_stop();
    131. }
    132. delay_ms(10);
    133. }
    134. }
    135. /**
    136. * @brief 关闭电机并清除状态
    137. * @param 无
    138. * @retval 无
    139. */
    140. void bldc_speed_stop(void)
    141. {
    142. pid_init();
    143. g_bldc_motor1.run_flag = STOP; /* 标记停机 */
    144. stop_motor1(); /* 停机 */
    145. g_bldc_motor1.speed = 0;
    146. motor_pwm_s = 0;
    147. g_bldc_motor1.pwm_duty = 0;
    148. }

     g_bldc_motor1.count_j就是高电平的计数值。在高电平时先清零累加。从1到0为低电平时。后去 g_bldc_motor1.count_j的值就是高电平的计数值。

    #define SPEED_COEFF      (uint32_t)((18000/4)*60)       /* 旋转一圈变化4个信号,2对级永磁体特性,NSNS共4级数 */

    速度计算:temp_speed = (SPEED_COEFF/g_bldc_motor1.count_j)

    速度的计算在代码的体现:电机是两对极。完全与公式是相同的。

      

     

  • 相关阅读:
    MySQL高级篇——事务
    基于nodejs+vue云旅青城系统
    全网超50万粉丝的Linux大咖良许,出书了!
    pg 时间操作方法
    入侵防御系统(IPS)网络安全设备介绍
    Django项目 - 合并PDF文件
    基于Java+vue前后端分离失物招领信息交互平台设计实现(源码+lw+部署文档+讲解等)
    PHP学习笔记(一往无前)
    实时监控Mysql等数据库变化_进行数据同步_了解Debezium_--Debezium工作笔记001
    R语言ggplot2可视化:使用patchwork包将2个ggplot2可视化结果横向组合、并自定义修改(更改)组合图像中指定子图的主题(theme)
  • 原文地址:https://blog.csdn.net/qq_41328470/article/details/127950618