AP_HAL_ChibiOS: add get_usb_baud - support for usb baudrate

This commit is contained in:
Michael Oborne 2020-10-26 13:32:47 +08:00 committed by Andrew Tridgell
parent eff4bc4cfb
commit d622aad592
5 changed files with 77 additions and 1 deletions

View File

@ -100,6 +100,11 @@ public:
*/
virtual uint64_t get_hw_rtc() const;
/*
get the requested usb baudrate - 0 = none
*/
virtual uint32_t get_usb_baud(uint16_t endpoint_id) { return 0; }
enum class FlashBootloader {
OK=0,
NO_CHANGE=1,

View File

@ -24,6 +24,7 @@
#include "hwdef/common/stm32_util.h"
#include "hwdef/common/watchdog.h"
#include "hwdef/common/flash.h"
#include "hwdef/common/usbcfg.h"
#include <AP_ROMFS/AP_ROMFS.h>
#include <AP_Common/ExpandingString.h>
#include "sdcard.h"
@ -225,6 +226,17 @@ uint64_t Util::get_hw_rtc() const
return stm32_get_utc_usec();
}
/*
get the requested usb baudrate - 0 = none
*/
uint32_t Util::get_usb_baud(uint16_t endpoint_id)
{
#if defined(HAL_USB_PRODUCT_ID) && HAL_HAVE_DUAL_USB_CDC
return ::get_usb_baud(endpoint_id);
#endif
return 0;
}
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
#if defined(HAL_NO_GCS) || defined(HAL_BOOTLOADER_BUILD)

View File

@ -110,6 +110,12 @@ private:
get system clock in UTC microseconds
*/
uint64_t get_hw_rtc() const override;
/*
get the requested usb baudrate - 0 = none
*/
uint32_t get_usb_baud(uint16_t endpoint_id) override;
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
FlashBootloader flash_bootloader() override;
#endif

View File

@ -44,6 +44,7 @@ extern SerialUSBDriver SDU1;
#if HAL_HAVE_DUAL_USB_CDC
extern SerialUSBDriver SDU2;
extern const SerialUSBConfig serusbcfg2;
uint32_t get_usb_baud(uint16_t endpoint_id);
#endif //HAL_HAVE_DUAL_USB_CDC
#endif
#define USB_DESC_MAX_STRLEN 100

View File

@ -41,6 +41,16 @@
SerialUSBDriver SDU1;
SerialUSBDriver SDU2;
cdc_linecoding_t linecoding = {
{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
};
/*
* Endpoints.
*/
@ -287,6 +297,20 @@ static const USBDescriptor *get_descriptor(USBDriver *usbp,
return NULL;
}
/*
get the requested usb baudrate - 0 = none
*/
uint32_t get_usb_baud(uint16_t endpoint_id)
{
#if defined(HAL_USB_PRODUCT_ID) && HAL_HAVE_DUAL_USB_CDC
if(endpoint_id == 0)
return *((uint32_t*)linecoding.dwDTERate);
if(endpoint_id == 2)
return *((uint32_t*)linecoding2.dwDTERate);
#endif
return 0;
}
/**
* @brief IN EP1 state.
*/
@ -446,12 +470,40 @@ static void usb_event(USBDriver *usbp, usbevent_t event) {
* SerialUSB handler.
*/
static bool requests_hook(USBDriver *usbp) {
if (((usbp->setup[0] & USB_RTYPE_RECIPIENT_MASK) == USB_RTYPE_RECIPIENT_INTERFACE) &&
(usbp->setup[1] == USB_REQ_SET_INTERFACE)) {
usbSetupTransfer(usbp, NULL, 0, NULL);
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;
}
}
return sduRequestsHook(usbp);
}