STM32、GD32 ppm协议解析源码分享

一、 什么是ppm协议
PPM(Pulse Position Modulation,脉冲位置调制)是无人机遥控系统中常用的信号传输协议,主要用于遥控器与接收机之间的通信。其核心原理是通过脉冲在时间轴上的相对位置来表示不同通道的控制信号。
1、协议结构
典型的PPM信号帧由以下部分组成:
- 同步脉冲:帧起始标志,宽度固定(通常≥2ms)
- 通道脉冲序列 :连续的多通道数据脉冲
- 每个脉冲代表一个通道的控制量
- 脉冲宽度范围:1.0ms~2.0ms(中立位1.5ms)
- 脉冲间隔:约300-500μs
完整帧周期公式:
T f r a m e = T s y n c + ∑ i = 1 n ( T p u l s e i + T i n t e r v a l ) T_{frame} = T_{sync} + \sum_{i=1}^{n} (T_{pulse_i} + T_{interval}) Tframe=Tsync+i=1∑n(Tpulsei+Tinterval)
其中 n n n为通道数,常见配置为8通道。
帧结构格式:
c
[Channel 1 Pulse] + [间隔] + [Channel 2 Pulse] + [间隔] + ... + [Channel N Pulse] + [同步间隔]

2、信号特征
- 时间分辨率:脉冲宽度以微秒级精度控制,典型分辨率10μs
- 信号编码 :
- 1.0ms脉宽:通道最小值(如方向舵左满舵)
- 1.5ms脉宽:通道中立位
- 2.0ms脉宽:通道最大值(如油门全开)
- 抗干扰机制 :
- 通过脉冲位置而非幅度传递信息
- 受噪声影响小于PWM协议
3、协议优势
- 多路复用:单线传输多通道信号(标准8通道)
- 带宽效率:比PWM协议节省约75%的带宽
- 兼容性:支持模拟/数字接收机
- 实时性:典型帧率50Hz(周期20ms)
4、关键参数表

5、与其他协议对比
| 特性 | PPM | PWM | SBUS |
|---|---|---|---|
| 传输方式 | 串行 | 并行 | 串行 |
| 通道数/线 | 8/1 | 1/1 | 16/1 |
| 典型延迟 | 20ms | 实时 | 9ms |
| 抗噪能力 | 中等 | 低 | 高 |
注意 :现代无人机系统常采用PPM与SBUS混合架构,其中PPM用于传统设备兼容,SBUS用于高速数字传输。实际应用中需注意接收机支持的协议类型及信号极性配置。调试时建议使用示波器观察脉冲波形,确保脉宽在 [ 1.0 , 2.0 ] [1.0, 2.0] [1.0,2.0]ms有效范围内。
二、STM32使用定时器脉冲捕获解析源码分享
ppm.h
c
/*************************************************
* @copyright:
* @author:Xupeng
* @date:2022-11-03
* @description:
**************************************************/
#ifndef _PPM_H_
#define _PPM_H_
#include "main_value.h"
#define PPM_CH_MAX 16
extern rt_uint16_t ppmVal[PPM_CH_MAX];
/*************************************************
* @function:rt_inline rt_uint16_t get_ch_val(const rt_uint8_t ch)
* @description: 获取通道值
* @calls:
* @input:
* @return:
* @others:
*************************************************/
rt_inline rt_uint16_t get_ppm_ch_val(const rt_uint8_t ch)
{
if(ch>=PPM_CH_MAX)
{
return 0;
}
return ppmVal[ch];
}
#endif
ppm.c
c
/*************************************************
* @copyright:
* @author:Xupeng
* @date:2022-11-03
* @description:
**************************************************/
#include "ppm.h"
#define DBG_TAG "ppm"
#define DBG_LVL DBG_LOG
#include <rtdbg.h>
TIM_HandleTypeDef TIM2_Handler; //定时器2句柄
/*************************************************
* @function:int ppm_init()
* @description: 初始化PPM
* @calls:
* @input:
* @return:
* @others:
*************************************************/
int ppm_init()
{
TIM_IC_InitTypeDef TIM2_CH1Config;
TIM2_Handler.Instance=TIM2; //通用定时器2
TIM2_Handler.Init.Prescaler=71; //分频系数
TIM2_Handler.Init.CounterMode=TIM_COUNTERMODE_UP; //向上计数器
TIM2_Handler.Init.Period=0xFFFF; //自动装载值
TIM2_Handler.Init.ClockDivision=TIM_CLOCKDIVISION_DIV1;//时钟分频因子
TIM2_Handler.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;//使能自动重载
HAL_TIM_IC_Init(&TIM2_Handler); //初始化输入捕获时基参数
TIM2_CH1Config.ICPolarity=TIM_ICPOLARITY_FALLING; //下升沿捕获
TIM2_CH1Config.ICSelection=TIM_ICSELECTION_DIRECTTI;//映射到TI1上
TIM2_CH1Config.ICPrescaler=TIM_ICPSC_DIV1; //配置输入分频,不分频
TIM2_CH1Config.ICFilter=0; //配置输入滤波器,不滤波
HAL_TIM_IC_ConfigChannel(&TIM2_Handler,&TIM2_CH1Config,TIM_CHANNEL_4);//配置TIM2通道4
HAL_TIM_IC_Start_IT(&TIM2_Handler,TIM_CHANNEL_4); //开启TIM2的捕获通道4,并且开启捕获中断
__HAL_TIM_ENABLE_IT(&TIM2_Handler,TIM_IT_UPDATE); //使能更新中断
HAL_NVIC_SetPriority(TIM2_IRQn,2,0); //设置中断优先级,抢占优先级2,子优先级0
HAL_NVIC_EnableIRQ(TIM2_IRQn);
return RT_EOK;
}
INIT_PREV_EXPORT(ppm_init);
//捕获状态
//[7]:0,没有成功的捕获;1,成功捕获到一次.
//[6]:0,还没捕获到低电平;1,已经捕获到低电平了.
//[5:0]:捕获低电平后溢出的次数
static uint8_t captureState=0; //输入捕获状态
static uint16_t captureValue; //输入捕获值(TIM5是16位)
static bool captureIsOk;
static rt_uint8_t captureCnt=0;
uint16_t ppmVal[PPM_CH_MAX];
//定时器2中断服务函数
void TIM2_IRQHandler(void)
{
HAL_TIM_IRQHandler(&TIM2_Handler); //定时器共用处理函数
}
//定时器更新中断(计数溢出)中断处理回调函数, 该函数在HAL_TIM_IRQHandler中会被调用
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)//更新中断(溢出)发生时执行
{
if((captureState&0X80)==0) //还未成功捕获
{
if(captureState&0X40) //已经捕获到高电平了
{
if((captureState&0X3F)==0X3F) //高电平太长了
{
captureState|=0X80; //标记成功捕获了一次
captureValue=0XFFFF;
}else captureState++;
}
}
}
//定时器输入捕获中断处理回调函数,该函数在HAL_TIM_IRQHandler中会被调用
void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim)//捕获中断发生时执行
{
if((captureState&0X80)==0) //还未成功捕获
{
if(captureState&0X40) //捕获到一个上升沿
{
captureState|=0X80; //标记成功捕获到一次高电平脉宽
captureValue=HAL_TIM_ReadCapturedValue(&TIM2_Handler,TIM_CHANNEL_4);//获取当前的捕获值.
captureState = 0;
if(captureValue >= 10000) //捕获到头部信息
{
captureIsOk = true;
captureCnt = 0;
}
else if(captureIsOk)
{
if(captureCnt <PPM_CH_MAX)
ppmVal[captureCnt++] = captureValue;
if(captureCnt >= PPM_CH_MAX)
{
captureIsOk = false;
captureCnt = 0;
}
}
TIM_RESET_CAPTUREPOLARITY(&TIM2_Handler,TIM_CHANNEL_4); //一定要先清除原来的设置!!
TIM_SET_CAPTUREPOLARITY(&TIM2_Handler,TIM_CHANNEL_4,TIM_ICPOLARITY_FALLING);//配置TIM2通道4下降沿捕获
}
else //还未开始,第一次捕获上升沿
{
captureState=0; //清空
captureValue=0;
captureState|=0X40; //标记捕获到了上升沿
__HAL_TIM_DISABLE(&TIM2_Handler); //关闭定时器2
__HAL_TIM_SET_COUNTER(&TIM2_Handler,0);
TIM_RESET_CAPTUREPOLARITY(&TIM2_Handler,TIM_CHANNEL_4); //一定要先清除原来的设置!!
TIM_SET_CAPTUREPOLARITY(&TIM2_Handler,TIM_CHANNEL_4,TIM_ICPOLARITY_RISING);//定时器2通道4设置为上升沿捕获
__HAL_TIM_ENABLE(&TIM2_Handler); //使能定时器2
}
}
}
/*************************************************
* @function:static void show_ppm()
* @description: 打印输出ppm信号
* @calls:
* @input:
* @return:
* @others:
*************************************************/
static void show_ppm()
{
for(uint8_t i=0;i<PPM_CH_MAX;i++)
{
rt_kprintf("ch%d:%d ",i,ppmVal[i]);
}
rt_kprintf("\r\n");
}
MSH_CMD_EXPORT(show_ppm,show ppm value);
