Skip to content

Commit dcb7e74

Browse files
committed
Add more info about S.Bus and add packet decoder in Python
1 parent efd48e4 commit dcb7e74

3 files changed

+157
-17
lines changed

doc/i-bus_decoder_for_saleae_format.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#!/usr/bin/env python3
22

33
'''
4-
Progran that decodes and exported binary file from a capture with the Saleae
4+
Progran that decodes an exported binary file from a capture with the Saleae
55
logic analyzer.
66
77
Use "logic" from Salaea and export only the serial port channel into .bin

doc/inverted-sbus-protocol.md doc/sbus-protocol.md

+30-16
Original file line numberDiff line numberDiff line change
@@ -1,28 +1,24 @@
1-
# Inverted SBUS
1+
# S.Bus
22

33
S.Bus is a proprietary protocol developed by Futaba.
44
(Dead link: https://www.futabarc.com/sbus/index.html)
55

66
S.Bus2 is an extension that supports telemetry.
77

8-
Some receivers on the market now output an "inverted SBUS" signal.
8+
Some receivers on the market output an "inverted SBUS" signal. However, it seems that those receivers are not suitable for RC cars as they only have S.Bus / Inverted S.Bus output and no traditional PWM servo output.
99

10+
For the light controller it only makes sense to implement standard S.Bus, which is supported by Futaba and FrSky receivers.
1011

11-
## Inverted SBUS, as LANE Boys RC understands it
1212

13-
(Source: https://quadmeup.com/generate-s-bus-with-arduino-in-a-simple-way/)
14-
15-
The original S.Bus system uses an inverted UART signal (idle=low).
16-
The LPC812 and LPC832 do not support inverted UART, hence S.Bus can not be supported.
13+
## S.Bus, as LANE Boys RC understands it
1714

18-
However, "inverted SBUS" as output by some receivers uses the traditional UART polarity (idle=high), which can be used with the Light Controller.
19-
20-
The Baudrate is 100000. This is a non-standard Baudrate, which is not supported by the WebUSB programmer or the CH340G chip in the USB-to-Serial dongle. This means that the test function can not be used with "inverted SBUS".
15+
(Source: https://quadmeup.com/generate-s-bus-with-arduino-in-a-simple-way/)
2116

2217
* The serial port uses 100000 BAUD, 8 bits, even parity, 2 stop bits (!)
2318
* There is also a fast mode that uses 200000 BAUD, 8 bits, even parity, 2 stop bits (The light controller will not support this mode)
2419
* Packets containing servo information are sent at regular intervals of about 10-20ms (FrSky: 6ms Futaba/FrSky fast mode: 3ms)
2520
* When the connection with the Transmitter is broken, the receiver sets a FAILSAFE flag in the packet
21+
2622
* A packet is always 25 bytes long and contains the following information:
2723
* 1 byte HEADER
2824
* 22 bytes payload for 16 servo channels (11 bits per channel)
@@ -36,10 +32,28 @@ The Baudrate is 100000. This is a non-standard Baudrate, which is not supported
3632
* The HEADER byte is 0x0f
3733
* The FOOTER byte is 0x00
3834
* The FOOTER2 byte is 0x4 or 0x8 (contents of the upper nibble is ignored, it contains a slot number for telemetry use)
35+
* FOOTER is used in the original S.Bus protocol, while S.Bus2 changed to FOOTER2.
36+
* The upper nibble of FOOTER2 contains a slot number used for telemetry (see _Example packets_ below).
37+
3938
* The servo information is 11 bits per channel
4039
Channel values describe the servo pulse duration from 0..2047
4140

42-
* FOOTER may have been used in S.Bus, while later S.Bus2 changed to FOOTER2. The upper nibble of FOOTER2 seems to contain a sequence number (see _Example packets_ below).
41+
42+
## Impact of S.Bus support on the light controller
43+
44+
The S.Bus system uses an inverted UART signal (idle=low).
45+
46+
The LPC812 and LPC832 do not support inverted UART, hence S.Bus can not be supported without additional hardware.
47+
(It would be possible to support "inverted SBUS" (idle=high), but as stated above this may not be useful due to lack of receiver support).
48+
49+
For the Mk4P and Mk4S PCB we could integrate an inverter (1 MosFET, 1 Resistor) and route the inverted UART signal to an unused pin (e.g. GPIO10). The software could then route the UART RX line to GPIO10 if S.Bus is configured.
50+
51+
For the user this means that only newer revisions of the Mk4P light controller (Rev3) can support S.Bus.
52+
53+
54+
The Baudrate used by S.Bus is 100000. This is a non-standard Baudrate, but it should be possible with the LPC8xx microcontroller. However, in case a Slave is used the Baudrate of the Slave would also have to be 100000 Baud.
55+
56+
The WebUSB programmer and the CH340G chip used in the USB-to-Serial dongle do neither support 100000 Baud nor the inverted UART signal. It will therefore not possible to implement the "Testing" function in the Configurator for S.Bus.
4357

4458

4559
## Example packets
@@ -86,15 +100,15 @@ S-Bus output from FrSky TFR8SB receiver in FASST-MULTI mode:
86100

87101
* There is conflicting info about the meaning of the servo channel value range.
88102

89-
Is 1023 center? https://github.com/mikeshub/FUTABA_SBUS/blob/master/FUTABA_SBUS/FUTABA_SBUS.cpp
103+
Is 1024 center? https://github.com/mikeshub/FUTABA_SBUS/blob/master/FUTABA_SBUS/FUTABA_SBUS.cpp
90104
Or 992? https://quadmeup.com/generate-s-bus-with-arduino-in-a-simple-way/
91105

92106
BetaFlight uses the following formula to convert S.Bus servo information to microseconds (servo pulse):
93107
servo_us = (5 * sbus / 8) + 880;
94108

95-
Using this formula would make S.Bus value 1023 translate to 1520 us, which is exactly what Futaba traditionally used as center value for servos.
109+
Using this formula would make S.Bus value 1024 translate to 1520 us, which is exactly what Futaba traditionally used as center value for servos.
96110

97-
But how does FrSky map the SBUS values? Most likely they are using 1500 as center
111+
But how does FrSky map the S.Bus values? Most likely they are using 1500 as center, hence the 992 value.
98112

99113

100114
* What are the possible values for FOOTER2?
@@ -105,7 +119,7 @@ https://github.com/cleanflight/cleanflight/issues/590#issuecomment-101706023
105119

106120
* Frame detection
107121

108-
Most libraries seem to use HEADER and FOOTER/FOOTER2 to detect frames. Those libraries will not work wiht the FASSTest 12CH mode, which uses 0x08 last byte.
122+
Most libraries seem to use HEADER and FOOTER/FOOTER2 to detect frames. Those libraries will not work with the FASSTest 12CH mode, which uses 0x08 last byte.
109123

110-
BetaFlight uses the maximum frame time of 3000 us + 500 us margin. If the time since the last byte is more than this 3500us then a start of frame is assumed. This will only work with interrupt-driven UART receive.
124+
BetaFlight uses the maximum frame time of 3000 us + 500 us margin. If the time since the last byte is more than 3500us then a start of frame is assumed. This will only work with interrupt-driven UART receive.
111125
(Source: https://github.com/betaflight/betaflight/blob/master/src/main/rx/sbus.c)

doc/sbus_packet_decoder.py

+126
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,126 @@
1+
#!/usr/bin/env python3
2+
3+
'''
4+
Progran that decodes S.Bus packets.
5+
6+
python sbus_decoder.py
7+
8+
'''
9+
10+
import array
11+
import struct
12+
import sys
13+
from collections import namedtuple
14+
15+
PACKET_LENGTH = 25
16+
HEADER = 0x0f
17+
FOOTER = 0x00
18+
FOOTER2 = 0x4
19+
FOOTER2b = 0x8
20+
21+
EXAMPLE_SBUS_PACKETS = [
22+
0x0f, 0x01, 0x04, 0x20, 0x00, 0xff, 0x07, 0x40, 0x00, 0x02, 0x10, 0x80, 0x2c, 0x64, 0x21, 0x0b, 0x59, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x00,
23+
0x0f, 0x5c, 0x91, 0x26, 0x37, 0x7f, 0xa4, 0x6a, 0xab, 0x00, 0x10, 0x80, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x70, 0x00, 0x02, 0x10, 0x80, 0x0c, 0x00,
24+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x09, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x04,
25+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x09, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x14,
26+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x09, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x24,
27+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x09, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x34,
28+
0x0f, 0x00, 0x1c, 0x20, 0x5b, 0x09, 0x08, 0xc0, 0x13, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x08,
29+
0x0f, 0x00, 0x1c, 0x21, 0x59, 0x09, 0x08, 0xc0, 0x13, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x08,
30+
0x0f, 0x00, 0x1c, 0x21, 0x5b, 0x09, 0x08, 0xc0, 0x13, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x08,
31+
0x0f, 0x00, 0x1c, 0x21, 0x5b, 0x09, 0x08, 0xc0, 0x13, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x08,
32+
0x0f, 0x00, 0x1c, 0x21, 0x59, 0x09, 0x08, 0xc0, 0x13, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x00, 0x01, 0x08, 0x40, 0x00, 0x02, 0x10, 0x80, 0x00, 0x08,
33+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x0b, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x00,
34+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x0b, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x00,
35+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x0b, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x00,
36+
0x0f, 0x04, 0x1c, 0xa1, 0x43, 0x0b, 0x48, 0x40, 0x04, 0x7a, 0x10, 0x2c, 0x00, 0x04, 0x20, 0x58, 0xc0, 0x13, 0x07, 0x38, 0x00, 0x10, 0x80, 0x00, 0x00,
37+
]
38+
39+
40+
def is_header(data):
41+
if data == HEADER:
42+
return True
43+
44+
return False
45+
46+
47+
def is_footer(data):
48+
if data == FOOTER:
49+
return True
50+
51+
if (data & 0x0f) == FOOTER2:
52+
return True
53+
54+
if (data & 0x0f) == FOOTER2b:
55+
return True
56+
57+
return False
58+
59+
60+
def decode_sbus_packet(packet):
61+
CH17_MASK = 0x01;
62+
CH18_MASK = 0x02;
63+
LOST_FRAME_MASK = 0x04;
64+
FAILSAFE_MASK = 0x08;
65+
66+
channels = [0] * 18
67+
channels[0] = (packet[1] | packet[2] << 8 & 0x07FF);
68+
channels[1] = (packet[2] >> 3 | packet[3] << 5 & 0x07FF);
69+
channels[2] = (packet[3] >> 6 | packet[4] << 2 | packet[5] << 10 & 0x07FF);
70+
channels[3] = (packet[5] >> 1 | packet[6] << 7 & 0x07FF);
71+
channels[4] = (packet[6] >> 4 | packet[7] << 4 & 0x07FF);
72+
channels[5] = (packet[7] >> 7 | packet[8] << 1 | packet[9] << 9 & 0x07FF);
73+
channels[6] = (packet[9] >> 2 | packet[10] << 6 & 0x07FF);
74+
channels[7] = (packet[10] >> 5 | packet[11] << 3 & 0x07FF);
75+
channels[8] = (packet[12] | packet[13] << 8 & 0x07FF);
76+
channels[9] = (packet[13] >> 3 | packet[14] << 5 & 0x07FF);
77+
channels[10] = (packet[14] >> 6 | packet[15] << 2 | packet[16] << 10 & 0x07FF);
78+
channels[11] = (packet[16] >> 1 | packet[17] << 7 & 0x07FF);
79+
channels[12] = (packet[17] >> 4 | packet[18] << 4 & 0x07FF);
80+
channels[13] = (packet[18] >> 7 | packet[19] << 1 | packet[20] << 9 & 0x07FF);
81+
channels[14] = (packet[20] >> 2 | packet[21] << 6 & 0x07FF);
82+
channels[15] = (packet[21] >> 5 | packet[22] << 3 & 0x07FF);
83+
channels[16] = packet[23] & CH17_MASK;
84+
channels[17] = packet[23] & CH18_MASK;
85+
lost_frame_ = packet[23] & LOST_FRAME_MASK;
86+
failsafe_ = packet[23] & FAILSAFE_MASK;
87+
88+
for index, channel in enumerate(channels):
89+
print(f'ch{index+1}: {channel} ', end='')
90+
91+
print()
92+
93+
def parse_sbus(data):
94+
WAIT_FOR_HEADER = 0
95+
# State values 1..23 are for receiving the packet bytes
96+
WAIT_FOR_FOOTER = PACKET_LENGTH - 1
97+
98+
state = WAIT_FOR_HEADER
99+
previous_byte = FOOTER
100+
packet = [FOOTER] * PACKET_LENGTH
101+
102+
for byte in data:
103+
packet.pop(0)
104+
packet.append(byte)
105+
106+
if state == WAIT_FOR_HEADER:
107+
if is_header(byte) and is_footer(previous_byte):
108+
state = 1
109+
110+
elif state > WAIT_FOR_HEADER and state < WAIT_FOR_FOOTER:
111+
state = state + 1
112+
113+
elif state == WAIT_FOR_FOOTER:
114+
if is_footer(byte):
115+
decode_sbus_packet(packet)
116+
else:
117+
print(f'Footer has unexpected value 0x{byte:02x}, discarding packet')
118+
state = WAIT_FOR_HEADER
119+
120+
previous_byte = byte
121+
122+
123+
124+
125+
if __name__ == '__main__':
126+
parse_sbus(EXAMPLE_SBUS_PACKETS)

0 commit comments

Comments
 (0)