mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed warning for USB
This commit is contained in:
parent
4daf4ad501
commit
8deaa1b46b
|
@ -244,8 +244,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 == 0) {
|
||||
uint32_t rate;
|
||||
memcpy(&rate, &linecoding.dwDTERate[0], sizeof(rate));
|
||||
return rate;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -307,8 +307,10 @@ static const USBDescriptor *get_descriptor(USBDriver *usbp,
|
|||
uint32_t get_usb_baud(uint16_t endpoint_id)
|
||||
{
|
||||
for (uint8_t i = 0; i < ARRAY_SIZE(linecoding); i++) {
|
||||
if(endpoint_id == ep_index[i])
|
||||
return *((uint32_t*)linecoding[i].dwDTERate);
|
||||
if (endpoint_id == ep_index[i]) {
|
||||
uint32_t rate;
|
||||
memcpy(&rate, &linecoding[i].dwDTERate[0], sizeof(rate));
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue