AP_SBusOut: fixed an init bug in SBUS output

This commit is contained in:
Andrew Tridgell 2018-11-28 14:36:21 +11:00
parent adf78ab8d3
commit d78be209fe
1 changed files with 1 additions and 0 deletions

View File

@ -81,6 +81,7 @@ void AP_SBusOut::sbus_format_frame(uint16_t *channels, uint8_t num_channels, uin
uint8_t index = 1;
uint8_t offset = 0;
memset(buffer, 0, SBUS_BSIZE);
buffer[0] = 0x0f;
/* construct sbus frame representing channels 1 through 16 (max) */