Uart Controller --- 架构uart controller driver

本文深入探讨了UART通信机制中的关键概念,如uartLineStatusRegister寄存器的作用及读取方法,Linux内核中用于数据刷新的工作机制,以及tty_port在UART体系中的作用等。通过分析,帮助读者理解UART通信过程中的数据流动方式。
/*  Register 
    uart Line Status Register 
 */
#define UART_REGISTER_LSR 
driver 的第一要义是要 深刻理解 该hardware所拥有的行为,
比如Altera cyclone V 的 Can controller 的 mo interrupt,印象好深刻

好了,这些hardware的行为背后是一大堆复杂的电路呈现出来的register,
下面会有对 触发器的详细介绍,一定要让你彻底明白什么是 D trigger

https://github.com/leesagacious/lee-TEE/tree/master/core/driver

在Linux kernel中 bitmap使用很是广泛, Register 是hardware中真正的 “位图”
这里写图片描述

1 : 看一下tee kernel中的实现

/*
    也许会问 不是有 Rx interrupt 吗 ?
*/
static bool serial8250_uart_have_rx_data(.....)
{
    /*
        #define LSR_DR      0x01  DATA Ready 

        就是读取LSR register 判断该register的bit[0].
    */
    return (read32(base + UART_LSR) & LSR_DR);
}

2 : 下面是linux kernel 中的实现

/*
    刷缓冲区中的数据到线路规程中.
    flush data from the buffer chain to the line discipline
    1 : 幕后推手是谁 ?
         software interrupt, 好,为什么是software interrupt,
         而不是其他
*/
static void flush_to_ldisc(struct work_struct *work)
{
    /**
        tty_port 它也维护了一个缓冲区,类比uart_port也维护了一个缓冲区,
        (每个port的发送数据的 struct circ_buf 发送缓冲区)
        只是这两个buffer分别在不同的层中,他们是间接的联系在一起的. 
        层多了,显然影响效率,那就使用缓存了, 哈哈

        其实,整个写入的流程是:
        tty core -> line discipline -> tty driver ->uart driver
        -> circ_buf 发送缓冲区中的
        好,上面说了 推动数据最终流动到circ_buf中的是 software interrupt
        下面详细说这个circ_buf是怎么分配的 为什么要分配一个page大小, 这和
        UART_MAX_SIZE 有关系吗

        你仔细看这个 contianer_of() 实现的很妙, 当然了用户空间也可
        使用container_of() ,
        只是您必须加上头文件 #include <stddef.h>

        好了,来看看这个tty_port 是什么了,
        1. uart_state,tty_struct, tty_driver 都维护了它, 果然集千万宠爱于一身,
        2. 在uart_register_driver()注册uart_driver的时候被初始化
           uart_state的时候被初始化了

        https://blog.youkuaiyun.com/leesagacious/article/details/54670735

        int uart_register_driver(...)
        {
            .....
            支持多少个物理port, 就给你几个圈圈转转
            好了,你想想物理port与tty_port之间的对应关系吧,一对一 ?
            for (i = 0; i < drv->nr; i++) {
                struct uart_state *state = drv->state + i;
                struct tty_port *port = &state->port;

                初始化tty_port 吧. 无非是初始化 mutex , buf ,wait_queue 之类的
                tty_port_init(port);
                port->ops = &uart_port_ops;
                .....
            }
        }
        tty_port 在整个uart体系中只是一个配角.
        重要性低于tty_driver,tty_struct,以及 各个 ops.
        好了,用到了在说吧.

        这里拿出来tty_port是为了什么呢 ? 
        很显然 : 

        1 : 是为了获取它维护的缓冲区
        2 :获取维护的tty_struct,
            因为tty_struct维护了线路规程, 
            该函数的目的就是 将tty_port中维护的缓冲区的数据刷入到线路规程中
            该函数一上来就开始准备这些,
            最终一个一个位写入到uart register的时候
            速度是恒定的,发送一个位 耗时 1/115200 (s) ,显然速度很慢
            在这里临时抱抱佛脚,也没关系的. 是吧? 哈哈
        3 : tty_port维护了一个32位的位图,iflags, 正在刷入线路规程的时候
            缓冲区是锁定的, 看下面的图示 
     */
    struct tty_port *port = container_of(work, struct tty_port, buf.work);
    /*
        port维护的这个buf 很有意义. 下面用到了再说吧
        这里先放过他.
    */
    struct tty_bufhead *buf = &port->buf;
    /**
        这个鬼也来凑热闹,... 
        上面说了,获取它就是为了获取它维护的线路规程.
        看.. serial_in()从 register中读取字符开始,到这里刷入line discipline之前各路大神都请来了,不容易呀.
    */
    struct tty_struct *tty;
    /*
        该变量你应该知道的. 哈哈,
    */
    unsigned long   flags;
    /*
        线路规程, 下面会给它赋值,
        看到了吧, 在这里开始进行"串线", 可增加独有的线路规程,
        然后将数据刷入到自定义的线路规程中
        当然了,如果不想这样做, 还有其他更好的方法.
        请移步 ; 
        https://blog.youkuaiyun.com/leesagacious/article/details/78237306

        底层统一的数据, 从这里要开始分道扬镳了. 而不是像signal那样速途同归.
        https://blog.youkuaiyun.com/leesagacious/article/details/53678666
    */
    struct tty_ldisc *disc;
    /*
        获取tty_struct. 
        什么时候开始建立关联关系的 ?

        当用户空间调用 open()的时候, tty_open() 会被调用
        于是 :
        tty_open()
        {
            ....
            初始化一个 tty device.
            tty = tty_init_dev(driver, index);
            {
                struct tty_struct *tty;
                tty = alloc_tty_struct(); // 分配
                ....
                tty->port->itty = tty;   // 赋值
            }
        }
    */
    tty = port->itty;
    if (tty == NULL)
        return;

    /*
        怎么获取的 ?
        请移步 : https://blog.youkuaiyun.com/leesagacious/article/details/77170670
    */  
    disc = tty_ldisc_ref(tty);
    if (disc == NULL)   /*  !TTY_LDISC */
        return;

    /*
        这个一定要有的.
        https://blog.youkuaiyun.com/leesagacious/article/details/64980255
    */
    spin_lock_irqsave(&buf->lock, flags);
    /*
        还好,这不是"独角戏" 该来的大神都请来了, 登台演戏吧, 
    */
    if (!test_and_set_bit(TTYP_FLUSHING, &port->iflags)) {  

    }
}

这里写图片描述

#ifndef MOTOR_CONTROLLER_H #define MOTOR_CONTROLLER_H #define ENCODER_LINES 13 #define GEAR_RATIO 20 #define PULSES_PER_REVOLUTION (ENCODER_LINES * 4 * GEAR_RATIO) #include "motor_driver.h" #include "encoder_driver.h" #include "usart_driver.h" #include "math.h" // 电机控制器配置 typedef struct { float kp; float ki; float kd; float integral_limit; float min_output; float max_output; } MotorControllerConfig; // 电机控制器 typedef struct { MotorDriver* motor_driver; EncoderDriver* encoder_driver; UartDriver* uart_driver; float target_speed; // 目标转速 (RPM) float current_speed; // 当前转速 (RPM) float duty_cycle; // 占空比 (%) float dt; // 采样时间 (秒) int direction; // 电机方向 // PID控制器 float kp; float ki; float kd; float integral_limit; float min_output; float max_output; float error; float prev_error; float integral; float derivative; float output; uint32_t last_encoder_value; uint32_t last_time; float prev_speed; // 用于微分计算的上一次速度 float prev_derivative; // 用于滤波的上一次微分值 float derivative_filter_alpha; int output_saturated; } MotorController; // 初始化电机控制器 void motor_controller_init(MotorController* controller, MotorControllerConfig* config); // 计算当前速度 float motor_controller_calculate_speed(MotorController* controller); // PID计算 void motor_controller_pid_calculate(MotorController* controller); // 控制电机 void motor_controller_control(MotorController* controller); // 发送速度数据到串口 void motor_controller_send_speed(MotorController* controller); #endif /* MOTOR_CONTROLLER_H */#include "motor_driver.h" #include "encoder_driver.h" #include "usart_driver.h" #include "math.h" #include "stdio.h" #include "motor_controller.h" void motor_controller_init(MotorController* controller, MotorControllerConfig* config) { // 初始化驱动 controller->motor_driver = get_motor_driver(); controller->encoder_driver = get_encoder_driver(); controller->uart_driver = get_uart_driver(); // 初始化驱动 controller->motor_driver->init(); controller->encoder_driver->init(); controller->uart_driver->init(); // 初始化参数 controller->kp = config->kp; controller->ki = config->ki; controller->kd = config->kd; controller->integral_limit = config->integral_limit; controller->min_output = config->min_output; controller->max_output = config->max_output; // 初始化状态 controller->target_speed = 100.0f; controller->current_speed = 0.0f; controller->duty_cycle = 0.0f; controller->direction = 1; controller->dt = 0.005f; // 5ms 采样时间 // 初始化PID controller->error = 0.0f; controller->prev_error = 0.0f; controller->integral = 0.0f; controller->derivative = 0.0f; controller->output = 0.0f; controller->prev_speed = 0.0f; controller->prev_derivative = 0.0f; controller->derivative_filter_alpha = 0.3f; controller->output_saturated = 0; // 初始化编码器 controller->last_encoder_value = controller->encoder_driver->read(); controller->last_time = HAL_GetTick(); HAL_Delay(100); } float motor_controller_calculate_speed(MotorController* controller) { int32_t current_count = controller->encoder_driver->read(); uint32_t now = HAL_GetTick(); uint32_t dt_ms = now - controller->last_time; if (dt_ms == 0) return controller->current_speed; // 处理编码器回绕 - 使用无符号差值来处理16位回绕 uint16_t current_count_16 = (uint16_t)current_count; uint16_t last_count_16 = (uint16_t)controller->last_encoder_value; int16_t delta = (int16_t)(current_count_16 - last_count_16); // 转换为RPM float rpm = (float)delta * 60000.0f / (dt_ms * PULSES_PER_REVOLUTION); // 保存当前速度用于后续计算 controller->current_speed = rpm; controller->last_encoder_value = current_count; controller->last_time = now; return rpm; } void motor_controller_pid_calculate(MotorController* controller) { // 计算误差 controller->error = controller->target_speed - controller->current_speed; // 比例项 float proportional = controller->kp * controller->error; // 积分项 - 条件性累积 float integral_term = 0; if (controller->ki != 0.0f) { // 只在输出未饱和时累积积分 if (!controller->output_saturated) { controller->integral += controller->error * controller->dt; // 积分限幅 if (controller->integral > controller->integral_limit) controller->integral = controller->integral_limit; else if (controller->integral < -controller->integral_limit) controller->integral = -controller->integral_limit; } integral_term = controller->ki * controller->integral; } // 微分项 - 使用测量值微分避免设定值变化的冲击,并加入滤波 float derivative = 0; if (controller->kd != 0.0f) { // 测量值微分:对过程变量求导,而不是误差 float derivative_of_pv = (controller->current_speed - controller->prev_speed) / controller->dt; float derivative_term_1 = -controller->kd * derivative_of_pv; // 简单的低通滤波:一阶惯性环节 derivative = controller->derivative_filter_alpha * derivative_term_1 + (1 - controller->derivative_filter_alpha) * controller->prev_derivative; controller->prev_derivative = derivative; } float derivative_term = controller->kd * derivative; // PID计算 controller->output = proportional + integral_term + derivative_term; // 输出限幅 controller->output_saturated = 0; if (controller->output > controller->max_output) { controller->output = controller->max_output; controller->output_saturated = 1; } else if (controller->output < controller->min_output) { controller->output = controller->min_output; controller->output_saturated = 1; } // 保存状态用于下一次计算 controller->prev_error = controller->error; controller->prev_speed = controller->current_speed; } void motor_controller_control(MotorController* controller) { // 设置方向 controller->direction = (controller->output >= 0) ? 1 : -1; // 设置占空比 controller->duty_cycle = fabsf(controller->output); // 通过驱动层控制电机 controller->motor_driver->set_direction(controller->direction); controller->motor_driver->set_duty(controller->duty_cycle); } void motor_controller_send_speed(MotorController* controller) { char buffer[32]; sprintf(buffer, "%.1f,%.1f\n", controller->current_speed, controller->target_speed); controller->uart_driver->send(buffer); }#ifndef MOTOR_DRIVER_H #define MOTOR_DRIVER_H #include "main.h" // 电机驱动接口 typedef struct { void (*init)(void); void (*set_duty)(float duty); void (*set_direction)(int direction); } MotorDriver; // 获取驱动实例 MotorDriver* get_motor_driver(void); #endif /* MOTOR_DRIVER_H */#include "motor_driver.h" #include "tim.h" #include "math.h" // 驱动实现 static void motor_init(void); static void motor_set_duty(float duty); static void motor_set_direction(int direction); static MotorDriver motor_driver = { .init = motor_init, .set_duty = motor_set_duty, .set_direction = motor_set_direction }; void motor_init(void) { // 初始化PWM HAL_TIM_PWM_Start(&htim2, TIM_CHANNEL_1); } void motor_set_duty(float duty) { // 死区处理 (5%) if (fabs(duty) < 5.0f) { duty = 0.0f; } // 占空比限幅 (0-100%) if (duty > 100.0f) duty = 100.0f; if (duty < 0.0f) duty = 0.0f; // 计算PWM值 uint32_t pwm_value = (uint32_t)(duty * (htim2.Init.Period) / 100.0f); __HAL_TIM_SET_COMPARE(&htim2, TIM_CHANNEL_1, pwm_value); } void motor_set_direction(int direction) { if (direction == 1) { HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_SET); HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET); } else if (direction == -1) { HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_SET); } else { HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET); } } MotorDriver* get_motor_driver(void) { return &motor_driver; }/* USER CODE BEGIN Header */ /** ****************************************************************************** * @file : main.c * @brief : Main program body ****************************************************************************** * @attention * * Copyright (c) 2025 STMicroelectronics. * All rights reserved. * * This software is licensed under terms that can be found in the LICENSE file * in the root directory of this software component. * If no LICENSE file comes with this software, it is provided AS-IS. * ****************************************************************************** */ /* USER CODE END Header */ /* Includes ------------------------------------------------------------------*/ #include "main.h" #include "adc.h" #include "dma.h" #include "i2c.h" #include "tim.h" #include "usart.h" #include "gpio.h" /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ #include "motor_controller.h" /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ /* USER CODE BEGIN PTD */ MotorControllerConfig motor_config = { .kp = 0.4, // 增加KP以提供更强的控制势 .ki = 0.6, // 启用积分项以消除稳濁误巿 .kd = 0.00, // 添加微分项以抑制振荡 .integral_limit = 2000.0f, // 设置合理的积分限广 .min_output = -100.0f, .max_output = 100.0f }; // 电机控制器实便 MotorController motor_controller; /* USER CODE END PTD */ /* Private define ------------------------------------------------------------*/ /* USER CODE BEGIN PD */ /* USER CODE END PD */ /* Private macro -------------------------------------------------------------*/ /* USER CODE BEGIN PM */ /* USER CODE END PM */ /* Private variables ---------------------------------------------------------*/ /* USER CODE BEGIN PV */ /* USER CODE END PV */ /* Private function prototypes -----------------------------------------------*/ void SystemClock_Config(void); /* USER CODE BEGIN PFP */ /* USER CODE END PFP */ /* Private user code ---------------------------------------------------------*/ /* USER CODE BEGIN 0 */ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { if (htim == &htim4) { // 计算当前速度 motor_controller.current_speed = motor_controller_calculate_speed(&motor_controller); // PID计算 motor_controller_pid_calculate(&motor_controller); // 控制电机 motor_controller_control(&motor_controller); // 发鿁鿟度数据 motor_controller_send_speed(&motor_controller); } } /* USER CODE END 0 */ /** * @brief The application entry point. * @retval int */ int main(void) { /* USER CODE BEGIN 1 */ /* USER CODE END 1 */ /* MCU Configuration--------------------------------------------------------*/ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ HAL_Init(); /* USER CODE BEGIN Init */ /* USER CODE END Init */ /* Configure the system clock */ SystemClock_Config(); /* USER CODE BEGIN SysInit */ /* USER CODE END SysInit */ /* Initialize all configured peripherals */ MX_GPIO_Init(); MX_DMA_Init(); MX_ADC1_Init(); MX_TIM2_Init(); MX_TIM3_Init(); MX_TIM4_Init(); MX_USART1_UART_Init(); MX_I2C1_Init(); /* USER CODE BEGIN 2 */ /* 初始化电机控制器 */ motor_controller_init(&motor_controller, &motor_config); HAL_TIM_Base_Start_IT(&htim4); motor_controller.motor_driver->set_direction(1); motor_controller.motor_driver->set_duty(20.0f); /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ } /* USER CODE END 3 */ } /** * @brief System Clock Configuration * @retval None */ void SystemClock_Config(void) { RCC_OscInitTypeDef RCC_OscInitStruct = {0}; RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; /** Initializes the RCC Oscillators according to the specified parameters * in the RCC_OscInitTypeDef structure. */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; 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_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) { Error_Handler(); } PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV2; if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) { Error_Handler(); } } /* USER CODE BEGIN 4 */ /* USER CODE END 4 */ /** * @brief This function is executed in case of error occurrence. * @retval None */ void Error_Handler(void) { /* USER CODE BEGIN Error_Handler_Debug */ /* User can add his own implementation to report the HAL error return state */ __disable_irq(); while (1) { } /* USER CODE END Error_Handler_Debug */ } #ifdef USE_FULL_ASSERT /** * @brief Reports the name of the source file and the source line number * where the assert_param error has occurred. * @param file: pointer to the source file name * @param line: assert_param error line source number * @retval None */ void assert_failed(uint8_t *file, uint32_t line) { /* USER CODE BEGIN 6 */ /* User can add his own implementation to report the file name and line number, ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ /* USER CODE END 6 */ } #endif /* USE_FULL_ASSERT */
最新发布
11-06
评论
成就一亿技术人!
拼手气红包6.0元
还能输入1000个字符
 
红包 添加红包
表情包 插入表情
 条评论被折叠 查看
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值