读取RC遥控信号(PWM和PPM)

前言:受益于毕业后的狂欢🐟博客鸽了半个月。也不算是完全鸽掉,这段时间搞了一艘RC船,通信部分是基础中的基础,因此记录一下自己写的STM32读取接收机信号的成果。

RC接收机

图片中就是市面上最常见的“富士”系列接收机,可以输出数个通道的数据(对应于RC遥控器上的各个控制通道),而这些远程传输来的数据以PWM信号的形式供给舵机或者自驾仪,比如这款可以输出10个通道PWM信号。同时这款接收机还支持输出PPM信号(和1通道共用引脚),PPM信号如下图所示,只要使用1个引脚就能传输多个通道的数据,相比PWM来说节省了大量的走线和空间,这个信号也是笔者更偏爱的接收方式。

PPMandPWM

接下来本文将分为三个部分,欢迎读者按需跳读:

  • PWM与PPM信号
  • 单定时器读取多路PWM信号
  • 读取PPM信号

PWM与PPM信号

PWM信号全称脉冲宽度调制信号(Pulse Width Modulation),也就是信号的高电平宽度表示信号有效值。但是用于RC遥控的接收机,输出的PWM信号是有一套标准的:

  • 高电平的时间范围为0.5ms ~ 2.5ms
  • 每个通道的PWM信号周期为20ms
  • 接收机供电和输出电平标准为5V

之所以有这一套标准,是为了给广大模友提供即插即用的便利,因此很多舵机也都是兼容这套标准的。

PWM信号对于传输数值的表示非常直接,但是肯定也有着大量缺陷,其中之一是:当使用到多路控制信号时,走线非常多!这一点促使人们发明了PPM编码的传输方式,从上面可以知道RC的一个PWM信号占空比最高为12.5%,所以PPM为了提高效率就把几路信号都塞进一个通道里串起来,一般塞10个通道并满足:

  • 每个通道高电平时间为0.5ms~1.5ms
  • 每个通道结尾都有一个固定0.5ms的低电平
  • 一个帧内所有通道传输完成后,在末尾插入一个用于补齐帧长度至20ms的高电平段

单定时器读取多路PWM信号

接收机输出的多路PWM信号都是上升沿对齐的,所以我们可以仅使用一个定时器读取多个通道。笔者这里使用的是STM32CubeMX工具配置STM32F103,设置好时钟源和各个通道(输入捕获模式),并注意将参数设置为:

  • 配置定时器的时钟和周期计数值,使计数溢出周期时间略大于20ms
  • 尽量将周期计数值配置大,以提高测量精度
  • 选一个用来对齐周期的通道(比如笔者使用通道1),输入捕获极性为上升沿
  • 其他通道配置为下降沿捕获
  • 各个通道配置适量的输入滤波(Input Filter)。若走线长、噪声大,必须使用较大的该参数;否则,从0开始增加调教至参数读取稳定即可

CubeMX配置输入捕获

⚠ 务必如图打开定时器的中断!因为下列代码是在定时器中断服务中实现的

配置结束后,即可copy下代码块中的中断服务程序。定时器的初始化程序由CubeMX工具生成,使用时只需确保在定时器初始化完成后调用HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)接口即可。

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
116
117
118
119
#include "bsp.h"

#define RC_TIMER_HANDLER (&htim2)


uint16_t RC_ChannelsVal[RC_CHANNEL_NUM]; // 各个通道PWM数据

uint32_t RC_TIM_IC_RISSING = 1; // 表示正在检测的为上升沿

/**
* @brief 初始化RC接收机驱动程序
* @param None
* @retval None
*/
void PWMCap_init(void)
{
//-- 启动输入捕获中断
HAL_TIM_IC_Start_IT(RC_TIMER_HANDLER,TIM_CHANNEL_1);
HAL_TIM_IC_Start_IT(RC_TIMER_HANDLER,TIM_CHANNEL_2);
HAL_TIM_IC_Start_IT(RC_TIMER_HANDLER,TIM_CHANNEL_3);
HAL_TIM_IC_Start_IT(RC_TIMER_HANDLER,TIM_CHANNEL_4);

//-- 设置各个通道的捕获极性
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_1,TIM_INPUTCHANNELPOLARITY_RISING); // 只有第一个通道设置为上升沿,用来对齐周期
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_2,TIM_INPUTCHANNELPOLARITY_FALLING);
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_3,TIM_INPUTCHANNELPOLARITY_FALLING);
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_4,TIM_INPUTCHANNELPOLARITY_FALLING);

}

/**
* @brief 定时器2中断程序(专用来接收RC)
* @param None
* @retval None
*/
void TIM2_IRQHandler(void)
{
/* 计数器溢出或者更新 */
if (__HAL_TIM_GET_FLAG(RC_TIMER_HANDLER, TIM_FLAG_UPDATE) != RESET)
{
if (__HAL_TIM_GET_IT_SOURCE(RC_TIMER_HANDLER, TIM_IT_UPDATE) != RESET)
{
__HAL_TIM_CLEAR_IT(RC_TIMER_HANDLER, TIM_IT_UPDATE);

// 处理
}
}

/* 输入捕获 1 */
if (__HAL_TIM_GET_FLAG(RC_TIMER_HANDLER, TIM_FLAG_CC1) != RESET)
{
if (__HAL_TIM_GET_IT_SOURCE(RC_TIMER_HANDLER, TIM_IT_CC1) != RESET)
{
__HAL_TIM_CLEAR_IT(RC_TIMER_HANDLER, TIM_IT_CC1);

/* Input capture event */
if(RC_TIM_IC_RISSING) // 如果是在等上升沿
{
__HAL_TIM_SET_COUNTER(RC_TIMER_HANDLER,0); // 计数器清0

// 设置通道进入 “下降沿捕获“ 模式
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_1,TIM_INPUTCHANNELPOLARITY_FALLING);

RC_TIM_IC_RISSING = 0; // 表示正在检测的为下降沿
}
else{ // 在等下降沿

// 读取数值
RC_ChannelsVal[0] = RC_TIMER_HANDLER->Instance->CCR1;

// 设置第一个通道为对齐通道,因此转为上升沿捕获
__HAL_TIM_SET_CAPTUREPOLARITY(RC_TIMER_HANDLER,TIM_CHANNEL_1,TIM_INPUTCHANNELPOLARITY_RISING);
RC_TIM_IC_RISSING = 1; // 表示正在检测的为上升沿
}
}
}

/* 输入捕获 2 */
if (__HAL_TIM_GET_FLAG(RC_TIMER_HANDLER, TIM_FLAG_CC2) != RESET)
{
if (__HAL_TIM_GET_IT_SOURCE(RC_TIMER_HANDLER, TIM_IT_CC2) != RESET)
{
__HAL_TIM_CLEAR_IT(RC_TIMER_HANDLER, TIM_IT_CC2);

/* Input capture event */
// 读取数值
RC_ChannelsVal[1] = RC_TIMER_HANDLER->Instance->CCR2;
}
}

/* 输入捕获 3 */
if (__HAL_TIM_GET_FLAG(RC_TIMER_HANDLER, TIM_FLAG_CC3) != RESET)
{
if (__HAL_TIM_GET_IT_SOURCE(RC_TIMER_HANDLER, TIM_IT_CC3) != RESET)
{
__HAL_TIM_CLEAR_IT(RC_TIMER_HANDLER, TIM_IT_CC3);

/* Input capture event */
// 读取数值
RC_ChannelsVal[2] = RC_TIMER_HANDLER->Instance->CCR3;
}
}

/* 输入捕获 4 */
if (__HAL_TIM_GET_FLAG(RC_TIMER_HANDLER, TIM_FLAG_CC4) != RESET)
{
if (__HAL_TIM_GET_IT_SOURCE(RC_TIMER_HANDLER, TIM_IT_CC4) != RESET)
{
__HAL_TIM_CLEAR_IT(RC_TIMER_HANDLER, TIM_IT_CC4);

/* Input capture event */
// 读取数值
RC_ChannelsVal[3] = RC_TIMER_HANDLER->Instance->CCR4;
}
}


}

读取PPM信号

读取PPM信号在驱动程序上使用的HAL库接口与读取PWM信号基本一致,但是为了提高笔者和读者的水平和见识,这里使用了STM的高级定时器进行示范。相比普通/通用定时器,高级定时器的中断请求更加细致,如下图所示,我们可以配置更新中断、捕获比较中断、通信中断、Break事件中断。笔者使用更新中断(update interrupt)和捕获比较中断(capture compare interrupt)。

CubeMX配置高级定时器中断

使用高级定时器读取PPM信号的代码如下所示,将解码程序分到了两个中断函数中实现:

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
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
#include "tim.h"
#include "main.h"

#define PPM_TIM_HANDLER (&htim1)
#define PPM_CHANNELS_NUM (8)
#define PPM_TIM_COUNT_FREQ (2400) // 单位kHz

// 接收的各通道占空比的最大值和最小值
#define PPM_DUTY_RANGE_MIN 500 // 单位 us
#define PPM_DUTY_RANGE_MAX 1500 // 单位us

// 帧尾 判断最小时间长度 的计数值!
#define PPM_FRAMEEND_COUNTVALUE (( 20 - 0.5*(PPM_CHANNELS_NUM+1) - (PPM_DUTY_RANGE_MAX/1000)*PPM_CHANNELS_NUM ) * PPM_TIM_COUNT_FREQ)

// 通道数据 的计数值范围
#define PPM_DUTY_MIN (PPM_DUTY_RANGE_MIN/1000 * PPM_TIM_COUNT_FREQ) // 最小
#define PPM_DUTY_MAX (PPM_DUTY_RANGE_MAX/1000 * PPM_TIM_COUNT_FREQ) // 最大


typedef enum{
WAIT_RAISSING,
WAIT_FALLING
} PPM_EDGE;

uint32_t PPM_Channel_Now = 0; // 当前操作的通道号。注:初始化为0,操作范围为1~PPM_CHANNELS_NUM
uint32_t PPM_Time_Cache = 1; // 用于计算通道时长的临时存储
PPM_EDGE PPM_timer_cap_edge = WAIT_RAISSING; // 标记当前准备检测的边沿

uint32_t PPM_error = 0; // 标记PPM解码失效
uint32_t PPM_resault[PPM_CHANNELS_NUM] = {0}; // 解码结果

/**
* @brief 定时器更新中断函数
* @note 把定时器的更新周期设置为严格大于50Hz的PPM帧频率,所以溢出表示当前帧错误
在 帧尾的下降沿 检测时,清空定时器计数值
* @param None
* @retval None
*/
void TIM1_UP_IRQHandler(void)
{
// TODO:这个if判断可以优化掉,在确保中断触发安全的情况下
if((__HAL_TIM_GET_FLAG(PPM_TIM_HANDLER, TIM_FLAG_UPDATE) != RESET) // 检查标志位
&&
(__HAL_TIM_GET_IT_SOURCE(PPM_TIM_HANDLER, TIM_IT_UPDATE) != RESET) // 检查中断开启
)
{
__HAL_TIM_CLEAR_IT(PPM_TIM_HANDLER, TIM_IT_UPDATE); // 清除中断标志位

/* 执行 定时器溢出(超时)、强制刷新 事件处理任务 */
PPM_error = 1; // 记录PPM为错误解码状态
}
}

/**
* @brief 定时器 输入捕获 中断
* @note 初始化时必须设置为输入捕获!这个接口本质上是捕获和比较一体中断
这里负责检测 各通道值、帧有效性 和 定时器清空
* @param None
* @retval None
*/
void TIM1_CC_IRQHandler(void)
{
// TODO:这个if判断可以优化掉,在确保中断触发安全的情况下
// 这三个 if逻辑 参考HAL库中的HAL_TIM_IRQHandler接口
if((__HAL_TIM_GET_FLAG(PPM_TIM_HANDLER, // 检查标志位
TIM_FLAG_CC1) != RESET)
&&
(__HAL_TIM_GET_IT_SOURCE(PPM_TIM_HANDLER, // 检查中断是否开启
TIM_IT_CC1)
!= RESET) // TIM_FLAG_CC1代表第1通道
)
{
__HAL_TIM_CLEAR_IT(PPM_TIM_HANDLER, TIM_IT_CC1); // 清除中断标志位

/* 执行 输入捕获 事件处理任务 */
if ((PPM_TIM_HANDLER->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) // CCMR1 是捕获/比较模式寄存器
{
if( PPM_timer_cap_edge == WAIT_RAISSING ) // 到达的是 上升沿
{
// 记录当前的计数值(起始时间)
PPM_Time_Cache = PPM_TIM_HANDLER->Instance->CCR1;
// 记录一下 当前进入的数据通道
PPM_Channel_Now = PPM_Channel_Now +1;

// 设置下一个为下降沿触发
__HAL_TIM_SET_CAPTUREPOLARITY(PPM_TIM_HANDLER, // timer handler
TIM_CHANNEL_1, // channel
TIM_INPUTCHANNELPOLARITY_FALLING); // polarity
PPM_timer_cap_edge = WAIT_FALLING;

}
else{ // 到达的是 下降沿
// 计算时长,放在这个位置能够保证测量指令延时等长(提高精度)
PPM_Time_Cache = PPM_TIM_HANDLER->Instance->CCR1 - PPM_Time_Cache;
// 设置下一个为上升沿触发
__HAL_TIM_SET_CAPTUREPOLARITY(PPM_TIM_HANDLER, // timer handler
TIM_CHANNEL_1, // channel
TIM_INPUTCHANNELPOLARITY_RISING); // polarity
PPM_timer_cap_edge = WAIT_RAISSING;

/* 开始鉴别数据通道 、 检测帧尾 、 判断帧有效 、 处理计数器 */
// 判断帧尾
if( PPM_Time_Cache > PPM_FRAMEEND_COUNTVALUE)
{
__HAL_TIM_SET_COUNTER(PPM_TIM_HANDLER, 0); // 清空计数器

if(PPM_Channel_Now == PPM_CHANNELS_NUM)
{ // 前面采集到的通道数量有效

PPM_error = 0; // 当前帧结果可用
// TODO:为了防止通信断开带来的异常,这里可加 用DMA打包一组数据 做隔离
}

PPM_Channel_Now = 0; // 复位通道标记

}
else
{ // 不是帧尾,可能是通道数据

// 判断通道操作数的有效性
if( PPM_Channel_Now <= PPM_CHANNELS_NUM && PPM_Channel_Now > 0)
{
// 存储这个通道的数据
PPM_resault[PPM_Channel_Now-1] = PPM_Time_Cache;
}
else{
PPM_error = 1; // 通道数量超标!
}
}
}
}
}
}

Donate
  • Copyright: Copyright is owned by the author. For commercial reprints, please contact the author for authorization. For non-commercial reprints, please indicate the source.
  • Copyrights © 2022-2023 RY.J
  • Visitors: | Views:

请我喝杯咖啡吧~

支付宝
微信