Browse Source

HAL_ChibiOS: add missing return to Dual CDC get_usb_baud()

gps-1.3.1
Nick Exton 3 years ago committed by Andrew Tridgell
parent
commit
ffa2bba35c
  1. 1
      libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c

1
libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c

@ -310,6 +310,7 @@ uint32_t get_usb_baud(uint16_t endpoint_id) @@ -310,6 +310,7 @@ uint32_t get_usb_baud(uint16_t endpoint_id)
if (endpoint_id == ep_index[i]) {
uint32_t rate;
memcpy(&rate, &linecoding[i].dwDTERate[0], sizeof(rate));
return rate;
}
}
return 0;

Loading…
Cancel
Save