/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* © Copyright (c) 2022 STMicroelectronics.
* All rights reserved.
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "bsp_delay.h"
#include "bsp_key.h"
#include "bsp_motor.h"
#include "bsp_usart.h"
#include "bsp_pid.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim3;
TIM_HandleTypeDef htim8;
UART_HandleTypeDef huart1;
/* USER CODE BEGIN PV */
int16_t g_update_cnt = 0;
uint32_t g_step_timer_pulse_num; /* 电机运行一步需要定时器的脉冲数 */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_TIM8_Init(void);
static void MX_USART1_UART_Init(void);
static void MX_TIM3_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_TIM8_Init();
MX_USART1_UART_Init();
MX_TIM3_Init();
/* USER CODE BEGIN 2 */
delay_init(168);
usart_init();
pid_init();
HAL_GPIO_WritePin(GPIOD, GPIO_PIN_3, GPIO_PIN_RESET); /* 设置方向 */
HAL_GPIO_WritePin(GPIOD, GPIO_PIN_7, GPIO_PIN_RESET); /* 使能ENABLE */
uint32_t tick_start_run; /* 开始运行时刻 */
uint32_t tick;
uint8_t buffer_usart_send[16];
uint8_t i;
uint16_t sum;
uint32_t speed_step_per_second;
uint8_t run = 0;
uint32_t velocity_current;
__IO uint32_t step;
__IO uint32_t period;
__HAL_TIM_SET_COUNTER(&htim3, 0);
__HAL_TIM_CLEAR_FLAG(&htim3, TIM_FLAG_UPDATE);
__HAL_TIM_ENABLE_IT(&htim3, TIM_IT_UPDATE);
HAL_TIM_Encoder_Start(&htim3, TIM_CHANNEL_ALL);
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
usart_task();
if(KEY1_StateRead()==KEY_DOWN)
{
MOTOR_DIR_FORWARD;
tick_start_run = HAL_GetTick();
run = 1;
g_step_timer_pulse_num = 65535;
TIM8->CCR1 = g_step_timer_pulse_num >> 1;
TIM8->ARR = g_step_timer_pulse_num;
HAL_TIM_PWM_Start_IT(&htim8, TIM_CHANNEL_1);
}
if (KEY2_StateRead() == KEY_DOWN)
{
MOTOR_DIR_REVERSE;
tick_start_run = HAL_GetTick();
g_step_timer_pulse_num = 300;
TIM8->CCR1 = g_step_timer_pulse_num >> 1;
TIM8->ARR = g_step_timer_pulse_num;
HAL_TIM_PWM_Start_IT(&htim8, TIM_CHANNEL_1);
}
if (1 == run)
{
pid_ctrl(get_pid_velocity().target);
}
tick = HAL_GetTick();
if (1 == run)
{
speed_step_per_second = TIM_CLK / g_step_timer_pulse_num;
velocity_current = get_velocity_current() * 1000;
buffer_usart_send[0] = 0x01; /* 帧头 */
buffer_usart_send[1] = 0x67; /* 帧头 */
buffer_usart_send[2] = 0x42; /* 帧头 */
buffer_usart_send[3] = 0xc0; /* 帧头 */
buffer_usart_send[4] = (tick - tick_start_run) >> 8; /* 时刻 */
buffer_usart_send[5] = (tick - tick_start_run) & 0xff; /* 时刻 */
buffer_usart_send[6] = speed_step_per_second >> 24; /* 电机速度,step/s */
buffer_usart_send[7] = speed_step_per_second >> 16; /* 电机速度,step/s */
buffer_usart_send[8] = speed_step_per_second >> 8; /* 电机速度,step/s */
buffer_usart_send[9] = speed_step_per_second & 0xff; /* 电机速度,step/s */
buffer_usart_send[10] = velocity_current >> 24; /* 编码器速度,0.001mm/s */
buffer_usart_send[11] = velocity_current >> 16; /* 编码器速度,0.001mm/s */
buffer_usart_send[12] = velocity_current >> 8; /* 编码器速度,0.001mm/s */
buffer_usart_send[13] = velocity_current & 0xff; /* 编码器速度,0.001mm/s */
sum = 0;
for (i = 4; i < 14; i++)
{
sum += buffer_usart_send[i];
}
buffer_usart_send[14] = sum >> 8;
buffer_usart_send[15] = sum & 0xff;
HAL_UART_Transmit(&huart1, buffer_usart_send, 16, 1000);
//delay_ms(10);
}
else
{
tick_start_run = HAL_GetTick();
}
/* 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 = 8;
RCC_OscInitStruct.PLL.PLLN = 336;
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();
}
}
/**
* @brief TIM3 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM3_Init(void)
{
/* USER CODE BEGIN TIM3_Init 0 */
/* USER CODE END TIM3_Init 0 */
TIM_Encoder_InitTypeDef sConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM3_Init 1 */
/* USER CODE END TIM3_Init 1 */
htim3.Instance = TIM3;
htim3.Init.Prescaler = 0;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 65535;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
sConfig.EncoderMode = TIM_ENCODERMODE_TI12;
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
sConfig.IC1Filter = 0;
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
sConfig.IC2Filter = 0;
if (HAL_TIM_Encoder_Init(&htim3, &sConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM3_Init 2 */
/* USER CODE END TIM3_Init 2 */
}
/**
* @brief TIM8 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM8_Init(void)
{
/* USER CODE BEGIN TIM8_Init 0 */
/* USER CODE END TIM8_Init 0 */
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
/* USER CODE BEGIN TIM8_Init 1 */
/* USER CODE END TIM8_Init 1 */
htim8.Instance = TIM8;
htim8.Init.Prescaler = 20;
htim8.Init.CounterMode = TIM_COUNTERMODE_UP;
htim8.Init.Period = 65535;
htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim8.Init.RepetitionCounter = 0;
htim8.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim8) != HAL_OK)
{
Error_Handler();
}
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_Init(&htim8) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_OnePulse_Init(&htim8, TIM_OPMODE_SINGLE) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 65535;
sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
if (HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
__HAL_TIM_DISABLE_OCxPRELOAD(&htim8, TIM_CHANNEL_1);
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
sBreakDeadTimeConfig.DeadTime = 0;
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
if (HAL_TIMEx_ConfigBreakDeadTime(&htim8, &sBreakDeadTimeConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM8_Init 2 */
__HAL_TIM_ENABLE_IT(&htim8, TIM_IT_UPDATE);
/* USER CODE END TIM8_Init 2 */
HAL_TIM_MspPostInit(&htim8);
}
/**
* @brief USART1 Initialization Function
* @param None
* @retval None
*/
static void MX_USART1_UART_Init(void)
{
/* USER CODE BEGIN USART1_Init 0 */
/* USER CODE END USART1_Init 0 */
/* USER CODE BEGIN USART1_Init 1 */
/* USER CODE END USART1_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
if (HAL_UART_Init(&huart1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOE_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOH_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOI_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOF, GPIO_PIN_11, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOD, GPIO_PIN_11|GPIO_PIN_3|GPIO_PIN_7, GPIO_PIN_RESET);
/*Configure GPIO pins : PE2 PE3 PE4 PE0
PE1 */
GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_0
|GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
/*Configure GPIO pin : PF11 */
GPIO_InitStruct.Pin = GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
/*Configure GPIO pins : PD11 PD3 PD7 */
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_3|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
}
/* 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) COPYRIGHT STMicroelectronics *****END OF FILE****/
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f4xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* © Copyright (c) 2022 STMicroelectronics.
* All rights reserved.
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f4xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "bsp_motor.h"
#include "bsp_usart_host.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* 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 -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
extern TIM_HandleTypeDef htim3;
extern TIM_HandleTypeDef htim8;
extern UART_HandleTypeDef huart1;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M4 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
/* USER CODE END W1_MemoryManagement_IRQn 0 */
}
}
/**
* @brief This function handles Pre-fetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_BusFault_IRQn 0 */
/* USER CODE END W1_BusFault_IRQn 0 */
}
}
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_UsageFault_IRQn 0 */
/* USER CODE END W1_UsageFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVCall_IRQn 0 */
/* USER CODE END SVCall_IRQn 0 */
/* USER CODE BEGIN SVCall_IRQn 1 */
/* USER CODE END SVCall_IRQn 1 */
}
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
/* USER CODE BEGIN DebugMonitor_IRQn 1 */
/* USER CODE END DebugMonitor_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_IRQn 1 */
}
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F4xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f4xx.s). */
/******************************************************************************/
/**
* @brief This function handles TIM3 global interrupt.
*/
void TIM3_IRQHandler(void)
{
/* USER CODE BEGIN TIM3_IRQn 0 */
/* USER CODE END TIM3_IRQn 0 */
HAL_TIM_IRQHandler(&htim3);
/* USER CODE BEGIN TIM3_IRQn 1 */
/* USER CODE END TIM3_IRQn 1 */
}
/**
* @brief This function handles USART1 global interrupt.
*/
void USART1_IRQHandler(void)
{
/* USER CODE BEGIN USART1_IRQn 0 */
/* USER CODE END USART1_IRQn 0 */
HAL_UART_IRQHandler(&huart1);
/* USER CODE BEGIN USART1_IRQn 1 */
/* USER CODE END USART1_IRQn 1 */
}
/**
* @brief This function handles TIM8 update interrupt and TIM13 global interrupt.
*/
void TIM8_UP_TIM13_IRQHandler(void)
{
/* USER CODE BEGIN TIM8_UP_TIM13_IRQn 0 */
/* USER CODE END TIM8_UP_TIM13_IRQn 0 */
HAL_TIM_IRQHandler(&htim8);
/* USER CODE BEGIN TIM8_UP_TIM13_IRQn 1 */
/* USER CODE END TIM8_UP_TIM13_IRQn 1 */
}
/* USER CODE BEGIN 1 */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
if (htim == &htim3)
{
if (__HAL_TIM_IS_TIM_COUNTING_DOWN(&htim3))
{
g_update_cnt--;
}
else
{
g_update_cnt++;
}
}
if (htim == &htim8)
{
HAL_TIM_PWM_Stop_IT(&htim8, TIM_CHANNEL_1);
TIM8->CCR1 = g_step_timer_pulse_num >> 1;
TIM8->ARR = g_step_timer_pulse_num;
HAL_TIM_PWM_Start_IT(&htim8, TIM_CHANNEL_1);
}
}
/**
* @brief usart接收中断处理回调函数
* @param huart 指针,指向产生中断的huart
* @note:
* @retval 无
*/
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
if(huart == &HUSART_HOST)
{
usart_wr_rxfifo_host(&g_usart_host_rx_data, 1);
HAL_UART_Receive_IT(huart, &g_usart_host_rx_data, 1);
}
}
/**
* @brief 如果usart产生错误中断,重新初始化usart
* @param huart 指针,指向产生中断的huart
* @note:
* @retval 无
*/
void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart)
{
if(huart == &HUSART_HOST)
{
host_usart1_uart_init();
}
}
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
#ifndef BSP_FIFO_H
#define BSP_FIFO_H
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
#define FIFO_DATA_LEN 128 // 取2的n次方
typedef struct
{
uint8_t data[FIFO_DATA_LEN]; // 数据缓冲区,最大256
uint8_t wr, rd; // 读写索引: 指针重合时为空, 最多存(bufferSize - 1)个字节
} fifo_typedef;
uint8_t write_fifo(fifo_typedef *fifo, uint8_t val);
uint8_t read_fifo(fifo_typedef *fifo, uint8_t *val);
void clear_fifo(fifo_typedef *fifo);
#ifdef __cplusplus
}
#endif
#endif /* BSP_FIFO_H */
/**
******************************************************************************
* @file bsp_fifo.c
* @author
* @version V1.0
* @date
* @brief 读写FIFO
* @others
* @copyright
******************************************************************************
* @history
*
* 1.date
* author
* modification
*
******************************************************************************
*/
#include "bsp_fifo.h"
#include
/**
* @brief 写FIFO
* @param fifo: 指针,指向要将数据写入的FIFO
* @param val:写入FIFO的数值
* @note:
* @retval 0:写入成功
* 1:写入失败
*/
uint8_t write_fifo(fifo_typedef *fifo, uint8_t val)
{
uint8_t ret;
if (((fifo->wr + 1) & (FIFO_DATA_LEN - 1)) != fifo->rd) /* 判断是否已满,若FIFO没有被写满则进入if语句 */
{
fifo->data[fifo->wr] = val;
fifo->wr = (fifo->wr + 1) & (FIFO_DATA_LEN - 1);
ret = 0; /* 成功写入 */
}
else
{
ret = 1;
}
return ret;
}
/**
* @brief 读FIFO
* @param fifo:指针,指向要读的FIFO
* @param val:指针,指向读出来的数值
* @note:
* @retval 0:读取成功
* 1:读取失败
*/
uint8_t read_fifo(fifo_typedef *fifo, uint8_t *val)
{
uint8_t ret;
if (fifo->wr != fifo->rd) /* 判断FIFO是否为空,若不为空则进入if语句 */
{
*val = fifo->data[fifo->rd];
fifo->rd = (fifo->rd + 1) & (FIFO_DATA_LEN - 1);
ret = 0; /* 成功读出 */
}
else
{
ret = 1;
}
return ret;
}
/**
* @brief 清除FIFO中的数据,将FIFO中的数据全部置零,并设置为空FIFO
* @param fifo:指针,指向要清除的FIFO
* @note:
* @retval 无
*/
void clear_fifo(fifo_typedef *fifo)
{
memset(fifo->data, 0, FIFO_DATA_LEN);
fifo->rd = 0;
fifo->wr = 0;
}
#ifndef BSP_USART_HOST_H
#define BSP_USART_HOST_H
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
#define HUSART_HOST huart1
extern uint8_t g_usart_host_rx_data;
void host_usart1_uart_init(void);
uint8_t usart_init_host(void);
uint8_t usart_rd_txfifo_host(void);
uint8_t usart_rd_rxfifo_host(uint8_t *data);
uint8_t usart_wr_txfifo_host(uint8_t *data, uint16_t len);
uint8_t usart_wr_rxfifo_host(uint8_t* data, uint16_t len);
#ifdef __cplusplus
}
#endif
#endif /* BSP_USART_HOST_H */
/**
******************************************************************************
* @file bsp_usart_host.c
* @author
* @version V1.0
* @date
* @brief 与下位机RS485通信处理相关代码
* @others
* @copyright
******************************************************************************
* @history
*
* 1.date
* author
* modification
*
******************************************************************************
*/
#include "bsp_usart_host.h"
#include "bsp_fifo.h"
/* 接收下位机发送过来的数据,中断函数中会使用 */
uint8_t g_usart_host_rx_data;
static fifo_typedef s_fifo_tx;
static fifo_typedef s_fifo_rx;
/**
* @brief 当串口进入错误中断后,对串口重新初始化
* @param
* @note:
* @retval 0:执行成功
*/
void host_usart1_uart_init(void)
{
/* USER CODE BEGIN USART2_Init 0 */
HAL_UART_DeInit(&huart1);
/* USER CODE END USART2_Init 0 */
/* USER CODE BEGIN USART2_Init 1 */
/* USER CODE END USART2_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
if (HAL_UART_Init(&huart1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART2_Init 2 */
/* USER CODE END USART2_Init 2 */
}
/**
* @brief 对FIFO初始化,使能串口接收中断
* @param
* @note:
* @retval 0:执行成功
*/
uint8_t usart_init_host(void)
{
clear_fifo(&s_fifo_tx);
clear_fifo(&s_fifo_rx);
HAL_UART_Receive_IT(&HUSART_HOST, &g_usart_host_rx_data, 1);
return 0;
}
/**
* @brief 如果用于串口发送的FIFO_TX中有数据,将数据从FIFO_TX中读出来,然后串口发送
* @param
* @note:
* @retval 0:执行成功
*/
uint8_t usart_rd_txfifo_host(void)
{
uint8_t data;
if ((HUSART_HOST.Instance->SR & UART_FLAG_TXE) != 0) /* 发送数据寄存器为空,表示可以写数据 */
{
if (read_fifo(&s_fifo_tx, &data) == 0) /* FIFO读取成功 */
{
HUSART_HOST.Instance->DR = data;
}
}
return 0;
}
/**
* @brief 如果用于串口接收的FIFO_RX中有数据,将数据从FIFO_RX中读出来
* @param data:指针,指向从FIFO中读出来的数据
* @note:
* @retval 0:读取成功
* 1:读取失败
*/
uint8_t usart_rd_rxfifo_host(uint8_t *data)
{
if (read_fifo(&s_fifo_rx, data) == 0) /* FIFO读取成功 */
{
return 0;
}
else
{
return 1;
}
}
/**
* @brief 将需要发送的数据写入到FIFO中
* @param data:指针,指向需要发送数据的数组
* @param len:数组长度
* @note:
* @retval 0:写入成功
* 1:写入失败
*/
uint8_t usart_wr_txfifo_host(uint8_t *data, uint16_t len)
{
uint16_t i;
for (i = 0; i < len; i++)
{
if (write_fifo(&s_fifo_tx, data[i]) != 0) /* 写FIFO失败 */
{
return 1;
}
}
return 0;
}
/**
* @brief 将接收到的数据写入到FIFO中
* @param data:指针,指向接收到数据的数组
* @param len:数组长度
* @note:
* @retval 0:写入成功
* 1:写入失败
*/
uint8_t usart_wr_rxfifo_host(uint8_t* data, uint16_t len)
{
uint16_t i;
for (i = 0; i < len; i++)
{
if (write_fifo(&s_fifo_rx, data[i]) != 0) /* 写FIFO失败 */
{
return 1;
}
}
return 0;
}
#ifndef BSP_FRAME_HOST_H
#define BSP_FRAME_HOST_H
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
uint8_t frame_check_host(uint8_t *data, uint16_t len);
static uint8_t frame_parse_host(void);
#ifdef __cplusplus
}
#endif
#endif /* BSP_FRAME_HOST_H */
/**
******************************************************************************
* @file bsp_frame_host.c
* @author
* @version V1.0
* @date
* @brief
* @others
* @copyright
******************************************************************************
* @history
*
* 1.date
* author
* modification
*
******************************************************************************
*/
#include "bsp_frame_host.h"
#include "bsp_pid.h"
static const uint8_t s_frame_header[] = { 0x01, 0x67, 0x42, 0xc0 }; /* 帧头4字节 */
#define FRAME_BUFFER_LEN 128 /* 帧缓存数组大小 */
static uint8_t s_frame_buffer_rx[FRAME_BUFFER_LEN]; /*帧缓存,用于缓存接收到的数据*/
static uint8_t frame_parse_host(void);
/**
* @brief 协议帧校验
* @param data 指针,指向接收到数据的数组
* @param len 数组data长度
* @note:
* @retval 0:执行成功
* 1:执行失败
*/
uint8_t frame_check_host(uint8_t *data, uint16_t len)
{
static uint16_t frame_index_rx = 0; /* 接收帧收到了几个有效字节 */
static uint16_t frame_len_rx; /* 接收帧中显示的帧长度 */
static uint16_t frame_calc_sum;
uint16_t i;
uint16_t frame_check_code; /* 接收帧中显示的校验码 */
for (i = 0; i < len; i++)
{
if (frame_index_rx >= FRAME_BUFFER_LEN) /* 如果帧缓存的字节数已经超过数组长度 */
{
frame_index_rx = 0;
}
if (frame_index_rx == 0) /* 还未接收到帧头,则进入if语句,寻找帧头 */
{
s_frame_buffer_rx[0] = s_frame_buffer_rx[1];
s_frame_buffer_rx[1] = s_frame_buffer_rx[2];
s_frame_buffer_rx[2] = s_frame_buffer_rx[3];
s_frame_buffer_rx[3] = data[i];
if ((s_frame_buffer_rx[0] == s_frame_header[0]) && (s_frame_buffer_rx[1] == s_frame_header[1])
&& (s_frame_buffer_rx[2] == s_frame_header[2]) && (s_frame_buffer_rx[3] == s_frame_header[3]))
{
frame_index_rx = 4; /* 接收到帧头 */
frame_len_rx = 0;
frame_calc_sum = 0;
}
}
else
{
s_frame_buffer_rx[frame_index_rx] = data[i];
if (frame_index_rx < frame_len_rx + 8)
{
frame_calc_sum += data[i];
if (frame_index_rx == 7)
{
frame_len_rx = ((uint16_t)s_frame_buffer_rx[6] << 8) | data[i];
if (frame_len_rx >= FRAME_BUFFER_LEN - 10) /* 帧过长 */
{
frame_index_rx = 0;
continue;
}
}
}
else /* 接收到校验码 */
{
if (frame_index_rx == frame_len_rx + 9)
{
frame_check_code = ((uint16_t)s_frame_buffer_rx[frame_index_rx - 1] << 8) | data[i];
if (frame_calc_sum == frame_check_code)
{
frame_parse_host(); /* 帧解析 */
}
frame_index_rx = 0; /* 接收到一帧完整帧 */
continue;
}
}
frame_index_rx++;
}
}
return 0;
}
/**
* @brief 协议帧解析
* @param
* @note:
* @retval 0:执行成功
*/
static uint8_t frame_parse_host(void)
{
uint8_t frame_type;
uint32_t pos_pid_target;
uint32_t pos_pid_p;
uint32_t pos_pid_i;
uint32_t pos_pid_d;
uint32_t velocity_pid_target;
uint32_t velocity_pid_p;
uint32_t velocity_pid_i;
uint32_t velocity_pid_d;
frame_type = s_frame_buffer_rx[4];
if (0x00 == frame_type) /* 熔炼命令帧 */
{
pos_pid_target = ((uint32_t)s_frame_buffer_rx[8] << 24) | ((uint32_t)s_frame_buffer_rx[9] << 16)
| ((uint32_t)s_frame_buffer_rx[10] << 8) | ((uint32_t)s_frame_buffer_rx[11] << 0);
set_pid_pos_target(pos_pid_target * 1.0 / 1000);
pos_pid_p = ((uint32_t)s_frame_buffer_rx[12] << 24) | ((uint32_t)s_frame_buffer_rx[13] << 16)
| ((uint32_t)s_frame_buffer_rx[14] << 8) | ((uint32_t)s_frame_buffer_rx[15] << 0);
set_pid_pos_p(pos_pid_p * 1.0 / 1000);
pos_pid_i = ((uint32_t)s_frame_buffer_rx[16] << 24) | ((uint32_t)s_frame_buffer_rx[17] << 16)
| ((uint32_t)s_frame_buffer_rx[18] << 8) | ((uint32_t)s_frame_buffer_rx[19] << 0);
set_pid_pos_i(pos_pid_i * 1.0 / 1000);
pos_pid_d = ((uint32_t)s_frame_buffer_rx[20] << 24) | ((uint32_t)s_frame_buffer_rx[21] << 16)
| ((uint32_t)s_frame_buffer_rx[22] << 8) | ((uint32_t)s_frame_buffer_rx[23] << 0);
set_pid_pos_d(pos_pid_d * 1.0 / 1000);
velocity_pid_target = ((uint32_t)s_frame_buffer_rx[24] << 24) | ((uint32_t)s_frame_buffer_rx[25] << 16)
| ((uint32_t)s_frame_buffer_rx[26] << 8) | ((uint32_t)s_frame_buffer_rx[27] << 0);
set_pid_velocity_target(velocity_pid_target * 1.0 / 1000);
velocity_pid_p = ((uint32_t)s_frame_buffer_rx[28] << 24) | ((uint32_t)s_frame_buffer_rx[29] << 16)
| ((uint32_t)s_frame_buffer_rx[30] << 8) | ((uint32_t)s_frame_buffer_rx[31] << 0);
set_pid_velocity_p(velocity_pid_p * 1.0 / 1000);
velocity_pid_i = ((uint32_t)s_frame_buffer_rx[32] << 24) | ((uint32_t)s_frame_buffer_rx[33] << 16)
| ((uint32_t)s_frame_buffer_rx[34] << 8) | ((uint32_t)s_frame_buffer_rx[35] << 0);
set_pid_velocity_i(velocity_pid_i * 1.0 / 1000);
velocity_pid_d = ((uint32_t)s_frame_buffer_rx[36] << 24) | ((uint32_t)s_frame_buffer_rx[37] << 16)
| ((uint32_t)s_frame_buffer_rx[38] << 8) | ((uint32_t)s_frame_buffer_rx[39] << 0);
set_pid_velocity_d(velocity_pid_d * 1.0 / 1000);
}
return 0;
}
#ifndef BSP_RS485_H
#define BSP_RS485_H
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
uint8_t usart_init(void);
uint8_t usart_task(void);
#ifdef __cplusplus
}
#endif
#endif /* BSP_RS485_H */
/**
******************************************************************************
* @file bsp_usart.c
* @author
* @version V1.0
* @date
* @brief
* @others
* @copyright
******************************************************************************
* @history
*
* 1.date
* author
* modification
*
******************************************************************************
*/
#include "bsp_usart.h"
#include "bsp_usart_host.h"
#include "bsp_frame_host.h"
/**
* @brief usart相关接口初始化
* @param
* @note:
* @retval 0:执行成功
*/
uint8_t usart_init(void)
{
usart_init_host();
return 0;
}
/**
* @brief usart相关执行程序,在主循环中轮询执行
* @param
* @note:
* @retval 0:执行成功
*/
uint8_t usart_task(void)
{
uint8_t data;
usart_rd_txfifo_host(); /* 如果用于串口发送的FIFO_TX中有数据,将数据从FIFO_TX中读出来,然后串口发送 */
if (0 == usart_rd_rxfifo_host(&data)) /* 如果用于串口接收的FIFO_RX中有数据,将数据从FIFO_RX中读出来,进入if语句 */
{
frame_check_host(&data, 1);
}
return 0;
}
#ifndef BSP_PID_H
#define BSP_PID_H
#include "main.h"
#ifdef __cplusplus
extern "C" {
#endif
#define STEP_ENCODER_CIRCLE 2400
//#define LEAD_MOTOR 4
typedef struct
{
double target; /* 目标值 */
double p;
double i;
double d;
}pid_typedef;
uint8_t pid_init(void);
double inc_pid_calc_velocity(double current_val, double target_val);
uint8_t pid_ctrl(double target_val);
pid_typedef get_pid_pos(void);
uint8_t set_pid_pos_target(float target);
uint8_t set_pid_pos_p(float p);
uint8_t set_pid_pos_i(float i);
uint8_t set_pid_pos_d(float d);
pid_typedef get_pid_velocity(void);
uint8_t set_pid_velocity_target(float target);
uint8_t set_pid_velocity_p(float p);
uint8_t set_pid_velocity_i(float i);
uint8_t set_pid_velocity_d(float d);
double get_velocity_current(void);
#ifdef __cplusplus
}
#endif
#endif /* BSP_PID_H */
/**
******************************************************************************
* @file bsp_pid.c
* @author
* @version V1.0
* @date
* @brief
* @others
* @copyright
******************************************************************************
* @history
*
* 1.date
* author
* modification
*
******************************************************************************
*/
#include "bsp_pid.h"
#include "bsp_motor.h"
/*static*/ pid_typedef s_pos_pid;
/*static*/ pid_typedef s_velocity_pid;
/*static*/ double s_velocity_current; /* 单位:1mm/s */
/**
* @brief 协议帧校验
* @param data 指针,指向接收到数据的数组
* @param len 数组data长度
* @note:
* @retval 0:执行成功
* 1:执行失败
*/
uint8_t pid_init(void)
{
s_pos_pid.target = 50; /* 单位:mm */
s_pos_pid.p = 10;
s_pos_pid.i = 0;
s_pos_pid.d = 0;
s_velocity_pid.target = 5; /* 单位:mm/s */
s_velocity_pid.p = 0.11;
s_velocity_pid.i = 0.12;
s_velocity_pid.d = 0.03;
return 0;
}
/**
* @brief 增量式PID速度环计算
* @param current_val 当前值
* @param target_val 目标值
* @note:
* @retval 经过PID运算得到的增量值
*/
double inc_pid_calc_velocity(double current_val, double target_val)
{
double error = 0; /* 当前误差 */
static double inc_pid = 0;
static double last_error = 0;
static double prev_error = 0;
error = target_val - current_val; /* 增量计算 */
inc_pid += (s_velocity_pid.p * (error - last_error)) /* E[k]项 */
+ (s_velocity_pid.i * error) /* E[k-1]项 */
+ (s_velocity_pid.d * (error - 2 * last_error + prev_error)); /* E[k-2]项 */
prev_error = last_error; /* 存储误差,用于下次计算 */
last_error = error;
return inc_pid; /* 返回增量值 */
}
/**
* @brief PID控制
* @param target_val 目标值,单位:1mm/s
* @note:
* @retval
*/
uint8_t pid_ctrl(double target_val)
{
static uint32_t tick_old = 0;
uint32_t tick_current;
static uint32_t encoder_step_new = 0;
static uint32_t encoder_step_old = 0;
double inc_val; /* 增量值 */
double velocity_calc; /* PID计算后的速度 */
tick_current = HAL_GetTick();
if (tick_current - tick_old > 20)
{
encoder_step_new = g_update_cnt * htim3.Init.Period + __HAL_TIM_GET_COUNTER(&htim3);
s_velocity_current = (encoder_step_new - encoder_step_old) * 1.0 / STEP_ENCODER_CIRCLE * MOTOR_LEAD * 1000 / (tick_current - tick_old);
inc_val = inc_pid_calc_velocity(s_velocity_current, target_val);
velocity_calc = s_velocity_current + inc_val;
g_step_timer_pulse_num = TIM_CLK * 1.0 / (velocity_calc * 1.0 * STEP_PER_CIRCLE * MOTOR_DRIVER_SUBDIVISION / MOTOR_LEAD);
encoder_step_old = encoder_step_new;
tick_old = tick_current;
}
return 0;
}
/**
* @brief 获取位置PID参数
* @note:
* @retval
*/
pid_typedef get_pid_pos(void)
{
return s_pos_pid;
}
/**
* @brief 设置位置PID参数
* @note:
* @retval
*/
uint8_t set_pid_pos_target(float target)
{
s_pos_pid.target = target;
return 0;
}
/**
* @brief 设置位置PID参数
* @note:
* @retval
*/
uint8_t set_pid_pos_p(float p)
{
s_pos_pid.p = p;
return 0;
}
/**
* @brief 设置位置PID参数
* @note:
* @retval
*/
uint8_t set_pid_pos_i(float i)
{
s_pos_pid.i = i;
return 0;
}
/**
* @brief 设置位置PID参数
* @note:
* @retval
*/
uint8_t set_pid_pos_d(float d)
{
s_pos_pid.d = d;
return 0;
}
/**
* @brief 获取速度PID参数
* @note:
* @retval
*/
pid_typedef get_pid_velocity(void)
{
return s_velocity_pid;
}
/**
* @brief 获取速度PID参数
* @note:
* @retval
*/
uint8_t set_pid_velocity_target(float target)
{
s_velocity_pid.target = target;
return 0;
}
/**
* @brief 获取速度PID参数
* @note:
* @retval
*/
uint8_t set_pid_velocity_p(float p)
{
s_velocity_pid.p = p;
return 0;
}
/**
* @brief 获取速度PID参数
* @note:
* @retval
*/
uint8_t set_pid_velocity_i(float i)
{
s_velocity_pid.i = i;
return 0;
}
/**
* @brief 获取速度PID参数
* @note:
* @retval
*/
uint8_t set_pid_velocity_d(float d)
{
s_velocity_pid.d = d;
return 0;
}
/**
* @brief 获取实时速度,单位:mm/s
* @note:
* @retval
*/
double get_velocity_current(void)
{
return s_velocity_current;
}
总结:
1、串口可以设置PID参数
2、
3、
4、
5、
6、
7、
8、
9、
10、
11、
12、
13、
14、