1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Adding RP2350 SDK and target framework (#13988)

* Adding RP2350 SDK and target framework

* Spacing

* Removing board definitions
This commit is contained in:
J Blackman 2024-10-23 10:02:48 +11:00 committed by GitHub
parent 462cb05930
commit 2dd6f95aad
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
576 changed files with 435012 additions and 0 deletions

View file

@ -0,0 +1,163 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_STDIO_USB_H
#define _PICO_STDIO_USB_H
#include "pico/stdio.h"
/** \brief Support for stdin/stdout over USB serial (CDC)
* \defgroup pico_stdio_usb pico_stdio_usb
* \ingroup pico_stdio
*
* Linking this library or calling `pico_enable_stdio_usb(TARGET ENABLED)` in the CMake (which
* achieves the same thing) will add USB CDC to the drivers used for standard input/output
*
* Note this library is a developer convenience. It is not applicable in all cases; for one it takes full control of the USB device precluding your
* use of the USB in device or host mode. For this reason, this library will automatically disengage if you try to using it alongside \ref tinyusb_device or
* \ref tinyusb_host. It also takes control of a lower level IRQ and sets up a periodic background task.
*
* This library also includes (by default) functionality to enable the RP-series microcontroller to be reset over the USB interface.
*/
// PICO_CONFIG: PICO_STDIO_USB_DEFAULT_CRLF, Default state of CR/LF translation for USB output, type=bool, default=PICO_STDIO_DEFAULT_CRLF, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_DEFAULT_CRLF
#define PICO_STDIO_USB_DEFAULT_CRLF PICO_STDIO_DEFAULT_CRLF
#endif
// PICO_CONFIG: PICO_STDIO_USB_STDOUT_TIMEOUT_US, Number of microseconds to be blocked trying to write USB output before assuming the host has disappeared and discarding data, default=500000, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_STDOUT_TIMEOUT_US
#define PICO_STDIO_USB_STDOUT_TIMEOUT_US 500000
#endif
// todo perhaps unnecessarily frequent?
// PICO_CONFIG: PICO_STDIO_USB_TASK_INTERVAL_US, Period of microseconds between calling tud_task in the background, default=1000, advanced=true, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_TASK_INTERVAL_US
#define PICO_STDIO_USB_TASK_INTERVAL_US 1000
#endif
// PICO_CONFIG: PICO_STDIO_USB_LOW_PRIORITY_IRQ, Explicit User IRQ number to claim for tud_task() background execution instead of letting the implementation pick a free one dynamically (deprecated), advanced=true, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_LOW_PRIORITY_IRQ
// this variable is no longer set by default (one is claimed dynamically), but will be respected if specified
#endif
// PICO_CONFIG: PICO_STDIO_USB_ENABLE_RESET_VIA_BAUD_RATE, Enable/disable resetting into BOOTSEL mode if the host sets the baud rate to a magic value (PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE), type=bool, default=1 if application is not using TinyUSB directly, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_ENABLE_RESET_VIA_BAUD_RATE
#if !defined(LIB_TINYUSB_HOST) && !defined(LIB_TINYUSB_DEVICE)
#define PICO_STDIO_USB_ENABLE_RESET_VIA_BAUD_RATE 1
#endif
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE, Baud rate that if selected causes a reset into BOOTSEL mode (if PICO_STDIO_USB_ENABLE_RESET_VIA_BAUD_RATE is set), default=1200, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE
#define PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE 1200
#endif
// PICO_CONFIG: PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS, Maximum number of milliseconds to wait during initialization for a CDC connection from the host (negative means indefinite) during initialization, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS
#define PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS 0
#endif
// PICO_CONFIG: PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS, Number of extra milliseconds to wait when using PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS after a host CDC connection is detected (some host terminals seem to sometimes lose transmissions sent right after connection), default=50, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS
#define PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS 50
#endif
// PICO_CONFIG: PICO_STDIO_USB_DEINIT_DELAY_MS, Number of milliseconds to wait before deinitializing stdio_usb, default=110, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_DEINIT_DELAY_MS
#define PICO_STDIO_USB_DEINIT_DELAY_MS 110
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED, Optionally define a pin to use as bootloader activity LED when BOOTSEL mode is entered via USB (either VIA_BAUD_RATE or VIA_VENDOR_INTERFACE), type=int, min=0, max=29, group=pico_stdio_usb
// PICO_CONFIG: PICO_STDIO_USB_RESET_BOOTSEL_FIXED_ACTIVITY_LED, Whether the pin specified by PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED is fixed or can be modified by picotool over the VENDOR USB interface, type=bool, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_BOOTSEL_FIXED_ACTIVITY_LED
#define PICO_STDIO_USB_RESET_BOOTSEL_FIXED_ACTIVITY_LED 0
#endif
// Any modes disabled here can't be re-enabled by picotool via VENDOR_INTERFACE.
// PICO_CONFIG: PICO_STDIO_USB_RESET_BOOTSEL_INTERFACE_DISABLE_MASK, Optionally disable either the mass storage interface (bit 0) or the PICOBOOT interface (bit 1) when entering BOOTSEL mode via USB (either VIA_BAUD_RATE or VIA_VENDOR_INTERFACE), type=int, min=0, max=3, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_BOOTSEL_INTERFACE_DISABLE_MASK
#define PICO_STDIO_USB_RESET_BOOTSEL_INTERFACE_DISABLE_MASK 0u
#endif
// PICO_CONFIG: PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE, Enable/disable resetting into BOOTSEL mode via an additional VENDOR USB interface - enables picotool based reset, type=bool, default=1 if application is not using TinyUSB directly, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
#if !defined(LIB_TINYUSB_HOST) && !defined(LIB_TINYUSB_DEVICE)
#define PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE 1
#endif
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL, If vendor reset interface is included allow rebooting to BOOTSEL mode, type=bool, default=1, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL
#define PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL 1
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT, If vendor reset interface is included allow rebooting with regular flash boot, type=bool, default=1, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT
#define PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT 1
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR, If vendor reset interface is included add support for Microsoft OS 2.0 Descriptor, type=bool, default=1, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR
#define PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR 1
#endif
// PICO_CONFIG: PICO_STDIO_USB_RESET_RESET_TO_FLASH_DELAY_MS, Delay in ms before rebooting via regular flash boot, default=100, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_RESET_RESET_TO_FLASH_DELAY_MS
#define PICO_STDIO_USB_RESET_RESET_TO_FLASH_DELAY_MS 100
#endif
// PICO_CONFIG: PICO_STDIO_USB_CONNECTION_WITHOUT_DTR, Disable use of DTR for connection checking meaning connection is assumed to be valid, type=bool, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_CONNECTION_WITHOUT_DTR
#define PICO_STDIO_USB_CONNECTION_WITHOUT_DTR 0
#endif
// PICO_CONFIG: PICO_STDIO_USB_DEVICE_SELF_POWERED, Set USB device as self powered device, type=bool, default=0, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_DEVICE_SELF_POWERED
#define PICO_STDIO_USB_DEVICE_SELF_POWERED 0
#endif
// PICO_CONFIG: PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK, Enable USB STDIO support for stdio_set_chars_available_callback. Can be disabled to make use of USB CDC RX callback elsewhere, type=bool, default=1, group=pico_stdio_usb
#ifndef PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
#define PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK 1
#endif
#ifdef __cplusplus
extern "C" {
#endif
extern stdio_driver_t stdio_usb;
/*! \brief Explicitly initialize USB stdio and add it to the current set of stdin drivers
* \ingroup pico_stdio_usb
*
* \ref PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS can be set to cause this method to wait for a CDC connection
* from the host before returning, which is useful if you don't want any initial stdout output to be discarded
* before the connection is established.
*
* \return true if the USB CDC was initialized, false if an error occurred
*/
bool stdio_usb_init(void);
/*! \brief Explicitly deinitialize USB stdio and remove it from the current set of stdin drivers
* \ingroup pico_stdio_usb
*
* \return true if the USB CDC was deinitialized, false if an error occurred
*/
bool stdio_usb_deinit(void);
/*! \brief Check if there is an active stdio CDC connection to a host
* \ingroup pico_stdio_usb
*
* \return true if stdio is connected over CDC
*/
bool stdio_usb_connected(void);
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,13 @@
/*
* Copyright (c) 2021 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_STDIO_USB_RESET_INTERFACE_H
#define _PICO_STDIO_USB_RESET_INTERFACE_H
// definitions have been moved here
#include "pico/usb_reset_interface.h"
#endif

View file

@ -0,0 +1,50 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
* Copyright (c) 2020 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
*/
#ifndef _PICO_STDIO_USB_TUSB_CONFIG_H
#define _PICO_STDIO_USB_TUSB_CONFIG_H
#include "pico/stdio_usb.h"
#if !defined(LIB_TINYUSB_HOST) && !defined(LIB_TINYUSB_DEVICE)
#define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE)
#define CFG_TUD_CDC (1)
#define CFG_TUD_CDC_RX_BUFSIZE (256)
#define CFG_TUD_CDC_TX_BUFSIZE (256)
// We use a vendor specific interface but with our own driver
// Vendor driver only used for Microsoft OS 2.0 descriptor
#if !PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR
#define CFG_TUD_VENDOR (0)
#else
#define CFG_TUD_VENDOR (1)
#define CFG_TUD_VENDOR_RX_BUFSIZE (256)
#define CFG_TUD_VENDOR_TX_BUFSIZE (256)
#endif
#endif
#endif

View file

@ -0,0 +1,185 @@
/**
* Copyright (c) 2021 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "tusb.h"
#include "pico/bootrom.h"
#if !defined(LIB_TINYUSB_HOST)
#if PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE && !(PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL || PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT)
#warning PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE has been selected but neither PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL nor PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT have been selected.
#endif
#if PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
#include "pico/stdio_usb/reset_interface.h"
#include "hardware/watchdog.h"
#include "device/usbd_pvt.h"
static uint8_t itf_num;
#if PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR
// Support for Microsoft OS 2.0 descriptor
#define BOS_TOTAL_LEN (TUD_BOS_DESC_LEN + TUD_BOS_MICROSOFT_OS_DESC_LEN)
#define MS_OS_20_DESC_LEN 166
#define USBD_ITF_RPI_RESET 2
uint8_t const desc_bos[] =
{
// total length, number of device caps
TUD_BOS_DESCRIPTOR(BOS_TOTAL_LEN, 1),
// Microsoft OS 2.0 descriptor
TUD_BOS_MS_OS_20_DESCRIPTOR(MS_OS_20_DESC_LEN, 1)
};
TU_VERIFY_STATIC(sizeof(desc_bos) == BOS_TOTAL_LEN, "Incorrect size");
uint8_t const * tud_descriptor_bos_cb(void)
{
return desc_bos;
}
static const uint8_t desc_ms_os_20[] =
{
// Set header: length, type, windows version, total length
U16_TO_U8S_LE(0x000A), U16_TO_U8S_LE(MS_OS_20_SET_HEADER_DESCRIPTOR), U32_TO_U8S_LE(0x06030000), U16_TO_U8S_LE(MS_OS_20_DESC_LEN),
// Function Subset header: length, type, first interface, reserved, subset length
U16_TO_U8S_LE(0x0008), U16_TO_U8S_LE(MS_OS_20_SUBSET_HEADER_FUNCTION), USBD_ITF_RPI_RESET, 0, U16_TO_U8S_LE(0x009C),
// MS OS 2.0 Compatible ID descriptor: length, type, compatible ID, sub compatible ID
U16_TO_U8S_LE(0x0014), U16_TO_U8S_LE(MS_OS_20_FEATURE_COMPATBLE_ID), 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // sub-compatible
// MS OS 2.0 Registry property descriptor: length, type
U16_TO_U8S_LE(0x0080), U16_TO_U8S_LE(MS_OS_20_FEATURE_REG_PROPERTY),
U16_TO_U8S_LE(0x0001), U16_TO_U8S_LE(0x0028), // wPropertyDataType, wPropertyNameLength and PropertyName "DeviceInterfaceGUID" in UTF-16
'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, 't', 0x00, 'e', 0x00,
'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00,
U16_TO_U8S_LE(0x004E), // wPropertyDataLength
// Vendor-defined Property Data: {bc7398c1-73cd-4cb7-98b8-913a8fca7bf6}
'{', 0, 'b', 0, 'c', 0, '7', 0, '3', 0, '9', 0,
'8', 0, 'c', 0, '1', 0, '-', 0, '7', 0, '3', 0,
'c', 0, 'd', 0, '-', 0, '4', 0, 'c', 0, 'b', 0,
'7', 0, '-', 0, '9', 0, '8', 0, 'b', 0, '8', 0,
'-', 0, '9', 0, '1', 0, '3', 0, 'a', 0, '8', 0,
'f', 0, 'c', 0, 'a', 0, '7', 0, 'b', 0, 'f', 0,
'6', 0, '}', 0, 0, 0
};
TU_VERIFY_STATIC(sizeof(desc_ms_os_20) == MS_OS_20_DESC_LEN, "Incorrect size");
bool tud_vendor_control_xfer_cb(uint8_t rhport, uint8_t stage, tusb_control_request_t const * request)
{
// nothing to with DATA & ACK stage
if (stage != CONTROL_STAGE_SETUP) return true;
if (request->bRequest == 1 && request->wIndex == 7) {
// Get Microsoft OS 2.0 compatible descriptor
return tud_control_xfer(rhport, request, (void*)(uintptr_t) desc_ms_os_20, sizeof(desc_ms_os_20));
} else {
return false;
}
// stall unknown request
return false;
}
#endif
static void resetd_init(void) {
}
static void resetd_reset(uint8_t __unused rhport) {
itf_num = 0;
}
static uint16_t resetd_open(uint8_t __unused rhport, tusb_desc_interface_t const *itf_desc, uint16_t max_len) {
TU_VERIFY(TUSB_CLASS_VENDOR_SPECIFIC == itf_desc->bInterfaceClass &&
RESET_INTERFACE_SUBCLASS == itf_desc->bInterfaceSubClass &&
RESET_INTERFACE_PROTOCOL == itf_desc->bInterfaceProtocol, 0);
uint16_t const drv_len = sizeof(tusb_desc_interface_t);
TU_VERIFY(max_len >= drv_len, 0);
itf_num = itf_desc->bInterfaceNumber;
return drv_len;
}
// Support for parameterized reset via vendor interface control request
static bool resetd_control_xfer_cb(uint8_t __unused rhport, uint8_t stage, tusb_control_request_t const * request) {
// nothing to do with DATA & ACK stage
if (stage != CONTROL_STAGE_SETUP) return true;
if (request->wIndex == itf_num) {
#if PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_BOOTSEL
if (request->bRequest == RESET_REQUEST_BOOTSEL) {
#ifdef PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED
uint gpio_mask = 1u << PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED;
#else
uint gpio_mask = 0u;
#endif
#if !PICO_STDIO_USB_RESET_BOOTSEL_FIXED_ACTIVITY_LED
if (request->wValue & 0x100) {
gpio_mask = 1u << (request->wValue >> 9u);
}
#endif
reset_usb_boot(gpio_mask, (request->wValue & 0x7f) | PICO_STDIO_USB_RESET_BOOTSEL_INTERFACE_DISABLE_MASK);
// does not return, otherwise we'd return true
}
#endif
#if PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_RESET_TO_FLASH_BOOT
if (request->bRequest == RESET_REQUEST_FLASH) {
watchdog_reboot(0, 0, PICO_STDIO_USB_RESET_RESET_TO_FLASH_DELAY_MS);
return true;
}
#endif
}
return false;
}
static bool resetd_xfer_cb(uint8_t __unused rhport, uint8_t __unused ep_addr, xfer_result_t __unused result, uint32_t __unused xferred_bytes) {
return true;
}
static usbd_class_driver_t const _resetd_driver =
{
#if CFG_TUSB_DEBUG >= 2
.name = "RESET",
#endif
.init = resetd_init,
.reset = resetd_reset,
.open = resetd_open,
.control_xfer_cb = resetd_control_xfer_cb,
.xfer_cb = resetd_xfer_cb,
.sof = NULL
};
// Implement callback to add our custom driver
usbd_class_driver_t const *usbd_app_driver_get_cb(uint8_t *driver_count) {
*driver_count = 1;
return &_resetd_driver;
}
#endif
#if PICO_STDIO_USB_ENABLE_RESET_VIA_BAUD_RATE
// Support for default BOOTSEL reset by changing baud rate
void tud_cdc_line_coding_cb(__unused uint8_t itf, cdc_line_coding_t const* p_line_coding) {
if (p_line_coding->bit_rate == PICO_STDIO_USB_RESET_MAGIC_BAUD_RATE) {
#ifdef PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED
const uint gpio_mask = 1u << PICO_STDIO_USB_RESET_BOOTSEL_ACTIVITY_LED;
#else
const uint gpio_mask = 0u;
#endif
reset_usb_boot(gpio_mask, PICO_STDIO_USB_RESET_BOOTSEL_INTERFACE_DISABLE_MASK);
}
}
#endif
#endif

View file

@ -0,0 +1,305 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef LIB_TINYUSB_HOST
#include "tusb.h"
#include "pico/stdio_usb.h"
// these may not be set if the user is providing tud support (i.e. LIB_TINYUSB_DEVICE is 1 because
// the user linked in tinyusb_device) but they haven't selected CDC
#if (CFG_TUD_ENABLED | TUSB_OPT_DEVICE_ENABLED) && CFG_TUD_CDC
#include "pico/binary_info.h"
#include "pico/time.h"
#include "pico/stdio/driver.h"
#include "pico/mutex.h"
#include "hardware/irq.h"
#include "device/usbd_pvt.h" // for usbd_defer_func
static mutex_t stdio_usb_mutex;
#if PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
static void (*chars_available_callback)(void*);
static void *chars_available_param;
#endif
// when tinyusb_device is explicitly linked we do no background tud processing
#if !LIB_TINYUSB_DEVICE
// if this crit_sec is initialized, we are not in periodic timer mode, and must make sure
// we don't either create multiple one shot timers, or miss creating one. this crit_sec
// is used to protect the one_shot_timer_pending flag
static critical_section_t one_shot_timer_crit_sec;
static volatile bool one_shot_timer_pending;
#ifdef PICO_STDIO_USB_LOW_PRIORITY_IRQ
static_assert(PICO_STDIO_USB_LOW_PRIORITY_IRQ >= NUM_IRQS - NUM_USER_IRQS, "");
#define low_priority_irq_num PICO_STDIO_USB_LOW_PRIORITY_IRQ
#else
static uint8_t low_priority_irq_num;
#endif
static int64_t timer_task(__unused alarm_id_t id, __unused void *user_data) {
int64_t repeat_time;
if (critical_section_is_initialized(&one_shot_timer_crit_sec)) {
critical_section_enter_blocking(&one_shot_timer_crit_sec);
one_shot_timer_pending = false;
critical_section_exit(&one_shot_timer_crit_sec);
repeat_time = 0; // don't repeat
} else {
repeat_time = PICO_STDIO_USB_TASK_INTERVAL_US;
}
if (irq_is_enabled(low_priority_irq_num)) {
irq_set_pending(low_priority_irq_num);
return repeat_time;
} else {
return 0; // don't repeat
}
}
static void low_priority_worker_irq(void) {
if (mutex_try_enter(&stdio_usb_mutex, NULL)) {
tud_task();
#if PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
uint32_t chars_avail = tud_cdc_available();
#endif
mutex_exit(&stdio_usb_mutex);
#if PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
if (chars_avail && chars_available_callback) chars_available_callback(chars_available_param);
#endif
} else {
// if the mutex is already owned, then we are in non IRQ code in this file.
//
// it would seem simplest to just let that code call tud_task() at the end, however this
// code might run during the call to tud_task() and we might miss a necessary tud_task() call
//
// if we are using a periodic timer (crit_sec is not initialized in this case),
// then we are happy just to wait until the next tick, however when we are not using a periodic timer,
// we must kick off a one-shot timer to make sure the tud_task() DOES run (this method
// will be called again as a result, and will try the mutex_try_enter again, and if that fails
// create another one shot timer again, and so on).
if (critical_section_is_initialized(&one_shot_timer_crit_sec)) {
bool need_timer;
critical_section_enter_blocking(&one_shot_timer_crit_sec);
need_timer = !one_shot_timer_pending;
one_shot_timer_pending = true;
critical_section_exit(&one_shot_timer_crit_sec);
if (need_timer) {
add_alarm_in_us(PICO_STDIO_USB_TASK_INTERVAL_US, timer_task, NULL, true);
}
}
}
}
static void usb_irq(void) {
irq_set_pending(low_priority_irq_num);
}
#endif
static void stdio_usb_out_chars(const char *buf, int length) {
static uint64_t last_avail_time;
if (!mutex_try_enter_block_until(&stdio_usb_mutex, make_timeout_time_ms(PICO_STDIO_DEADLOCK_TIMEOUT_MS))) {
return;
}
if (stdio_usb_connected()) {
for (int i = 0; i < length;) {
int n = length - i;
int avail = (int) tud_cdc_write_available();
if (n > avail) n = avail;
if (n) {
int n2 = (int) tud_cdc_write(buf + i, (uint32_t)n);
tud_task();
tud_cdc_write_flush();
i += n2;
last_avail_time = time_us_64();
} else {
tud_task();
tud_cdc_write_flush();
if (!stdio_usb_connected() ||
(!tud_cdc_write_available() && time_us_64() > last_avail_time + PICO_STDIO_USB_STDOUT_TIMEOUT_US)) {
break;
}
}
}
} else {
// reset our timeout
last_avail_time = 0;
}
mutex_exit(&stdio_usb_mutex);
}
static void stdio_usb_out_flush(void) {
if (!mutex_try_enter_block_until(&stdio_usb_mutex, make_timeout_time_ms(PICO_STDIO_DEADLOCK_TIMEOUT_MS))) {
return;
}
do {
tud_task();
} while (tud_cdc_write_flush());
mutex_exit(&stdio_usb_mutex);
}
int stdio_usb_in_chars(char *buf, int length) {
// note we perform this check outside the lock, to try and prevent possible deadlock conditions
// with printf in IRQs (which we will escape through timeouts elsewhere, but that would be less graceful).
//
// these are just checks of state, so we can call them while not holding the lock.
// they may be wrong, but only if we are in the middle of a tud_task call, in which case at worst
// we will mistakenly think we have data available when we do not (we will check again), or
// tud_task will complete running and we will check the right values the next time.
//
int rc = PICO_ERROR_NO_DATA;
if (stdio_usb_connected() && tud_cdc_available()) {
if (!mutex_try_enter_block_until(&stdio_usb_mutex, make_timeout_time_ms(PICO_STDIO_DEADLOCK_TIMEOUT_MS))) {
return PICO_ERROR_NO_DATA; // would deadlock otherwise
}
if (stdio_usb_connected() && tud_cdc_available()) {
int count = (int) tud_cdc_read(buf, (uint32_t) length);
rc = count ? count : PICO_ERROR_NO_DATA;
} else {
// because our mutex use may starve out the background task, run tud_task here (we own the mutex)
tud_task();
}
mutex_exit(&stdio_usb_mutex);
}
return rc;
}
#if PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
void stdio_usb_set_chars_available_callback(void (*fn)(void*), void *param) {
chars_available_callback = fn;
chars_available_param = param;
}
#endif
stdio_driver_t stdio_usb = {
.out_chars = stdio_usb_out_chars,
.out_flush = stdio_usb_out_flush,
.in_chars = stdio_usb_in_chars,
#if PICO_STDIO_USB_SUPPORT_CHARS_AVAILABLE_CALLBACK
.set_chars_available_callback = stdio_usb_set_chars_available_callback,
#endif
#if PICO_STDIO_ENABLE_CRLF_SUPPORT
.crlf_enabled = PICO_STDIO_USB_DEFAULT_CRLF
#endif
};
bool stdio_usb_init(void) {
if (get_core_num() != alarm_pool_core_num(alarm_pool_get_default())) {
// included an assertion here rather than just returning false, as this is likely
// a coding bug, rather than anything else.
assert(false);
return false;
}
#if !PICO_NO_BI_STDIO_USB
bi_decl_if_func_used(bi_program_feature("USB stdin / stdout"));
#endif
#if !defined(LIB_TINYUSB_DEVICE)
// initialize TinyUSB, as user hasn't explicitly linked it
tusb_init();
#else
assert(tud_inited()); // we expect the caller to have initialized if they are using TinyUSB
#endif
if (!mutex_is_initialized(&stdio_usb_mutex)) mutex_init(&stdio_usb_mutex);
bool rc = true;
#if !LIB_TINYUSB_DEVICE
#ifdef PICO_STDIO_USB_LOW_PRIORITY_IRQ
user_irq_claim(PICO_STDIO_USB_LOW_PRIORITY_IRQ);
#else
low_priority_irq_num = (uint8_t) user_irq_claim_unused(true);
#endif
irq_set_exclusive_handler(low_priority_irq_num, low_priority_worker_irq);
irq_set_enabled(low_priority_irq_num, true);
if (irq_has_shared_handler(USBCTRL_IRQ)) {
critical_section_init_with_lock_num(&one_shot_timer_crit_sec, spin_lock_claim_unused(true));
// we can use a shared handler to notice when there may be work to do
irq_add_shared_handler(USBCTRL_IRQ, usb_irq, PICO_SHARED_IRQ_HANDLER_LOWEST_ORDER_PRIORITY);
} else {
// we use initialization state of the one_shot_timer_critsec as a flag
memset(&one_shot_timer_crit_sec, 0, sizeof(one_shot_timer_crit_sec));
rc = add_alarm_in_us(PICO_STDIO_USB_TASK_INTERVAL_US, timer_task, NULL, true) >= 0;
}
#endif
if (rc) {
stdio_set_driver_enabled(&stdio_usb, true);
#if PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS
#if PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS > 0
absolute_time_t until = make_timeout_time_ms(PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS);
#else
absolute_time_t until = at_the_end_of_time;
#endif
do {
if (stdio_usb_connected()) {
#if PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS != 0
sleep_ms(PICO_STDIO_USB_POST_CONNECT_WAIT_DELAY_MS);
#endif
break;
}
sleep_ms(10);
} while (!time_reached(until));
#endif
}
return rc;
}
bool stdio_usb_deinit(void) {
if (get_core_num() != alarm_pool_core_num(alarm_pool_get_default())) {
// included an assertion here rather than just returning false, as this is likely
// a coding bug, rather than anything else.
assert(false);
return false;
}
assert(tud_inited()); // we expect the caller to have initialized when calling sdio_usb_init
bool rc = true;
stdio_set_driver_enabled(&stdio_usb, false);
#if PICO_STDIO_USB_DEINIT_DELAY_MS != 0
sleep_ms(PICO_STDIO_USB_DEINIT_DELAY_MS);
#endif
#if !LIB_TINYUSB_DEVICE
if (irq_has_shared_handler(USBCTRL_IRQ)) {
spin_lock_unclaim(spin_lock_get_num(one_shot_timer_crit_sec.spin_lock));
critical_section_deinit(&one_shot_timer_crit_sec);
// we can use a shared handler to notice when there may be work to do
irq_remove_handler(USBCTRL_IRQ, usb_irq);
} else {
// timer is disabled by disabling the irq
}
irq_set_enabled(low_priority_irq_num, false);
user_irq_unclaim(low_priority_irq_num);
#endif
return rc;
}
bool stdio_usb_connected(void) {
#if PICO_STDIO_USB_CONNECTION_WITHOUT_DTR
return tud_ready();
#else
// this actually checks DTR
return tud_cdc_connected();
#endif
}
#else
#warning stdio USB was configured along with user use of TinyUSB device mode, but CDC is not enabled
bool stdio_usb_init(void) {
return false;
}
#endif // CFG_TUD_ENABLED && CFG_TUD_CDC
#else
#warning stdio USB was configured, but is being disabled as TinyUSB host is explicitly linked
bool stdio_usb_init(void) {
return false;
}
#endif // !LIB_TINYUSB_HOST

View file

@ -0,0 +1,188 @@
/*
* This file is based on a file originally part of the
* MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
* Copyright (c) 2019 Damien P. George
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#if !defined(LIB_TINYUSB_HOST) && !defined(LIB_TINYUSB_DEVICE)
#include "tusb.h"
#include "pico/stdio_usb/reset_interface.h"
#include "pico/unique_id.h"
#ifndef USBD_VID
#define USBD_VID (0x2E8A) // Raspberry Pi
#endif
#ifndef USBD_PID
#if PICO_RP2040
#define USBD_PID (0x000a) // Raspberry Pi Pico SDK CDC for RP2040
#else
#define USBD_PID (0x0009) // Raspberry Pi Pico SDK CDC
#endif
#endif
#ifndef USBD_MANUFACTURER
#define USBD_MANUFACTURER "Raspberry Pi"
#endif
#ifndef USBD_PRODUCT
#define USBD_PRODUCT "Pico"
#endif
#define TUD_RPI_RESET_DESC_LEN 9
#if !PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
#define USBD_DESC_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN)
#else
#define USBD_DESC_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_RPI_RESET_DESC_LEN)
#endif
#if !PICO_STDIO_USB_DEVICE_SELF_POWERED
#define USBD_CONFIGURATION_DESCRIPTOR_ATTRIBUTE (0)
#define USBD_MAX_POWER_MA (250)
#else
#define USBD_CONFIGURATION_DESCRIPTOR_ATTRIBUTE TUSB_DESC_CONFIG_ATT_SELF_POWERED
#define USBD_MAX_POWER_MA (1)
#endif
#define USBD_ITF_CDC (0) // needs 2 interfaces
#if !PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
#define USBD_ITF_MAX (2)
#else
#define USBD_ITF_RPI_RESET (2)
#define USBD_ITF_MAX (3)
#endif
#define USBD_CDC_EP_CMD (0x81)
#define USBD_CDC_EP_OUT (0x02)
#define USBD_CDC_EP_IN (0x82)
#define USBD_CDC_CMD_MAX_SIZE (8)
#define USBD_CDC_IN_OUT_MAX_SIZE (64)
#define USBD_STR_0 (0x00)
#define USBD_STR_MANUF (0x01)
#define USBD_STR_PRODUCT (0x02)
#define USBD_STR_SERIAL (0x03)
#define USBD_STR_CDC (0x04)
#define USBD_STR_RPI_RESET (0x05)
// Note: descriptors returned from callbacks must exist long enough for transfer to complete
static const tusb_desc_device_t usbd_desc_device = {
.bLength = sizeof(tusb_desc_device_t),
.bDescriptorType = TUSB_DESC_DEVICE,
// On Windows, if bcdUSB = 0x210 then a Microsoft OS 2.0 descriptor is required, else the device won't be detected
// This is only needed for driverless access to the reset interface - the CDC interface doesn't require these descriptors
// for driverless access, but will still not work if bcdUSB = 0x210 and no descriptor is provided. Therefore always
// use bcdUSB = 0x200 if the Microsoft OS 2.0 descriptor isn't enabled
#if PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE && PICO_STDIO_USB_RESET_INTERFACE_SUPPORT_MS_OS_20_DESCRIPTOR
.bcdUSB = 0x0210,
#else
.bcdUSB = 0x0200,
#endif
.bDeviceClass = TUSB_CLASS_MISC,
.bDeviceSubClass = MISC_SUBCLASS_COMMON,
.bDeviceProtocol = MISC_PROTOCOL_IAD,
.bMaxPacketSize0 = CFG_TUD_ENDPOINT0_SIZE,
.idVendor = USBD_VID,
.idProduct = USBD_PID,
.bcdDevice = 0x0100,
.iManufacturer = USBD_STR_MANUF,
.iProduct = USBD_STR_PRODUCT,
.iSerialNumber = USBD_STR_SERIAL,
.bNumConfigurations = 1,
};
#define TUD_RPI_RESET_DESCRIPTOR(_itfnum, _stridx) \
/* Interface */\
9, TUSB_DESC_INTERFACE, _itfnum, 0, 0, TUSB_CLASS_VENDOR_SPECIFIC, RESET_INTERFACE_SUBCLASS, RESET_INTERFACE_PROTOCOL, _stridx,
static const uint8_t usbd_desc_cfg[USBD_DESC_LEN] = {
TUD_CONFIG_DESCRIPTOR(1, USBD_ITF_MAX, USBD_STR_0, USBD_DESC_LEN,
USBD_CONFIGURATION_DESCRIPTOR_ATTRIBUTE, USBD_MAX_POWER_MA),
TUD_CDC_DESCRIPTOR(USBD_ITF_CDC, USBD_STR_CDC, USBD_CDC_EP_CMD,
USBD_CDC_CMD_MAX_SIZE, USBD_CDC_EP_OUT, USBD_CDC_EP_IN, USBD_CDC_IN_OUT_MAX_SIZE),
#if PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
TUD_RPI_RESET_DESCRIPTOR(USBD_ITF_RPI_RESET, USBD_STR_RPI_RESET)
#endif
};
static char usbd_serial_str[PICO_UNIQUE_BOARD_ID_SIZE_BYTES * 2 + 1];
static const char *const usbd_desc_str[] = {
[USBD_STR_MANUF] = USBD_MANUFACTURER,
[USBD_STR_PRODUCT] = USBD_PRODUCT,
[USBD_STR_SERIAL] = usbd_serial_str,
[USBD_STR_CDC] = "Board CDC",
#if PICO_STDIO_USB_ENABLE_RESET_VIA_VENDOR_INTERFACE
[USBD_STR_RPI_RESET] = "Reset",
#endif
};
const uint8_t *tud_descriptor_device_cb(void) {
return (const uint8_t *)&usbd_desc_device;
}
const uint8_t *tud_descriptor_configuration_cb(__unused uint8_t index) {
return usbd_desc_cfg;
}
const uint16_t *tud_descriptor_string_cb(uint8_t index, __unused uint16_t langid) {
#ifndef USBD_DESC_STR_MAX
#define USBD_DESC_STR_MAX (20)
#elif USBD_DESC_STR_MAX > 127
#error USBD_DESC_STR_MAX too high (max is 127).
#elif USBD_DESC_STR_MAX < 17
#error USBD_DESC_STR_MAX too low (min is 17).
#endif
static uint16_t desc_str[USBD_DESC_STR_MAX];
// Assign the SN using the unique flash id
if (!usbd_serial_str[0]) {
pico_get_unique_board_id_string(usbd_serial_str, sizeof(usbd_serial_str));
}
uint8_t len;
if (index == 0) {
desc_str[1] = 0x0409; // supported language is English
len = 1;
} else {
if (index >= sizeof(usbd_desc_str) / sizeof(usbd_desc_str[0])) {
return NULL;
}
const char *str = usbd_desc_str[index];
for (len = 0; len < USBD_DESC_STR_MAX - 1 && str[len]; ++len) {
desc_str[1 + len] = str[len];
}
}
// first byte is length (including header), second byte is string type
desc_str[0] = (uint16_t) ((TUSB_DESC_STRING << 8) | (2 * len + 2));
return desc_str;
}
#endif