Browse Source

AP_RCProtocol: fixed support for 22ms multi-frame DSM

c415-sdk
Andrew Tridgell 5 years ago
parent
commit
74ca9033e2
  1. 2
      libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp

2
libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp

@ -139,6 +139,8 @@ void AP_RCProtocol_DSM::dsm_guess_format(bool reset, const uint8_t dsm_frame[16]
0xff, /* 8 channels (DX8) */ 0xff, /* 8 channels (DX8) */
0x1ff, /* 9 channels (DX9, etc.) */ 0x1ff, /* 9 channels (DX9, etc.) */
0x3ff, /* 10 channels (DX10) */ 0x3ff, /* 10 channels (DX10) */
0x7ff, /* 11 channels DX8 22ms */
0xfff, /* 12 channels DX8 22ms */
0x1fff, /* 13 channels (DX10t) */ 0x1fff, /* 13 channels (DX10t) */
0x3fff /* 18 channels (DX10) */ 0x3fff /* 18 channels (DX10) */
}; };

Loading…
Cancel
Save