基于HAL库的stm32的can收发实验
十六、CAN
-
1.CAN简介
CAN协议,全称为Controller Area Network(控制器局域网络),是一种广泛应用的串行通信协议,最初由 德国BOSCH公司开发,并已成为国际标准。 低速CAN(ISO11519)通信速率 10~125Kbps,总线长度可达 1000 米。 高速CAN(ISO11898)通信速率 125Kbps~1Mbps,总线长度 ≤40 米。
定义:CAN协议是一种基于差分信号的异步串行通信协议,采用双绞线作为传输介质,具有高性能、高 可靠性和独特的设计特点
特点:
多主控制:支持多主方式,即任何一个节点都可以在总线上发送数据,其他节点根据需要进行接 收。当两个以上的节点同时开始发送数据时,会根据标识符(ID)决定优先级。
系统柔软性:与总线相连的单元没有类似于“地址”的信息,因此在总线上增加单元时,连接在总线 上的其他单元的软硬件及应用层都不需要改变。
仲裁检测
通信速度快、距离远:数据传输速率较高,标准速率为125kbps,扩展速率可达1Mbps,且通信 距离远,最远可达10KM(速率低于5Kbps)。
错误检测与恢复:具有错误检测、错误通知和错误恢复功能,能够确保数据传输的可靠性。
故障封闭功能:能够判断出错误的类型,并将引起故障的单元从总线上隔离出去。
应用领域汽车 ECU之间通讯,工业自动化,航空航天
2. CAN物理层介绍
CAN网络通常由CAN控制器、CAN收发器和双绞线组成。
CAN控制器:负责处理数据的收发和协议转换。
CAN收发器:负责将控制器的数字信号转换为差分信号进行传输,同时也负责将总线上的差分信号转换 为数字信号供控制器处理。
终端电阻: 在高速CAN总线的两端分别连接一个电阻,称为终端电阻。终端电阻的主要作用是匹配总线阻抗,提高 信号质量,减少回波反射。一般来说,终端电阻的阻值为120Ω。
2.1 总线拓扑图
2.2 电平标准
CAN使用差分信号进行数据传输,根据CAN_H和CAN_L上的电位差来判断总线电平。
显性电平表示逻辑 0 ,通常 CAN_H 和 CAN_L 有 2V 的压差;
隐性电平表示逻辑 1 ,通常 CAN_H 和 CAN_L 有 0V 的压差。
显性电平在通信中具有优先权,能够覆盖隐性电平,确保数据的正确传输。
隐性电平则作为总线的空闲或监听状态存在,等待有节点发送数据。
正常情况下是隐性电平---显隐压差不同
2.3 CAN控制器与收发器
不用交叉接线
3、CAN协议层介绍
3.1 CAN帧种类介绍
1. 数据帧(Data Frame):数据帧是CAN总线上用于传输用户数据的帧,包括必要的帧头、标识符、控 制位、数据长度代码、数据域、CRC校验码和应答域等部分,是CAN通信中最基本和最重要的帧类型。
2. 遥控帧(Remote Frame):遥控帧用于向总线上的其他节点请求发送具有相同标识符的数据帧,它 没有数据域,仅通过标识符来指定所需的数据。遥控帧的帧结构与数据帧相似,但缺少数据部分。
裁判
3. 错误帧(Error Frame):当CAN总线上的任何节点检测到通信错误时,会发送错误帧来通知其他节 点。错误帧包含错误标志和错误界定符,用于指示错误的存在和类型。
4. 过载帧(Overload Frame):过载帧用于在连续的数据帧或远程帧之间提供额外的延时,以指示接收 节点尚未准备好接收下一个帧。当接收节点因内部条件限制而无法立即接收数据时,会发送过载帧来请 求发送节点暂停发送。
5. 帧间隔(Interframe Space):帧间隔用于隔离数据帧与前面的帧,确保它们之间的时间间隔足够 长,以避免总线上的冲突和数据丢失。帧间隔包括连续三个隐性位(间隔段)和可能存在的空闲段,用于将数据帧或远程帧与前面的帧分隔开来。
3.2 CAN数据帧介绍
数据帧由7段组成。数据帧又分为标准帧(CAN2.0A)和扩展帧(CAN2.0B),主要体现在仲裁段和控制段。
- 帧起始(Frame Start): 功能:表示数据帧的开始。 特点:由一个显性位(Dominant Bit)构成,此时CAN_H为高电平(如3.5V),CAN_L为低电平 (如1.5V),二者之间的电位差形成信号。 2. 仲裁段(Arbitration Field): 功能:确定发送优先级,并包含标识符(Identifier)用于唯一标识发送者和接收者之间的通信关 系。 组成: 标准数据帧的仲裁场由11位ID和1位RTR位(远程发送请求位)组成。RTR位用于区分数据帧 (显性电平)和遥控帧(隐性电平)。 扩展数据帧中,还包含SRR位(Substituted Remote Request,替代的远程请求)和IDE位 (Identifier Extension,标识符扩展)。SRR位用于指示发送方是否发送了远程请求帧,IDE 位用于指示标识符字段是否使用了扩展格式(29位)。 3. 控制段(Control Field): 功能:包含数据长度代码(DLC),用于定义数据帧中数据域的长度。 特点:DLC占4位,其取值范围为0到8个字节,表示数据帧中包含的数据字节数。 4. 数据段(Data Field): 功能:包含要传输的数据,是数据帧的主体部分。 特点:数据域的长度可以根据DLC字段的值从0到8个字节不等,数据从最高位(MSB)开始传 输。 5. CRC段(CRC Field): 功能:用于检测数据帧的传输错误。 特点:CRC(循环冗余校验)是一种通过对数据进行计算生成的校验码,发送方在发送数据帧时会 根据数据计算出CRC值,并将其添加到数据帧的CRC段中。接收方在接收到数据帧后会重新计算 CRC值,并与接收到的CRC值进行比较,以确认数据在传输过程中是否发生错误。 6. 应答段(ACK Field): 功能:用来确认数据帧的正常接收。 组成:由ACK槽(ACK Slot)和ACK界定符两个位构成。当接收节点成功解析了数据帧并确认无误 后,会在ACK槽中发送一个显性位作为应答信号。 7. 帧结束(Frame End): 功能:表示数据帧的结束。 特点:由7个连续的隐性位构成,标志着数据帧的传输完成。
-
3.3 CAN位时序
CAN总线以“位同步”机制,实现对电平的正确采样。位数据都由四段组成:同步段(SS)、传播时间段(PTS)、 相位缓冲段1(PBS1)和相位缓冲段2(PBS2),每段又由多个位时序Tq组成。
-
所谓采样点是读取总线电平,并将读到的电平作为位值的点。位置在 PBS1 结束处。
CAN总线通过时钟同步机制来确保各个节点在通信过程中保持同步。时钟同步机制包括硬同步和再同步两 种:
1.硬同步:
硬同步只在帧的起始位(SOF)处进行。
当接收节点检测到帧起始位的下降沿时,会将其与自身的位时间进行对齐,从而实现同步。
2.再同步:
再同步在帧的后续数据位中进行。
如果接收节点检测到数据位的跳变沿不在自身的同步段内,则会通过延长或缩短相位缓冲段的时 间来调整自身的位时间,以重新获得同步。
再同步时,PBS1和PBS2中增加或者减少的时间被称为“再同步补偿宽度(SJW)”,其范围:1~4 Tq。
3.4 CAN仲裁机制
CAN总线处于空闲状态,最先开始发送消息的单元获得发送权。
多个单元同时开始发送时,从仲裁段(报文ID)的第一位开始进行仲裁。仲裁原理如下:
1.标识符优先级:
CAN总线中传输的数据帧的起始部分为数据的标识符(ID)。这个标识符不仅用于区分消息,还 表示消息的优先级。在CAN 2.0标准中,标识符可以是11位或29位(对于扩展帧)。标识符的数 值越小,优先级越高。
例如,在11位标识符的情况下,ID为0x000的消息具有最高优先级,而ID为0x7FF的消息具有最低 优先级。
2.逐位仲裁:
当两个或两个以上的节点同时开始传送报文时,就会产生总线访问冲突。此时,各节点会按照标 识符的位顺序逐位进行仲裁。
在仲裁过程中,每个节点都会将自己发送的电平与总线上的电平进行比较。如果电平相同,则节 点继续发送下一位;如果电平不同,则优先级低的节点停止发送,而优先级高的节点继续发送。 这种仲裁方式是非破坏性的,即优先级低的节点在仲裁过程中不会破坏总线上已经存在的数据。
3.显性电平优先
在CAN总线上,显性电平(逻辑0)的优先级高于隐性电平(逻辑1)。因此,在仲裁过程中,如 果某个节点发送的是隐性电平,但检测到总线上存在显性电平,那么该节点就会知道有更高优先 级的消息正在发送,并主动停止发送。
一旦仲裁结束,优先级最高的节点将获得总线控制权并开始传输数据。其他节点则成为接收节点并监听总线 上的数据,并会自动检测总线空闲,在第一时间再次尝试发送。
4.STM32 CAN控制器介绍
4.1CAN控制器介绍
STM32的bxCAN,即基本扩展CAN(Basic Extend CAN),是STM32微控制器系列中集成的CAN控制器模 块。
1. 协议支持:支持CAN协议2.0A和2.0B的主动模式。
2. 高波特率:波特率最高可达1兆位/秒。
3. 时间触发通信:支持时间触发通信功能,CAN的硬件内部定时器可以在TX/RX的帧起始位的采样点位置 生成时间戳。
4. 发送功能:
具有3个发送邮箱,发送报文的优先级特性可软件配置。
记录发送SOF(Start Of Frame,帧起始)时刻的时间。
接收功能: 具有3级深度的2个FIFO(First In First Out,先进先出队列),每个FIFO都可以存放3个完整的报 文,完全由硬件管理。
共有14个位宽可变的过滤器组(部分STM32型号可能支持更多),由整个CAN共享,用于筛选有 效报文。
记录接收SOF时刻的时间。
支持禁止自动重传模式。
4.2CAN控制器模式
CAN控制器的工作模式有三种:初始化模式、正常模式和睡眠模式。
睡眠模式:在睡眠模式下,CAN控制器的时钟停止,以降低功耗。但软件仍然可以访问邮箱寄存器。
初始化模式:在初始化模式下,禁止报文的接收和发送,并且CANTX引脚输出隐性位(高电平)。此时,可 以对CAN控制器的相关寄存器进行配置,如位时间特性(CAN_BTR)和控制(CAN_MCR)等。
正常模式:作为总线的正常节点,可以向总线发送或接收数据。
CAN控制器的测试模式有三种:静默模式、环回模式和环回静默模式,主要用于特定的测试或调试目的,以 确保CAN控制器的功能正常。
静默模式
特点: 在静默模式下,CAN控制器可以正常地接收数据帧和远程帧,但只能发出隐性位,而不能真正发送报 文。
这意味着,虽然CAN控制器在尝试发送数据,但实际上它并没有在CAN总线上产生任何显性位,因此不 会对总线上的其他节点产生影响。
应用场景: 静默模式通常用于分析CAN总线的活动,而不会对总线上的其他通信造成干扰。
开发人员可以使用此模式来观察总线上的数据流,而无需担心他们的测试设备会发送出不必要的报文。
环回模式
特点:
在环回模式下,CAN控制器会把发送的报文当作接收的报文并保存(如果可以通过接收过滤)。
这意味着,当CAN控制器发送一个报文时,它会立即在自己的接收缓冲区中看到这个报文,就像它是从 总线上接收到的一样。
应用场景:
环回模式通常用于自测试,以验证CAN控制器的发送和接收功能是否正常。
通过发送一个报文并检查它是否被正确接收,开发人员可以确保CAN控制器的硬件
和固件都按预期工 作。
环回静默模式
特点:
环回静默模式结合了静默模式和环回模式的特点。
在该模式下,CANRX引脚与CAN总线断开,同时CANTX引脚被驱动到隐性位状态。
这意味着,虽然CAN控制器在尝试发送报文,但它实际上并没有在CAN总线上产生任何显性位,并且它 会将发送的报文视为接收到的报文。
应用场景:
环回静默模式通常用于“热自测试”,即可以在不影响CANTX和CANRX所连接的整个CAN系统的情况下进 行测试。
这种模式允许开发人员在不干扰总线上的其他通信的情况下,验证CAN控制器的发送和接收功能。
4.2 CAN控制器框图
CAN控制内核:包含各种控制/状态/配置寄存器,用于配置CAN控制器的模式、波特率等参数。 发送邮箱(Transmit Mailbox):用来缓存待发送的CAN报文。STM32等微控制器通常具有多个发送
发送邮箱(Transmit Mailbox):用来缓存待发送的CAN报文。STM32等微控制器通常具有多个发送邮箱 (如3个),以支持同时缓存多个报文。
接收FIFO(First In First Out):缓存接收到的有效CAN报文。CAN控制器通常具有多个接收FIFO(如2 个),以提高接收效率。
接收过滤器(Receive Filter):筛选接收到的CAN报文,只将符合特定条件的报文保存到接收FIFO中。这 有助于减少CPU的处理负担,提高系统的响应速度。
接收处理过程:
有效报文指的是(数据帧直到EOF段的最后一位都没有错误),且通过过滤器组对
标识符过滤。
接收过滤器:
当总线上报文数据量很大时,总线上的设备会频繁获取报文,占用CPU。过滤器的存在,选择性接收有效报 文,减轻系统负担。
STM32的CAN控制器支持配置过滤器组, 每个过滤器组包含2个32位的寄存器CAN_FxR1和CAN_FxR2, 用于 存储要筛选的ID或掩码。 对于STM32F103C8T6, 如果只有一个CAN控制器, 则可以配置14个过滤器组, 对 应的编号为0到13。
过滤器可以配置为不同的位宽,以适应不同长度的CAN ID。常见的位宽包括16位(用于标准帧)和32位 (用于扩展帧)。
选择模式可设置屏蔽位模式或标识符列表模式,寄存器内容的功能就有所区别。屏蔽位模式,可以选择出一 组符合条件的报文。寄存器内容功能相当于是否符合条件。标识符列表模式,可以选择出几个特定ID的报 文。寄存器内容功能就是标识符本
身。
4.3 CAN控制器位时序
设TS1=8、TS2=7、BRP=3,波特率 = 36000 / [( 9 + 8 + 1 ) * 4] = 500Kbps。 注意:通信双方波特率需要一致才能通信成功。
CAN寄存器及库函数介绍
22.9.2 CAN控制和状态寄存器
CAN发送状态寄存器 (CAN_TSR)
CAN位时序寄存器 (CAN_BTR)

发送邮箱标识符寄存器 (CAN_TIxR) (x=0..2)
发送邮箱数据长度和时间戳寄存器 (CAN_TDTxR) (x=0..2)
位3:0 DLC[15:0]: 发送数据长度 (Data length code) 该域指定了数据报文的数据长度或者远程帧请求的数据长度。1个报文包含0到8个字节数据, 而这由DLC决定。
发送邮箱低字节数据寄存器 (CAN_TDLxR) (x=0..2)64位8字节 保存低字节
发送邮箱高字节数据寄存器 (CAN_TDHxR) (x=0..2)
22.9.4 CAN过滤器寄存器
CAN 过滤器模式寄存器 (CAN_FM1R)
CAN 过滤器位宽寄存器 (CAN_FS1R)
CAN 过滤器FIFO关联寄存器 (CAN_FFA1R)

CAN 过滤器组i的寄存器x (CAN_FiRx)
(互联产品中i=0..27,其它产品中i=0..13; x=1..2)
根据过滤器位宽和模式的不同设置,过滤器组中的两个寄存器的功能也不尽相同。关于过滤器 的映射,功能描述和屏蔽寄存器的关联,请参见22.7.4节标识符过滤。
函数
HAL_CAN_Init
HAL_CAN_ConfigFilter
HAL_CAN_Start 收发数据
HAL_CAN_AddTxMessage
HAL_CAN_GetRxMessage
HAL_CAN_GetTxMailboxesFreeLevel 等待发送完成
HAL_CAN_GetRxFifoFillLevel 等待接收完成
TimeSeg1
流程图
小实验:CAN收发实验
实验目的
1. 使用回环模式实现自发自收;
2两个CAN设备实现收发。
硬件清单 TJA1050
为什么只能
为什么只能发数据却收不到数据
用NORMAL的时候就发给另一台设备
/------------------------------------can.c-----------------------------------/
初始化
void can_init(void)
{can_handle.Instance = CAN1;//外设基地址//波特率,位时序can_handle.Init.Mode = CAN_MODE_LOOPBACK;//回环模式自己发自己收用作测试//波特率can_handle.Init.Prescaler = 4; //波特率预分频can_handle.Init.TimeSeg1 = CAN_BS1_9TQ;//tq取8但是这里取9个TQ为什么?can_handle.Init.TimeSeg2 = CAN_BS1_8TQ;//tq取8但是这里取9个TQcan_handle.Init.SyncJumpWidth = CAN_SJW_1TQ;//1~4个Tqcan_handle.Init.AutoBusOff = DISABLE; //禁止自动离线管理can_handle.Init.AutoRetransmission = DISABLE; //禁止自动重发can_handle.Init.AutoWakeUp = DISABLE; //禁止自动唤醒can_handle.Init.ReceiveFifoLocked = DISABLE; //禁止接收FIFO锁定can_handle.Init.TimeTriggeredMode = DISABLE; //禁止时间触发通信模式can_handle.Init.TransmitFifoPriority = DISABLE; //禁止发送FIFO优先级HAL_CAN_Init(&can_handle);//过滤器配置CAN_FilterTypeDef can_filterconfig = {0};//结构体can_filterconfig.FilterMode = CAN_FILTERMODE_IDMASK; //工作模式按摩 掩码。和列表模式can_filterconfig.FilterScale = CAN_FILTERSCALE_32BIT;//拓展帧32位can_filterconfig.FilterIdHigh = 0;//不过滤任何东西什么东西来都接收can_filterconfig.FilterIdLow = 0;can_filterconfig.FilterMaskIdHigh = 0;can_filterconfig.FilterMaskIdLow = 0;can_filterconfig.FilterBank = 0;//使用0号寄存器can_filterconfig.FilterFIFOAssignment = CAN_FilterFIFO0;//进到FIFO 0中can_filterconfig.FilterActivation = CAN_FILTER_ENABLE;//使能过滤器can_filterconfig.SlaveStartFilterBank = 14;//---HAL_CAN_ConfigFilter(&can_handle,&can_filterconfig);HAL_CAN_Start(&can_handle);
}
底层配置
void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan)
{__HAL_RCC_CAN1_CLK_ENABLE();__HAL_RCC_GPIOA_CLK_ENABLE();GPIO_InitTypeDef gpio_initstruct;gpio_initstruct.Pin = GPIO_PIN_12; gpio_initstruct.Mode = GPIO_MODE_AF_PP; gpio_initstruct.Pull = GPIO_PULLUP; gpio_initstruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(GPIOA, &gpio_initstruct);gpio_initstruct.Pin = GPIO_PIN_11; gpio_initstruct.Mode = GPIO_MODE_AF_INPUT; HAL_GPIO_Init(GPIOA, &gpio_initstruct);
}
can发送数据
void can_send_data(uint32_t id,uint8_t *buf,uint8_t len)
{CAN_TxHeaderTypeDef tx_header = {0};uint32_t tx_mail = CAN_TX_MAILBOX0;//邮箱0tx_header.ExtId = id;tx_header.DLC = len;tx_header.IDE = CAN_ID_EXT;//标准针还是拓展帧tx_header.RTR = CAN_RTR_DATA;//数据帧HAL_CAN_AddTxMessage(&can_handle,&tx_header,buf,&tx_mail);//句柄 结构体 指定邮箱//等待三个邮箱都空while(HAL_CAN_GetTxMailboxesFreeLevel(&can_handle) != 3);uint8_t i =0;printf("发送数据: \r\n");//将buf中的数字打印出来for(i = 0;i <len;i++)printf("%X ",buf[i]);printf("\r\n");
}
接收数据
uint8_t can_receive_data(uint8_t *buf)
{CAN_RxHeaderTypeDef rx_header = {0};if(HAL_CAN_GetRxFifoFillLevel(&can_handle,CAN_RX_FIFO0) == 0)return 0;//没有接收到数据//句柄 FIFO0,机构体,缓冲区HAL_CAN_GetRxMessage(&can_handle,CAN_RX_FIFO0,&rx_header,buf);uint32_t i = 0;printf("接收数据: \r\n");for(i =0;i < rx_header.DLC;i++)printf("%X ", buf[i]);printf("\r\n");return rx_header.DLC;}
/------------------------------------------main.c---------------------------/
#include "sys.h"
#include "delay.h"
#include "led.h"
#include "uart1.h"
#include "key.h"
#include "can.h"
#include "stdio.h"uint8_t data_send[8] = {0x11,0x22,0x33,0x44,0x55,0x66,0x77,0x88};
uint8_t data_receive[8];int main(void)
{HAL_Init(); /* 初始化HAL库 */stm32_clock_init(RCC_PLL_MUL9); /* 设置时钟, 72Mhz */led_init(); /* LED初始化 */uart1_init(115200);can_init();key_init();
// led1_on();
// led1_off();printf("hello world!\r\n");uint8_t i = 0;while(1){ //按下KEY1发送数据if(key_scan() == 1){for(i=0;i<8;i++)data_send[i]++;can_send_data(0x12345678,data_send,8);}can_receive_data(data_receive);}
}
实验现象
相关文章:

基于HAL库的stm32的can收发实验
十六、CAN 1.CAN简介 CAN协议,全称为Controller Area Network(控制器局域网络),是一种广泛应用的串行通信协议,最初由 德国BOSCH公司开发,并已成为国际标准。 低速CAN(ISO11519)通…...

重构(二)
继续"提高代码质量" 接着上文提高代码质量, 需要从这几个特点入手 1、代码重用性。2、可读性。3、可扩展性。4、可靠性。5、高内聚,低耦合。 仅仅就"可读性"去分析一下吧, 毕竟例子实在是太多了 递归的"可读性"不如while循环 递归…...

centos7下制作DockerFile 镜像
文章目录 介绍DockerFile 常用命令示例1.创建Dockerfile文件2.构建Dockerfile镜像3.验证结果 小结 介绍 Dockerfile 是一个文本文件,包含了用于构建 Docker 镜像的所有命令和指令。它定义了镜像的构建过程,包括基础镜像、安装软件、设置环境变量、复制文…...

GFPS扩展技术原理(七)-音频切换消息流
音频切换消息流 Seeker和Provider通过消息流来同步音频切换能力,触发连接做切换,获取或设置音频切换偏好,通知连接状态等等。为此专门定义了音频切换消息流Message Group 为0x07,Message codes如下: MAC of Audio s…...

压缩qcow2镜像带来的性能损失简单分析
本文拟对压缩qcow2镜像所带来的虚拟机性能损失进行简单分析 背景 生产中发现使用压缩镜像启动的虚拟机开机总是会慢一些。 qcow2镜像的压缩方式为:qemu-img convert -p -c -O qcow2 zero_disk.qcow2 compress_disk.qcow2 分析 qemu代码:https://down…...

Kali操作系统简单介绍
Kali是一个集成了各种安全工具的操作系统 安全问题的根源 1.分层思想:网络和软件开发的分层方法 2.安全问题:分层思想导致的片面认识和系统脆弱性 3.人的因素:安全问题的最终根源是人的错误 传统安全建设 1.防护型安全建设:关闭不…...

LabVIEW物联网开发实战:专栏总述
本专栏以LabVIEW为开发平台,讲解物联网通信组网原理与开发方法,覆盖RS232、TCP、MQTT、蓝牙、Wi-Fi、NB-IoT等协议。 结合实际案例,展示如何利用LabVIEW和常用模块实现物联网系统的快速开发与原型设计,助你从基础到实战࿰…...

高效处理PDF文件的终极工具:构建一个多功能PDF转换器
在日常工作中,处理PDF文件几乎是每个人都不可避免的任务。无论是从PDF中提取数据、合并多个PDF文件,还是处理文件中的敏感信息和图像,PDF文件的处理都可能成为繁琐且耗时的工作。如果你是数据分析师、工程师,或者从事文档管理的工…...

Y3编辑器教程6:触发器进阶案例
文章目录 一、地形制作1.1 地形制作流程1.2 关卡白盒1.3 场景美化1.4 优化场景 二、触发结构三、玩家指引(函数封装)3.1 项目拆解3.2 功能实现3.2.1 绘制UI界面3.2.2 UI的读取显示和刷新3.2.3 交互功能3.2.4 最终实现 四、NPC对话系统4.1 项目拆解4.2 UI…...

react Ant Design
一、通过项目模版创建一个react项目 set NPM_CONFIG_REGISTRYhttps://registry.npmmirror.com pnpm create vite antd-demo cd antd-demo pnpm install pnpm install antd --save 打开项目: 修改:welcome.tsx import React from react; import { Butto…...

汽车电子零部件(14):APA(自动泊车辅助)/RPA(远程遥控泊车)/AVP(自动代客泊车)
APA: Automated Parking Assist (APA) systems,自动泊车辅助系统,是自动驾驶汽车的一个关键功能。自动泊车辅助系统(APA)利用超声波雷达、视觉传感器和ADAS处理器来定位合适的停车位。它识别适合车辆大小的停车位,规划停车路线,并控制方向盘、变速箱和油门踏板以辅助停…...

Hot100刷题计划-Day2-滑动窗口、双指针、数组、链表、动态规划
LeetCode Hot 100 是最常被考察的题目集合,涵盖了面试中常见的算法和数据结构问题。刷 Hot100可以让你在有限的时间内集中精力解决最常考的问题。不仅要写出代码,还要理解问题的本质、优化解法和复杂度分析。 滑动窗口 438. 找到字符串中所有字母异位词…...

[react 3种方法] 获取ant组件ref用ts如何定义?
获取ant的轮播图组件, 我用ts如何定义? Strongly Type useRef with ElementRef | Total TypeScript import React, { ElementRef } from react; const lunboRef useRef<ElementRef<typeof Carousel>>(null); <Carousel autoplay ref{lunboRef}> 这样就…...

考前倒计时98天
2024年12月21日到2025年3月29日共有 98 天 一、计算机基础 思维分类特征强调学科代表理论思维(推理思维)推理和演绎推理数学实验思维(证实思维)观察和总结自然规律归纳物理学计算思维(构造思维)设计和构造…...

iterm2 focus时灰色蒙层出现的解决办法
问题描述: 当前我的iterm2版本是3.5.10,是我最近才更新的,然后就出现以下页面显示问题,如图所示: 我个人对终端、编辑器等使用存在洁癖,尤其是页面显示效果不满意更是不能忍受,之前找了很久没有…...

合并K个升序链表(最优解)
题目来源 23. 合并 K 个升序链表 - 力扣(LeetCode) 题目描述 给你一个链表数组,每个链表都已经按升序排列。 请你将所有链表合并到一个升序链表中,返回合并后的链表。 示例 1: 输入:lists [[1,4,5],[1,3,…...

kubernates实战
使用k8s来部署tomcat 1、创建一个部署,并指定镜像地址 kubectl create deployment tomcat6 --imagetomcat:6.0.53-jre82、查看部署pod状态 kubectl get pods # 获取default名称空间下的pods kubectl get pods --all-namespaces # 获取所有名称空间下的pods kubect…...

How to run Flutter on an Embedded Device
basysKom GmbH | How to run Flutter on an Embedded Device https://github.com/sony/flutter-embedded-linux/wiki/Building-Flutter-Engine-from-source flutter源码下载(最新)-CSDN博客 flutter_engine 交叉编译【自定义编译器(最新)】_flutter。engine 修改-CSDN博客 …...

airflow docker 安装
mkdir -p /root/airflow cd /root/airflow && mkdir -p ./dags ./logs ./plugins ./configcd /root/airflow/ wget https://airflow.apache.org/docs/apache-airflow/2.10.4/docker-compose.yaml nano docker-compose.yamlAIRFLOW__CORE__LOAD_EXAMPLES: false #初始化…...

浅析InnoDB引擎架构(已完结)
大家好,我是此林。 今天来介绍下InnoDB底层架构。 1. 磁盘架构 我们所有的数据库文件都保存在 /var/lib/mysql目录下。 由于我这边是docker部署的mysql,用如下命令查看mysql数据挂载。 docker inspect mysql-master 如下图,目前只有一个数…...

华为云计算HCIE笔记02
第二章:华为云Stack规划设计 交付总流程 准备工作:了解客户的基本现场,并且对客户的需求有基本的认知。 HLD方案BOQ报价设备采购和设备上架 2.安装部署流程 硬件架构设计 硬件设备选配 设备上架与初始化配置 准备相关资料(自动下载…...

鸿蒙项目云捐助第十讲鸿蒙App应用分类页面二级联动功能实现
鸿蒙项目云捐助第十讲鸿蒙App应用分类页面二级联动功能实现 在之前的教程中完成了分类页面的左右两侧的列表结构,如下图所示。 接下来需要实现左侧分类导航项的点击操作,可以友好的提示用户选择了哪一个文字分类导航项。 一、左侧文字分类导航的处理 …...

STM32低功耗模式结合看门狗
STM32低功耗模式结合看门狗 前言 最近做到一个需求要使用STM32的低功耗模式进行长时间待机应用,每隔十分钟发送一次数据到服务器上,当不发送的时候就处于低功耗模式。在经过一段时间的测试以后发现板子过三四天左右就没有数据上传服务器了,…...

数据迁移工具,用这8种!
前言 最近有些小伙伴问我,ETL数据迁移工具该用哪些。 ETL(是Extract-Transform-Load的缩写,即数据抽取、转换、装载的过程),对于企业应用来说,我们经常会遇到各种数据的处理、转换、迁移的场景。 今天特地给大家汇总了一些目前…...

Sapro编程软件
Sapro软件是由西门子建筑科技公司开发的一款编程软件,主要用于Climatix控制器的编程、调试及相关功能实现.以下是其具体介绍: • 功能强大:可进行HVAC控制编程,实现设备控制、HMI用户访问和设备集成等功能,满足复杂的…...

Python图注意力神经网络GAT与蛋白质相互作用数据模型构建、可视化及熵直方图分析...
全文链接:https://tecdat.cn/?p38617 本文聚焦于图注意力网络GAT在蛋白质 - 蛋白质相互作用数据集中的应用。首先介绍了研究背景与目的,阐述了相关概念如归纳设置与转导设置的差异。接着详细描述了数据加载与可视化的过程,包括代码实现与分析…...

2024年图像处理、多媒体技术与机器学习
重要信息 官网:www.ipmml.org 时间:2024年12月27-29日 地点:中国-大理 简介 2024年图像处理、多媒体技术与机器学习(CIPMT 2024)将于2024年12月27-29日于中国大理召开。将围绕图像处理与多媒体技术、机器学习等在…...

java 1.8+springboot文件上传+vue3+ts+antdv
1.参考 使用SpringBoot优雅的实现文件上传_51CTO博客_springboot 上传文件 2.postman测试 报错 :postman调用时body参数中没有file单词 Resolved [org.springframework.web.multipart.support.MissingServletRequestPartException: Required request part file is…...
【机器人】机械臂轨迹和转矩控制对比
动力学控制和轨迹跟踪控制是机器人控制中的两个概念,它们在目标、方法和应用上有所不同,但也有一定关联。以下是它们的区别和联系: 1. 动力学控制 动力学控制是基于机器人动力学模型的控制方法,目标是控制机器人关节力矩或力&…...

如何利用矩阵化简平面上的二次型曲线
二次型曲线的定义 在二维欧式平面上,一个二次型曲线都可以写成一个关于 x , y x,y x,y的二元二次多项式: F ( x , y ) a 11 x 2 2 a 12 x y a 22 y 2 2 a 1 x 2 a 2 y a 0 0 \begin{equation} F(x,y)a_{11}x^22a_{12}xya_{22}y^22a_1x2a_2ya_00…...