diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c index fd04b9abab..3a2bcf8b12 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c @@ -39,7 +39,7 @@ /* Virtual serial port over USB.*/ SerialUSBDriver SDU1; -cdc_linecoding_t linecoding = { +static cdc_linecoding_t linecoding = { {0x00, 0x96, 0x00, 0x00}, /* 38400. */ LC_STOP_1, LC_PARITY_NONE, 8 }; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c index c3c35e02d8..5a407d748d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c @@ -34,6 +34,10 @@ #include "usbcfg.h" +#ifndef ARRAY_SIZE +#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0])) +#endif + #if defined(HAL_USB_PRODUCT_ID) && HAL_HAVE_DUAL_USB_CDC /* * Virtual serial ports over USB. @@ -41,15 +45,14 @@ SerialUSBDriver SDU1; SerialUSBDriver SDU2; -cdc_linecoding_t linecoding = { - {0x00, 0x96, 0x00, 0x00}, /* 38400. */ - LC_STOP_1, LC_PARITY_NONE, 8 +static cdc_linecoding_t linecoding[] = { + {{0x00, 0x96, 0x00, 0x00}, /* 38400. */ + LC_STOP_1, LC_PARITY_NONE, 8}, + {{0x00, 0x96, 0x00, 0x00}, /* 38400. */ + LC_STOP_1, LC_PARITY_NONE, 8} }; -cdc_linecoding_t linecoding2 = { - {0x00, 0x96, 0x00, 0x00}, /* 38400. */ - LC_STOP_1, LC_PARITY_NONE, 8 -}; +static uint8_t ep_index[] = {0, 2}; /* * Endpoints. @@ -303,11 +306,11 @@ static const USBDescriptor *get_descriptor(USBDriver *usbp, #if HAL_USE_SERIAL_USB uint32_t get_usb_baud(uint16_t endpoint_id) { - if(endpoint_id == 0) - return *((uint32_t*)linecoding.dwDTERate); - if(endpoint_id == 2) - return *((uint32_t*)linecoding2.dwDTERate); - return 0; + for (uint8_t i = 0; i < ARRAY_SIZE(linecoding); i++) { + if(endpoint_id == ep_index[i]) + return *((uint32_t*)linecoding[i].dwDTERate); + } + return 0; } #endif /** @@ -475,34 +478,23 @@ static bool requests_hook(USBDriver *usbp) { return true; } // process only index=2 commands here - ie the second interface - the first interface is handled via the default handler - if ((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS && usbp->setup[4] == 0x02 && usbp->setup[5] == 0x00) { - switch (usbp->setup[1]) { - case CDC_GET_LINE_CODING: - usbSetupTransfer(usbp, (uint8_t *)&linecoding2, sizeof(linecoding2), NULL); - return true; - case CDC_SET_LINE_CODING: - usbSetupTransfer(usbp, (uint8_t *)&linecoding2, sizeof(linecoding2), NULL); - return true; - case CDC_SET_CONTROL_LINE_STATE: - /* Nothing to do, there are no control lines.*/ - usbSetupTransfer(usbp, NULL, 0, NULL); - return true; - } - } - if ((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS && usbp->setup[4] == 0x00 && usbp->setup[5] == 0x00) { - switch (usbp->setup[1]) { - case CDC_GET_LINE_CODING: - usbSetupTransfer(usbp, (uint8_t *)&linecoding, sizeof(linecoding), NULL); - return true; - case CDC_SET_LINE_CODING: - usbSetupTransfer(usbp, (uint8_t *)&linecoding, sizeof(linecoding), NULL); - return true; - case CDC_SET_CONTROL_LINE_STATE: - /* Nothing to do, there are no control lines.*/ - usbSetupTransfer(usbp, NULL, 0, NULL); - return true; + for (uint8_t i = 0; i < ARRAY_SIZE(linecoding); i++) { + if ((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS && usbp->setup[4] == ep_index[i] && usbp->setup[5] == 0x00) { + switch (usbp->setup[1]) { + case CDC_GET_LINE_CODING: + usbSetupTransfer(usbp, (uint8_t *)&linecoding[i], sizeof(linecoding[i]), NULL); + return true; + case CDC_SET_LINE_CODING: + usbSetupTransfer(usbp, (uint8_t *)&linecoding[i], sizeof(linecoding[i]), NULL); + return true; + case CDC_SET_CONTROL_LINE_STATE: + /* Nothing to do, there are no control lines.*/ + usbSetupTransfer(usbp, NULL, 0, NULL); + return true; + } } } + return sduRequestsHook(usbp); }