PX4串口驱动的三种方式:系统级操作、task/work_queue、类似PX4IO中断响应

2023-05-16

因为项目需要,需在px4实现与stm32F407串口通信功能,以200Hz双工交互数据,所以探究了3种不同的串口驱动方式。三种方式概况参考了AcmeUavs公众号的文章:PX4-6-串口设备驱动,本篇主要详细记录自己摸索3种方式的过程。

其中第三部分 从底层实现硬件级别串口中断+DMA不定长接收 未在网上找到相关实现教程,具有比较大的参考意义。

目录

    • 利用Linux系统接口+task任务
      • 基本操作
        • 初始化串口句柄
        • 设置波特率
        • read/write读取或者写入
        • poll实现类似中断的读取
      • 一些注意的事情
        • 另一个神奇的配置串口的地方
        • 读取超长数据时的处理
      • 测试结果
    • 利用Linux系统接口+work_queue队列
      • TFMINI代码分析
      • 优先级问题
      • 测试结果
    • 从底层实现硬件级别串口中断+DMA不定长接收
      • 单片机配置UART+DMA不定长接收
      • 使用的寄存器、函数
      • 配置硬件级别串口中断+DMA不定长接收
      • 测试结果
    • 致谢

利用Linux系统接口+task任务

这个是网上实现方式最多的,可以参考以下文章:
Pixhawk—通过串口方式添加一个自定义传感器(超声波为例)
Pixhawk原生固件PX4之串口读取信息
在源代码中,主要可以参考的有:

PX4-Autopilot\src\systemcmds

其中
test_uart_baudchange.c
test_uart_break.c
test_uart_console.c
test_uart_loopback.c
test_uart_send.c
都可以作为参考。

基本操作

利用这种方式调用串口就几件事情:

  1. 初始化一个串口句柄
  2. 初始化波特率
  3. 调用write/read写入、读取
  4. 利用poll实现类似中断的读取

初始化串口句柄

int serial_fd = open(uart_name, O_RDWR|O_NOCTTY  |O_DIRECT | O_NONBLOCK);

返回的int值就是fd句柄,可以用在其他函数中。
参数uart_name就是Linux系统路径下的串口路径,Pixhawk4上面唯一空闲的就是"/dev/ttyS3",也即单片机硬件串口UART4
其余的串口路径可以参考

	/*
	 * TELEM1 : /dev/ttyS1
	 * TELEM2 : /dev/ttyS2
	 * GPS    : /dev/ttyS3
	 * NSH    : /dev/ttyS5
	 * SERIAL4: /dev/ttyS6
	 * N/A    : /dev/ttyS4
	 * IO DEBUG (RX only):/dev/ttyS0
	 */

设置波特率

设置波特率可以参考test_uart_break.c中#101行

	/* Set baud rate */
	//对于波特率的设置通常使用cfsetospeed和cfsetispeed函数来完成。获取波特率信息是通过cfgetispeed和cfgetospeed函数来完成的。
	if (cfsetispeed(&uart2_config, B9600) < 0 || cfsetospeed(&uart2_config, B9600) < 0) {
		printf("ERROR setting termios config for UART2: %d\n", termios_state);
		ret = ERROR;
		goto cleanup;
	}

	if ((termios_state = tcsetattr(uart2, TCSANOW, &uart2_config)) < 0) {
		printf("ERROR setting termios config for UART2\n");
		ret = termios_state;
		goto cleanup;
	}

将其封装为自己的函数,直接调用就可以读取,其中fd就是我们刚才返回的serial_fd:

int set_uart_baudrate(const int fd, unsigned int baud)
{
	int speed;

	switch (baud) {
	case 9600:   speed = B9600;   break;

	case 19200:  speed = B19200;  break;

	case 38400:  speed = B38400;  break;

	case 57600:  speed = B57600;  break;

	case 115200: speed = B115200; break;

	case 460800: speed = B460800; break;

	case 921600: speed = B921600; break;

	case 1000000: speed = B1000000; break;

	default:
		warnx("ERR: baudrate: %d\n", baud);
		return -EINVAL;
	}

	struct termios uart_config;

	int termios_state;

	/* 以新的配置填充结构体 */
	/* 设置某个选项,那么就使用"|="运算,
	 * 如果关闭某个选项就使用"&="和"~"运算
	 * */
	tcgetattr(fd, &uart_config); // 获取终端参数

	/* clear ONLCR flag (which appends a CR for every LF) */
	uart_config.c_oflag &= ~ONLCR;// 将NL转换成CR(回车)-NL后输出。

	/* 无偶校验,一个停止位 */
	uart_config.c_cflag &= ~(CSTOPB | PARENB);// CSTOPB 使用两个停止位,PARENB 表示偶校验

	/* 设置波特率 */
	if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
		warnx("ERR: %d (cfsetispeed)\n", termios_state);
		return false;
	}

	if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
		warnx("ERR: %d (cfsetospeed)\n", termios_state);
		return false;
	}

	// 设置与终端相关的参数,TCSANOW 立即改变参数
	if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
		warnx("ERR: %d (tcsetattr)\n", termios_state);
		return false;
	}

	return true;
}

read/write读取或者写入

还是几件事情:先初始化一个u8/char数组作为缓存,然后read或者write
read就是第一个参数写串口句柄,第二个写缓存数组首地址指针,第三个写要放进去多少字节

	char rxdata[40]={0};
	read(UART4, data, 20);

write类似,第一个参数写串口句柄,第二个写发送的缓存数组首地址指针,第三个写要发出去多少字节

	char txdata[40]={0};
	write(UART4, data, 20);

poll实现类似中断的读取

此处pollfd先写入监视句柄、监视动作POLLIN,然后在死循环中反复利用poll()读取是否有更新,timeout是超时等待时长


   	pollfd fds[1];
	fds[0].fd = _serial_fd;
	fds[0].events = POLLIN;
	
	while(1){
		int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
	
		if (ret > 0) {
			/* if we have new data from GPS, go handle it */
			if (fds[0].revents & POLLIN) {
		          ...
		          //处理数据,read之类
		    }
	  	}
	}

一些注意的事情

另一个神奇的配置串口的地方

PX4-Autopilot\boards\px4\fmu-v5\nuttx-config\nsh\defconfig

CONFIG_UART4_BAUD=1000000
CONFIG_UART4_RXBUFSIZE=40
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXDMA=y
CONFIG_UART4_TXBUFSIZE=40

在这里写会有奇效,比如默认是没有TXDMA的,加上后会改善一丢丢CPU占用
没加入TXDMA=y:
没加入RXDMA
加入TXDMA=y:
在这里插入图片描述

读取超长数据时的处理

如果读取特别长的数据,在poll触发后立刻读取,会产生只能读到开头一部分的问题,参考gps驱动中的驱动,发现其根据波特率、读取数据长度计算了传输时间,进行了微妙量级的等待后再进行read,具体代码如下:

	pollfd fds[1];
	fds[0].fd = _serial_fd;
	fds[0].events = POLLIN;

	int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), math::min(max_timeout, timeout));

	if (ret > 0) {
		/* if we have new data from GPS, go handle it */
		if (fds[0].revents & POLLIN) {
			/*
			 * We are here because poll says there is some data, so this
			 * won't block even on a blocking device. But don't read immediately
			 * by 1-2 bytes, wait for some more data to save expensive read() calls.
			 * If we have all requested data available, read it without waiting.
			 * If more bytes are available, we'll go back to poll() again.
			 */
			const unsigned character_count = 32; // minimum bytes that we want to read
			unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate;
			const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);
			px4_usleep(sleeptime);
			ret = ::read(_serial_fd, buf, buf_length);

		} else {
			ret = -1;
		}
	}

其中重点就在于这一行计算等待时间:

const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);

测试结果

可以做到400Hz下数据一个不丢,但是数据间隔不整齐,意味着实时性比较差。

利用Linux系统接口+work_queue队列

这个资料相对少了很多,主要可以参考PX4里面的这个代码

PX4-Autopilot\src\drivers\distance_sensor\tfmini

串口只有在调度周期达到时尝试读取一次,没有获取到数据则直接返回,这样读取延时最大为一个调度周期。

TFMINI代码分析

模块入口,用来和nsh命令行交互

src/drivers/distance_sensor/tfmini/tfmini_main.cpp

解码程序,使用状态机思路解码

src/drivers/distance_sensor/tfmini/tfmini_parser.cpp

真正读取实现文件

src/drivers/distance_sensor/tfmini/TFMINI.cpp

在读取实现中,较为重要的是初始化绑定串口,其中serial_port_to_wq是预先为我们定义好的,传入参数为上文提到的Linux串口路径,例如"/dev/ttyS3":

TFMINI::TFMINI(const char *port, uint8_t rotation) :
	ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port))

设置读取间隔:

void
TFMINI::start()
{
	// schedule a cycle to start things (the sensor sends at 100Hz, but we run a bit faster to avoid missing data)
	ScheduleOnInterval(5_ms);
}

另一个比较重要的是真正收集数据的collect()函数,略去了不太重要的部分,解释写在注释中

int
TFMINI::collect()
{
	// clear buffer if last read was too long ago
	int64_t read_elapsed = hrt_elapsed_time(&_last_read);

	// the buffer for read chars is buflen minus null termination
	char readbuf[sizeof(_linebuf)] {};
	unsigned readlen = sizeof(readbuf) - 1;

	int ret = 0;
	float distance_m = -1.0f;

	// 类似中断环形,bytes_available告诉我们有多少读入缓存等待处理
	int bytes_available = 0;
	::ioctl(_fd, FIONREAD, (unsigned long)&bytes_available);

	// parse entire buffer
	const hrt_abstime timestamp_sample = hrt_absolute_time();

	do {
		// read from the sensor (uart buffer)
		ret = ::read(_fd, &readbuf[0], readlen);

		if (ret < 0) {
			//错误情况下处理,略去
		}

		_last_read = hrt_absolute_time();

		// 解码
		for (int i = 0; i < ret; i++) {
			tfmini_parse(readbuf[i], _linebuf, &_linebuf_index, &_parse_state, &distance_m);
		}

		// bytes left to parse
		bytes_available -= ret;

	} while (bytes_available > 0);

	// publish uorb
	_px4_rangefinder.update(timestamp_sample, distance_m);
	return PX4_OK;
}

至此,其他部分照抄应该就可以实现我们自己的队列读入程序了

优先级问题

上面提到了serial_port_to_wq,跟踪到:

platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp

如果把末尾那个数字设置的太小,usart本身优先级就不高,那实时性就无从保证,所以要提高其优先级
在这里插入图片描述

测试结果

可以做到200Hz下数据间隔较为整齐,但是再提高频率就要加快扫描频率,且占用CPU会随频率升高而增加。

从底层实现硬件级别串口中断+DMA不定长接收

这个就是复现了PX4FMU和PX4IO两个芯片的通信手段,直接从底层下手解决问题,完全绕开操作系统,实时性最好,但是难度也最大。
首先分析一下PX4IO的结构,其中相关代码在:
小单片机PX4IO:

PX4-Autopilot\src\modules\px4iofirmware\serial.c

主单片机PX4FMU:

PX4-Autopilot\src\drivers\px4io\px4io_serial.cpp
PX4-Autopilot\platforms\nuttx\src\px4\stm\stm32f7\px4io_serial\px4io_serial.cpp

这两组文件是我们主要参考来源,但是存在一个矛盾,就是我们的串口要添加在FMU的F7单片机上,硬件寄存器操作会类似于FMU中的代码,而FMU为了实习这一功能进行了复杂的类继承,不利于参考;而小单片机使用了F1系列,代码简单但是和F7系列寄存器不兼容,没法照搬。

单片机配置UART+DMA不定长接收

所以我们回到最基本的单片机使用串口+DMA接收不定长数据上来,其基本原理包括:

  1. 初始化串口、DMA(时钟、管脚、DMA到串口stream映射等)
  2. 初始化串口IDLE空闲中断

具体可以参考,第二篇非常好
STM32F4 UART1 DMA发送和接收不定长度数据
DMA和UART的深刻认识–串口接收的3种工作方式(附STM32F4代码)

这两篇文章虽然都是F4的,但是F4和F7在这里的寄存器差别不是那么大,有部分参考意义。

使用的寄存器、函数

此外,由于Nuttx对于F7的支持并非使用了HAL库而是直接操作寄存器,所以有必要研究一下其支持方式。

有关USART寄存器的宏定义在:

PX4-Autopilot\build\px4_fmu-v5_default\NuttX\nuttx\arch\arm\src\stm32f7\hardware\stm32f74xx77xx_uart.h

有关DMA寄存器的宏定义在:

PX4-Autopilot\build\px4_fmu-v5_default\NuttX\nuttx\arch\arm\src\stm32f7\hardware\stm32f76xx77xx_dma.h

需要注意的是,这里需要根据直接使用的硬件版本来寻找文件,此外,也需要make一下才有这些文件。

其中串口使用到的主要寄存器有,将其定义为自定义宏:

#define F4REG(_x) (*(volatile uint32_t *)(F4IO_SERIAL_BASE + (_x)))
#define F4rISR F4REG(STM32_USART_ISR_OFFSET)
#define F4rISR_ERR_FLAGS_MASK (0x1f)
#define F4rICR F4REG(STM32_USART_ICR_OFFSET)
#define F4rRDR F4REG(STM32_USART_RDR_OFFSET)
#define F4rTDR F4REG(STM32_USART_TDR_OFFSET)
#define F4rBRR F4REG(STM32_USART_BRR_OFFSET)
#define F4rCR1 F4REG(STM32_USART_CR1_OFFSET)
#define F4rCR2 F4REG(STM32_USART_CR2_OFFSET)
#define F4rCR3 F4REG(STM32_USART_CR3_OFFSET)
#define F4rGTPR F4REG(STM32_USART_GTPR_OFFSET)

其中主要操作ICR中断寄存器,CR1、CR3串口配置寄存器

对于DMA,有部分封装函数可以使用,在

PX4-Autopilot\platforms\nuttx\NuttX\nuttx\arch\arm\src\stm32f7\stm32_dma.c

主要使用了

//映射DMA通道到UART
DMA_HANDLE stm32_dmachannel(unsigned int chan);
//配置DMA设置
void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
                    size_t ntransfers, uint32_t ccr);
//启动DMA
void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg,
                    bool half);

对于没有函数封装部分,主要使用了寄存器:

#define STM32_DMA1_S2CR           (STM32_DMA1_BASE+STM32_DMA_S2CR_OFFSET)

此外,为了操作寄存器,还使用了封装函数:

void modifyreg32(unsigned int addr, uint32_t clearbits, uint32_t setbits)

就是对addr处寄存器,&= ~clearbits,|= setbits。达到赋值和清除的目的。

配置硬件级别串口中断+DMA不定长接收

所以可以进行相关配置操作:

/* 声明DMA句柄 */
static DMA_HANDLE F4rx_dma;
static DMA_HANDLE F4tx_dma;

int interface_init(void)
{
	/* 配置DMA通道到UART4 */
	F4tx_dma = stm32_dmachannel(F4IO_SERIAL_TX_DMAMAP);
	F4rx_dma = stm32_dmachannel(F4IO_SERIAL_RX_DMAMAP);

	if ((F4rx_dma == NULL)|(F4tx_dma == NULL))
	{
		return -1;
	}
	/*配置接收DMA*/
	stm32_dmasetup(
		F4rx_dma,
		(F4IO_SERIAL_BASE + STM32_USART_RDR_OFFSET),
		(uint32_t)(&F4IORXBuffer[0]), /* 自定义接收缓存数组首地址 */
		BUFFER_SIZE,			/* 自定义接收缓存数组容量 */
		DMA_SCR_CIRC		|	/* 循环模式 */
		DMA_SCR_DIR_P2M		|	/* 硬件到内存方向 */
		DMA_SCR_MINC		|
		DMA_SCR_PSIZE_8BITS	|
		DMA_SCR_MSIZE_8BITS	|
		DMA_SCR_PBURST_SINGLE|
		DMA_SCR_MBURST_SINGLE
		);
	/**/
	stm32_dmastart(F4rx_dma, _dma_callback, NULL, false);
	/*配置发送DMA*/
	stm32_dmasetup(
		F4tx_dma,
		F4IO_SERIAL_BASE + STM32_USART_TDR_OFFSET,
		(uint32_t)F4IOTXBuffer, /* 自定义发送缓存数组首地址 */
		14,						/* 自定义发送缓存数组容量 */
		DMA_SCR_DIR_M2P		|	/* 内存到硬件方向 */
		DMA_SCR_MINC		|
		DMA_SCR_PSIZE_8BITS	|
		DMA_SCR_MSIZE_8BITS	|
		DMA_SCR_PBURST_SINGLE	|
		DMA_SCR_MBURST_SINGLE);
	/*启动发送DMA*/
	stm32_dmastart(F4tx_dma, NULL, NULL, false);
	/* 启动UART时钟 */
	modifyreg32(F4IO_SERIAL_RCC_REG, 0, F4IO_SERIAL_RCC_EN);

	/* 配置UART物理管脚 */
	px4_arch_configgpio(F4IO_SERIAL_TX_GPIO);
	px4_arch_configgpio(F4IO_SERIAL_RX_GPIO);

	/* 清理寄存器 */
	F4rCR1 = 0;
	F4rCR2 = 0;
	F4rCR3 = 0;

	/* 清理中断寄存器、接收寄存器 */
	if (F4rISR & USART_ISR_RXNE)
	{
		(void)F4rRDR;
	}
	// F4rCR3 = USART_CR3_EIE;

	F4rICR = F4rISR & F4rISR_ERR_FLAGS_MASK; /* clear the flags */

	/* 配置波特率F4IO_SERIAL_BITRATE */
	uint32_t usartdiv32 = (F4IO_SERIAL_CLOCK + (F4IO_SERIAL_BITRATE) / 2) / (F4IO_SERIAL_BITRATE);
	F4rBRR = usartdiv32;

	/* 添加自定义中断函数至UART中断函数 */
	int ret = irq_attach(F4IO_SERIAL_VECTOR, _interrupt, NULL);

	PX4_INFO("RET%i", ret);
	up_enable_irq(F4IO_SERIAL_VECTOR);
	/* 配置UART为DMA收发模式 */
	F4rCR3 |= USART_CR3_DMAR;
	F4rCR3 |= USART_CR3_DMAT;

	/* 配置UART中断模式 */
	F4rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;

	PX4_INFO("f4io serial init\r\n");
	return 0;
}

之后写入串口中断配置:

int _interrupt(int irq, void *context, void *arg)
{
	_do_interrupt();
	return 0;
}

void
_do_interrupt()
{
	uint32_t sr = F4rISR;	/* get UART status register */
	if (sr & USART_ISR_IDLE) {
		//PX4_INFO("IDLE");
		//disable DMA
		modifyreg32(STM32_DMA1_S2CR,((uint32_t)0x00000001),0);
		if (sr & USART_ISR_RXNE) {
			(void)F4rRDR;	/* read DR to clear RXNE */
		}
		/*自定义处理数据代码*/
		//enable DMA
		modifyreg32(STM32_DMA1_S2CR,0,((uint32_t)0x00000001));
		F4rICR = sr & F4rISR_ERR_FLAGS_MASK;	/* clear flags */
	}
}

其中需要注意的是,如果不写下面这些也能用,但是会把缓存变成ring buffer模式,继下一次数据跟在上一次数据屁股后面,到头了又从缓存数组头部续写,给读取造成了一定麻烦。

modifyreg32(STM32_DMA1_S2CR,((uint32_t)0x00000001),0);
modifyreg32(STM32_DMA1_S2CR,0,((uint32_t)0x00000001));

至此,只需要自定义一个module task,在其中调用上面函数就可以配置自己的硬件外设中断了

测试结果

从下图可以看到这种实现方式几乎不占用CPU时间。
在这里插入图片描述
而且接收的数据实时性非常好,即便在400Hz的数据接收频率下,间隔也几乎做到了μs量级误差(单位μs)
在这里插入图片描述

致谢

特别感谢PX4 User Group 🇨🇳Beijing群聊中的
@天蓝
@wj - 港科
@小火炉
等几位大佬

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4串口驱动的三种方式:系统级操作、task/work_queue、类似PX4IO中断响应 的相关文章

随机推荐

  • 基于单片机的数字钟设计

    文末下载完整资料 摘 要 基于单片机的定时和控制装置在许多行业有着广泛的应用 xff0c 而数字钟是其中最基本的 xff0c 也是最具有代表性的一个例子 在基于单片机系统的数字钟电路中 xff0c 除了基本的单片机系统和外围电路外 xff0
  • 电子设计大赛-电源电路

    文末下载完整资料 集成直流稳压电源的设计 直流稳压电源是电子设备的能源电路 xff0c 关系到整个电路设计的稳定性和可靠性 xff0c 是电路设计中非常关键的一个环节 本节重点介绍三端固定式 xff08 正 负压 xff09 集成稳压器 三
  • 总线的分类和区别

    总线分类 xff1a 点击查看原文 全套资料免费下载 xff1a 关注v x 公 众 号 xff1a 嵌入式基地 后 台 回 复 xff1a 电赛 即可获资料 回复 编程 即可获取 包括有 xff1a C C 43 43 C JAVA Py
  • 电子设计大赛-室内可见光定位装置

    室内可见光定位装置 1 1 设计任务 设计并制作可见光室内定位装置 xff0c 其构成示意图如图 1 所示 参赛者自行搭建不小于 80cm 80cm 80cm 的立方空间 xff08 包含顶部 底部和 3 个侧面 xff09 顶部平面放置
  • 嵌入式面试题

    首先给大家分享一个在线练习面试题的网站 xff1a 牛客网 该网站包含使用实例 应用技巧 基本知识点总结和需要注意事项 xff0c 具有参考价值 xff0c 需要的朋友可以参考一下 嵌入式面试题 点击进行练习 嵌入式面试题 第一部分 xff
  • ESP32 DIY 机器狗

    关注v x 公 众 号 xff1a 嵌入式基地 后 台 回 复 xff1a 电赛 即可获资料 回复 编程 即可获取 包括有 xff1a C C 43 43 C JAVA Python JavaScript PHP 数据库 微信小程序 人工智
  • 半桥与全桥的优缺点

    关注v x 公 众 号 xff1a 嵌入式基地 后 台 回 复 xff1a 电赛 即可获资料 回复 编程 即可获取 包括有 xff1a C C 43 43 C JAVA Python JavaScript PHP 数据库 微信小程序 人工智
  • 分享几个适合新手的C/C++开源项目

    分享几个适合新手的C C 43 43 开源项目 今天主要给大家分享一些github内适合初学者练手的c c 43 43 开源项目 所有项目均提供项目下载地址 xff0c 无法使用github的读者 xff0c 也可以在文末进行获取 如果说不
  • 树莓派VNC viewer显示cannot currently show the desktop的三种可能与解决办法(自己遇到过的)

    一 储存空间满了 var cache apt archives提示空间不够 xff0c 下线后再次连接VNC可能会黑屏 xff0c 改分辨率没有用 解决方法 xff1a sudo apt span class token operator
  • 程序员常用刷题网站分享

    1 牛客网 https www nowcoder com link pc csdncpt qrsjd c 该网站内集成了面试 题库 社群交流 课程教育 面试 招聘内推等多个模块 另外还是一个交流学习的平台 xff0c 在该网站经常会有大佬对
  • C语言刷题(二)

    作者简介 xff1a 大家好我是 xff1a 嵌入式基地 xff0c 是一名嵌入式工程师 xff0c 希望一起努力 xff0c 一起进步 xff01 x1f4c3 个人主页 xff1a 嵌入式基地 x1f525 系列专栏 xff1a 牛客网
  • 嵌入式软件工程师面试题(八)

    作者简介 xff1a 大家好我是 xff1a 嵌入式基地 xff0c 是一名嵌入式工程师 xff0c 希望一起努力 xff0c 一起进步 xff01 x1f4c3 个人主页 xff1a 嵌入式基地 x1f525 系列专栏 xff1a 嵌入式
  • 嵌入式软件工程师面试题(九)

    作者简介 xff1a 大家好我是 xff1a 嵌入式基地 xff0c 是一名嵌入式工程师 xff0c 希望一起努力 xff0c 一起进步 xff01 x1f4c3 个人主页 xff1a 嵌入式基地 x1f525 系列专栏 xff1a 嵌入式
  • 单片机、嵌入式的大神都平时浏览什么网站?

    单片机 嵌入式的大神都平时浏览什么网站 xff1f 1 基础学习 xff08 C C 43 43 xff0c Linux基础等 xff09 菜鸟教程 xff08 C语言学习 xff09 c语言中文网计算机科学网站 xff08 C语言部分 x
  • 一文读懂锁相环基本原理

    1 锁相环是什么 xff1f 锁相环电路是使一个特殊系统跟踪另外一个系统 xff0c 更确切的说是一种输出信号在频率和相位上能够与输入参考信号同步的电路 xff0c 它是模拟及数模混合电路中的一个基本的而且是非常重要的模块 2 锁相环基本理
  • 史上最全—毕业设计答辩技巧

    史上最全 毕业设计答辩技巧 一 常见问题二 答辩技巧三 论文答辩 图表穿插四 论文答辩 语流适中五 论文答辩六 论文答辩七 论文答辩八 论文答辩 紧扣主题九 论文答辩 人称使用十 完整版下载 一 常见问题 1 自己为什么选择这个课题 xff
  • 毕业设计答辩常见问题汇总

    毕设答辩常见问题汇总 1 P0 口需不需要加上拉电阻问题 xff1f 2 本课题的选课背景 意义等等 xff1f 3 数码管采用的是什么扫描方式 xff1f 4 蜂鸣器或继电器的驱动三极管为什么选用pnp型的 xff08 9012 8550
  • 【C语言】判断素数的函数

    文章目录 一 函数描述二 素数定义三 函数实现 一 函数描述 自定义一个函数 xff0c 传入一个整数n xff0c 判断是否为素数 若是返回1 xff0c 否则返回0 二 素数定义 素数又称质数 一个大于1的自然数 xff0c 除了1和它
  • 【C语言】判断闰年的函数

    文章目录 一 函数描述二 相关说明三 函数实现 一 函数描述 自定义一个函数 xff0c 传入一个年份n xff0c 判断是否为闰年 若是返回1 xff0c 否则返回0 二 相关说明 平年二月28 xff0c 闰年二月29 平年有365天
  • PX4串口驱动的三种方式:系统级操作、task/work_queue、类似PX4IO中断响应

    因为项目需要 xff0c 需在px4实现与stm32F407串口通信功能 xff0c 以200Hz双工交互数据 xff0c 所以探究了3种不同的串口驱动方式 三种方式概况参考了AcmeUavs公众号的文章 xff1a PX4 6 串口设备驱