mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: expand DSM test to 8 channels
This commit is contained in:
parent
da0301c208
commit
b4c551b56c
|
@ -193,9 +193,11 @@ void loop()
|
|||
const uint16_t sbus_output[] = {1562, 1496, 1000, 1530, 1806, 2006, 1494, 1494, 874,
|
||||
874, 874, 874, 874, 874, 874, 874};
|
||||
|
||||
const uint8_t dsm_bytes[] = {0x00, 0xB2, 0x8C, 0x03, 0x2F, 0x6C, 0x10, 0xB4,
|
||||
0x26, 0x16, 0x34, 0x01, 0x04, 0x75, 0x1C, 0x40};
|
||||
const uint16_t dsm_output[] = {1501, 1004, 1568, 1537, 1814, 2015, 1500};
|
||||
const uint8_t dsm_bytes[] = {0x00, 0xab, 0x00, 0xae, 0x08, 0xbf, 0x10, 0xd0, 0x18,
|
||||
0xe1, 0x20, 0xf2, 0x29, 0x03, 0x31, 0x14, 0x00, 0xab,
|
||||
0x39, 0x25, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
|
||||
0xff, 0xff, 0xff, 0xff, 0xff};
|
||||
const uint16_t dsm_output[] = {1010, 1020, 1000, 1030, 1040, 1050, 1060, 1070};
|
||||
|
||||
const uint8_t sumd_bytes[] = {0xA8, 0x01, 0x08, 0x2F, 0x50, 0x31, 0xE8, 0x21, 0xA0,
|
||||
0x2F, 0x50, 0x22, 0x60, 0x22, 0x60, 0x2E, 0xE0, 0x2E,
|
||||
|
|
Loading…
Reference in New Issue