Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion cores/arduino/ch32/pinmap.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,15 +130,19 @@ void pin_function(PinName pin, int function)
case CH_CNF_OUTPUT_PP:
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
break;
#if !defined(CH32X035)
case CH_CNF_OUTPUT_OD:
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
break;
#endif
case CH_CNF_OUTPUT_AFPP:
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
break;
#if !defined(CH32X035)
case CH_CNF_OUTPUT_AFOD:
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
break;
break;
#endif
default:
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
break;
Expand Down
2 changes: 1 addition & 1 deletion libraries/Adafruit_TinyUSB_Arduino
Submodule Adafruit_TinyUSB_Arduino updated 63 files
+1 −0 README.md
+7 −0 examples/CDC/cdc_multi/cdc_multi.ino
+7 −0 examples/CDC/no_serial/no_serial.ino
+9 −1 examples/Composite/mouse_ramdisk/mouse_ramdisk.ino
+7 −0 examples/HID/hid_boot_keyboard/hid_boot_keyboard.ino
+9 −2 examples/HID/hid_boot_mouse/hid_boot_mouse.ino
+9 −2 examples/HID/hid_composite/hid_composite.ino
+8 −1 examples/HID/hid_composite_joy_featherwing/hid_composite_joy_featherwing.ino
+9 −1 examples/HID/hid_dual_interfaces/hid_dual_interfaces.ino
+7 −0 examples/HID/hid_gamepad/hid_gamepad.ino
+9 −2 examples/HID/hid_generic_inout/hid_generic_inout.ino
+9 −5 examples/MIDI/midi_multi_ports/midi_multi_ports.ino
+9 −2 examples/MIDI/midi_test/midi_test.ino
+8 −3 examples/MassStorage/msc_esp32_file_browser/msc_esp32_file_browser.ino
+19 −21 examples/MassStorage/msc_external_flash/msc_external_flash.ino
+8 −2 examples/MassStorage/msc_external_flash_sdcard/msc_external_flash_sdcard.ino
+21 −28 examples/MassStorage/msc_internal_flash_samd/msc_internal_flash_samd.ino
+9 −2 examples/MassStorage/msc_ramdisk/msc_ramdisk.ino
+9 −2 examples/MassStorage/msc_ramdisk_dual/msc_ramdisk_dual.ino
+14 −13 examples/MassStorage/msc_sd/msc_sd.ino
+17 −19 examples/MassStorage/msc_sdfat/msc_sdfat.ino
+7 −0 examples/Vendor/i2c_tiny_usb_adapter/i2c_tiny_usb_adapter.ino
+7 −0 examples/Video/video_capture/video_capture.ino
+9 −1 examples/WebUSB/webusb_rgb/webusb_rgb.ino
+7 −1 examples/WebUSB/webusb_serial/webusb_serial.ino
+2 −2 library.properties
+2 −0 src/arduino/Adafruit_TinyUSB_API.cpp
+16 −9 src/arduino/ports/ch32/Adafruit_TinyUSB_ch32.cpp
+4 −2 src/arduino/ports/ch32/tusb_config_ch32.h
+7 −0 src/arduino/ports/nrf/tusb_config_nrf.h
+3 −2 src/arduino/webusb/Adafruit_USBD_WebUSB.cpp
+2 −2 src/class/audio/audio.h
+416 −255 src/class/audio/audio_device.c
+59 −41 src/class/audio/audio_device.h
+37 −8 src/class/bth/bth_device.c
+104 −141 src/class/cdc/cdc_device.c
+75 −118 src/class/cdc/cdc_device.h
+143 −142 src/class/hid/hid_device.c
+43 −65 src/class/hid/hid_device.h
+3 −1 src/class/hid/hid_host.c
+2 −2 src/class/net/ncm_device.c
+1 −2 src/common/tusb_fifo.c
+41 −18 src/common/tusb_mcu.h
+9 −0 src/common/tusb_types.h
+5 −5 src/common/tusb_verify.h
+11 −26 src/device/dcd.h
+89 −83 src/device/usbd.c
+13 −13 src/device/usbd.h
+4 −1 src/host/usbh.c
+1 −1 src/host/usbh.h
+1 −1 src/osal/osal_freertos.h
+119 −63 src/portable/analog/max3421/hcd_max3421.c
+5 −5 src/portable/nordic/nrf5x/dcd_nrf5x.c
+10 −3 src/portable/raspberrypi/rp2040/rp2040_usb.c
+437 −689 src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
+2 −38 src/portable/st/stm32_fsdev/fsdev_ch32.h
+0 −391 src/portable/st/stm32_fsdev/fsdev_common.h
+59 −21 src/portable/st/stm32_fsdev/fsdev_stm32.h
+307 −0 src/portable/st/stm32_fsdev/fsdev_type.h
+27 −17 src/portable/synopsys/dwc2/dcd_dwc2.c
+18 −25 src/portable/synopsys/dwc2/dwc2_esp32.h
+1 −1 src/tusb.c
+7 −1 src/tusb_option.h
35 changes: 35 additions & 0 deletions libraries/USBPD_SINK/src/usbpd_sink.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,41 @@ void usbpd_sink_clear_ready(void)
pdControl_g.cc_USBPD_READY = 0;
}

uint8_t usbpd_sink_get_pdo_num(void)
{
return pdControl_g.cc_SourcePDONum;
}

uint8_t usbpd_sink_get_pps_num(void)
{
return pdControl_g.cc_SourcePPSNum;
}

uint16_t usbpd_sink_get_pdo_voltage(int index)
{
return pdControl_g.cc_FixedSourceCap[index].Voltage;
}

uint16_t usbpd_sink_get_pdo_current(int index)
{
return pdControl_g.cc_FixedSourceCap[index].Current;
}

uint16_t usbpd_sink_get_pps_min_voltage(int index)
{
return pdControl_g.cc_PPSSourceCap[index].MinVoltage;
}

uint16_t usbpd_sink_get_pps_max_voltage(int index)
{
return pdControl_g.cc_PPSSourceCap[index].MaxVoltage;
}

uint16_t usbpd_sink_get_pps_current(int index)
{
return pdControl_g.cc_PPSSourceCap[index].Current;
}

bool usbpd_sink_set_request_fixed_voltage(Request_voltage_t requestVoltage)
{
uint16_t targetVoltage;
Expand Down
8 changes: 8 additions & 0 deletions libraries/USBPD_SINK/src/usbpd_sink.h
Original file line number Diff line number Diff line change
Expand Up @@ -202,6 +202,14 @@ void usbpd_sink_process(void);
uint8_t usbpd_sink_get_ready(void);
void usbpd_sink_clear_ready(void);

uint8_t usbpd_sink_get_pdo_num(void);
uint8_t usbpd_sink_get_pps_num(void);
uint16_t usbpd_sink_get_pdo_voltage(int index);
uint16_t usbpd_sink_get_pdo_current(int index);
uint16_t usbpd_sink_get_pps_min_voltage(int index);
uint16_t usbpd_sink_get_pps_max_voltage(int index);
uint16_t usbpd_sink_get_pps_current(int index);

bool usbpd_sink_set_request_fixed_voltage(Request_voltage_t requestVoltage);


Expand Down
6 changes: 3 additions & 3 deletions system/CH32L10x/SRC/Debug/debug.c
Original file line number Diff line number Diff line change
Expand Up @@ -149,8 +149,6 @@ void USART_Printf_Init(uint32_t baudrate)
*
* @return size: Data length
*/

#if 0
__attribute__((used))
int _write(int fd, char *buf, int size)
{
Expand All @@ -171,7 +169,6 @@ int _write(int fd, char *buf, int size)

return size;
}
#endif

/*********************************************************************
* @fn _sbrk
Expand All @@ -193,3 +190,6 @@ void *_sbrk(ptrdiff_t incr)
curbrk += incr;
return curbrk - incr;
}

void _fini() {}
void _init() {}
3 changes: 2 additions & 1 deletion system/CH32L10x/SRC/Debug/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
* File Name : debug.h
* Author : WCH
* Version : V1.0.0
* Date : 2023/07/08
* Date : 2023/11/06
* Description : This file contains all the functions prototypes for UART
* Printf , Delay functions.
*********************************************************************************
Expand Down Expand Up @@ -34,6 +34,7 @@ extern uint32_t OPA_Trim;
extern uint16_t ADC_Trim;
extern uint32_t TS_Val;
extern uint32_t CHIPID;
extern uint16_t USBPD_CFG;

void Delay_Init(void);
void Delay_Us(uint32_t n);
Expand Down
40 changes: 17 additions & 23 deletions system/CH32L10x/SRC/Peripheral/inc/ch32l103.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
* File Name : ch32l103.h
* Author : WCH
* Version : V1.0.0
* Date : 2023/07/08
* Date : 2024/11/06
* Description : CH32L103 Device Peripheral Access Layer Header File.
*********************************************************************************
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
Expand All @@ -16,7 +16,9 @@
extern "C" {
#endif

#ifndef HSE_VALUE
#define HSE_VALUE ((uint32_t)8000000) /* Value of the External oscillator in Hz */
#endif

/* In the following line adjust the External High Speed oscillator (HSE) Startup Timeout value */
#define HSE_STARTUP_TIMEOUT ((uint16_t)0x1000) /* Time out for HSE start up */
Expand All @@ -27,7 +29,7 @@ extern "C" {

/* Standard Peripheral Library version number */
#define __CH32L103_STDPERIPH_VERSION_MAIN (0x01) /* [15:8] main version */
#define __CH32L103_STDPERIPH_VERSION_SUB (0x00) /* [7:0] sub version */
#define __CH32L103_STDPERIPH_VERSION_SUB (0x03) /* [7:0] sub version */
#define __CH32L103_STDPERIPH_VERSION ((__CH32L103_STDPERIPH_VERSION_MAIN << 8)\
|(__CH32L103_STDPERIPH_VERSION_SUB << 0))

Expand All @@ -40,7 +42,7 @@ typedef enum IRQn
Ecall_M_Mode_IRQn = 5, /* Ecall M Mode Interrupt */
Ecall_U_Mode_IRQn = 8, /* Ecall U Mode Interrupt */
Break_Point_IRQn = 9, /* Break Point Interrupt */
SysTicK_IRQn = 12, /* System timer Interrupt */
SysTick_IRQn = 12, /* System timer Interrupt */
Software_IRQn = 14, /* Software Interrupt */

/****** RISC-V specific Interrupt Numbers *********************************************************/
Expand Down Expand Up @@ -94,14 +96,15 @@ typedef enum IRQn
LPTIM_IRQn = 63, /* LPTIM global Interrupt */
OPA_IRQn = 64, /* OPA global Interrupt */
USBPD_IRQn = 65, /* USBPD global Interrupt */
TKeyWakeUp_IRQn = 66, /* TKey WakeUp Interrupt */

USBPDWakeUp_IRQn = 67, /* USBPD WakeUp Interrupt */
CMPWakeUp_IRQn = 68, /* CMP WakeUp Interrupt */

} IRQn_Type;

#define HardFault_IRQn EXC_IRQn
#define ADC1_2_IRQn ADC_IRQn
#define SysTicK_IRQn SysTick_IRQn

#include <stdint.h>
#include "core_riscv.h"
Expand Down Expand Up @@ -166,13 +169,7 @@ typedef struct
__IO uint16_t TPCTLR;
uint16_t RESERVED12;
__IO uint16_t TPCSR;
uint16_t RESERVED13[5];
__IO uint16_t DATAR11;
uint16_t RESERVED14;
__IO uint16_t DATAR12;
uint16_t RESERVED15;
__IO uint16_t DATAR13;
uint16_t RESERVED16;
uint16_t RESERVED13;
} BKP_TypeDef;

/* Controller Area Network TxMailBox */
Expand Down Expand Up @@ -824,7 +821,7 @@ typedef struct
#define ADC_TRIM_BASE ((uint32_t)0x1FFFF728)
#define HSI_LP_TRIM_BASE ((uint32_t)0x1FFFF72A)
#define CHIPID_BASE ((uint32_t)0x1FFFF704)

#define USBPD_CFG_BASE ((uint32_t)0x1FFFF730)

/* Peripheral declaration */
#define TIM2 ((TIM_TypeDef *)TIM2_BASE)
Expand Down Expand Up @@ -906,8 +903,9 @@ typedef struct
#define ADC_SCAN ((uint32_t)0x00000100) /* Scan mode */
#define ADC_AWDSGL ((uint32_t)0x00000200) /* Enable the watchdog on a single channel in scan mode */
#define ADC_JAUTO ((uint32_t)0x00000400) /* Automatic injected group conversion */
#define ADC_RDISCEN ((uint32_t)0x00000800) /* Discontinuous mode on regular channels */
#define ADC_DISCEN ((uint32_t)0x00000800) /* Discontinuous mode on regular channels */
#define ADC_JDISCEN ((uint32_t)0x00001000) /* Discontinuous mode on injected channels */
#define ADC_RDISCEN ADC_DISCEN

#define ADC_DISCNUM ((uint32_t)0x0000E000) /* DISCNUM[2:0] bits (Discontinuous mode channel count) */
#define ADC_DISCNUM_0 ((uint32_t)0x00002000) /* Bit 0 */
Expand Down Expand Up @@ -1278,15 +1276,6 @@ typedef struct
/******************* Bit definition for BKP_DATAR10 register *******************/
#define BKP_DATAR10_D ((uint16_t)0xFFFF) /* Backup data */

/******************* Bit definition for BKP_DATAR11 register *******************/
#define BKP_DATAR11_D ((uint16_t)0xFFFF) /* Backup data */

/******************* Bit definition for BKP_DATAR12 register *******************/
#define BKP_DATAR12_D ((uint16_t)0xFFFF) /* Backup data */

/******************* Bit definition for BKP_DATAR13 register *******************/
#define BKP_DATAR13_D ((uint16_t)0xFFFF) /* Backup data */

/****************** Bit definition for BKP_OCTLR register *******************/
#define BKP_CAL ((uint16_t)0x007F) /* Calibration value */
#define BKP_CCO ((uint16_t)0x0080) /* Calibration Clock Output */
Expand Down Expand Up @@ -3547,7 +3536,8 @@ typedef struct
#define AFIO_PCFR1_CAN_RM_0 ((uint32_t)0x00002000) /* Bit 0 */
#define AFIO_PCFR1_CAN_RM_1 ((uint32_t)0x00004000) /* Bit 1 */

#define AFIO_PCFR1_PD01_RM ((uint32_t)0x00008000) /* Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
#define AFIO_PCFR1_PD0PD1_RM ((uint32_t)0x00008000) /* Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
#define AFIO_PCFR1_PD01_RM AFIO_PCFR1_PD0PD1_RM

#define AFIO_PCFR1_SW_CFG ((uint32_t)0x07000000) /* SW_CFG[2:0] bits (SDI configuration) */
#define AFIO_PCFR1_SW_CFG_0 ((uint32_t)0x01000000) /* Bit 0 */
Expand Down Expand Up @@ -4643,6 +4633,7 @@ typedef struct
/******************* Bit definition for OPA_CFGR2 register *******************/
#define OPA_CFGR2_POLL_VLU ((uint32_t)0x000001FF)
#define OPA_CFGR2_POLL_NUM ((uint32_t)0x00000E00)
#define OPA_CFGR2_POLL_CNT ((uint32_t)0x00007000)

/******************* Bit definition for OPA_CTLR1 register *******************/
#define OPA_CTLR1_EN1 ((uint32_t)0x00000001)
Expand All @@ -4661,16 +4652,19 @@ typedef struct
#define OPA_CTLR2_MODE1 ((uint32_t)0x00000006)
#define OPA_CTLR2_NSEL1 ((uint32_t)0x00000008)
#define OPA_CTLR2_PSEL1 ((uint32_t)0x00000010)
#define OPA_CTLR2_HYEN1 ((uint32_t)0x00000020)
#define OPA_CTLR2_LP1 ((uint32_t)0x00000040)
#define OPA_CTLR2_EN2 ((uint32_t)0x00000100)
#define OPA_CTLR2_MODE2 ((uint32_t)0x00000600)
#define OPA_CTLR2_NSEL2 ((uint32_t)0x00000800)
#define OPA_CTLR2_PSEL2 ((uint32_t)0x00001000)
#define OPA_CTLR2_HYEN2 ((uint32_t)0x00002000)
#define OPA_CTLR2_LP2 ((uint32_t)0x00004000)
#define OPA_CTLR2_EN3 ((uint32_t)0x00010000)
#define OPA_CTLR2_MODE3 ((uint32_t)0x00060000)
#define OPA_CTLR2_NSEL3 ((uint32_t)0x00080000)
#define OPA_CTLR2_PSEL3 ((uint32_t)0x00100000)
#define OPA_CTLR2_HYEN3 ((uint32_t)0x00200000)
#define OPA_CTLR2_LP3 ((uint32_t)0x00400000)

#define OPA_CTLR2_WKUP_MD ((uint32_t)0x03000000)
Expand Down
9 changes: 1 addition & 8 deletions system/CH32L10x/SRC/Peripheral/inc/ch32l103_adc.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
* File Name : ch32l103_adc.h
* Author : WCH
* Version : V1.0.0
* Date : 2023/07/08
* Date : 2024/05/06
* Description : This file contains all the functions prototypes for the
* ADC firmware library.
*********************************************************************************
Expand Down Expand Up @@ -153,12 +153,6 @@ typedef struct
#define ADC_FLAG_JSTRT ((uint8_t)0x08)
#define ADC_FLAG_STRT ((uint8_t)0x10)

/* ADC_TKey_WakeUp_IO_mode_definition */
#define ADC_TKey_WakeUp_Mode0 ((uint32_t)0x00000000)
#define ADC_TKey_WakeUp_Mode1 ((uint32_t)0x00080000)
#define ADC_TKey_WakeUp_Mode2 ((uint32_t)0x00100000)
#define ADC_TKey_WakeUp_Mode3 ((uint32_t)0x00180000)

/* ADC_Sample_mode_definition */
#define ADC_Sample_NoOver_1M_Mode ((uint32_t)0x00000000)
#define ADC_Sample_Over_1M_Mode ((uint32_t)0x00000020)
Expand Down Expand Up @@ -202,7 +196,6 @@ ITStatus ADC_GetITStatus(ADC_TypeDef *ADCx, uint16_t ADC_IT);
void ADC_ClearITPendingBit(ADC_TypeDef *ADCx, uint16_t ADC_IT);
s32 TempSensor_Volt_To_Temper(s32 Value);
void ADC_BufferCmd(ADC_TypeDef *ADCx, FunctionalState NewState);
void ADC_TKey_WakeUpCmd(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint32_t IO_Mode, FunctionalState NewState);
void ADC_TKey_ChannelxMulShieldCmd(ADC_TypeDef *ADCx, uint8_t ADC_Channel, FunctionalState NewState);
void ADC_TKey_MulShieldCmd(ADC_TypeDef *ADCx, FunctionalState NewState);
void ADC_DutyDelayCmd(ADC_TypeDef *ADCx, FunctionalState NewState);
Expand Down
3 changes: 1 addition & 2 deletions system/CH32L10x/SRC/Peripheral/inc/ch32l103_exti.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
* File Name : ch32l103_exti.h
* Author : WCH
* Version : V1.0.0
* Date : 2023/07/08
* Date : 2024/05/06
* Description : This file contains all the functions prototypes for the
* EXTI firmware library.
*********************************************************************************
Expand Down Expand Up @@ -69,7 +69,6 @@ typedef struct
#define EXTI_Line15 ((uint32_t)0x08000) /* External interrupt line 15 */
#define EXTI_Line16 ((uint32_t)0x10000) /* External interrupt line 16 Connected to the PVD Output */
#define EXTI_Line17 ((uint32_t)0x20000) /* External interrupt line 17 Connected to the RTC Alarm event */
#define EXTI_Line18 ((uint32_t)0x40000) /* External interrupt line 18 Connected to the Tkey Wakeup event */
#define EXTI_Line19 ((uint32_t)0x80000) /* External interrupt line 19 Connected to the USBPD Wakeup event */
#define EXTI_Line20 ((uint32_t)0x100000) /* External interrupt line 20 Connected to the USBFS Wakeup event */
#define EXTI_Line21 ((uint32_t)0x200000) /* External interrupt line 21 Connected to the LPTIM Wakeup event */
Expand Down
4 changes: 2 additions & 2 deletions system/CH32L10x/SRC/Peripheral/inc/ch32l103_gpio.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
* File Name : ch32l103_gpio.h
* Author : WCH
* Version : V1.0.0
* Date : 2023/07/08
* Date : 2024/03/01
* Description : This file contains all the functions prototypes for the
* GPIO firmware library.
*********************************************************************************
Expand Down Expand Up @@ -121,7 +121,7 @@ typedef enum
#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /* CAN1 Alternate Function mapping */
#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /* CAN1 Alternate Function mapping */
#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /* PD01 Alternate Function mapping */
#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /* Full SWJ Disabled (JTAG-DP + SW-DP) */
#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /* GPIO_Remap_SWJ_Disable - Full SDI Disabled (SDI) */

//bit[31:30] = 01b - PCFR2
#define GPIO_Remap_USART4 ((uint32_t)0x40000001) /* USART4 Alternate Function mapping */
Expand Down
4 changes: 2 additions & 2 deletions system/CH32L10x/SRC/Peripheral/inc/ch32l103_i2c.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ typedef struct
#define I2C_IT_ADDR ((uint32_t)0x02000002)
#define I2C_IT_SB ((uint32_t)0x02000001)

/* SR2 register flags */
/* STAR2 register flags */
#define I2C_FLAG_DUALF ((uint32_t)0x00800000)
#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000)
#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000)
Expand All @@ -115,7 +115,7 @@ typedef struct
#define I2C_FLAG_BUSY ((uint32_t)0x00020000)
#define I2C_FLAG_MSL ((uint32_t)0x00010000)

/* SR1 register flags */
/* STAR1 register flags */
#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000)
#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000)
#define I2C_FLAG_PECERR ((uint32_t)0x10001000)
Expand Down
Loading