STM32 Futaba SBUS协议解析

1. S.BUS

1.1 协议介绍

在这里插入图片描述
S.BUS是FUTABA提出的舵机控制总线,全称Serial Bus,别名S-BUS或SBUS,也称 Futaba S.BUS
S.BUS是一个串行通信协议,也是一个数字串行通信接口(单线),适合与飞控连接。它可以连接很多设备,每个设备通过一个HUB与它相连,得到各自的控制信息。
S.BUS可以传输16个比例通道和2个数字(bool)通道。其硬件上基于RS232协议,采用TTL电平,但高位取反(负逻辑,低电平为“1”,高电平为“0”),通信波特率为100K(不兼容波特率115200)。

1.2 协议解析

  1. 通信接口:USART(TTL)
  2. 通信参数:1个起始位+8个数据位+偶校验位+2个停止位,波特率=100000bit/s,电平逻辑反转。
  3. 通信速率:每14ms(模拟模式)或7ms(高速模式)发送,即数据帧间隔为 11ms(模拟模式)或4ms(高速模式)。
  4. 数据帧格式:[1]
字节位byte1byte2-23byte24byte25
类型开始字节通道数据字节(含16个脉宽通道)标志位字节(含2个数字通道)结束字节
数据0x0F通道数据范围11Bits = [0,2047]2个数字通道位+2个状态位0x00

byte1:
startbyte = 0000 1111b (0x0F)

byte2-23:
databytes = 22bytes = 22 x 8Bits = 16 x 11Bits(CH1-16)
通道数据低位在前,高位在后,每个数据取11位,具体协议如下:
读取的databyte值:

byte234567etc
内容123456781234567812345678123456781234567812345678etc

转化后的通道值:

通道CH01CH02CH03CH04etc
内容67812345678345678123458123456781256781234567etc

byte24:

Bit76543210
含义数字通道CH17数字通道CH18帧丢失位故障保护激活位N/AN/AN/AN/A

byte25:
endbyte = 0000 0000b (0x00)

2. 硬件设计

2.1 硬件参数

  1. 主控芯片:STM32F103VET6
  2. 接收端口:USART2(带反相电路)
  3. S.BUS设备:walkera RX-SBUS[2](配DEVO 10遥控器)

2.2 反相电路

由于此芯片串口不带反相器,我们需要外部搭建反相电路。如果芯片串口内部带反相器,可以省略此步。反相电路设计如下图:
SBUS

  1. J1为4Pin排针,适配S.BUS接口,可5V输出为SBUS接收机供电。
  2. J1的Pin-4接S.BUS数据发送端,连接一个由NPN三极管构成的反相器,将反相后的信号送入芯片USART2的RXD引脚。

3.程序设计

3.1 数据接收

分析一:根据 1.2 的协议解析,开始字节(0x0F)和结束字节(0x00)都是数据字节中很容易出现的字节,所以不能完全作为数据帧接收开始和结束的标志。
分析二:每个数据帧之间的间隔至少4ms,则可以利用这个空闲时间来接收数据帧。(需要设计一个系统时钟)
分析三:STM32 USART或UART有空闲中断,即检测到总线空闲(无数据传输),就产生中断。
接收程序设计:综上,利用USART2接收中断(RXNE)来接收每个字节,利用USART2空闲中断(IDLE)来判断数据帧是否接收完毕。

USART2 初始化函数代码如下:

/**
  * @name   SBUS_Configuration
  * @brief  Configure SBUS(Usart2) clock, gpio and nvic:
  *         SBUS_RX  USART2_RX  PD6
  * @param  None
  * @retval None
  */
void SBUS_Configuration(void)
{
	GPIO_InitTypeDef  GPIO_InitStructure;
	USART_InitTypeDef USART_InitStructure;
	NVIC_InitTypeDef  NVIC_InitStructure;

	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_AFIO, ENABLE);
	RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2,ENABLE);
	
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
	GPIO_Init(GPIOD, &GPIO_InitStructure);
	
	GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);

	//  波特率100000 8个数据位 偶校验位 2个停止位
	USART_InitStructure.USART_BaudRate = 100000;
	USART_InitStructure.USART_WordLength = USART_WordLength_8b;
	USART_InitStructure.USART_StopBits = USART_StopBits_2;
	USART_InitStructure.USART_Parity = USART_Parity_Even;
	USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
	USART_InitStructure.USART_Mode = USART_Mode_Rx;

	USART_Init(USART2, &USART_InitStructure);

	NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
	NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 3;
	NVIC_InitStructure.NVIC_IRQChannelSubPriority = 3;
	NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
	NVIC_Init(&NVIC_InitStructure);

	USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
	USART_ITConfig(USART2, USART_IT_IDLE, ENABLE);

	USART_Cmd(USART2, ENABLE);
}

USART2 中断函数代码如下:


uint8_t USART2_RX_BUF[26];

/**
  * @name   USART2_IRQHandler
  * @brief  This function handles USART2 Handler
  * @param  None
  * @retval None
  */
void USART2_IRQHandler(void)
{
	uint8_t res;
	uint8_t clear = 0;
	static uint8_t Rx_Sta = 1;
	
	if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
	{
		res =USART2->DR;
		USART2_RX_BUF[Rx_Sta++] = res;
	}
	else if(USART_GetITStatus(USART2, USART_IT_IDLE) != RESET)
	{
		clear = USART2->SR;
		clear = USART2->DR;
		USART2_RX_BUF[0] = Rx_Sta - 1;
		Rx_Sta = 1;
	}
}
  1. USART2_RX_BUF为接收缓存区,定义为26个字节,第一个字节USART2_RX_BUF[0]为接收到的字节个数,后面为接收到的数据。
  2. USART2_RX_BUF[0]可以作为数据帧字节长度的判断。
  3. 中断服务函数具体解释请参考STM32 串口接收不定长字节数据

3.2 数据处理

直接上代码:

uint16_t CH[18];  // 通道值
uint8_t  rc_flag = 0;

void Sbus_Data_Count(uint8_t *buf)
{
	CH[ 0] = ((int16_t)buf[ 2] >> 0 | ((int16_t)buf[ 3] << 8 )) & 0x07FF;
	CH[ 1] = ((int16_t)buf[ 3] >> 3 | ((int16_t)buf[ 4] << 5 )) & 0x07FF;
	CH[ 2] = ((int16_t)buf[ 4] >> 6 | ((int16_t)buf[ 5] << 2 )  | (int16_t)buf[ 6] << 10 ) & 0x07FF;
	CH[ 3] = ((int16_t)buf[ 6] >> 1 | ((int16_t)buf[ 7] << 7 )) & 0x07FF;
	CH[ 4] = ((int16_t)buf[ 7] >> 4 | ((int16_t)buf[ 8] << 4 )) & 0x07FF;
	CH[ 5] = ((int16_t)buf[ 8] >> 7 | ((int16_t)buf[ 9] << 1 )  | (int16_t)buf[10] <<  9 ) & 0x07FF;
	CH[ 6] = ((int16_t)buf[10] >> 2 | ((int16_t)buf[11] << 6 )) & 0x07FF;
	CH[ 7] = ((int16_t)buf[11] >> 5 | ((int16_t)buf[12] << 3 )) & 0x07FF;
	
	CH[ 8] = ((int16_t)buf[13] << 0 | ((int16_t)buf[14] << 8 )) & 0x07FF;
	CH[ 9] = ((int16_t)buf[14] >> 3 | ((int16_t)buf[15] << 5 )) & 0x07FF;
	CH[10] = ((int16_t)buf[15] >> 6 | ((int16_t)buf[16] << 2 )  | (int16_t)buf[17] << 10 ) & 0x07FF;
	CH[11] = ((int16_t)buf[17] >> 1 | ((int16_t)buf[18] << 7 )) & 0x07FF;
	CH[12] = ((int16_t)buf[18] >> 4 | ((int16_t)buf[19] << 4 )) & 0x07FF;
	CH[13] = ((int16_t)buf[19] >> 7 | ((int16_t)buf[20] << 1 )  | (int16_t)buf[21] <<  9 ) & 0x07FF;
	CH[14] = ((int16_t)buf[21] >> 2 | ((int16_t)buf[22] << 6 )) & 0x07FF;
	CH[15] = ((int16_t)buf[22] >> 5 | ((int16_t)buf[23] << 3 )) & 0x07FF;
}

接收到的报文和解析出来的数据如下:
RX:0F E0 03 1F 58 C0 07 16 B0 80 05 2C 60 01 0B F8 C0 07 00 00 00 00 00 03 00
CH: 992 992 352 992 352 352 352 352 352 352 992 992 000 000 000 000
RX:0F 60 01 0B 58 C0 07 66 30 83 19 7C 60 06 1F F8 C0 07 00 00 00 00 00 03 00
CH: 352 352 352 992 1632 1632 1632 992 1632 992 992 992 000 000 000 000

  1. 接收的byte24数据并非和协议解析中的一样,无论断开遥控器还是连接遥控器,读取的值都是0x03。
  2. 接收机只支持12个通道,所以通道13-16没有值。
  3. 读取的通道值中间值为992,最大值为1632,最小值为352。

4. 最后

    本教程由 Brendon Tan 原创发布,版权所有。该文档仅供个人学习交流使用,不得用于其他用途,禁止商用, 转载或公开使用请联系作者授权。
    此教程由本人独立整理,如有不当之处,欢迎指正。


  1. 该协议解析参考Futaba S-BUS controlled by mbed[Uwe Gartmann,Created 07 Mar 2012,Last updated 09 Mar 2012] ↩︎

  2. 某猫链接walkera RX-SBUS[Copied May 2012] ↩︎

  • 51
    点赞
  • 259
    收藏
    觉得还不错? 一键收藏
  • 16
    评论
SBUS是一种串行总线通信协议,用于无人机和遥控器之间的数字信号传输。SBUSFutaba公司开发的一种数字通信协议,可以通过单根信号线传输16个通道的数据,同时还可以传输其他的控制信息。 STM32是一种单片机,可以通过编程实现对SBUS信号的解析。以下是STM32解析SBUS的步骤: 1. 配置串口 首先需要选择一个可用的串口,并将其配置为接收模式。在STM32中,可以使用USART或UART模块实现串口通信。需要设置串口的波特率、数据位数、停止位数和校验位等参数。 2. 接收数据 配置好串口后,可以通过读取串口接收缓冲区中的数据来接收SBUS信号。SBUS信号以帧的形式传输,每一帧的长度为25个字节。读取串口缓冲区中的数据,并判断接收到的数据是否为完整的一帧,如果是,则进行下一步处理。 3. 解析数据 接收到完整的一帧数据后,需要对其中的数据进行解析SBUS信号的第一字节为0x0F,用于标识这是一帧SBUS数据。接下来的16个字节分别对应16个通道的数据,每个通道的数据占用11位,最高位为标识位。还有两个字节分别用于标识数字信号的状态和传输错误的计数。 4. 处理数据 解析出每个通道的数据后,可以根据需要进行相应的处理,比如将数据转换为实际控制量,或者存储到数组中以备后续使用。 5. 发送数据 如果需要将处理后的数据发送到其他设备,则需要将数据通过串口发送出去。发送数据的方法与接收数据的方法类似,只是需要将数据写入串口发送缓冲区中。 以上就是STM32解析SBUS信号的基本步骤,需要对串口通信和数据解析有一定的了解。

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 16
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值