This commit is contained in:
parent
1c265bee21
commit
a9eb7a6831
|
@ -4,8 +4,7 @@
|
|||
"board.h": "c",
|
||||
"motor.h": "c",
|
||||
"main.h": "c",
|
||||
"app.h": "c",
|
||||
"type_traits": "c"
|
||||
"app.h": "c"
|
||||
},
|
||||
"C_Cpp.errorSquiggles": "disabled"
|
||||
}
|
|
@ -154,7 +154,7 @@ void DMA1_Channel1_IRQHandler(void)
|
|||
/* USER CODE END DMA1_Channel1_IRQn 0 */
|
||||
|
||||
/* USER CODE BEGIN DMA1_Channel1_IRQn 1 */
|
||||
adc_convert_callback(adc1);
|
||||
|
||||
/* USER CODE END DMA1_Channel1_IRQn 1 */
|
||||
}
|
||||
|
||||
|
@ -168,7 +168,7 @@ void DMA1_Channel2_3_IRQHandler(void)
|
|||
/* USER CODE END DMA1_Channel2_3_IRQn 0 */
|
||||
|
||||
/* USER CODE BEGIN DMA1_Channel2_3_IRQn 1 */
|
||||
uart_dma_reception_callback(uarts[UART_NUM_1]);
|
||||
|
||||
/* USER CODE END DMA1_Channel2_3_IRQn 1 */
|
||||
}
|
||||
|
||||
|
@ -198,11 +198,13 @@ void TIM21_IRQHandler(void)
|
|||
/* USER CODE BEGIN TIM21_IRQn 0 */
|
||||
|
||||
/* USER CODE END TIM21_IRQn 0 */
|
||||
|
||||
/* USER CODE BEGIN TIM21_IRQn 1 */
|
||||
if (LL_TIM_IsActiveFlag_UPDATE(TIM21))
|
||||
{
|
||||
__NOP();
|
||||
step_motor_update(motor);
|
||||
LL_TIM_ClearFlag_UPDATE(TIM21);
|
||||
__NOP();
|
||||
}
|
||||
/* USER CODE END TIM21_IRQn 1 */
|
||||
}
|
||||
|
@ -216,7 +218,7 @@ void USART1_IRQHandler(void)
|
|||
|
||||
/* USER CODE END USART1_IRQn 0 */
|
||||
/* USER CODE BEGIN USART1_IRQn 1 */
|
||||
uart_reception_callback(uarts[UART_NUM_1]);
|
||||
|
||||
/* USER CODE END USART1_IRQn 1 */
|
||||
}
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -1,5 +1,5 @@
|
|||
#include "app.h"
|
||||
// #include "board.h"
|
||||
#include "board.h"
|
||||
#include "uarts.h"
|
||||
#include "sys.h"
|
||||
#include <stdio.h>
|
||||
|
@ -12,6 +12,7 @@ uint8_t mem_percent = 0; // 内存使用率
|
|||
|
||||
void app_init(void)
|
||||
{
|
||||
motor_process_init();
|
||||
flow_init(); // 流程初始化
|
||||
}
|
||||
|
||||
|
|
|
@ -8,13 +8,15 @@
|
|||
typedef struct
|
||||
{
|
||||
bool is_open;
|
||||
uint32_t calibration_value;
|
||||
float32 calibration_value;
|
||||
uint32_t original_value;
|
||||
} calibration_sensor_data_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
calibration_sensor_data_t torsion_in13; // 扭力
|
||||
calibration_sensor_data_t pressure_in7; // 压力
|
||||
calibration_sensor_data_t pressure_in8; // 流量
|
||||
} adcs_t;
|
||||
|
||||
typedef struct
|
||||
|
|
|
@ -17,7 +17,15 @@ static uint8_t adc_inspection(struct flow *fl)
|
|||
FL_HEAD(fl);
|
||||
for (;;)
|
||||
{
|
||||
// 扭力
|
||||
app.adc.torsion_in13.original_value = adc_get_result_average(IN13);
|
||||
app.adc.torsion_in13.calibration_value = torsion_detect(app.adc.torsion_in13.original_value);
|
||||
// 压力
|
||||
app.adc.pressure_in7.original_value = adc_get_result_average(IN7);
|
||||
app.adc.pressure_in7.calibration_value = pressure_detect(app.adc.pressure_in7.original_value);
|
||||
// 流量
|
||||
app.adc.pressure_in8.original_value = adc_get_result_average(IN8);
|
||||
app.adc.pressure_in8.calibration_value = flow_detect(app.adc.pressure_in8.original_value);
|
||||
FL_LOCK_DELAY(fl, FL_CLOCK_100MSEC); /* 延时100毫秒 */
|
||||
}
|
||||
FL_TAIL(fl);
|
||||
|
@ -28,6 +36,7 @@ static uint8_t systom_inspection(struct flow *fl)
|
|||
FL_HEAD(fl);
|
||||
for (;;)
|
||||
{
|
||||
motor_process();
|
||||
FL_LOCK_DELAY(fl, FL_CLOCK_100MSEC); /* 延时100毫秒 */
|
||||
}
|
||||
FL_TAIL(fl);
|
||||
|
|
|
@ -1,2 +0,0 @@
|
|||
#include "motor.h"
|
||||
|
|
@ -1,8 +0,0 @@
|
|||
#ifndef __MOTOR_APP_H__
|
||||
#define __MOTOR_APP_H__
|
||||
|
||||
|
||||
|
||||
extern void motor_process(void);
|
||||
|
||||
#endif
|
|
@ -1,167 +1,44 @@
|
|||
#include "board.h"
|
||||
#include "motor.h"
|
||||
|
||||
void motor_process(frame_msg_t *rx, frame_msg_t *bk);
|
||||
void sensor_procss(frame_msg_t *rx, frame_msg_t *bk);
|
||||
|
||||
/************************************* 串口通讯 *************************************/
|
||||
uart_t *uarts[UART_NUM_MAX];
|
||||
__IO static BOOL deal_done_flag = FALSE; // 数据处理标志
|
||||
__IO static frame_msg_t rx_frame;
|
||||
__IO static frame_msg_t bk_frame;
|
||||
__IO static uint8_t send_buffer[UART_TXSIZE];
|
||||
|
||||
// 串口发送
|
||||
static void host_send_msg(uint8_t *data, uint16_t len)
|
||||
{
|
||||
uart_send_data(uarts[UART_NUM_1], data, len);
|
||||
}
|
||||
|
||||
// 接收数据解码
|
||||
static void host_data_decode(uint8_t *data, uint16_t len, frame_msg_t *msg)
|
||||
{
|
||||
DBG_ASSERT(data != NULL __DBG_LINE);
|
||||
DBG_ASSERT(msg != NULL __DBG_LINE);
|
||||
|
||||
msg->state = data[1];
|
||||
msg->dev_no = data[2];
|
||||
msg->cmd_no = data[3];
|
||||
msg->len = data[4];
|
||||
osel_memcpy(msg->data, (uint8_t *)&data[5], msg->len);
|
||||
}
|
||||
|
||||
// 发送数据编码
|
||||
static void send_data_encode(frame_msg_t *msg)
|
||||
{
|
||||
uint16_t ver_len = 0, ver_crc = 0;
|
||||
uint8_t *sp = (uint8_t *)send_buffer;
|
||||
DBG_ASSERT(msg != NULL __DBG_LINE);
|
||||
|
||||
*sp++ = PACKET_STX; // 包头
|
||||
ver_len++;
|
||||
*sp++ = msg->state; // 状态
|
||||
ver_len++;
|
||||
*sp++ = msg->dev_no; // 设备号
|
||||
ver_len++;
|
||||
*sp++ = msg->cmd_no; // 命令号
|
||||
ver_len++;
|
||||
*sp++ = msg->len; // 长度
|
||||
ver_len++;
|
||||
osel_memcpy(sp, msg->data, msg->len); // 数据
|
||||
sp += msg->len;
|
||||
ver_len += msg->len;
|
||||
|
||||
ver_crc = crc16_compute((uint8_t *)&send_buffer[1], (ver_len - 1)); // 减去包头
|
||||
ver_crc = S2B_UINT16(ver_crc);
|
||||
osel_memcpy(sp, (uint8_t *)&ver_crc, 2); // 校验
|
||||
sp += 2;
|
||||
ver_len += 2;
|
||||
|
||||
*sp++ = PACKET_ETX; // 包尾
|
||||
ver_len++;
|
||||
|
||||
// 发送
|
||||
host_send_msg((uint8_t *)send_buffer, ver_len);
|
||||
}
|
||||
|
||||
// 数据处理
|
||||
void host_data_deal(uint8_t *data, uint16_t len)
|
||||
{
|
||||
frame_msg_t *rx_msg = (frame_msg_t *)&rx_frame;
|
||||
frame_msg_t *bk_msg = (frame_msg_t *)&bk_frame;
|
||||
|
||||
if (deal_done_flag == TRUE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
// 解析
|
||||
host_data_decode(data, len, rx_msg);
|
||||
// 执行
|
||||
switch (rx_msg->dev_no)
|
||||
{
|
||||
case ADC_SENSOR:
|
||||
sensor_procss(rx_msg, bk_msg);
|
||||
break;
|
||||
case MOTOR:
|
||||
motor_process(rx_msg, bk_msg);
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
}
|
||||
// 回复(组包 + 发送)
|
||||
send_data_encode(bk_msg);
|
||||
// 修改标志位
|
||||
deal_done_flag = TRUE;
|
||||
osel_memset((uint8_t *)rx_msg, 0, sizeof(rx_frame));
|
||||
osel_memset((uint8_t *)bk_msg, 0, sizeof(bk_frame));
|
||||
}
|
||||
|
||||
// 数据完整性检查
|
||||
static BOOL host_data_verify(uint8_t *data, uint16_t len)
|
||||
{
|
||||
BOOL ret = TRUE;
|
||||
uint16_t ver_len = 0;
|
||||
uint16_t ver_crc = 0, rx_crc = 0;
|
||||
|
||||
// 包头包尾检查
|
||||
if (data[0] != PACKET_STX || data[1] != MASTER_CODE || data[len - 1] != PACKET_ETX)
|
||||
{
|
||||
ret = FALSE;
|
||||
return ret;
|
||||
}
|
||||
// 帧长度检查
|
||||
ver_len = data[4] + PACKET_MIN_LEN;
|
||||
if (ver_len != len)
|
||||
{
|
||||
ret = FALSE;
|
||||
return ret;
|
||||
}
|
||||
// CRC校验
|
||||
ver_crc = crc16_compute((uint8_t *)(data + 1), (len - 4)); // 减去包头、包尾、校验
|
||||
ver_crc = S2B_UINT16(ver_crc);
|
||||
osel_memcpy((uint8_t *)&rx_crc, (uint8_t *)(data + len - 3), 2);
|
||||
if (ver_crc != rx_crc)
|
||||
{
|
||||
ret = FALSE;
|
||||
return ret;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
// 串口接收回调
|
||||
static void host_rx_cb(uint8_t uart_index, uint8_t *data, uint16_t len)
|
||||
{
|
||||
BOOL ret = FALSE;
|
||||
|
||||
// 数据完整性检查
|
||||
ret = host_data_verify(data, len);
|
||||
// 数据处理
|
||||
if (ret == TRUE && deal_done_flag == TRUE)
|
||||
{
|
||||
deal_done_flag = FALSE;
|
||||
}
|
||||
}
|
||||
|
||||
// 串口初始化
|
||||
void host_uart_init(void)
|
||||
{
|
||||
if (uarts[UART_NUM_1] == NULL)
|
||||
{
|
||||
uarts[UART_NUM_1] = uart_create(USART1, TRUE, UART_RXSIZE, host_rx_cb, TRUE, UART_TXSIZE, NULL);
|
||||
uarts[UART_NUM_1]->uart_index = UART_NUM_1;
|
||||
uarts[UART_NUM_1]->dma = DMA1;
|
||||
uarts[UART_NUM_1]->dma_rx_channel = LL_DMA_CHANNEL_3;
|
||||
uarts[UART_NUM_1]->dma_tx_channel = LL_DMA_CHANNEL_2;
|
||||
uart_recv_en(uarts[UART_NUM_1]);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************* 电机 *************************************/
|
||||
// 电机对象
|
||||
motor_t *motor;
|
||||
motor_ctrl_t *motor_param = NULL;
|
||||
uint8_t motor_state = MOTOR_IDEL;
|
||||
|
||||
adc_t adc1 = {
|
||||
.adc = ADC1,
|
||||
.dma = DMA1,
|
||||
.dma_channel = LL_DMA_CHANNEL_1,
|
||||
};
|
||||
|
||||
// 单位:N·m
|
||||
float32 torsion_detect(uint16_t adc)
|
||||
{
|
||||
float32 val = 0;
|
||||
val = ((float32)adc - 1500) / (1.934 * 3) * 10;
|
||||
|
||||
return val;
|
||||
}
|
||||
|
||||
// 单位:kPa
|
||||
float32 pressure_detect(uint16_t adc)
|
||||
{
|
||||
float32 val = 0;
|
||||
val = ((float32)adc - 600) / (10 * 15) / 16 * 10;
|
||||
|
||||
return val;
|
||||
}
|
||||
|
||||
// 单位:SLPM
|
||||
float32 flow_detect(uint16_t adc)
|
||||
{
|
||||
float32 val = 0;
|
||||
val = ((float32)adc - 600) / (10 * 15) / 16 * 300;
|
||||
|
||||
return val;
|
||||
}
|
||||
|
||||
// 电机初始化
|
||||
static void motor_init(void)
|
||||
{
|
||||
motor = motor_create(STEP_MOTOR);
|
||||
|
@ -173,73 +50,40 @@ static void motor_init(void)
|
|||
.port = ENA_GPIO_Port,
|
||||
.pin = ENA_Pin,
|
||||
};
|
||||
motor->handle.step_motor.interface.init(motor, dir, en, MIN_STEP_ANGLE, TIM21, LL_TIM_CHANNEL_CH2);
|
||||
motor->handle.step_motor.interface.init(motor, dir, en, MAX_STEP_ANGLE, TIM21, LL_TIM_CHANNEL_CH2);
|
||||
}
|
||||
|
||||
// 电机任务
|
||||
void motor_process(frame_msg_t *rx, frame_msg_t *bk)
|
||||
void motor_process_init(void)
|
||||
{
|
||||
// BOOL ret = TRUE;
|
||||
motor_param = (motor_ctrl_t *)osel_mem_alloc(sizeof(motor_ctrl_t));
|
||||
DBG_ASSERT(motor_param != NULL __DBG_LINE);
|
||||
osel_memset((uint8_t *)motor_param, 0, sizeof(motor_ctrl_t));
|
||||
}
|
||||
|
||||
switch (rx->cmd_no)
|
||||
void motor_process(void)
|
||||
{
|
||||
case SET_MOTOR_SPEED: // 设置电机转速
|
||||
break;
|
||||
case SET_DRIVER_PULSE: // 设置驱动器脉冲
|
||||
break;
|
||||
case GET_MIN_STEP: // 获取最小步距
|
||||
break;
|
||||
case GET_MOTOR_STATE: // 获取电机运行状态
|
||||
break;
|
||||
case MOTOR_MOVE: // 运行电机
|
||||
break;
|
||||
case MOTOR_STOP: // 停止电机
|
||||
break;
|
||||
}
|
||||
step_motor_t *step_motor = &motor->handle.step_motor;
|
||||
|
||||
bk->dev_no = MOTOR;
|
||||
bk->cmd_no = rx->cmd_no;
|
||||
}
|
||||
|
||||
/************************************* ADc传感器 *************************************/
|
||||
// AD传感器
|
||||
adc_t adc1 = {
|
||||
.adc = ADC1,
|
||||
.dma = DMA1,
|
||||
.dma_channel = LL_DMA_CHANNEL_1,
|
||||
};
|
||||
|
||||
// 获取扭力值
|
||||
static BOOL get_tors_value(frame_msg_t *bk)
|
||||
switch (motor_state)
|
||||
{
|
||||
uint16_t value = 0;
|
||||
|
||||
bk->len = sizeof(uint16_t);
|
||||
value = adc_get_result_average(IN13);
|
||||
value = S2B_UINT16(value);
|
||||
osel_memcpy(bk->data, (uint8_t *)&value, bk->len);
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
// 传感器任务
|
||||
void sensor_procss(frame_msg_t *rx, frame_msg_t *bk)
|
||||
{
|
||||
BOOL ret = TRUE;
|
||||
|
||||
switch (rx->cmd_no)
|
||||
{
|
||||
case GET_TORS_VALUE: // 获取扭力值
|
||||
ret = get_tors_value(bk);
|
||||
case MOTOR_RUN:
|
||||
step_motor->interface.run(motor, (dir_e)motor_param->dir);
|
||||
motor_state = MOTOR_IDEL;
|
||||
break;
|
||||
case MOTOR_STOP:
|
||||
step_motor->interface.stop(motor);
|
||||
motor_state = MOTOR_IDEL;
|
||||
case MOTOR_STEP:
|
||||
step_motor->interface.set_angle(motor, motor_param->angle, (dir_e)motor_param->dir);
|
||||
motor_state = MOTOR_IDEL;
|
||||
break;
|
||||
case MOTOR_IDEL:
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
bk->state = ret;
|
||||
bk->dev_no = ADC_SENSOR;
|
||||
bk->cmd_no = rx->cmd_no;
|
||||
}
|
||||
|
||||
/************************************* 板卡 *************************************/
|
||||
// 板卡初始化
|
||||
void board_init(void)
|
||||
{
|
||||
motor = NULL;
|
||||
|
|
|
@ -4,32 +4,11 @@
|
|||
#include "adcs.h"
|
||||
#include "uarts.h"
|
||||
|
||||
// 串口协议参数
|
||||
#define UART_RXSIZE (240u) // 接收缓冲区 240个字节
|
||||
#define UART_TXSIZE (240u) // 发送缓冲区 240个字节
|
||||
|
||||
// 包头 + 状态码 + 设备号 + 命令号 + 长度 + 数据 + 校验 + 包尾
|
||||
// 1 1 1 1 1 0~128 2 1
|
||||
#define PACKET_STX 0xff // 包头
|
||||
#define PACKET_ETX 0x3c // 包尾
|
||||
#define MASTER_CODE 0x00 // 状态码-主机
|
||||
|
||||
// 最大数据长度
|
||||
#define DATA_MAX_LEN 128
|
||||
// 最小帧长度:包头 + 状态码 + 设备号 + 命令号 + 长度 + 校验 + 包尾
|
||||
#define PACKET_MIN_LEN 8
|
||||
// 最大帧长度
|
||||
#define PACKET_MAX_LEN (DATA_MAX_LEN + PACKET_MIN_LEN)
|
||||
|
||||
// 电机初始默认值
|
||||
#define PULSE_REV 18000.0 // 每圈脉冲数(驱动器脉冲)
|
||||
#define MIN_STEP_ANGLE (360 / PULSE_REV) // 最小步距
|
||||
|
||||
typedef enum
|
||||
{
|
||||
ADC_SENSOR,
|
||||
MOTOR,
|
||||
} dev_id_e;
|
||||
#define UART_RXSIZE (240u) // 接收240个字节
|
||||
#define UART_TXSIZE (240u) // 发送240个字节
|
||||
#define PULSE_REV 18000.0 /* 每圈脉冲数 */
|
||||
#define MAX_STEP_ANGLE (360 / PULSE_REV) /* 最小步距(360/PULSE_REV) */
|
||||
#define ANGLE 180 // 步进电机180度,转盘转动1度
|
||||
|
||||
typedef enum
|
||||
{
|
||||
|
@ -43,37 +22,23 @@ typedef enum
|
|||
|
||||
typedef enum
|
||||
{
|
||||
SET_MOTOR_SPEED,
|
||||
SET_DRIVER_PULSE,
|
||||
GET_MIN_STEP,
|
||||
GET_MOTOR_STATE,
|
||||
MOTOR_MOVE,
|
||||
MOTOR_IDEL,
|
||||
MOTOR_RUN,
|
||||
MOTOR_STOP,
|
||||
} motor_cmd_e;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
GET_TORS_VALUE,
|
||||
} sensor_cmd_e;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
ST_DEV_NORMAL,
|
||||
ST_DEV_BUSY,
|
||||
ST_MSG_MISS,
|
||||
} status_code_e;
|
||||
MOTOR_STEP,
|
||||
} motor_process_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t state; // 状态
|
||||
uint8_t dev_no; // 设备号
|
||||
uint8_t cmd_no; // 命令号
|
||||
uint8_t len; // 长度
|
||||
uint8_t data[DATA_MAX_LEN]; // 数据
|
||||
|
||||
} frame_msg_t;
|
||||
uint8_t dir;
|
||||
uint32_t angle;
|
||||
} motor_ctrl_t;
|
||||
|
||||
extern void board_init(void);
|
||||
void host_data_deal(uint8_t *data, uint16_t len);
|
||||
extern void motor_process_init(void);
|
||||
extern void motor_process(void);
|
||||
extern float32 torsion_detect(uint16_t adc);
|
||||
extern float32 pressure_detect(uint16_t adc);
|
||||
extern float32 flow_detect(uint16_t adc);
|
||||
|
||||
#endif // __BOARD_H__
|
||||
|
|
|
@ -20,6 +20,8 @@ static void step_motor_run(motor_t *motor, dir_e dir)
|
|||
handle->attribute.dir = dir;
|
||||
handle->attribute.en = TRUE;
|
||||
dir == DIR_CCW ? handle->gpios.dir->set(*handle->gpios.dir) : handle->gpios.dir->reset(*handle->gpios.dir);
|
||||
LL_TIM_EnableIT_UPDATE(handle->pwm_timer);
|
||||
// LL_TIM_EnableIT_CC2(handle->pwm_timer);
|
||||
PWM_START(handle->pwm_timer, handle->pwm_channel);
|
||||
}
|
||||
|
||||
|
@ -86,7 +88,8 @@ void step_motor_update(motor_t *motor)
|
|||
if (handle->attribute.pulse_count <= 0) /* 当脉冲数等于0的时候 代表需要发送的脉冲个数已完成,停止定时器输出 */
|
||||
{
|
||||
LOG_PRINT("累计旋转的角度:%d\r\n", (int)(handle->attribute.add_pulse_count * handle->attribute.min_step_angle)); /* 打印累计转动了多少角度 */
|
||||
handle->interface.stop(motor); /* 停止接口一输出 */
|
||||
handle->interface.stop(motor);
|
||||
/* 停止接口一输出 */
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -65,24 +65,24 @@
|
|||
|
||||
typedef enum
|
||||
{
|
||||
IN0 = 0,
|
||||
IN1,
|
||||
// IN0 = 0,
|
||||
// IN1,
|
||||
// IN2,
|
||||
// IN3,
|
||||
// IN4,
|
||||
// IN5,
|
||||
IN6,
|
||||
// IN6,
|
||||
IN7,
|
||||
IN8,
|
||||
IN9,
|
||||
IN10,
|
||||
IN11,
|
||||
IN12,
|
||||
// IN9,
|
||||
// IN10,
|
||||
// IN11,
|
||||
// IN12,
|
||||
IN13,
|
||||
// IN14,
|
||||
// IN15,
|
||||
INVREF,
|
||||
INTEMP,
|
||||
// INVREF,
|
||||
// INTEMP,
|
||||
INMAX,
|
||||
} adc_num_t; // ADC通道号,根据cubemax配置的通道数量而定
|
||||
|
||||
|
|
|
@ -41,79 +41,6 @@
|
|||
} \
|
||||
} while (__LINE__ == -1)
|
||||
|
||||
/**
|
||||
* @file uarts.c
|
||||
* @brief This file contains the implementation of DMA_CLEAR_FLAG_TC_CHANNEL macro.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Clear the Transfer Complete (TC) flag of a specific DMA channel.
|
||||
*
|
||||
* @param dma The DMA peripheral.
|
||||
* @param channel The DMA channel number.
|
||||
*/
|
||||
#define DMA_CLEAR_FLAG_TC_CHANNEL(dma, channel) \
|
||||
switch (channel) \
|
||||
{ \
|
||||
case 1: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 1); \
|
||||
break; \
|
||||
case 2: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 2); \
|
||||
break; \
|
||||
case 3: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 3); \
|
||||
break; \
|
||||
case 4: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 4); \
|
||||
break; \
|
||||
case 5: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 5); \
|
||||
break; \
|
||||
case 6: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 6); \
|
||||
break; \
|
||||
case 7: \
|
||||
DMA_ClEAR_FLAG_TC(dma, 7); \
|
||||
break; \
|
||||
default: \
|
||||
break; \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clear the Transfer Error (TE) flag for the specified DMA channel.
|
||||
*
|
||||
* @param dma The DMA peripheral.
|
||||
* @param channel The DMA channel number.
|
||||
*/
|
||||
#define DMA_CLEAR_FLAG_TE_CHANNEL(dma, channel) \
|
||||
switch (channel) \
|
||||
{ \
|
||||
case 1: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 1); \
|
||||
break; \
|
||||
case 2: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 2); \
|
||||
break; \
|
||||
case 3: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 3); \
|
||||
break; \
|
||||
case 4: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 4); \
|
||||
break; \
|
||||
case 5: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 5); \
|
||||
break; \
|
||||
case 6: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 6); \
|
||||
break; \
|
||||
case 7: \
|
||||
DMA_ClEAR_FLAG_TE(dma, 7); \
|
||||
break; \
|
||||
default: \
|
||||
break; \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 创建一个UART设备
|
||||
* @param {USART_TypeDef} *huart USART总线设备句柄
|
||||
|
@ -203,8 +130,6 @@ void uart_recv_en(uart_t *uart)
|
|||
LL_DMA_SetMemoryAddress(uart->dma, uart->dma_tx_channel, (uint32_t)uart->txbuf);
|
||||
LL_DMA_EnableIT_TC(uart->dma, uart->dma_tx_channel);
|
||||
LL_USART_EnableDMAReq_TX(uart->huart);
|
||||
|
||||
uart->tx_dma_ok = TRUE;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -244,9 +169,8 @@ void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len)
|
|||
DBG_ASSERT(data != NULL __DBG_LINE);
|
||||
DBG_ASSERT(len > 0 __DBG_LINE);
|
||||
uint8_t count = 0;
|
||||
if (TRUE == uart->tx_dma_en && uart->tx_dma_ok == TRUE)
|
||||
if (TRUE == uart->tx_dma_en)
|
||||
{
|
||||
uart->tx_dma_ok = FALSE;
|
||||
osel_memcpy(uart->txbuf, data, len); // 拷贝数据到发送缓冲区
|
||||
LL_DMA_DisableChannel(uart->dma, uart->dma_tx_channel);
|
||||
// 配置数据长度
|
||||
|
@ -256,7 +180,6 @@ void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len)
|
|||
}
|
||||
else
|
||||
{
|
||||
count = 0;
|
||||
for (uint16_t i = 0; i < len; i++)
|
||||
{
|
||||
count = 0;
|
||||
|
@ -268,7 +191,6 @@ void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len)
|
|||
}
|
||||
}
|
||||
LL_USART_TransmitData8(uart->huart, data[i]);
|
||||
}
|
||||
count = 0;
|
||||
while (!LL_USART_IsActiveFlag_TC(uart->huart))
|
||||
{
|
||||
|
@ -279,6 +201,7 @@ void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len)
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 接收中断回调函数
|
||||
|
@ -365,12 +288,13 @@ void uart_dma_reception_callback(uart_t *uart)
|
|||
LL_DMA_DisableChannel(uart->dma, uart->dma_tx_channel);
|
||||
|
||||
// 清除发送中断标志位
|
||||
DMA_CLEAR_FLAG_TC_CHANNEL(uart->dma, uart->dma_tx_channel + 1);
|
||||
DMA_ClEAR_FLAG_TC(uart->dma, 2);
|
||||
DMA_ClEAR_FLAG_TC(uart->dma, 7);
|
||||
|
||||
// 使能发送中断,用于关闭发送使能引脚
|
||||
LL_USART_EnableIT_TC(uart->huart); // 使能发送中断,用于关闭发送使能引脚
|
||||
uart->tx_dma_ok = TRUE;
|
||||
|
||||
// 清除传输错误标志
|
||||
DMA_CLEAR_FLAG_TE_CHANNEL(uart->dma, uart->dma_tx_channel + 1);
|
||||
// 清除接收中断标志位
|
||||
DMA_ClEAR_FLAG_TE(uart->dma, 2);
|
||||
DMA_ClEAR_FLAG_TE(uart->dma, 7);
|
||||
}
|
||||
|
|
|
@ -1,132 +1,47 @@
|
|||
/**
|
||||
* @file uarts.h
|
||||
* @brief Header file for UARTs module.
|
||||
*
|
||||
* This file contains the definitions and function prototypes for UARTs module.
|
||||
* The UARTs module provides functions for creating and managing UART instances,
|
||||
* enabling reception, sending data, and handling interrupts.
|
||||
*/
|
||||
|
||||
#ifndef __UARTS_H__
|
||||
#define __UARTS_H__
|
||||
|
||||
#include "lib.h"
|
||||
#include "main.h"
|
||||
|
||||
/**
|
||||
* @brief Callback function type for UART receive interrupt.
|
||||
*
|
||||
* This function type is used to define the callback function for UART receive interrupt.
|
||||
* The callback function is called when data is received on the UART.
|
||||
*
|
||||
* @param uart_index The index of the UART.
|
||||
* @param data The received data.
|
||||
* @param len The length of the received data.
|
||||
*/
|
||||
//
|
||||
typedef void (*rx_interupt_cb_t)(uint8_t uart_index, uint8_t *data, uint16_t len);
|
||||
|
||||
/**
|
||||
* @brief Callback function type for UART transmit complete.
|
||||
*
|
||||
* This function type is used to define the callback function for UART transmit complete.
|
||||
* The callback function is called when the UART transmission is complete.
|
||||
*/
|
||||
//
|
||||
typedef void (*tx_complete_cb_t)(void);
|
||||
|
||||
/**
|
||||
* @brief Enumeration for UART status.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
UART_OK = 0x00u, /**< The action was successful. */
|
||||
UART_ERROR = 0xFFu /**< Generic error. */
|
||||
} uart_status_e;
|
||||
|
||||
/**
|
||||
* @brief Structure representing a UART instance.
|
||||
*/
|
||||
//
|
||||
typedef struct
|
||||
{
|
||||
uint8_t uart_index; /**< The index of the UART. */
|
||||
USART_TypeDef *huart; /**< The UART peripheral. */
|
||||
DMA_TypeDef *dma; /**< The DMA peripheral. */
|
||||
uint32_t dma_rx_channel; /**< The DMA receive channel. */
|
||||
uint32_t dma_tx_channel; /**< The DMA transmit channel. */
|
||||
uint16_t rx_index; /**< The receive data index. */
|
||||
BOOL rx_dma_en; /**< Flag indicating if DMA reception is enabled. */
|
||||
uint8_t *rxbuf; /**< The receive buffer. */
|
||||
uint16_t rxsize; /**< The size of the receive buffer. */
|
||||
uint16_t tx_index; /**< The transmit data index. */
|
||||
BOOL tx_dma_en; /**< Flag indicating if DMA transmission is enabled. */
|
||||
uint8_t *txbuf; /**< The transmit buffer. */
|
||||
uint16_t txsize; /**< The size of the transmit buffer. */
|
||||
__IO BOOL tx_dma_ok; /**< Flag indicating if DMA transmission is complete. */
|
||||
rx_interupt_cb_t rx_interupt_cb; /**< The receive interrupt callback function. */
|
||||
tx_complete_cb_t tx_complete_cb; /**< The transmit complete callback function. */
|
||||
uint8_t uart_index; // 串口索引
|
||||
USART_TypeDef *huart;
|
||||
DMA_TypeDef *dma; // 外部设置
|
||||
uint32_t dma_rx_channel; // 外部设置
|
||||
uint32_t dma_tx_channel; // 外部设置
|
||||
|
||||
uint16_t rx_index; // 接收数据索引
|
||||
BOOL rx_dma_en;
|
||||
uint8_t *rxbuf;
|
||||
uint16_t rx_sta;
|
||||
uint16_t rxsize;
|
||||
|
||||
uint16_t tx_index;
|
||||
BOOL tx_dma_en;
|
||||
uint8_t *txbuf;
|
||||
uint16_t txsize;
|
||||
|
||||
// 接收中断回调
|
||||
rx_interupt_cb_t rx_interupt_cb;
|
||||
// 发生完成回调
|
||||
tx_complete_cb_t tx_complete_cb;
|
||||
|
||||
} uart_t;
|
||||
|
||||
/**
|
||||
* @brief Creates a UART instance.
|
||||
*
|
||||
* This function creates a UART instance with the specified parameters.
|
||||
*
|
||||
* @param huart The UART peripheral.
|
||||
* @param rx_dma_en Flag indicating if DMA reception is enabled.
|
||||
* @param rxsize The size of the receive buffer.
|
||||
* @param rx_cb The receive interrupt callback function.
|
||||
* @param tx_dma_en Flag indicating if DMA transmission is enabled.
|
||||
* @param txsize The size of the transmit buffer.
|
||||
* @param tx_complete_cb The transmit complete callback function.
|
||||
* @return The created UART instance.
|
||||
*/
|
||||
extern uart_t *uart_create(USART_TypeDef *huart, BOOL rx_dma_en, uint16_t rxsize, rx_interupt_cb_t rx_cb,
|
||||
BOOL tx_dma_en, uint16_t txsize, tx_complete_cb_t tx_complete_cb);
|
||||
|
||||
/**
|
||||
* @brief Frees the resources of a UART instance.
|
||||
*
|
||||
* This function frees the resources allocated for a UART instance.
|
||||
*
|
||||
* @param uart The UART instance to free.
|
||||
*/
|
||||
extern void uart_free(uart_t *uart);
|
||||
|
||||
/**
|
||||
* @brief Enables UART reception.
|
||||
*
|
||||
* This function enables reception on the specified UART instance.
|
||||
*
|
||||
* @param uart The UART instance.
|
||||
*/
|
||||
extern void uart_recv_en(uart_t *uart);
|
||||
|
||||
/**
|
||||
* @brief Sends data over UART.
|
||||
*
|
||||
* This function sends the specified data over the specified UART instance.
|
||||
*
|
||||
* @param uart The UART instance.
|
||||
* @param data The data to send.
|
||||
* @param len The length of the data.
|
||||
*/
|
||||
extern void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len);
|
||||
|
||||
/**
|
||||
* @brief UART receive interrupt callback.
|
||||
*
|
||||
* This function is the interrupt callback for UART receive interrupt.
|
||||
*
|
||||
* @param uart The UART instance.
|
||||
*/
|
||||
extern void uart_reception_callback(uart_t *uart);
|
||||
|
||||
/**
|
||||
* @brief DMA receive interrupt callback.
|
||||
*
|
||||
* This function is the interrupt callback for DMA receive interrupt.
|
||||
*
|
||||
* @param uart The UART instance.
|
||||
*/
|
||||
extern void uart_dma_reception_callback(uart_t *uart);
|
||||
BOOL tx_dma_en, uint16_t txsize, tx_complete_cb_t tx_complete_cb); // 创建uart
|
||||
extern void uart_free(uart_t *uart); // 释放uart资源
|
||||
extern void uart_recv_en(uart_t *uart); // 使能接收
|
||||
extern void uart_send_data(uart_t *uart, uint8_t *data, uint16_t len); // 发送数据
|
||||
extern void uart_reception_callback(uart_t *uart); // 接收中断回调
|
||||
extern void uart_dma_reception_callback(uart_t *uart); // DMA接收中断回调
|
||||
|
||||
#endif // __UARTS_H__
|
||||
|
|
Reference in New Issue