CAN通信和M3508无刷减速电机

CAN通信

CAN(Controller Area Network)是一种广泛应用于汽车和工业领域的串行通信网络。它允许在没有主计算机的情况下,多个微控制器和设备相互通信。CAN通信接口的设计旨在允许微控制器和设备在高噪声环境下进行可靠的通信,同时减少连接线束的数量。

理论知识

理论知识部分大多数内容来自【中科大RM电控合集】小白也能看懂的CAN通信+STM32CubeMX编程, 本文选取了一部分在这篇博客中,仅作方便查找相关知识
不妨去给大佬的视频三连支持一下!

和计算机的通信架构相似,CAN通信是一种使用了分层思想的通信方式。我们可以简单地理解为CAN有3层架构:物理信号层,链路传输层,应用数据层

这只是一种简单的理解方式,和实际有出入
对于新手和不开放硬件的嵌入式开发者来说,理解这3层就足够了

物理信号层

CAN通信采取总线接法,这意味着信号是以广播的方式传递给线路上的所有设备的。每个设备引出两根线接入总线:一根是CAN_H,一根是CAN_L。而总线的CAN_HCAN_L通过120Ohm的电阻连接,防止信号不稳定

单线CAN也有但是速度慢我们不用

CAN通信接线方式示意

为了保证信号传输的稳定性,CAN通信采取差分信号传输的方式,即根据CAN_HCAN_L的电平差来识别信号
通常所说的“高电平”信号 1 在CAN通信中被编码为CAN_HCAN_L的电平相同,即电平差为0。我们称信号1为隐性电平。一般两根线的电平均为2.5V
通常所说的“高电平”信号 0 在CAN通信中被编码为CAN_HCAN_L的电平不同,通常电平差为2V。我们称信号0为显性电平。一般CAN_H为3.5V,CAN_L为1.5V

为什么有显性电平和隐性电平的区分呢?
这是因为两种电平的表达优先级不同。当一条线路上有两个设备同时发送一个显性电平0和一个隐性电平1时,显性电平会覆盖掉隐性电平
发生这种情况的时候,接收方就只知道此时接收到了一个显性电平,而不知道此时还有一个隐性电平

  • 比特率: 每秒传输的二进制码元的数量
  • 波特率:每秒传输的有效信息码元的数量

举个例子:

  • CAN通信使用二进制字符编码,有效信息码元就是二进制码元,所以比特率等于波特率
  • 十六进制字符编码中,一个有效信息码元需要4位二进制码元表示。如果每秒传输1000个字符,那么波特率就是1000 symbol/s;此时每秒需要传输4000个二进制字符来表示这1000个十六进制字符,那么比特率就是4000 bit/s

CAN通信采用异步通信
异步通信将每个比特细分为不同功能的时间片,不同的时间片做不同的事情

时间片 作用
同步段 对整条总线的各个设备进行同步
传播段 等待一段时间,确保物理信号能够传播到接收方处
相位缓冲段1(Seg1) 等待采样
<<<<<<< HEAD
采样点 硬件设备在Seg1和Seg2中间的这个时间点,也就是采样点,进行采样。
这时当前比特的状态是什么那么接收方就会认为它接收到的数据是什么
=======
采样点 硬件设备在Seg1和Seg2中间的这个时间点,也就是采样点,进行采样。
这时当前比特的状态是什么那么接收方就会认为它接收到的数据是什么

parent of de52741 (.)
|相位缓冲段2(Seg2)|等待下一个比特|

CAN通信有4中收发模式:

收发模式 发送 接收
常规模式 向总线发送 从总线接收
回环模式 向总线发送 仅从本机接收
静默模式 仅向本机发送 从总线和本机接收
回环静默模式 自收自发,不向总线发送 自收自发,不从总线接收

链路传输层

为了能够在广播式的总线协议中区分硬件,CAN通信中使用CAN ID来区分同一网络中的终端
CAN ID有类似于地址的功能,是一个一帧的标识符,用来指明是”谁发的”

一根物理意义上的导线不可能同时是高电平和低电平,我们不是用量子在通信的,因此通信时需要一定的冲突处理机制来解决不同发送方的矛盾
冲突的处理机制有两种:

  • 冲突检测
    发现可能出现冲突时解决冲突
    当一台设备试图在总线中发送隐性电平1的时候,如果此时检测到总线处于显性电平0的状态,就会暂停发送——因为有其他设备正在发送
  • 冲突避免
    防患于未然,避免冲突的发生

一条总线上传输的信息未必是所有接收设备都需要的信息
给接收设备配置滤波器可以解决这个问题。滤波器可以过滤出接收设备所需要的信息
值得注意的是,滤波器的机制是 过滤通过,即符合条件的信息才会被接收,而不是过滤排除
掩码则是辅助滤波器工作的。当使用CAN ID作为匹配规则的时候,滤波器会比对掩码为1的位上接收到的CAN ID是否和预设的CAN ID相同

例如:
如果希望过滤出CAN ID 范围为 0x114~0x117 的数据,我们需要把滤波器的过滤目标设置为0x114,掩码设置为0x7fc,这样滤波器就会忽略过滤目标的后两位二进制码是否相同,只判断前几位是否相同

CAN通信发送数据遵守一定的帧数据格式,下面是标准帧数据格式:
(表格是中科大RM电控合集【3.2】42:31的表格)

分段 内容 长度(bit) 备注
起始段 SOF,Start Of Frame 1 标志帧起始,必须是显性电平0
仲裁段 ID 11 表示CAN ID,同时用于仲裁,ID小的优先发
RTR,Remote Transmission Request 1 远程发送请求,数据帧中是显性电平0,遥控帧中是隐性电平1
控制段 IDE,IDentifier Extension 1 扩展帧格式标记,标准数据帧中是显性电平0,扩展帧中是隐性电平1
r0 1 保留位,必须是显性电平0
DLC,Data Length Code 4 数据长度的字节数,CAN协议中数据长度为0-8字节。但是接收方如果接收到DLC为9以上的数据不会认为出错
数据段 Data (0~8)*8 数据内容
校验段 CRC,Cyclic Redundancy Check 15 利用CRC算法生成的校验码
CRC delimiter 1 CRC界定符,标识CRC段的结束,必须为隐性电平1
回复段 ACK,ACKnowledge 1 该位由接收设备控制电平,如果正确接收则为显式电平0,否则为隐性电平1
ACK delimiter 1 ACK界定符,标识ACK段结束,必须为隐性电平1
结束段 EOF,End Of Frame 7 标志帧结束,必须为隐性电平1

扩展帧格式就不介绍了,要了解自己去看大佬视频

应用数据层

应用数据层就是被传输的数据主体。应用层的数据经过链路层的封装,在物理层被编码成物理信号发送出去
STM32自带CAN控制器,一般搭配的收发器型号为SN65HVD230。当我们把发送的数据加到CAN收发器中,CAN收发器就会自主控制进行发送了
STM32收发示意图(中科大版)

代码实践

首先在工程文件中新建两个文件motor.hmotor.c

默认的文件保存路径为项目地址\MDK-ARM
然而其他文件的保存地址在项目地址\Core\
保存到默认路径不仅需要修改文件的扫描路径,还没有把.h和.c文件分开,因此B觉得这不是很妥
建议将.h文件保存到项目地址\Core\Inc
.c文件保存到项目地址\Core\Src

先在motor.h中声明我们需要的函数和结构体类型:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
//motor.h
#include "fdcan.h"

#ifndef MOTOR_H
#define MOTOR_H

/**
* @brief CAN发送函数
*/
uint8_t CAN_Send(FDCAN_HandleTypeDef* can,int16_t motor1, int16_t motor2, int16_t motor3, int16_t motor4 );

void CAN_Open(FDCAN_HandleTypeDef* can);

/**
* @brief 描述电机状态
*
* @param ecd 电机编码器值,范围0-8191,对应0-360度,表示转子机械角度
* @param speed_rpm 电机速度,单位rpm
* @param given_current 电机实际转矩电流
* @param temperate 电机温度
* @param last_ecd 上次电机编码器值
* @param angle_armature 转子角度值,范围-180°-180°
* @param last_angle_armature 上次转子角度值
* @param turn 转子转过圈数,范围-19到19
* @param angle 转轴角度值,范围-180°-180°
* @param last_angle 上次转轴角度值
*/
typedef struct
{
uint16_t ecd;
int16_t speed_rpm;
int16_t given_current;
uint8_t temperate;
int16_t last_ecd;
float angle_armature;
int8_t turn;
float angle;
float last_angle_armature;
float last_angle;
} motor_measure_t;

/*CAN接收的ID*/
typedef enum
{
//add by langgo
CAN_3508Moto1_ID = 0x201,
CAN_3508Moto2_ID = 0x202,
CAN_3508Moto3_ID = 0x203,
CAN_3508Moto4_ID = 0x204

}CAN_Message_ID;

#endif

你经常可以在各种头文件中看到这样的语句:

1
2
3
4
5
6
7
// motor.c
#ifndef MOTOR_H
#define MOTOR_H

// Code

#endif

这个宏的意义在于防止同一文件被多次引用,编译,导致函数重复定义报错
你可以去掉这个宏试试看,我看你的代码能不能编译通过
这个宏还有一种更精简的写法:

1
2
3
#pragma once

// Code

这样可以声明这个文件只编译一次,效果是相同的

函数void CAN_Open(FDCAN_HandleTypeDef* can)uint8_t CAN_Send(FDCAN_HandleTypeDef* can,int16_t motor1, int16_t motor2, int16_t motor3, int16_t motor4 )都是从学长那里继承的

  • void CAN_Open(FDCAN_HandleTypeDef* can)
    • 初始化CAN收发器,请写在USER CODE 2
    • 参数FDCAN_HandleTypeDef* can填入CAN收发器的地址,比如&hfdcan1
  • uint8_t CAN_Send(FDCAN_HandleTypeDef* can,int16_t motor1, int16_t motor2, int16_t motor3, int16_t motor4 )
    • 通过CAN收发器发送电机电流信号
    • 参数FDCAN_HandleTypeDef* can填入CAN收发器的地址,比如&hfdcan1
    • 后4个参数int16_t motorn填入对应电机的电流
    • 通过电调的信号灯来判断电机的ID,具体自行看RoboMaster C620无刷电机调速器使用说明

结构体motor_measure_t是我改了学长的版本,添加了一些变量
这个结构体用来接收处理电机发回的电机数据,每个结构体成员变量的功能已经用注释清楚了

搞定.h之后我们打开.c文件

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
// motor.c
# include "motor.h"

void get_motor_measure(motor_measure_t* ptr, uint8_t* data)
{
ptr->last_ecd = ptr->ecd;
ptr->ecd = (uint16_t)((data)[0] << 8 | (data)[1]);
ptr->speed_rpm = (int16_t)((data)[2] << 8 | (data)[3]);
ptr->given_current = (int16_t)((data)[4] << 8 | (data)[5]);
ptr->temperate = (data)[6];

/* 该部分省略了一段代码,因为这是培训的任务内容 */
/* B 会分享个人的思路,但是源码还是你自己写吧 */
}


uint8_t chassis_can_send_data[8];
/**
* @brief CAN发送函数,电流值-16384 ~ 16384对应电流值-20 ~ 20A
* @param can: CAN句柄
* @param motor1: 电机1电流
* @param motor2: 电机2电流
* @param motor3: 电机3电流
* @param motor4: 电机4电流
* @retval 发送状态,1成功,0失败
*/
uint8_t CAN_Send(FDCAN_HandleTypeDef* can,int16_t motor1, int16_t motor2, int16_t motor3, int16_t motor4 )
{
FDCAN_TxHeaderTypeDef txHeader;
txHeader.Identifier = (uint32_t)0x200;//0x200是电机1-4,0x1FF是电机5-8
txHeader.IdType = FDCAN_STANDARD_ID;
txHeader.TxFrameType = FDCAN_DATA_FRAME;
txHeader.DataLength = FDCAN_DLC_BYTES_8;
txHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
txHeader.BitRateSwitch = FDCAN_BRS_OFF;
txHeader.FDFormat = FDCAN_CLASSIC_CAN;
txHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
txHeader.MessageMarker = 0x00;

chassis_can_send_data[0] = motor1 >> 8;
chassis_can_send_data[1] = motor1;
chassis_can_send_data[2] = motor2 >> 8;
chassis_can_send_data[3] = motor2;
chassis_can_send_data[4] = motor3 >> 8;
chassis_can_send_data[5] = motor3;
chassis_can_send_data[6] = motor4 >> 8;
chassis_can_send_data[7] = motor4;

if(HAL_FDCAN_AddMessageToTxFifoQ(can, &txHeader,chassis_can_send_data) != HAL_OK)
{
return 0;
}
else
{
return 1;
}
}

/**
* @brief 初始化滤波器
*
* @param can CAN句柄
*/
void CAN_Open(FDCAN_HandleTypeDef* can)
{
FDCAN_FilterTypeDef filter; //< 声明局部变量 can过滤器结构体
filter.IdType = FDCAN_STANDARD_ID; //< id设置为标准id
filter.FilterIndex = 0; //< 设值筛选器的编号,标准id选择0-127
filter.FilterType = FDCAN_FILTER_MASK; //< 设置工作模式为掩码模式
filter.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; //< 将经过过滤的数据存储到 fifo0
filter.FilterID1 = 0x000; //< 筛选器的id
filter.FilterID2 = 0x000;

HAL_FDCAN_ConfigFilter(can, &filter); //< 配置过滤器
HAL_FDCAN_Start(can); //< 使能can
//该check来测试can控制器是否使能,可以把该赋值去掉
HAL_FDCAN_ActivateNotification(can, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0); // 使能fifo0接收到新信息中断

}

motor_measure_t motor_chassis[4] = {0};//4 chassis motor

/**
* @brief CAN中断回调函数
*
* @param hcan CAN句柄
* @param RxFifo0ITs
*/
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hcan,uint32_t RxFifo0ITs)
{
if(hcan==&hfdcan1){
FDCAN_RxHeaderTypeDef rx_header;
uint8_t rx_data[8];

HAL_FDCAN_GetRxMessage(hcan, FDCAN_RX_FIFO0, &rx_header, rx_data);

switch (rx_header.Identifier) {
case CAN_3508Moto1_ID:
case CAN_3508Moto2_ID:
case CAN_3508Moto3_ID:
case CAN_3508Moto4_ID: {
static uint8_t i = 0;
//get motor id
i = rx_header.Identifier - CAN_3508Moto1_ID;
get_motor_measure(&motor_chassis[i], rx_data);

break;
}
default: {
break;
}
}
}
}

void get_motor_measure(motor_measure_t* ptr, uint8_t* data)是处理电机返回数据的函数
没有被隐去的部分是学长已经提供了的

学长本来是用宏函数写的

1
2
3
4
5
6
7
8
#define get_motor_measure(ptr, data)\
{ \
(ptr)->last_ecd = (ptr)->ecd; \
(ptr)->ecd = (uint16_t)((data)[0] << 8 | (data)[1]); \
(ptr)->speed_rpm = (uint16_t)((data)[2] << 8 | (data)[3]); \
(ptr)->given_current = (uint16_t)((data)[4] << 8 | (data)[5]); \
(ptr)->temperate = (data)[6]; \
}

B在改写这个函数的时候发现如果还使用宏函数写就非常麻烦了(用三元运算符?:也不是不能写但是那就很史了)
于是改成了正常的函数形式

至于你问为什么接收数据的代码要这么写?
参考RoboMaster C620无刷电机调速器使用说明得知返回的电机数据DATA的格式:

数据域内容
DATA[0]转子机械角度高8位
DATA[1]转子机械角度低8位
DATA[2]转子转速高8位
DATA[3]转子转速低8位
DATA[4]实际转矩电流高8位
DATA[5]实际转矩电流低8位
DATA[6]电机温度
DATA[7]NULL

这里的高8位低8位的意思是,原有的数据太大了,需要两个数据域来发送,接收时,只需要将高8位的数据和低8位的数据”拼接”回一个数据就可以了

隐藏的代码的功能是实现下面这个功能

在电机数据接受的基础上试着得到电机转轴的角度,-180——180度表示(10)

转轴的角度并不能直接从ecd值计算而来。这是因为转子转过完整的一圈转轴才转1/19圈,一个ecd值可能对应转轴角度的19种(或者20种)可能情况
这时,我们可以引入变量turn来记录转轴相对于初始位置向哪个方向转了几圈。有了圈数turn,再结合ecd就可以算出转轴位置了
查阅RoboMaster M3508直流无刷减速电机使用说明可以得到以下需要用到的关键数据:

电机特征参数
空载转速(转轴) 482 rpm
额定转速(转轴) 469 rpm
减速比 3591/187
信号发送频率 1kHz
编码器(ecd)值范围 0~8191

函数void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hcan,uint32_t RxFifo0ITs) 是CAN通信中断回调函数
总之也是从学长那里继承的,代码内容可以对照着理论知识自行了解,这里不多赘述,CAN通信会用就行


写好motor.cmotor.h之后,就可以使用CAN通信了
和前面的串口通信类似,你同样需要在USER CODE 2内写上CAN通信的初始化函数CAN_Open(&hfdcan_n)(hfdcan_n表示hfdcan1或者hfdcan2)
设置电机的电流值就可以使用CAN_Send()函数

—END—

参考:
【中科大RM电控合集】小白也能看懂的CAN通信+STM32CubeMX编程,BV1HY411D7Ar
stm32H750转RM3508电机(纯实践教程)
附件:
RoboMaster C620无刷电机调速器使用说明
RoboMaster M3508直流无刷减速电机使用说明


CAN通信和M3508无刷减速电机
http://chose-b-log.netlify.app/CAN通信和M3508无刷减速电机/
作者
B
发布于
2025年10月21日
许可协议