|
| 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