-
Notifications
You must be signed in to change notification settings - Fork 15
/
Copy pathsbus_packet_decoder.py
executable file
·135 lines (103 loc) · 5.48 KB
/
sbus_packet_decoder.py
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
135
#!/usr/bin/env python3
'''
Progran that decodes S.Bus packets.
python sbus_decoder.py
'''
import array
import struct
import sys
from collections import namedtuple
PACKET_LENGTH = 25
HEADER = 0x0f
FOOTER = 0x00
FOOTER2 = 0x4
FOOTER2b = 0x8
EXAMPLE_SBUS_PACKETS = [
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
# Packet from our sbus-simulator
15, 48, 5, 31, 192, 129, 132, 73, 240, 129, 15, 124, 224, 3, 31, 248, 192, 7, 62, 240, 129, 15, 124, 0, 0
]
def is_header(data):
if data == HEADER:
return True
return False
def is_footer(data):
if data == FOOTER:
return True
if (data & 0x0f) == FOOTER2:
return True
if (data & 0x0f) == FOOTER2b:
return True
return False
def sbus_to_servo_us(value):
return (5 * value // 8) + 880
def decode_sbus_packet(packet):
CH17_MASK = 0x01;
CH18_MASK = 0x02;
LOST_FRAME_MASK = 0x04;
FAILSAFE_MASK = 0x08;
channels = [0] * 18
channels[0] = (packet[1] | packet[2] << 8 & 0x07FF);
channels[1] = (packet[2] >> 3 | packet[3] << 5 & 0x07FF);
channels[2] = (packet[3] >> 6 | packet[4] << 2 | packet[5] << 10 & 0x07FF);
channels[3] = (packet[5] >> 1 | packet[6] << 7 & 0x07FF);
channels[4] = (packet[6] >> 4 | packet[7] << 4 & 0x07FF);
channels[5] = (packet[7] >> 7 | packet[8] << 1 | packet[9] << 9 & 0x07FF);
channels[6] = (packet[9] >> 2 | packet[10] << 6 & 0x07FF);
channels[7] = (packet[10] >> 5 | packet[11] << 3 & 0x07FF);
channels[8] = (packet[12] | packet[13] << 8 & 0x07FF);
channels[9] = (packet[13] >> 3 | packet[14] << 5 & 0x07FF);
channels[10] = (packet[14] >> 6 | packet[15] << 2 | packet[16] << 10 & 0x07FF);
channels[11] = (packet[16] >> 1 | packet[17] << 7 & 0x07FF);
channels[12] = (packet[17] >> 4 | packet[18] << 4 & 0x07FF);
channels[13] = (packet[18] >> 7 | packet[19] << 1 | packet[20] << 9 & 0x07FF);
channels[14] = (packet[20] >> 2 | packet[21] << 6 & 0x07FF);
channels[15] = (packet[21] >> 5 | packet[22] << 3 & 0x07FF);
channels[16] = packet[23] & CH17_MASK;
channels[17] = packet[23] & CH18_MASK;
lost_frame_ = packet[23] & LOST_FRAME_MASK;
failsafe_ = packet[23] & FAILSAFE_MASK;
for index, channel in enumerate(channels):
if index < 16:
print(f'ch{index+1}: {sbus_to_servo_us(channel)} ', end='')
else:
print(f'ch{index+1}: {channel} ', end='')
print()
def parse_sbus(data):
WAIT_FOR_HEADER = 0
# State values 1..23 are for receiving the packet bytes
WAIT_FOR_FOOTER = PACKET_LENGTH - 1
state = WAIT_FOR_HEADER
previous_byte = FOOTER
packet = [FOOTER] * PACKET_LENGTH
for byte in data:
packet.pop(0)
packet.append(byte)
if state == WAIT_FOR_HEADER:
if is_header(byte) and is_footer(previous_byte):
state = 1
elif state > WAIT_FOR_HEADER and state < WAIT_FOR_FOOTER:
state = state + 1
elif state == WAIT_FOR_FOOTER:
if is_footer(byte):
decode_sbus_packet(packet)
else:
print(f'Footer has unexpected value 0x{byte:02x}, discarding packet')
state = WAIT_FOR_HEADER
previous_byte = byte
if __name__ == '__main__':
parse_sbus(EXAMPLE_SBUS_PACKETS)