老规矩,先上效果,这是基于STM32F103C8T6解码出来的效果,遥感对应的是每个通道的值,一个遥感相当于对应4个数据通道,两个就是对应8个数据通道,而按钮则是最后一个通道,其它的通道是作为整个协议的备用通道,不同的遥控,实际能用的通道数不一样。
说明:部分程序和资料整理于网络平台,由于时间久远,找不到原始发文地址,这里向贡献这些资料的大佬们致敬 。
SBUS协议:
SBUS是FUTABA提出的舵机控制总线,全称Serial Bus,别名S-BUS或SBUS,也称 Futaba SBUS。它就是基于串口反电平逻辑的传输方式。
通信接口:USART(TTL)
通信参数设置:100Kps, 8E2(8位数据位,偶校验,2位停止位,无流控)
每帧25个字节,帧格式如下
[Start Byte] [Data0] [Data1] …. [Data21] [Flags][End Byte]
Start Byte= 0x0F,中间22个字节为16个通道的数据,每个通道用 11 bit表示,范围是0-2047。
End Byte:根据SBUS协议版本不同而不同。
因为遥控接收模块出来的电平信号跟普通串口逻辑是反逻辑,所以还需要下面这个电平转换电路
遥控接收模块反逻辑电平电路
我手里头的这款遥控型号:风迎M11,2017年底购买的,价格接近上千大洋,现在价格要好很多了,不到1/3之一的价格就可以拿到。传输距离一般有6公里左右,搭配远距离图传模块做一些远程遥控操作用。当时为了解码sbus过来的数据在网上找了不少资料,但是发现arduino的能用,STM32的没有一个完整的程序,所以只能参考sbus协议的代码,然后再结合arduino能工作的程序,分析串口传输过来的数据,一个一个去调整串口的配置。
下图是该遥控模块的接收模块,双天线和数据通道冗余,确保接收数据的可靠。
arduino接收程序
我们先使用arduino看下模块以及我们对协议的理解正确与否,验证没有问题后,稍后我们在移植到STM32上面去。
使用的是MEGA2560板子,反电平电路参考上面的电路连接,SBUS接收数据端口是19号引脚,也就是该板子的串口1,arduino软件安装完后自带的串口库,如果使用其它的arduino板子,请参考网上其它教程。
arduino串口参数设置:Serial1.begin(100000,SERIAL_8E2);
这部分代码是将接收到的串口数据进行解码,因为每个通道是11位数据,所以需要进行数据合成。
void update_channels(void)
{
channels[0] = ((sbus_data[1]|sbus_data[2]<< 8) & 0x07FF);
channels[1] = ((sbus_data[2]>>3|sbus_data[3]<<5) & 0x07FF);
channels[2] = ((sbus_data[3]>>6|sbus_data[4]<<2|sbus_data[5]<<10) & 0x07FF);
channels[3] = ((sbus_data[5]>>1|sbus_data[6]<<7) & 0x07FF);
channels[4] = ((sbus_data[6]>>4|sbus_data[7]<<4) & 0x07FF);
channels[5] = ((sbus_data[7]>>7|sbus_data[8]<<1|sbus_data[9]<<9) & 0x07FF);
channels[6] = ((sbus_data[9]>>2|sbus_data[10]<<6) & 0x07FF);
channels[7] = ((sbus_data[10]>>5|sbus_data[11]<<3) & 0x07FF); // & the other 8 + 2 channels if you need them
#ifdef ALL_CHANNELS
channels[8] = ((sbus_data[12]|sbus_data[13]<< 8) & 0x07FF);
channels[9] = ((sbus_data[13]>>3|sbus_data[14]<<5) & 0x07FF);
channels[10] = ((sbus_data[14]>>6|sbus_data[15]<<2|sbus_data[16]<<10) & 0x07FF);
channels[11] = ((sbus_data[16]>>1|sbus_data[17]<<7) & 0x07FF);
channels[12] = ((sbus_data[17]>>4|sbus_data[18]<<4) & 0x07FF);
channels[13] = ((sbus_data[18]>>7|sbus_data[19]<<1|sbus_data[20]<<9) & 0x07FF);
channels[14] = ((sbus_data[20]>>2|sbus_data[21]<<6) & 0x07FF);
channels[15] = ((sbus_data[21]>>5|sbus_data[22]<<3) & 0x07FF);
#endif
// Failsafe
failsafe_status = SBUS_SIGNAL_OK;
if (sbus_data[23] & (1<<2))
{
failsafe_status = SBUS_SIGNAL_LOST;
}
if (sbus_data[23] & (1<<3))
{
failsafe_status = SBUS_SIGNAL_FAILSAFE;
}
}
下面这部分代码是按照sbus的通信协议接收数据并缓存到缓冲区,判断接收到的数据是0x0f,则开始缓存数据,一直到缓冲完所有通道才结束,这里没有进行结尾检测影响不大,因为不同的接收模块结尾不一样,具体项目应用还请加上数据结尾检测。
void feedLine( void )
{
if( Serial1.available()>24 )
{
while(Serial1.available()>0)
{
inData = Serial1.read();
switch (feedState)
{
case 0:
if(inData != 0x0f)
{
while( Serial1.available()>0 )
{
inData = Serial1.read();
}
return;
}
else
{
bufferIndex = 0;
inBuffer[bufferIndex] = inData;
inBuffer[24] = 0xff;
feedState = 1;
}
break;
case 1:
bufferIndex ++;
inBuffer[bufferIndex] = inData;
if (bufferIndex < 24 && Serial1.available() == 0)
{
feedState = 0;
}
if (bufferIndex == 24)
{
feedState = 0;
if (inBuffer[0]==0x0f && inBuffer[24] == 0x00)
{
memcpy(sbus_data,inBuffer,25);
toChannels = 1;
}
}
break;
}
// if (inData == 0x0f)
// {
// bufferIndex = 0;
// inBuffer[bufferIndex] = inData;
// inBuffer[24] = 0xff;
// }
// else
// {
// bufferIndex ++;
// inBuffer[bufferIndex] = inData;
// }
// if(inBuffer[0]==0x0f & inBuffer[24] == 0x00)
// {
// memcpy(sbus_data,inBuffer,25);
// toChannels = 1;
// return;
// }
}
}
}
完整程序代码:
/*
Multiple Serial test
Receives from the main serial port, sends to the others.
Receives from serial port 1, sends to the main serial (Serial 0).
This example works only with boards with more than one serial like Arduino Mega, Due, Zero etc.
The circuit:
- any serial device attached to Serial port 1
- Serial Monitor open on Serial port 0
created 30 Dec 2008
modified 20 May 2012
by Tom Igoe & Jed Roach
modified 27 Nov 2015
by Arturo Guadalupi
This example code is in the public domain.
*/
#define SBUS_SIGNAL_OK 0x00
#define SBUS_SIGNAL_LOST 0x01
#define SBUS_SIGNAL_FAILSAFE 0x03
#define ALL_CHANNELS
uint8_t sbus_data[25] = {
0x00,0x00,0x00,0x20,0x00,0xff,0x07,0x40,0x00,0x02,0x10,0x80,0x2c,0x64,0x21,0x0b,0x59,0x08,0x40,0x00,0x02,0x10,0x80,0x00,0x00};
int16_t channels[18] = {
1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,0,0};
相关文章