mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
PICO: Remove tinyUsb direct (now using submodule)
This commit is contained in:
parent
3e2949f659
commit
d0a34b62dd
1494 changed files with 0 additions and 289509 deletions
|
@ -1,97 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2019 Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
/** \ingroup group_board
|
||||
* \defgroup group_ansi_esc ANSI Escape Code
|
||||
* @{ */
|
||||
|
||||
#ifndef _TUSB_ANSI_ESC_CODE_H_
|
||||
#define _TUSB_ANSI_ESC_CODE_H_
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define CSI_CODE(seq) "\33[" seq
|
||||
#define CSI_SGR(x) CSI_CODE(#x) "m"
|
||||
|
||||
//------------- Cursor movement -------------//
|
||||
/** \defgroup group_ansi_cursor Cursor Movement
|
||||
* @{ */
|
||||
#define ANSI_CURSOR_UP(n) CSI_CODE(#n "A") ///< Move cursor up
|
||||
#define ANSI_CURSOR_DOWN(n) CSI_CODE(#n "B") ///< Move cursor down
|
||||
#define ANSI_CURSOR_FORWARD(n) CSI_CODE(#n "C") ///< Move cursor forward
|
||||
#define ANSI_CURSOR_BACKWARD(n) CSI_CODE(#n "D") ///< Move cursor backward
|
||||
#define ANSI_CURSOR_LINE_DOWN(n) CSI_CODE(#n "E") ///< Move cursor to the beginning of the line (n) down
|
||||
#define ANSI_CURSOR_LINE_UP(n) CSI_CODE(#n "F") ///< Move cursor to the beginning of the line (n) up
|
||||
#define ANSI_CURSOR_POSITION(n, m) CSI_CODE(#n ";" #m "H") ///< Move cursor to position (n, m)
|
||||
/** @} */
|
||||
|
||||
//------------- Screen -------------//
|
||||
/** \defgroup group_ansi_screen Screen Control
|
||||
* @{ */
|
||||
#define ANSI_ERASE_SCREEN(n) CSI_CODE(#n "J") ///< Erase the screen
|
||||
#define ANSI_ERASE_LINE(n) CSI_CODE(#n "K") ///< Erase the line (n)
|
||||
#define ANSI_SCROLL_UP(n) CSI_CODE(#n "S") ///< Scroll the whole page up (n) lines
|
||||
#define ANSI_SCROLL_DOWN(n) CSI_CODE(#n "T") ///< Scroll the whole page down (n) lines
|
||||
/** @} */
|
||||
|
||||
//------------- Text Color -------------//
|
||||
/** \defgroup group_ansi_text Text Color
|
||||
* @{ */
|
||||
#define ANSI_TEXT_BLACK CSI_SGR(30)
|
||||
#define ANSI_TEXT_RED CSI_SGR(31)
|
||||
#define ANSI_TEXT_GREEN CSI_SGR(32)
|
||||
#define ANSI_TEXT_YELLOW CSI_SGR(33)
|
||||
#define ANSI_TEXT_BLUE CSI_SGR(34)
|
||||
#define ANSI_TEXT_MAGENTA CSI_SGR(35)
|
||||
#define ANSI_TEXT_CYAN CSI_SGR(36)
|
||||
#define ANSI_TEXT_WHITE CSI_SGR(37)
|
||||
#define ANSI_TEXT_DEFAULT CSI_SGR(39)
|
||||
/** @} */
|
||||
|
||||
//------------- Background Color -------------//
|
||||
/** \defgroup group_ansi_background Background Color
|
||||
* @{ */
|
||||
#define ANSI_BG_BLACK CSI_SGR(40)
|
||||
#define ANSI_BG_RED CSI_SGR(41)
|
||||
#define ANSI_BG_GREEN CSI_SGR(42)
|
||||
#define ANSI_BG_YELLOW CSI_SGR(43)
|
||||
#define ANSI_BG_BLUE CSI_SGR(44)
|
||||
#define ANSI_BG_MAGENTA CSI_SGR(45)
|
||||
#define ANSI_BG_CYAN CSI_SGR(46)
|
||||
#define ANSI_BG_WHITE CSI_SGR(47)
|
||||
#define ANSI_BG_DEFAULT CSI_SGR(49)
|
||||
/** @} */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _TUSB_ANSI_ESC_CODE_H_ */
|
||||
|
||||
/** @} */
|
|
@ -1,232 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2018, hathach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "board_api.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// newlib read()/write() retarget
|
||||
//--------------------------------------------------------------------+
|
||||
#ifdef __ICCARM__
|
||||
#define sys_write __write
|
||||
#define sys_read __read
|
||||
#elif defined(__MSP430__) || defined(__RX__)
|
||||
#define sys_write write
|
||||
#define sys_read read
|
||||
#else
|
||||
#define sys_write _write
|
||||
#define sys_read _read
|
||||
#endif
|
||||
|
||||
int sys_write(int fhdl, const char *buf, size_t count) TU_ATTR_USED;
|
||||
int sys_read(int fhdl, char *buf, size_t count) TU_ATTR_USED;
|
||||
|
||||
#if defined(LOGGER_RTT)
|
||||
// Logging with RTT
|
||||
|
||||
// If using SES IDE, use the Syscalls/SEGGER_RTT_Syscalls_SES.c instead
|
||||
#if !(defined __SES_ARM) && !(defined __SES_RISCV) && !(defined __CROSSWORKS_ARM)
|
||||
#include "SEGGER_RTT.h"
|
||||
|
||||
int sys_write(int fhdl, const char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
SEGGER_RTT_Write(0, (const char *) buf, (int) count);
|
||||
return (int) count;
|
||||
}
|
||||
|
||||
int sys_read(int fhdl, char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
int rd = (int) SEGGER_RTT_Read(0, buf, count);
|
||||
return (rd > 0) ? rd : -1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#elif defined(LOGGER_SWO)
|
||||
// Logging with SWO for ARM Cortex
|
||||
#include "board_mcu.h"
|
||||
|
||||
int sys_write (int fhdl, const char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
uint8_t const* buf8 = (uint8_t const*) buf;
|
||||
|
||||
for(size_t i=0; i<count; i++) {
|
||||
ITM_SendChar(buf8[i]);
|
||||
}
|
||||
|
||||
return (int) count;
|
||||
}
|
||||
|
||||
int sys_read (int fhdl, char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
(void) buf;
|
||||
(void) count;
|
||||
return 0;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// Default logging with on-board UART
|
||||
int sys_write (int fhdl, const char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
return board_uart_write(buf, (int) count);
|
||||
}
|
||||
|
||||
int sys_read (int fhdl, char *buf, size_t count) {
|
||||
(void) fhdl;
|
||||
int rd = board_uart_read((uint8_t*) buf, (int) count);
|
||||
return (rd > 0) ? rd : -1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
//int _close(int fhdl) {
|
||||
// (void) fhdl;
|
||||
// return 0;
|
||||
//}
|
||||
|
||||
//int _fstat(int file, struct stat *st) {
|
||||
// memset(st, 0, sizeof(*st));
|
||||
// st->st_mode = S_IFCHR;
|
||||
//}
|
||||
|
||||
// Clang use picolibc
|
||||
#if defined(__clang__)
|
||||
static int cl_putc(char c, FILE *f) {
|
||||
(void) f;
|
||||
return sys_write(0, &c, 1);
|
||||
}
|
||||
|
||||
static int cl_getc(FILE* f) {
|
||||
(void) f;
|
||||
char c;
|
||||
return sys_read(0, &c, 1) > 0 ? c : -1;
|
||||
}
|
||||
|
||||
static FILE __stdio = FDEV_SETUP_STREAM(cl_putc, cl_getc, NULL, _FDEV_SETUP_RW);
|
||||
FILE *const stdin = &__stdio;
|
||||
__strong_reference(stdin, stdout);
|
||||
__strong_reference(stdin, stderr);
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board API
|
||||
//--------------------------------------------------------------------+
|
||||
int board_getchar(void) {
|
||||
char c;
|
||||
return (sys_read(0, &c, 1) > 0) ? (int) c : (-1);
|
||||
}
|
||||
|
||||
|
||||
uint32_t tusb_time_millis_api(void) {
|
||||
return board_millis();
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------
|
||||
// FreeRTOS hooks
|
||||
//--------------------------------------------------------------------
|
||||
#if CFG_TUSB_OS == OPT_OS_FREERTOS && !TUSB_MCU_VENDOR_ESPRESSIF
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
|
||||
void vApplicationMallocFailedHook(void) {
|
||||
taskDISABLE_INTERRUPTS();
|
||||
TU_ASSERT(false, );
|
||||
}
|
||||
|
||||
void vApplicationStackOverflowHook(xTaskHandle pxTask, char *pcTaskName) {
|
||||
(void) pxTask;
|
||||
(void) pcTaskName;
|
||||
|
||||
taskDISABLE_INTERRUPTS();
|
||||
TU_ASSERT(false, );
|
||||
}
|
||||
|
||||
/* configSUPPORT_STATIC_ALLOCATION is set to 1, so the application must provide an
|
||||
* implementation of vApplicationGetIdleTaskMemory() to provide the memory that is
|
||||
* used by the Idle task. */
|
||||
void vApplicationGetIdleTaskMemory( StaticTask_t **ppxIdleTaskTCBBuffer, StackType_t **ppxIdleTaskStackBuffer, uint32_t *pulIdleTaskStackSize ) {
|
||||
/* If the buffers to be provided to the Idle task are declared inside this
|
||||
* function then they must be declared static - otherwise they will be allocated on
|
||||
* the stack and so not exists after this function exits. */
|
||||
static StaticTask_t xIdleTaskTCB;
|
||||
static StackType_t uxIdleTaskStack[ configMINIMAL_STACK_SIZE ];
|
||||
|
||||
/* Pass out a pointer to the StaticTask_t structure in which the Idle task's
|
||||
state will be stored. */
|
||||
*ppxIdleTaskTCBBuffer = &xIdleTaskTCB;
|
||||
|
||||
/* Pass out the array that will be used as the Idle task's stack. */
|
||||
*ppxIdleTaskStackBuffer = uxIdleTaskStack;
|
||||
|
||||
/* Pass out the size of the array pointed to by *ppxIdleTaskStackBuffer.
|
||||
Note that, as the array is necessarily of type StackType_t,
|
||||
configMINIMAL_STACK_SIZE is specified in words, not bytes. */
|
||||
*pulIdleTaskStackSize = configMINIMAL_STACK_SIZE;
|
||||
}
|
||||
|
||||
/* configSUPPORT_STATIC_ALLOCATION and configUSE_TIMERS are both set to 1, so the
|
||||
* application must provide an implementation of vApplicationGetTimerTaskMemory()
|
||||
* to provide the memory that is used by the Timer service task. */
|
||||
void vApplicationGetTimerTaskMemory( StaticTask_t **ppxTimerTaskTCBBuffer, StackType_t **ppxTimerTaskStackBuffer, uint32_t *pulTimerTaskStackSize ) {
|
||||
/* If the buffers to be provided to the Timer task are declared inside this
|
||||
* function then they must be declared static - otherwise they will be allocated on
|
||||
* the stack and so not exists after this function exits. */
|
||||
static StaticTask_t xTimerTaskTCB;
|
||||
static StackType_t uxTimerTaskStack[ configTIMER_TASK_STACK_DEPTH ];
|
||||
|
||||
/* Pass out a pointer to the StaticTask_t structure in which the Timer
|
||||
task's state will be stored. */
|
||||
*ppxTimerTaskTCBBuffer = &xTimerTaskTCB;
|
||||
|
||||
/* Pass out the array that will be used as the Timer task's stack. */
|
||||
*ppxTimerTaskStackBuffer = uxTimerTaskStack;
|
||||
|
||||
/* Pass out the size of the array pointed to by *ppxTimerTaskStackBuffer.
|
||||
Note that, as the array is necessarily of type StackType_t,
|
||||
configTIMER_TASK_STACK_DEPTH is specified in words, not bytes. */
|
||||
*pulTimerTaskStackSize = configTIMER_TASK_STACK_DEPTH;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X
|
||||
#include "iodefine.h"
|
||||
void vApplicationSetupTimerInterrupt(void) {
|
||||
/* Enable CMT0 */
|
||||
unsigned short oldPRCR = SYSTEM.PRCR.WORD;
|
||||
SYSTEM.PRCR.WORD = (0xA5u<<8) | TU_BIT(1);
|
||||
MSTP(CMT0) = 0;
|
||||
SYSTEM.PRCR.WORD = (0xA5u<<8) | oldPRCR;
|
||||
|
||||
CMT0.CMCNT = 0;
|
||||
CMT0.CMCOR = (unsigned short)(((configPERIPHERAL_CLOCK_HZ/configTICK_RATE_HZ)-1)/128);
|
||||
CMT0.CMCR.WORD = TU_BIT(6) | 2;
|
||||
IR(CMT0, CMI0) = 0;
|
||||
IPR(CMT0, CMI0) = configKERNEL_INTERRUPT_PRIORITY;
|
||||
IEN(CMT0, CMI0) = 1;
|
||||
CMT.CMSTR0.BIT.STR0 = 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
|
@ -1,197 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2019 Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_API_H_
|
||||
#define BOARD_API_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include <stdint.h>
|
||||
#include <inttypes.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "tusb.h"
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_FREERTOS
|
||||
#if TUSB_MCU_VENDOR_ESPRESSIF
|
||||
// ESP-IDF need "freertos/" prefix in include path.
|
||||
// CFG_TUSB_OS_INC_PATH should be defined accordingly.
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "freertos/queue.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/timers.h"
|
||||
#else
|
||||
#include "FreeRTOS.h"
|
||||
#include "semphr.h"
|
||||
#include "queue.h"
|
||||
#include "task.h"
|
||||
#include "timers.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Define the default baudrate
|
||||
#ifndef CFG_BOARD_UART_BAUDRATE
|
||||
#define CFG_BOARD_UART_BAUDRATE 115200 ///< Default baud rate
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board Porting API
|
||||
// For simplicity, only one LED and one Button are used
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// Initialize on-board peripherals : led, button, uart and USB
|
||||
void board_init(void);
|
||||
|
||||
// Init board after tinyusb is initialized
|
||||
void board_init_after_tusb(void) TU_ATTR_WEAK;
|
||||
|
||||
// Jump to bootloader
|
||||
void board_reset_to_bootloader(void) TU_ATTR_WEAK;
|
||||
|
||||
// Turn LED on or off
|
||||
void board_led_write(bool state);
|
||||
|
||||
// Control led pattern using phase duration in ms.
|
||||
// For each phase, LED is toggle then repeated, board_led_task() is required to be called
|
||||
//void board_led_pattern(uint32_t const phase_ms[], uint8_t count);
|
||||
|
||||
// Get the current state of button
|
||||
// a '1' means active (pressed), a '0' means inactive.
|
||||
uint32_t board_button_read(void);
|
||||
|
||||
// Get board unique ID for USB serial number. Return number of bytes. Note max_len is typically 16
|
||||
TU_ATTR_WEAK size_t board_get_unique_id(uint8_t id[], size_t max_len);
|
||||
|
||||
// Get characters from UART. Return number of read bytes
|
||||
int board_uart_read(uint8_t *buf, int len);
|
||||
|
||||
// Send characters to UART. Return number of sent bytes
|
||||
int board_uart_write(void const *buf, int len);
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
// Get current milliseconds, must be implemented when no RTOS is used
|
||||
uint32_t board_millis(void);
|
||||
|
||||
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
|
||||
static inline uint32_t board_millis(void) {
|
||||
return ( ( ((uint64_t) xTaskGetTickCount()) * 1000) / configTICK_RATE_HZ );
|
||||
}
|
||||
|
||||
#elif CFG_TUSB_OS == OPT_OS_MYNEWT
|
||||
static inline uint32_t board_millis(void) {
|
||||
return os_time_ticks_to_ms32( os_time_get() );
|
||||
}
|
||||
|
||||
#elif CFG_TUSB_OS == OPT_OS_PICO
|
||||
#include "pico/time.h"
|
||||
static inline uint32_t board_millis(void) {
|
||||
return to_ms_since_boot(get_absolute_time());
|
||||
}
|
||||
|
||||
#elif CFG_TUSB_OS == OPT_OS_RTTHREAD
|
||||
static inline uint32_t board_millis(void) {
|
||||
return (((uint64_t)rt_tick_get()) * 1000 / RT_TICK_PER_SECOND);
|
||||
}
|
||||
|
||||
#elif CFG_TUSB_OS == OPT_OS_CUSTOM
|
||||
// Implement your own board_millis() in any of .c file
|
||||
uint32_t board_millis(void);
|
||||
|
||||
#else
|
||||
#error "board_millis() is not implemented for this OS"
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Helper functions
|
||||
//--------------------------------------------------------------------+
|
||||
static inline void board_led_on(void) {
|
||||
board_led_write(true);
|
||||
}
|
||||
|
||||
static inline void board_led_off(void) {
|
||||
board_led_write(false);
|
||||
}
|
||||
|
||||
// Get USB Serial number string from unique ID if available. Return number of character.
|
||||
// Input is string descriptor from index 1 (index 0 is type + len)
|
||||
static inline size_t board_usb_get_serial(uint16_t desc_str1[], size_t max_chars) {
|
||||
uint8_t uid[16] TU_ATTR_ALIGNED(4);
|
||||
size_t uid_len;
|
||||
|
||||
// TODO work with make, but not working with esp32s3 cmake
|
||||
if ( board_get_unique_id ) {
|
||||
uid_len = board_get_unique_id(uid, sizeof(uid));
|
||||
}else {
|
||||
// fixed serial string is 01234567889ABCDEF
|
||||
uint32_t* uid32 = (uint32_t*) (uintptr_t) uid;
|
||||
uid32[0] = 0x67452301;
|
||||
uid32[1] = 0xEFCDAB89;
|
||||
uid_len = 8;
|
||||
}
|
||||
|
||||
if ( uid_len > max_chars / 2 ) uid_len = max_chars / 2;
|
||||
|
||||
for ( size_t i = 0; i < uid_len; i++ ) {
|
||||
for ( size_t j = 0; j < 2; j++ ) {
|
||||
const char nibble_to_hex[16] = {
|
||||
'0', '1', '2', '3', '4', '5', '6', '7',
|
||||
'8', '9', 'A', 'B', 'C', 'D', 'E', 'F'
|
||||
};
|
||||
uint8_t const nibble = (uid[i] >> (j * 4)) & 0xf;
|
||||
desc_str1[i * 2 + (1 - j)] = nibble_to_hex[nibble]; // UTF-16-LE
|
||||
}
|
||||
}
|
||||
|
||||
return 2 * uid_len;
|
||||
}
|
||||
|
||||
// TODO remove
|
||||
static inline void board_delay(uint32_t ms) {
|
||||
uint32_t start_ms = board_millis();
|
||||
while ( board_millis() - start_ms < ms ) {
|
||||
// take chance to run usb background
|
||||
#if CFG_TUD_ENABLED
|
||||
tud_task();
|
||||
#endif
|
||||
|
||||
#if CFG_TUH_ENABLED
|
||||
tuh_task();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// stdio getchar() is blocking, this is non-blocking version
|
||||
int board_getchar(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,193 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020, Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef BOARD_MCU_H_
|
||||
#define BOARD_MCU_H_
|
||||
|
||||
#include "tusb_option.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Low Level MCU header include. Example should be
|
||||
// platform independent and mostly doesn't need to include this file.
|
||||
// However there are still certain situation where this file is needed:
|
||||
// - FreeRTOSConfig.h to set up correct clock and NVIC interrupts for ARM Cortex
|
||||
// - SWO logging for Cortex M with ITM_SendChar() / ITM_ReceiveChar()
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// Include order follows OPT_MCU_ number
|
||||
#if TU_CHECK_MCU(OPT_MCU_LPC11UXX, OPT_MCU_LPC13XX, OPT_MCU_LPC15XX) || \
|
||||
TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC18XX) || \
|
||||
TU_CHECK_MCU(OPT_MCU_LPC40XX, OPT_MCU_LPC43XX)
|
||||
#include "chip.h"
|
||||
|
||||
#elif TU_CHECK_MCU(OPT_MCU_LPC51UXX, OPT_MCU_LPC54XXX, OPT_MCU_LPC55XX, OPT_MCU_MCXN9)
|
||||
#include "fsl_device_registers.h"
|
||||
|
||||
#elif TU_CHECK_MCU(OPT_MCU_KINETIS_KL, OPT_MCU_KINETIS_K32L, OPT_MCU_KINETIS_K)
|
||||
#include "fsl_device_registers.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_NRF5X
|
||||
#include "nrf.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_SAMD11 || CFG_TUSB_MCU == OPT_MCU_SAMD21 || \
|
||||
CFG_TUSB_MCU == OPT_MCU_SAMD51 || CFG_TUSB_MCU == OPT_MCU_SAME5X || \
|
||||
CFG_TUSB_MCU == OPT_MCU_SAML22 || CFG_TUSB_MCU == OPT_MCU_SAML21
|
||||
#include "sam.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_SAMG
|
||||
#undef LITTLE_ENDIAN // hack to suppress "LITTLE_ENDIAN" redefined
|
||||
#include "sam.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F0
|
||||
#include "stm32f0xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F1
|
||||
#include "stm32f1xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F2
|
||||
#include "stm32f2xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F3
|
||||
#include "stm32f3xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F4
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32F7
|
||||
#include "stm32f7xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32G4
|
||||
#include "stm32g4xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32H5
|
||||
#include "stm32h5xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32H7
|
||||
#include "stm32h7xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32L0
|
||||
#include "stm32l0xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32L1
|
||||
#include "stm32l1xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32L4
|
||||
#include "stm32l4xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32WB
|
||||
#include "stm32wbxx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32U5
|
||||
#include "stm32u5xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32G0
|
||||
#include "stm32g0xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_STM32C0
|
||||
#include "stm32c0xx.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_CXD56
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MSP430x5xx
|
||||
#include "msp430.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MSP432E4
|
||||
#include "msp.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_VALENTYUSB_EPTRI
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MIMXRT1XXX
|
||||
#include "fsl_device_registers.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_NUC120
|
||||
#include "NUC100Series.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_NUC121 || CFG_TUSB_MCU == OPT_MCU_NUC126
|
||||
#include "NuMicro.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_NUC505
|
||||
#include "NUC505Series.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_ESP32S2
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_ESP32S3
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_DA1469X
|
||||
#include "DA1469xAB.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_RP2040
|
||||
#include "pico.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_EFM32GG
|
||||
#include "em_device.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_RAXXX
|
||||
#include "bsp_api.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_GD32VF103
|
||||
#include "gd32vf103.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MM32F327X
|
||||
#include "mm32_device.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_XMC4000
|
||||
#include "xmc_device.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_TM4C123
|
||||
#include "TM4C123.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_CH32F20X
|
||||
#include "ch32f20x.h"
|
||||
|
||||
#elif TU_CHECK_MCU(OPT_MCU_BCM2711, OPT_MCU_BCM2835, OPT_MCU_BCM2837)
|
||||
// no header needed
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MAX32690
|
||||
#include "max32690.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MAX32650
|
||||
#include "max32650.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MAX32666
|
||||
#include "max32665.h"
|
||||
|
||||
#elif CFG_TUSB_MCU == OPT_MCU_MAX78002
|
||||
#include "max78002.h"
|
||||
|
||||
#else
|
||||
#error "Missing MCU header"
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* BOARD_MCU_H_ */
|
|
@ -1,8 +0,0 @@
|
|||
set(CMAKE_SYSTEM_PROCESSOR arm1176jzf-s CACHE INTERNAL "System Processor")
|
||||
#set(SUFFIX "")
|
||||
|
||||
function(update_board TARGET)
|
||||
target_compile_definitions(${TARGET} PUBLIC
|
||||
BCM_VERSION=2835
|
||||
)
|
||||
endfunction()
|
|
@ -1,38 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020, Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -1,5 +0,0 @@
|
|||
CPU_CORE = arm1176jzf-s
|
||||
CFLAGS += -DBCM_VERSION=2835 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_BCM2835
|
||||
|
||||
SUFFIX =
|
|
@ -1,159 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2019 Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
// Suppress warning caused by mcu driver
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-qual"
|
||||
#pragma GCC diagnostic ignored "-Wredundant-decls"
|
||||
#endif
|
||||
|
||||
#include "broadcom/cpu.h"
|
||||
#include "broadcom/gpio.h"
|
||||
#include "broadcom/interrupts.h"
|
||||
#include "broadcom/mmu.h"
|
||||
#include "broadcom/caches.h"
|
||||
#include "broadcom/vcmailbox.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
// LED
|
||||
#define LED_PIN 18
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// UART TX
|
||||
#define UART_TX_PIN 14
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
void USB_IRQHandler(void) {
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
void board_init(void) {
|
||||
setup_mmu_flat_map();
|
||||
init_caches();
|
||||
|
||||
// LED
|
||||
gpio_set_function(LED_PIN, GPIO_FUNCTION_OUTPUT);
|
||||
gpio_set_pull(LED_PIN, BP_PULL_NONE);
|
||||
board_led_write(true);
|
||||
|
||||
// Uart
|
||||
COMPLETE_MEMORY_READS;
|
||||
AUX->ENABLES_b.UART_1 = true;
|
||||
|
||||
UART1->IER = 0;
|
||||
UART1->CNTL = 0;
|
||||
UART1->LCR_b.DATA_SIZE = UART1_LCR_DATA_SIZE_MODE_8BIT;
|
||||
UART1->MCR = 0;
|
||||
UART1->IER = 0;
|
||||
|
||||
uint32_t source_clock = vcmailbox_get_clock_rate_measured(VCMAILBOX_CLOCK_CORE);
|
||||
UART1->BAUD = ((source_clock / (115200 * 8)) - 1);
|
||||
UART1->CNTL |= UART1_CNTL_TX_ENABLE_Msk;
|
||||
COMPLETE_MEMORY_READS;
|
||||
|
||||
gpio_set_function(UART_TX_PIN, GPIO_FUNCTION_ALT5);
|
||||
|
||||
// Turn on USB peripheral.
|
||||
vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true);
|
||||
|
||||
// Timer 1/1024 second tick
|
||||
SYSTMR->CS_b.M1 = 1;
|
||||
SYSTMR->C1 = SYSTMR->CLO + 977;
|
||||
BP_EnableIRQ(TIMER_1_IRQn);
|
||||
|
||||
BP_SetPriority(USB_IRQn, 0x00);
|
||||
BP_ClearPendingIRQ(USB_IRQn);
|
||||
BP_EnableIRQ(USB_IRQn);
|
||||
BP_EnableIRQs();
|
||||
}
|
||||
|
||||
void board_led_write(bool state) {
|
||||
gpio_set_value(LED_PIN, state ? LED_STATE_ON : (1 - LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const* buf, int len) {
|
||||
for (int i = 0; i < len; i++) {
|
||||
const char* cbuf = buf;
|
||||
while (!UART1->STAT_b.TX_READY) {}
|
||||
if (cbuf[i] == '\n') {
|
||||
UART1->IO = '\r';
|
||||
while (!UART1->STAT_b.TX_READY) {}
|
||||
}
|
||||
UART1->IO = cbuf[i];
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
void TIMER_1_IRQHandler(void) {
|
||||
system_ticks++;
|
||||
SYSTMR->C1 += 977;
|
||||
SYSTMR->CS_b.M1 = 1;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void HardFault_Handler(void) {
|
||||
// asm("bkpt");
|
||||
}
|
||||
|
||||
// Required by __libc_init_array in startup code if we are compiling using
|
||||
// -nostdlib/-nostartfiles.
|
||||
void _init(void) {
|
||||
|
||||
}
|
|
@ -1,111 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
set(SDK_DIR ${TOP}/hw/mcu/broadcom)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS BCM2835 CACHE INTERNAL "")
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${SDK_DIR}/broadcom/link.ld)
|
||||
endif ()
|
||||
set(LD_FILE_Clang ${LD_FILE_GNU})
|
||||
|
||||
set(STARTUP_FILE_GNU ${SDK_DIR}/broadcom/boot.s)
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${SDK_DIR}/broadcom/gen/interrupt_handlers.c
|
||||
${SDK_DIR}/broadcom/gpio.c
|
||||
${SDK_DIR}/broadcom/interrupts.c
|
||||
${SDK_DIR}/broadcom/mmu.c
|
||||
${SDK_DIR}/broadcom/caches.c
|
||||
${SDK_DIR}/broadcom/vcmailbox.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
-O0
|
||||
-ffreestanding
|
||||
-mgeneral-regs-only
|
||||
-fno-exceptions
|
||||
-std=c17
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${SDK_DIR}
|
||||
)
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
"LINKER:--entry=_start"
|
||||
--specs=nosys.specs
|
||||
-nostartfiles
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_Clang}"
|
||||
"LINKER:--entry=_start"
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_BCM2835 ${RTOS})
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/synopsys/dwc2/dcd_dwc2.c
|
||||
${TOP}/src/portable/synopsys/dwc2/hcd_dwc2.c
|
||||
${TOP}/src/portable/synopsys/dwc2/dwc2_common.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_jlink(${TARGET})
|
||||
endfunction()
|
|
@ -1,45 +0,0 @@
|
|||
MCU_DIR = hw/mcu/broadcom
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
|
||||
CFLAGS += \
|
||||
-Wall \
|
||||
-O0 \
|
||||
-ffreestanding \
|
||||
-nostdlib \
|
||||
-nostartfiles \
|
||||
-mgeneral-regs-only \
|
||||
-fno-exceptions \
|
||||
-std=c17
|
||||
|
||||
CROSS_COMPILE = arm-none-eabi-
|
||||
|
||||
# mcu driver cause following warnings
|
||||
CFLAGS += -Wno-error=cast-qual -Wno-error=redundant-decls
|
||||
|
||||
SRC_C += \
|
||||
src/portable/synopsys/dwc2/dcd_dwc2.c \
|
||||
src/portable/synopsys/dwc2/hcd_dwc2.c \
|
||||
src/portable/synopsys/dwc2/dwc2_common.c \
|
||||
$(MCU_DIR)/broadcom/gen/interrupt_handlers.c \
|
||||
$(MCU_DIR)/broadcom/gpio.c \
|
||||
$(MCU_DIR)/broadcom/interrupts.c \
|
||||
$(MCU_DIR)/broadcom/mmu.c \
|
||||
$(MCU_DIR)/broadcom/caches.c \
|
||||
$(MCU_DIR)/broadcom/vcmailbox.c
|
||||
|
||||
LD_FILE = $(MCU_DIR)/broadcom/link$(SUFFIX).ld
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(MCU_DIR)
|
||||
|
||||
SRC_S += $(MCU_DIR)/broadcom/boot$(SUFFIX).s
|
||||
|
||||
$(BUILD)/kernel$(SUFFIX).img: $(BUILD)/$(PROJECT).elf
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
# Copy to kernel to netboot drive or SD card
|
||||
# Change destinaation to fit your need
|
||||
flash: $(BUILD)/kernel$(SUFFIX).img
|
||||
@$(CP) $< /home/$(USER)/Documents/code/pi_tinyusb/boot_cpy
|
|
@ -1,5 +0,0 @@
|
|||
set(CMAKE_SYSTEM_PROCESSOR cortex-a72 CACHE INTERNAL "System Processor")
|
||||
set(BCM_VERSION 2711)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -1,38 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020, Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -1,3 +0,0 @@
|
|||
CPU_CORE = cortex-a72
|
||||
CFLAGS += -DBCM_VERSION=2711 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_BCM2711
|
|
@ -1,5 +0,0 @@
|
|||
set(CMAKE_SYSTEM_PROCESSOR cortex-a53 CACHE INTERNAL "System Processor")
|
||||
set(BCM_VERSION 2837)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -1,38 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020, Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -1,3 +0,0 @@
|
|||
CPU_CORE = cortex-a53
|
||||
CFLAGS += -DBCM_VERSION=2837 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_BCM2837
|
|
@ -1,159 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2019 Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
// Suppress warning caused by mcu driver
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-qual"
|
||||
#pragma GCC diagnostic ignored "-Wredundant-decls"
|
||||
#endif
|
||||
|
||||
#include "broadcom/cpu.h"
|
||||
#include "broadcom/gpio.h"
|
||||
#include "broadcom/interrupts.h"
|
||||
#include "broadcom/mmu.h"
|
||||
#include "broadcom/caches.h"
|
||||
#include "broadcom/vcmailbox.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
// LED
|
||||
#define LED_PIN 18
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// UART TX
|
||||
#define UART_TX_PIN 14
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
void USB_IRQHandler(void) {
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
void board_init(void) {
|
||||
setup_mmu_flat_map();
|
||||
init_caches();
|
||||
|
||||
// LED
|
||||
gpio_set_function(LED_PIN, GPIO_FUNCTION_OUTPUT);
|
||||
gpio_set_pull(LED_PIN, BP_PULL_NONE);
|
||||
board_led_write(true);
|
||||
|
||||
// Uart
|
||||
COMPLETE_MEMORY_READS;
|
||||
AUX->ENABLES_b.UART_1 = true;
|
||||
|
||||
UART1->IER = 0;
|
||||
UART1->CNTL = 0;
|
||||
UART1->LCR_b.DATA_SIZE = UART1_LCR_DATA_SIZE_MODE_8BIT;
|
||||
UART1->MCR = 0;
|
||||
UART1->IER = 0;
|
||||
|
||||
uint32_t source_clock = vcmailbox_get_clock_rate_measured(VCMAILBOX_CLOCK_CORE);
|
||||
UART1->BAUD = ((source_clock / (115200 * 8)) - 1);
|
||||
UART1->CNTL |= UART1_CNTL_TX_ENABLE_Msk;
|
||||
COMPLETE_MEMORY_READS;
|
||||
|
||||
gpio_set_function(UART_TX_PIN, GPIO_FUNCTION_ALT5);
|
||||
|
||||
// Turn on USB peripheral.
|
||||
vcmailbox_set_power_state(VCMAILBOX_DEVICE_USB_HCD, true);
|
||||
|
||||
// Timer 1/1024 second tick
|
||||
SYSTMR->CS_b.M1 = 1;
|
||||
SYSTMR->C1 = SYSTMR->CLO + 977;
|
||||
BP_EnableIRQ(TIMER_1_IRQn);
|
||||
|
||||
BP_SetPriority(USB_IRQn, 0x00);
|
||||
BP_ClearPendingIRQ(USB_IRQn);
|
||||
BP_EnableIRQ(USB_IRQn);
|
||||
BP_EnableIRQs();
|
||||
}
|
||||
|
||||
void board_led_write(bool state) {
|
||||
gpio_set_value(LED_PIN, state ? LED_STATE_ON : (1 - LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const* buf, int len) {
|
||||
for (int i = 0; i < len; i++) {
|
||||
const char* cbuf = buf;
|
||||
while (!UART1->STAT_b.TX_READY) {}
|
||||
if (cbuf[i] == '\n') {
|
||||
UART1->IO = '\r';
|
||||
while (!UART1->STAT_b.TX_READY) {}
|
||||
}
|
||||
UART1->IO = cbuf[i];
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
void TIMER_1_IRQHandler(void) {
|
||||
system_ticks++;
|
||||
SYSTMR->C1 += 977;
|
||||
SYSTMR->CS_b.M1 = 1;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void HardFault_Handler(void) {
|
||||
// asm("bkpt");
|
||||
}
|
||||
|
||||
// Required by __libc_init_array in startup code if we are compiling using
|
||||
// -nostdlib/-nostartfiles.
|
||||
void _init(void) {
|
||||
|
||||
}
|
|
@ -1,118 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
set(SDK_DIR ${TOP}/hw/mcu/broadcom)
|
||||
set(CMSIS_5 ${TOP}/lib/CMSIS_5)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/aarch64_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS BCM2711 BCM2835 CACHE INTERNAL "")
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${SDK_DIR}/broadcom/link8.ld)
|
||||
endif ()
|
||||
set(LD_FILE_Clang ${LD_FILE_GNU})
|
||||
|
||||
set(STARTUP_FILE_GNU ${SDK_DIR}/broadcom/boot8.s)
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${SDK_DIR}/broadcom/gen/interrupt_handlers.c
|
||||
${SDK_DIR}/broadcom/gpio.c
|
||||
${SDK_DIR}/broadcom/interrupts.c
|
||||
${SDK_DIR}/broadcom/mmu.c
|
||||
${SDK_DIR}/broadcom/caches.c
|
||||
${SDK_DIR}/broadcom/vcmailbox.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
-O0
|
||||
-ffreestanding
|
||||
-mgeneral-regs-only
|
||||
-fno-exceptions
|
||||
-std=c17
|
||||
)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
BCM_VERSION=${BCM_VERSION}
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${SDK_DIR}
|
||||
${CMSIS_5}/CMSIS/Core_A/Include
|
||||
)
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
# target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
# )
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
"LINKER:--entry=_start"
|
||||
--specs=nosys.specs
|
||||
-nostartfiles
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_Clang}"
|
||||
"LINKER:--entry=_start"
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_BCM${BCM_VERSION} ${RTOS})
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/synopsys/dwc2/dcd_dwc2.c
|
||||
${TOP}/src/portable/synopsys/dwc2/hcd_dwc2.c
|
||||
${TOP}/src/portable/synopsys/dwc2/dwc2_common.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_jlink(${TARGET})
|
||||
endfunction()
|
|
@ -1,45 +0,0 @@
|
|||
MCU_DIR = hw/mcu/broadcom
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
|
||||
CFLAGS += \
|
||||
-Wall \
|
||||
-O0 \
|
||||
-ffreestanding \
|
||||
-nostdlib \
|
||||
-nostartfiles \
|
||||
--specs=nosys.specs \
|
||||
-mgeneral-regs-only \
|
||||
-std=c17
|
||||
|
||||
CROSS_COMPILE = aarch64-none-elf-
|
||||
|
||||
# mcu driver cause following warnings
|
||||
CFLAGS += -Wno-error=cast-qual -Wno-error=redundant-decls
|
||||
|
||||
SRC_C += \
|
||||
src/portable/synopsys/dwc2/dcd_dwc2.c \
|
||||
src/portable/synopsys/dwc2/hcd_dwc2.c \
|
||||
src/portable/synopsys/dwc2/dwc2_common.c \
|
||||
$(MCU_DIR)/broadcom/gen/interrupt_handlers.c \
|
||||
$(MCU_DIR)/broadcom/gpio.c \
|
||||
$(MCU_DIR)/broadcom/interrupts.c \
|
||||
$(MCU_DIR)/broadcom/mmu.c \
|
||||
$(MCU_DIR)/broadcom/caches.c \
|
||||
$(MCU_DIR)/broadcom/vcmailbox.c
|
||||
|
||||
LD_FILE = $(MCU_DIR)/broadcom/link8.ld
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(MCU_DIR) \
|
||||
$(TOP)/lib/CMSIS_5/CMSIS/Core_A/Include
|
||||
|
||||
SRC_S += $(MCU_DIR)/broadcom/boot8.s
|
||||
|
||||
$(BUILD)/kernel8.img: $(BUILD)/$(PROJECT).elf
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
# Copy to kernel to netboot drive or SD card
|
||||
# Change destinaation to fit your need
|
||||
flash: $(BUILD)/kernel8.img
|
||||
@$(CP) $< /home/$(USER)/Documents/code/pi_tinyusb/boot_cpy
|
|
@ -1,82 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright 2021 Bridgetek Pte Ltd
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
// Note: This definition file covers all MM900EV1B, MM900EV2B, MM900EV3B,
|
||||
// MM900EV-Lite boards.
|
||||
// Each of these boards has an FT900 device.
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// UART to use on this board.
|
||||
#ifndef BOARD_UART
|
||||
#define BOARD_UART UART0
|
||||
#endif
|
||||
|
||||
// UART is on connector CN1.
|
||||
#ifndef BOARD_GPIO_UART0_TX
|
||||
#define BOARD_GPIO_UART0_TX 48 // Pin 4 of CN1.
|
||||
#endif
|
||||
#ifndef BOARD_GPIO_UART0_RX
|
||||
#define BOARD_GPIO_UART0_RX 49 // Pin 6 of CN1.
|
||||
#endif
|
||||
|
||||
// LED is connected to pins 17 (signal) and 15 (GND) of CN1.
|
||||
#ifndef BOARD_GPIO_LED
|
||||
#define BOARD_GPIO_LED 35
|
||||
#endif
|
||||
#ifndef BOARD_GPIO_LED_STATE_ON
|
||||
#define BOARD_GPIO_LED_STATE_ON 1
|
||||
#endif
|
||||
// Button is connected to pins 13 (signal) and 15 (GND) of CN1.
|
||||
#ifndef BOARD_GPIO_BUTTON
|
||||
#define BOARD_GPIO_BUTTON 56
|
||||
#endif
|
||||
// Button is pulled up and grounded for active.
|
||||
#ifndef BOARD_GPIO_BUTTON_STATE_ACTIVE
|
||||
#define BOARD_GPIO_BUTTON_STATE_ACTIVE 0
|
||||
#endif
|
||||
|
||||
// Enable the Remote Wakeup signalling.
|
||||
// Remote wakeup is wired to pin 40 of CN1.
|
||||
#ifndef BOARD_GPIO_REMOTE_WAKEUP
|
||||
#define BOARD_GPIO_REMOTE_WAKEUP 18
|
||||
#endif
|
||||
|
||||
// USB VBus signal is connected directly to the FT900.
|
||||
#ifndef BOARD_USBD_VBUS_DTC_PIN
|
||||
#define BOARD_USBD_VBUS_DTC_PIN 3
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,256 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright 2021 Bridgetek Pte Ltd
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
#include <ft900.h>
|
||||
#include <registers/ft900_registers.h>
|
||||
|
||||
#if CFG_TUD_ENABLED
|
||||
int8_t board_ft9xx_vbus(void); // Board specific implementation of VBUS detection for USB device.
|
||||
extern void ft9xx_usbd_pm_ISR(uint16_t pmcfg); // Interrupt handler for USB device power management
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_GPIO_REMOTE_WAKEUP
|
||||
void gpio_ISR(void);
|
||||
#endif
|
||||
void timer_ISR(void);
|
||||
volatile unsigned int timer_ms = 0;
|
||||
void board_pm_ISR(void);
|
||||
|
||||
#define WELCOME_MSG "\x1B[2J\x1B[H" \
|
||||
"MM900EVxB board\r\n"
|
||||
|
||||
// Initialize on-board peripherals : led, button, uart and USB
|
||||
void board_init(void)
|
||||
{
|
||||
sys_reset_all();
|
||||
|
||||
// Enable the UART Device.
|
||||
sys_enable(sys_device_uart0);
|
||||
// Set BOARD_UART GPIO function pins for TXD and RXD.
|
||||
#ifdef BOARD_GPIO_UART_TX
|
||||
gpio_function(BOARD_GPIO_UART_TX, pad_uart0_txd); /* UART0 TXD */
|
||||
#endif
|
||||
#ifdef BOARD_GPIO_UART_RX
|
||||
gpio_function(BOARD_GPIO_UART_RX, pad_uart0_rxd); /* UART0 RXD */
|
||||
#endif
|
||||
uart_open(BOARD_UART, /* Device */
|
||||
1, /* Prescaler = 1 */
|
||||
UART_DIVIDER_19200_BAUD, /* Divider = 1302 */
|
||||
uart_data_bits_8, /* No. Data Bits */
|
||||
uart_parity_none, /* Parity */
|
||||
uart_stop_bits_1); /* No. Stop Bits */
|
||||
// Print out a welcome message.
|
||||
// Use sizeof to avoid pulling in strlen unnecessarily.
|
||||
board_uart_write(WELCOME_MSG, sizeof(WELCOME_MSG));
|
||||
|
||||
#ifdef BOARD_GPIO_LED
|
||||
gpio_function(BOARD_GPIO_LED, pad_func_0);
|
||||
gpio_idrive(BOARD_GPIO_LED, pad_drive_12mA);
|
||||
gpio_dir(BOARD_GPIO_LED, pad_dir_output);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_GPIO_BUTTON
|
||||
gpio_function(BOARD_GPIO_BUTTON, pad_func_0);
|
||||
// Pull up if active low. Down if active high.
|
||||
gpio_pull(BOARD_GPIO_BUTTON, (BOARD_GPIO_BUTTON_STATE_ACTIVE == 0)?pad_pull_pullup:pad_pull_pulldown);
|
||||
gpio_dir(BOARD_GPIO_BUTTON, pad_dir_input);
|
||||
#endif
|
||||
|
||||
sys_enable(sys_device_timer_wdt);
|
||||
/* Timer A = 1ms */
|
||||
timer_prescaler(timer_select_a, 1000);
|
||||
timer_init(timer_select_a, 100, timer_direction_down, timer_prescaler_select_on, timer_mode_continuous);
|
||||
timer_enable_interrupt(timer_select_a);
|
||||
timer_start(timer_select_a);
|
||||
interrupt_attach(interrupt_timers, (int8_t)interrupt_timers, timer_ISR);
|
||||
|
||||
// Setup VBUS detect GPIO. If the device is connected then this
|
||||
// will set the MASK_SYS_PMCFG_DEV_DETECT_EN bit in PMCFG.
|
||||
gpio_interrupt_disable(BOARD_USBD_VBUS_DTC_PIN);
|
||||
gpio_function(BOARD_USBD_VBUS_DTC_PIN, pad_vbus_dtc);
|
||||
gpio_pull(BOARD_USBD_VBUS_DTC_PIN, pad_pull_pulldown);
|
||||
gpio_dir(BOARD_USBD_VBUS_DTC_PIN, pad_dir_input);
|
||||
|
||||
interrupt_attach(interrupt_0, (int8_t)interrupt_0, board_pm_ISR);
|
||||
|
||||
#ifdef BOARD_GPIO_REMOTE_WAKEUP
|
||||
// Configuring GPIO pin to wakeup.
|
||||
// Set up the wakeup pin.
|
||||
gpio_dir(BOARD_GPIO_REMOTE_WAKEUP, pad_dir_input);
|
||||
gpio_pull(BOARD_GPIO_REMOTE_WAKEUP, pad_pull_pullup);
|
||||
|
||||
// Attach an interrupt handler.
|
||||
interrupt_attach(interrupt_gpio, (uint8_t)interrupt_gpio, gpio_ISR);
|
||||
gpio_interrupt_enable(BOARD_GPIO_REMOTE_WAKEUP, gpio_int_edge_falling);
|
||||
#endif
|
||||
|
||||
uart_disable_interrupt(BOARD_UART, uart_interrupt_tx);
|
||||
uart_disable_interrupt(BOARD_UART, uart_interrupt_rx);
|
||||
|
||||
// Enable all peripheral interrupts.
|
||||
interrupt_enable_globally();
|
||||
|
||||
TU_LOG1("MM900EV1B board setup complete\r\n");
|
||||
};
|
||||
|
||||
void timer_ISR(void)
|
||||
{
|
||||
if (timer_is_interrupted(timer_select_a))
|
||||
{
|
||||
timer_ms++;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef BOARD_GPIO_REMOTE_WAKEUP
|
||||
void gpio_ISR(void)
|
||||
{
|
||||
if (gpio_is_interrupted(BOARD_GPIO_REMOTE_WAKEUP))
|
||||
{
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Power management ISR */
|
||||
void board_pm_ISR(void)
|
||||
{
|
||||
uint16_t pmcfg = SYS->PMCFG_H;
|
||||
|
||||
#if defined(__FT930__)
|
||||
if (pmcfg & MASK_SYS_PMCFG_SLAVE_PERI_IRQ_PEND)
|
||||
{
|
||||
// Clear d2xx hw engine wakeup.
|
||||
SYS->PMCFG_H = MASK_SYS_PMCFG_SLAVE_PERI_IRQ_PEND;
|
||||
}
|
||||
#endif
|
||||
if (pmcfg & MASK_SYS_PMCFG_PM_GPIO_IRQ_PEND)
|
||||
{
|
||||
// Clear GPIO wakeup pending.
|
||||
SYS->PMCFG_H = MASK_SYS_PMCFG_PM_GPIO_IRQ_PEND;
|
||||
}
|
||||
|
||||
#if defined(__FT900__)
|
||||
// USB device power management interrupts.
|
||||
if (pmcfg & (MASK_SYS_PMCFG_DEV_CONN_DEV |
|
||||
MASK_SYS_PMCFG_DEV_DIS_DEV |
|
||||
MASK_SYS_PMCFG_HOST_RST_DEV |
|
||||
MASK_SYS_PMCFG_HOST_RESUME_DEV)
|
||||
)
|
||||
{
|
||||
#if CFG_TUD_ENABLED
|
||||
ft9xx_usbd_pm_ISR(pmcfg);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if CFG_TUD_ENABLED
|
||||
int8_t board_ft9xx_vbus(void)
|
||||
{
|
||||
return gpio_read(BOARD_USBD_VBUS_DTC_PIN);
|
||||
}
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// Turn LED on or off
|
||||
void board_led_write(bool state)
|
||||
{
|
||||
#ifdef BOARD_GPIO_LED
|
||||
gpio_write(BOARD_GPIO_LED, (state == 0)?(BOARD_GPIO_LED_STATE_ON?0:1):BOARD_GPIO_LED_STATE_ON);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Get the current state of button
|
||||
// a '1' means active (pressed), a '0' means inactive.
|
||||
uint32_t board_button_read(void)
|
||||
{
|
||||
uint32_t state = 0;
|
||||
#ifdef BOARD_GPIO_BUTTON
|
||||
state = (gpio_read(BOARD_GPIO_BUTTON) == BOARD_GPIO_BUTTON_STATE_ACTIVE)?1:0;
|
||||
#endif
|
||||
return state;
|
||||
}
|
||||
|
||||
// Get characters from UART
|
||||
int board_uart_read(uint8_t *buf, int len)
|
||||
{
|
||||
int r = 0;
|
||||
|
||||
#ifdef BOARD_UART
|
||||
if (uart_rx_has_data(BOARD_UART))
|
||||
{
|
||||
r = uart_readn(BOARD_UART, (uint8_t *)buf, len);
|
||||
}
|
||||
#endif
|
||||
|
||||
return r;
|
||||
}
|
||||
|
||||
// Send characters to UART
|
||||
int board_uart_write(void const *buf, int len)
|
||||
{
|
||||
int r = 0;
|
||||
|
||||
#ifdef BOARD_UART
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-qual" // uart_writen does not have const for buffer parameter.
|
||||
r = uart_writen(BOARD_UART, (uint8_t *)((const void *)buf), len);
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
return r;
|
||||
}
|
||||
|
||||
// Get current milliseconds
|
||||
uint32_t board_millis(void)
|
||||
{
|
||||
uint32_t safe_ms;
|
||||
|
||||
CRITICAL_SECTION_BEGIN
|
||||
safe_ms = timer_ms;
|
||||
CRITICAL_SECTION_END
|
||||
|
||||
return safe_ms;
|
||||
}
|
||||
|
||||
// Restart the program
|
||||
// Called in the event of a watchdog timeout
|
||||
void chip_reboot(void)
|
||||
{
|
||||
// SOFT reset
|
||||
__asm__("call 0");
|
||||
#if 0
|
||||
// HARD reset
|
||||
// Initiates data transfer from Flash Memory to Data Memory (DBG_CMDF2D3)
|
||||
// followed by a system reboot
|
||||
dbg_memory_copy(0xfe, 0, 0, 255);
|
||||
#endif
|
||||
}
|
|
@ -1,67 +0,0 @@
|
|||
# GCC prefix for FT90X compile tools.
|
||||
CROSS_COMPILE = ft32-elf-
|
||||
SKIP_NANOLIB = 1
|
||||
|
||||
# Set to use FT90X prebuilt libraries.
|
||||
FT9XX_PREBUILT_LIBS = 0
|
||||
ifeq ($(FT9XX_PREBUILT_LIBS),1)
|
||||
# If the FT90X toolchain is installed on Windows systems then the SDK
|
||||
# include files and prebuilt libraries are at: %FT90X_TOOLCHAIN%/hardware
|
||||
FT9XX_SDK = $(FT90X_TOOLCHAIN)/hardware
|
||||
INC += "$(FT9XX_SDK)/include"
|
||||
else
|
||||
# The submodule BRTSG-FOSS/ft90x-sdk contains header files and source
|
||||
# code for the Bridgetek SDK. This can be used instead of the prebuilt
|
||||
# library.
|
||||
DEPS_SUBMODULES += hw/mcu/bridgetek/ft9xx/ft90x-sdk
|
||||
# The SDK can be used to load specific files from the Bridgetek SDK.
|
||||
FT9XX_SDK = hw/mcu/bridgetek/ft9xx/ft90x-sdk/Source
|
||||
INC += "$(TOP)/$(FT9XX_SDK)/include"
|
||||
endif
|
||||
|
||||
# Add include files which are within the TinyUSB directory structure.
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH)
|
||||
|
||||
# Add required C Compiler flags for FT90X.
|
||||
CFLAGS += \
|
||||
-D__FT900__ \
|
||||
-fvar-tracking \
|
||||
-fvar-tracking-assignments \
|
||||
-fmessage-length=0 \
|
||||
-ffunction-sections \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_FT90X
|
||||
|
||||
# Maximum USB device speed supported by the board
|
||||
CFLAGS += -DBOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED
|
||||
|
||||
# lwip/src/core/raw.c:334:43: error: declaration of 'recv' shadows a global declaration
|
||||
CFLAGS += -Wno-error=shadow
|
||||
|
||||
# Set Linker flags.
|
||||
LD_FILE = hw/mcu/bridgetek/ft9xx/scripts/ldscript.ld
|
||||
LDFLAGS += $(addprefix -L,$(LDINC)) \
|
||||
-Xlinker --entry=_start \
|
||||
-Wl,-lc
|
||||
|
||||
# Additional Source files for FT90X.
|
||||
SRC_C += src/portable/bridgetek/ft9xx/dcd_ft9xx.c
|
||||
|
||||
# Linker library.
|
||||
ifneq ($(FT9XX_PREBUILT_LIBS),1)
|
||||
# Optionally add in files from the Bridgetek SDK instead of the prebuilt
|
||||
# library. These are the minimum required.
|
||||
SRC_C += $(FT9XX_SDK)/src/sys.c
|
||||
SRC_C += $(FT9XX_SDK)/src/interrupt.c
|
||||
SRC_C += $(FT9XX_SDK)/src/delay.c
|
||||
SRC_C += $(FT9XX_SDK)/src/timers.c
|
||||
SRC_C += $(FT9XX_SDK)/src/uart_simple.c
|
||||
SRC_C += $(FT9XX_SDK)/src/gpio.c
|
||||
else
|
||||
# Or if using the prebuilt libraries add them.
|
||||
LDFLAGS += -L"$(FT9XX_SDK)/lib"
|
||||
LIBS += -lft900
|
||||
endif
|
||||
|
||||
# Not required crt0 file for FT90X. Use compiler built-in file.
|
||||
#SRC_S += hw/mcu/bridgetek/ft9xx/scripts/crt0.S
|
|
@ -1,59 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023, Denis Krasutski
|
||||
*
|
||||
* 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 BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// LED: need to wire pin LED1 to PC0 in the P1 header
|
||||
#define LED_PORT GPIOC
|
||||
#define LED_PIN GPIO_Pin_1
|
||||
#define LED_STATE_ON 0
|
||||
#define LED_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE)
|
||||
|
||||
// Button: need to wire pin KEY to PC1 in the P1 header
|
||||
#define BUTTON_PORT GPIOC
|
||||
#define BUTTON_PIN GPIO_Pin_0
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
#define BUTTON_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE)
|
||||
|
||||
// UART
|
||||
#define UART_DEV USART2
|
||||
#define UART_DEV_IRQn USART2_IRQn
|
||||
#define UART_DEV_IRQHandler USART2_IRQHandler
|
||||
#define UART_DEV_GPIO_PORT GPIOA
|
||||
#define UART_DEV_TX_PIN GPIO_Pin_2
|
||||
#define UART_DEV_CLK_EN() do { \
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); \
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); \
|
||||
} while(0)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,7 +0,0 @@
|
|||
LD_FILE = $(FAMILY_PATH)/ch32f205.ld
|
||||
|
||||
SRC_S += \
|
||||
$(FAMILY_PATH)/startup_gcc_ch32f20x_d8c.s
|
||||
|
||||
CFLAGS += \
|
||||
-DCH32F20x_D8C
|
|
@ -1,111 +0,0 @@
|
|||
ENTRY(Reset_Handler)
|
||||
|
||||
_Min_Heap_Size = 0x200;
|
||||
_Min_Stack_Size = 0x400;
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K
|
||||
}
|
||||
SECTIONS
|
||||
{
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector))
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_stext = .;
|
||||
*(.text)
|
||||
*(.text*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.eh_frame)
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
. = ALIGN(4);
|
||||
_etext = .;
|
||||
} >FLASH
|
||||
.rodata :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.rodata)
|
||||
*(.rodata*)
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
KEEP (*(.fini_array*))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
_sidata = LOADADDR(.data);
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .;
|
||||
*(.data)
|
||||
*(.data*)
|
||||
. = ALIGN(4);
|
||||
_edata = .;
|
||||
} >RAM AT> FLASH
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
_sbss = .;
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = .;
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
__HeapStart = .;
|
||||
. = . + _Min_Heap_Size;
|
||||
__HeapEnd = .;
|
||||
__StackLimit = .;
|
||||
. = . + _Min_Stack_Size;
|
||||
__StackTop = .;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
_estack = __StackTop;
|
||||
_sstack = __StackLimit;
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -1,39 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32f20x_conf.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/08/08
|
||||
* Description : Library configuration file.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32F20x_CONF_H
|
||||
#define __CH32F20x_CONF_H
|
||||
|
||||
#include "ch32f20x_adc.h"
|
||||
#include "ch32f20x_bkp.h"
|
||||
#include "ch32f20x_can.h"
|
||||
#include "ch32f20x_crc.h"
|
||||
#include "ch32f20x_dac.h"
|
||||
#include "ch32f20x_dbgmcu.h"
|
||||
#include "ch32f20x_dma.h"
|
||||
#include "ch32f20x_exti.h"
|
||||
#include "ch32f20x_flash.h"
|
||||
#include "ch32f20x_fsmc.h"
|
||||
#include "ch32f20x_gpio.h"
|
||||
#include "ch32f20x_i2c.h"
|
||||
#include "ch32f20x_iwdg.h"
|
||||
#include "ch32f20x_pwr.h"
|
||||
#include "ch32f20x_rcc.h"
|
||||
#include "ch32f20x_rtc.h"
|
||||
#include "ch32f20x_sdio.h"
|
||||
#include "ch32f20x_spi.h"
|
||||
#include "ch32f20x_tim.h"
|
||||
#include "ch32f20x_usart.h"
|
||||
#include "ch32f20x_wwdg.h"
|
||||
#include "ch32f20x_it.h"
|
||||
#include "ch32f20x_misc.h"
|
||||
|
||||
#endif /* __CH32F20x_CONF_H */
|
|
@ -1,35 +0,0 @@
|
|||
#include "ch32f20x_it.h"
|
||||
|
||||
#include "ch32f20x.h"
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
||||
|
||||
void NMI_Handler(void) {
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
||||
|
||||
void MemManage_Handler(void) {
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
||||
|
||||
void BusFault_Handler(void) {
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
||||
|
||||
void UsageFault_Handler(void) {
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
||||
|
||||
void DebugMon_Handler(void) {
|
||||
|
||||
}
|
||||
|
||||
/* -------------------------------------------------------------------------- */
|
|
@ -1,25 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32f20x_it.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/08/08
|
||||
* Description : This file contains the headers of the interrupt handlers.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32F20xIT_H
|
||||
#define __CH32F20xIT_H
|
||||
|
||||
#include "ch32f20x.h"
|
||||
|
||||
void NMI_Handler(void);
|
||||
void HardFault_Handler(void);
|
||||
void MemManage_Handler(void);
|
||||
void BusFault_Handler(void);
|
||||
void UsageFault_Handler(void);
|
||||
void DebugMon_Handler(void);
|
||||
|
||||
|
||||
#endif /* __CH32F20xIT_H */
|
|
@ -1,11 +0,0 @@
|
|||
/* There is core_cm3.h wrapper just to avoid warnings from CMSIS headers */
|
||||
/* if you want use original file add to make file:
|
||||
INC += \
|
||||
$(TOP)/$(CH32F20X_SDK_SRC)/CMSIS
|
||||
*/
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
|
||||
|
||||
#include <../../CMSIS/core_cm3.h>
|
||||
|
||||
#pragma GCC diagnostic pop
|
|
@ -1,105 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023 Denis Krasutski
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
#include <ch32f20x.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "debug_uart.h"
|
||||
|
||||
#define UART_RINGBUFFER_SIZE_TX 64
|
||||
#define UART_RINGBUFFER_MASK_TX (UART_RINGBUFFER_SIZE_TX-1)
|
||||
|
||||
static char tx_buf[UART_RINGBUFFER_SIZE_TX];
|
||||
static unsigned int tx_produce = 0;
|
||||
static volatile unsigned int tx_consume = 0;
|
||||
|
||||
void UART_DEV_IRQHandler(void)
|
||||
{
|
||||
if(USART_GetITStatus(UART_DEV, USART_IT_TC) != RESET) {
|
||||
USART_ClearITPendingBit(UART_DEV, USART_IT_TC);
|
||||
|
||||
if(tx_consume != tx_produce) {
|
||||
USART_SendData(UART_DEV, tx_buf[tx_consume]);
|
||||
tx_consume = (tx_consume + 1) & UART_RINGBUFFER_MASK_TX;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void uart_write(char c)
|
||||
{
|
||||
unsigned int tx_produce_next = (tx_produce + 1) & UART_RINGBUFFER_MASK_TX;
|
||||
|
||||
NVIC_DisableIRQ(UART_DEV_IRQn);
|
||||
if((tx_consume != tx_produce) || (USART_GetFlagStatus(UART_DEV, USART_FLAG_TXE) == RESET)) {
|
||||
tx_buf[tx_produce] = c;
|
||||
tx_produce = tx_produce_next;
|
||||
} else {
|
||||
USART_SendData(UART_DEV, c);
|
||||
}
|
||||
NVIC_EnableIRQ(UART_DEV_IRQn);
|
||||
}
|
||||
|
||||
void uart_sync(void)
|
||||
{
|
||||
while(tx_consume != tx_produce) {
|
||||
//Waiting for transfer complete
|
||||
}
|
||||
}
|
||||
|
||||
void usart_printf_init(uint32_t baudrate)
|
||||
{
|
||||
tx_produce = 0;
|
||||
tx_consume = 0;
|
||||
|
||||
UART_DEV_CLK_EN();
|
||||
|
||||
GPIO_InitTypeDef gpio_config = {
|
||||
.GPIO_Pin = UART_DEV_TX_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
};
|
||||
GPIO_Init(UART_DEV_GPIO_PORT, &gpio_config);
|
||||
|
||||
USART_InitTypeDef uart_config = {
|
||||
.USART_BaudRate = baudrate,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Tx,
|
||||
};
|
||||
|
||||
USART_Init(UART_DEV, &uart_config);
|
||||
USART_ITConfig(UART_DEV, USART_IT_TC, ENABLE);
|
||||
USART_Cmd(UART_DEV, ENABLE);
|
||||
|
||||
NVIC_InitTypeDef nvic_config = {
|
||||
.NVIC_IRQChannel = UART_DEV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = 1,
|
||||
.NVIC_IRQChannelSubPriority = 3,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
};
|
||||
NVIC_Init(&nvic_config);
|
||||
}
|
|
@ -1,31 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023 Denis Krasutski
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
void uart_write(char c);
|
||||
void uart_sync(void);
|
||||
void usart_printf_init(uint32_t baudrate);
|
|
@ -1,141 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023 Denis Krasutski
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "stdio.h"
|
||||
#include "debug_uart.h"
|
||||
|
||||
#include "ch32f20x.h"
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void USBHS_IRQHandler(void)
|
||||
{
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
|
||||
/* Disable interrupts during init */
|
||||
__disable_irq();
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
#endif
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_FREERTOS
|
||||
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
|
||||
NVIC_SetPriority(USBHS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY);
|
||||
#endif
|
||||
|
||||
usart_printf_init(115200);
|
||||
|
||||
// USB HS Clock config
|
||||
RCC_USBCLK48MConfig(RCC_USBCLK48MCLKSource_USBPHY);
|
||||
RCC_USBHSPLLCLKConfig(RCC_HSBHSPLLCLKSource_HSE);
|
||||
RCC_USBHSConfig(RCC_USBPLL_Div2);
|
||||
RCC_USBHSPLLCKREFCLKConfig(RCC_USBHSPLLCKREFCLK_4M);
|
||||
RCC_USBHSPHYPLLALIVEcmd(ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_USBHS, ENABLE);
|
||||
|
||||
// LED
|
||||
LED_CLOCK_EN();
|
||||
GPIO_InitTypeDef led_pin_config = {
|
||||
.GPIO_Pin = LED_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_Out_OD,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
};
|
||||
GPIO_Init(LED_PORT, &led_pin_config);
|
||||
|
||||
// Button
|
||||
BUTTON_CLOCK_EN();
|
||||
GPIO_InitTypeDef button_pin_config = {
|
||||
.GPIO_Pin = BUTTON_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
};
|
||||
GPIO_Init(BUTTON_PORT, &button_pin_config);
|
||||
|
||||
/* Enable interrupts globally */
|
||||
__enable_irq();
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void)
|
||||
{
|
||||
return system_ticks;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void HardFault_Handler(void)
|
||||
{
|
||||
__asm("BKPT #0\n");
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_led_write(bool state)
|
||||
{
|
||||
GPIO_WriteBit(LED_PORT, LED_PIN, state);
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void)
|
||||
{
|
||||
return BUTTON_STATE_ACTIVE == GPIO_ReadInputDataBit(BUTTON_PORT, BUTTON_PIN);
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t *buf, int len)
|
||||
{
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const *buf, int len)
|
||||
{
|
||||
int txsize = len;
|
||||
while ( txsize-- )
|
||||
{
|
||||
uart_write(*(uint8_t const*) buf);
|
||||
buf++;
|
||||
}
|
||||
return len;
|
||||
}
|
|
@ -1,30 +0,0 @@
|
|||
# Submodules
|
||||
CH32F20X_SDK = hw/mcu/wch/ch32f20x
|
||||
DEPS_SUBMODULES += $(CH32F20X_SDK)
|
||||
|
||||
# WCH-SDK paths
|
||||
CH32F20X_SDK_SRC = $(CH32F20X_SDK)/EVT/EXAM/SRC
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
|
||||
CPU_CORE ?= cortex-m3
|
||||
|
||||
CFLAGS += \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_CH32F20X \
|
||||
-DBOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED
|
||||
|
||||
SRC_C += \
|
||||
src/portable/wch/dcd_ch32_usbhs.c \
|
||||
$(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_gpio.c \
|
||||
$(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_misc.c \
|
||||
$(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_rcc.c \
|
||||
$(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_usart.c
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(CH32F20X_SDK_SRC)/StdPeriphDriver/inc
|
||||
|
||||
# For freeRTOS port source
|
||||
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM3
|
||||
|
||||
flash: flash-stlink
|
|
@ -1,493 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file startup_gcc_ch32f20x_d8c.s
|
||||
* @author Denis Krasutski
|
||||
* @brief CH32F205 Devices vector table
|
||||
* This module performs:
|
||||
* - Set the initial SP
|
||||
* - Set the initial PC == Reset_Handler,
|
||||
* - Set the vector table entries with the exceptions ISR address
|
||||
* - Branches to main in the C library (which eventually
|
||||
* calls main()).
|
||||
* After Reset the Cortex-M3 processor is in Thread mode,
|
||||
* priority is Privileged, and the Stack is set to Main.
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m3
|
||||
.thumb
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
|
||||
/* start address for the initialization values of the .data section. defined in linker script */
|
||||
.word _sidata
|
||||
/* start address for the .data section. defined in linker script */
|
||||
.word _sdata
|
||||
/* end address for the .data section. defined in linker script */
|
||||
.word _edata
|
||||
/* start address for the .bss section. defined in linker script */
|
||||
.word _sbss
|
||||
/* end address for the .bss section. defined in linker script */
|
||||
.word _ebss
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
/* set stack pointer */
|
||||
ldr sp, =_estack
|
||||
/* Call the clock system initialization function.*/
|
||||
bl SystemInit
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
ldr r0, =_sdata
|
||||
ldr r1, =_edata
|
||||
ldr r2, =_sidata
|
||||
movs r3, #0
|
||||
b LoopCopyDataInit
|
||||
CopyDataInit:
|
||||
ldr r4, [r2, r3]
|
||||
str r4, [r0, r3]
|
||||
adds r3, r3, #4
|
||||
LoopCopyDataInit:
|
||||
adds r4, r0, r3
|
||||
cmp r4, r1
|
||||
bcc CopyDataInit
|
||||
|
||||
/* Zero fill the bss segment. */
|
||||
ldr r2, =_sbss
|
||||
ldr r4, =_ebss
|
||||
movs r3, #0
|
||||
b LoopFillZerobss
|
||||
FillZerobss:
|
||||
str r3, [r2]
|
||||
adds r2, r2, #4
|
||||
LoopFillZerobss:
|
||||
cmp r2, r4
|
||||
bcc FillZerobss
|
||||
/* Call static constructors */
|
||||
bl __libc_init_array
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
Infinite_Loop:
|
||||
b Infinite_Loop
|
||||
.size Default_Handler, .-Default_Handler
|
||||
|
||||
/******************************************************************************
|
||||
*
|
||||
* The minimal vector table for a Cortex M3. Note that the proper constructs
|
||||
* must be placed on this to ensure that it ends up at physical address
|
||||
* 0x0000.0000.
|
||||
*
|
||||
*******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type g_pfnVectors, %object
|
||||
.size g_pfnVectors, .-g_pfnVectors
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
.word MemManage_Handler
|
||||
.word BusFault_Handler
|
||||
.word UsageFault_Handler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word SVC_Handler
|
||||
.word DebugMon_Handler
|
||||
.word 0
|
||||
.word PendSV_Handler
|
||||
.word SysTick_Handler
|
||||
|
||||
/*******************************************************************************
|
||||
External Interrupts
|
||||
*******************************************************************************/
|
||||
.word WWDG_IRQHandler
|
||||
.word PVD_IRQHandler
|
||||
.word TAMPER_IRQHandler
|
||||
.word RTC_IRQHandler
|
||||
.word FLASH_IRQHandler
|
||||
.word RCC_IRQHandler
|
||||
.word EXTI0_IRQHandler
|
||||
.word EXTI1_IRQHandler
|
||||
.word EXTI2_IRQHandler
|
||||
.word EXTI3_IRQHandler
|
||||
.word EXTI4_IRQHandler
|
||||
.word DMA1_Channel1_IRQHandler
|
||||
.word DMA1_Channel2_IRQHandler
|
||||
.word DMA1_Channel3_IRQHandler
|
||||
.word DMA1_Channel4_IRQHandler
|
||||
.word DMA1_Channel5_IRQHandler
|
||||
.word DMA1_Channel6_IRQHandler
|
||||
.word DMA1_Channel7_IRQHandler
|
||||
.word ADC1_2_IRQHandler
|
||||
.word USB_HP_CAN1_TX_IRQHandler
|
||||
.word USB_LP_CAN1_RX0_IRQHandler
|
||||
.word CAN1_RX1_IRQHandler
|
||||
.word CAN1_SCE_IRQHandler
|
||||
.word EXTI9_5_IRQHandler
|
||||
.word TIM1_BRK_IRQHandler
|
||||
.word TIM1_UP_IRQHandler
|
||||
.word TIM1_TRG_COM_IRQHandler
|
||||
.word TIM1_CC_IRQHandler
|
||||
.word TIM2_IRQHandler
|
||||
.word TIM3_IRQHandler
|
||||
.word TIM4_IRQHandler
|
||||
.word I2C1_EV_IRQHandler
|
||||
.word I2C1_ER_IRQHandler
|
||||
.word I2C2_EV_IRQHandler
|
||||
.word I2C2_ER_IRQHandler
|
||||
.word SPI1_IRQHandler
|
||||
.word SPI2_IRQHandler
|
||||
.word USART1_IRQHandler
|
||||
.word USART2_IRQHandler
|
||||
.word USART3_IRQHandler
|
||||
.word EXTI15_10_IRQHandler
|
||||
.word RTCAlarm_IRQHandler
|
||||
.word 0
|
||||
.word TIM8_BRK_IRQHandler
|
||||
.word TIM8_UP_IRQHandler
|
||||
.word TIM8_TRG_COM_IRQHandler
|
||||
.word TIM8_CC_IRQHandler
|
||||
.word RNG_IRQHandler
|
||||
.word FSMC_IRQHandler
|
||||
.word SDIO_IRQHandler
|
||||
.word TIM5_IRQHandler
|
||||
.word SPI3_IRQHandler
|
||||
.word UART4_IRQHandler
|
||||
.word UART5_IRQHandler
|
||||
.word TIM6_IRQHandler
|
||||
.word TIM7_IRQHandler
|
||||
.word DMA2_Channel1_IRQHandler
|
||||
.word DMA2_Channel2_IRQHandler
|
||||
.word DMA2_Channel3_IRQHandler
|
||||
.word DMA2_Channel4_IRQHandler
|
||||
.word DMA2_Channel5_IRQHandler
|
||||
.word ETH_IRQHandler
|
||||
.word ETH_WKUP_IRQHandler
|
||||
.word CAN2_TX_IRQHandler
|
||||
.word CAN2_RX0_IRQHandler
|
||||
.word CAN2_RX1_IRQHandler
|
||||
.word CAN2_SCE_IRQHandler
|
||||
.word OTG_FS_IRQHandler
|
||||
.word USBHSWakeup_IRQHandler
|
||||
.word USBHS_IRQHandler
|
||||
.word DVP_IRQHandler
|
||||
.word UART6_IRQHandler
|
||||
.word UART7_IRQHandler
|
||||
.word UART8_IRQHandler
|
||||
.word TIM9_BRK_IRQHandler
|
||||
.word TIM9_UP_IRQHandler
|
||||
.word TIM9_TRG_COM_IRQHandler
|
||||
.word TIM9_CC_IRQHandler
|
||||
.word TIM10_BRK_IRQHandler
|
||||
.word TIM10_UP_IRQHandler
|
||||
.word TIM10_TRG_COM_IRQHandler
|
||||
.word TIM10_CC_IRQHandler
|
||||
.word DMA2_Channel6_IRQHandler
|
||||
.word DMA2_Channel7_IRQHandler
|
||||
.word DMA2_Channel8_IRQHandler
|
||||
.word DMA2_Channel9_IRQHandler
|
||||
.word DMA2_Channel10_IRQHandler
|
||||
.word DMA2_Channel11_IRQHandler
|
||||
|
||||
/*******************************************************************************
|
||||
*
|
||||
* Provide weak aliases
|
||||
*
|
||||
*******************************************************************************/
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
.weak UsageFault_Handler
|
||||
.thumb_set UsageFault_Handler,Default_Handler
|
||||
|
||||
.weak SVC_Handler
|
||||
.thumb_set SVC_Handler,Default_Handler
|
||||
|
||||
.weak DebugMon_Handler
|
||||
.thumb_set DebugMon_Handler,Default_Handler
|
||||
|
||||
.weak PendSV_Handler
|
||||
.thumb_set PendSV_Handler,Default_Handler
|
||||
|
||||
.weak SysTick_Handler
|
||||
.thumb_set SysTick_Handler,Default_Handler
|
||||
|
||||
.weak WWDG_IRQHandler
|
||||
.thumb_set WWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak PVD_IRQHandler
|
||||
.thumb_set PVD_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMPER_IRQHandler
|
||||
.thumb_set TAMPER_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_IRQHandler
|
||||
.thumb_set RTC_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_IRQHandler
|
||||
.thumb_set FLASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_IRQHandler
|
||||
.thumb_set RCC_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI0_IRQHandler
|
||||
.thumb_set EXTI0_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI1_IRQHandler
|
||||
.thumb_set EXTI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI2_IRQHandler
|
||||
.thumb_set EXTI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI3_IRQHandler
|
||||
.thumb_set EXTI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI4_IRQHandler
|
||||
.thumb_set EXTI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel1_IRQHandler
|
||||
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel2_IRQHandler
|
||||
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel3_IRQHandler
|
||||
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel4_IRQHandler
|
||||
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel5_IRQHandler
|
||||
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel6_IRQHandler
|
||||
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel7_IRQHandler
|
||||
.thumb_set DMA1_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC1_2_IRQHandler
|
||||
.thumb_set ADC1_2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_HP_CAN1_TX_IRQHandler
|
||||
.thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_LP_CAN1_RX0_IRQHandler
|
||||
.thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_RX1_IRQHandler
|
||||
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_SCE_IRQHandler
|
||||
.thumb_set CAN1_SCE_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI9_5_IRQHandler
|
||||
.thumb_set EXTI9_5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_BRK_IRQHandler
|
||||
.thumb_set TIM1_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_UP_IRQHandler
|
||||
.thumb_set TIM1_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_TRG_COM_IRQHandler
|
||||
.thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_CC_IRQHandler
|
||||
.thumb_set TIM1_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM2_IRQHandler
|
||||
.thumb_set TIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM3_IRQHandler
|
||||
.thumb_set TIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM4_IRQHandler
|
||||
.thumb_set TIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_EV_IRQHandler
|
||||
.thumb_set I2C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_ER_IRQHandler
|
||||
.thumb_set I2C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_EV_IRQHandler
|
||||
.thumb_set I2C2_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_ER_IRQHandler
|
||||
.thumb_set I2C2_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI1_IRQHandler
|
||||
.thumb_set SPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI2_IRQHandler
|
||||
.thumb_set SPI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART1_IRQHandler
|
||||
.thumb_set USART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART2_IRQHandler
|
||||
.thumb_set USART2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART3_IRQHandler
|
||||
.thumb_set USART3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI15_10_IRQHandler
|
||||
.thumb_set EXTI15_10_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTCAlarm_IRQHandler
|
||||
.thumb_set RTCAlarm_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_BRK_IRQHandler
|
||||
.thumb_set TIM8_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_UP_IRQHandler
|
||||
.thumb_set TIM8_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_TRG_COM_IRQHandler
|
||||
.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_CC_IRQHandler
|
||||
.thumb_set TIM8_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak RNG_IRQHandler
|
||||
.thumb_set RNG_IRQHandler,Default_Handler
|
||||
|
||||
.weak FSMC_IRQHandler
|
||||
.thumb_set FSMC_IRQHandler,Default_Handler
|
||||
|
||||
.weak SDIO_IRQHandler
|
||||
.thumb_set SDIO_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM5_IRQHandler
|
||||
.thumb_set TIM5_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI3_IRQHandler
|
||||
.thumb_set SPI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART4_IRQHandler
|
||||
.thumb_set UART4_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART5_IRQHandler
|
||||
.thumb_set UART5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM6_IRQHandler
|
||||
.thumb_set TIM6_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM7_IRQHandler
|
||||
.thumb_set TIM7_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel1_IRQHandler
|
||||
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel2_IRQHandler
|
||||
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel3_IRQHandler
|
||||
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel4_IRQHandler
|
||||
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel5_IRQHandler
|
||||
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak ETH_IRQHandler
|
||||
.thumb_set ETH_IRQHandler,Default_Handler
|
||||
|
||||
.weak ETH_WKUP_IRQHandler
|
||||
.thumb_set ETH_WKUP_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN2_TX_IRQHandler
|
||||
.thumb_set CAN2_TX_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN2_RX0_IRQHandler
|
||||
.thumb_set CAN2_RX0_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN2_RX1_IRQHandler
|
||||
.thumb_set CAN2_RX1_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN2_SCE_IRQHandler
|
||||
.thumb_set CAN2_SCE_IRQHandler,Default_Handler
|
||||
|
||||
.weak OTG_FS_IRQHandler
|
||||
.thumb_set OTG_FS_IRQHandler,Default_Handler
|
||||
|
||||
.weak USBHSWakeup_IRQHandler
|
||||
.thumb_set USBHSWakeup_IRQHandler,Default_Handler
|
||||
|
||||
.weak USBHS_IRQHandler
|
||||
.thumb_set USBHS_IRQHandler,Default_Handler
|
||||
|
||||
.weak DVP_IRQHandler
|
||||
.thumb_set DVP_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART6_IRQHandler
|
||||
.thumb_set UART6_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART7_IRQHandler
|
||||
.thumb_set UART7_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART8_IRQHandler
|
||||
.thumb_set UART8_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM9_BRK_IRQHandler
|
||||
.thumb_set TIM9_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM9_UP_IRQHandler
|
||||
.thumb_set TIM9_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM9_TRG_COM_IRQHandler
|
||||
.thumb_set TIM9_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM9_CC_IRQHandler
|
||||
.thumb_set TIM9_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM10_BRK_IRQHandler
|
||||
.thumb_set TIM10_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM10_UP_IRQHandler
|
||||
.thumb_set TIM10_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM10_TRG_COM_IRQHandler
|
||||
.thumb_set TIM10_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM10_CC_IRQHandler
|
||||
.thumb_set TIM10_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel6_IRQHandler
|
||||
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel7_IRQHandler
|
||||
.thumb_set DMA2_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel8_IRQHandler
|
||||
.thumb_set DMA2_Channel8_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel9_IRQHandler
|
||||
.thumb_set DMA2_Channel9_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel10_IRQHandler
|
||||
.thumb_set DMA2_Channel10_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA2_Channel11_IRQHandler
|
||||
.thumb_set DMA2_Channel11_IRQHandler,Default_Handler
|
File diff suppressed because it is too large
Load diff
|
@ -1,25 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32f20x.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/08/08
|
||||
* Description : CH32F20x Device Peripheral Access Layer System Header File.
|
||||
*******************************************************************************/
|
||||
#ifndef __SYSTEM_CH32F20x_H
|
||||
#define __SYSTEM_CH32F20x_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
/* System_Exported_Functions */
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__CH32F20x_SYSTEM_H */
|
|
@ -1,8 +0,0 @@
|
|||
set(LD_FLASH_SIZE 64K)
|
||||
set(LD_RAM_SIZE 20K)
|
||||
|
||||
function(update_board TARGET)
|
||||
target_compile_definitions(${TARGET} PUBLIC
|
||||
CFG_EXAMPLE_MSC_DUAL_READONLY
|
||||
)
|
||||
endfunction()
|
|
@ -1,20 +0,0 @@
|
|||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define LED_PORT GPIOA
|
||||
#define LED_PIN GPIO_Pin_10
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
#define BUTTON_PORT GPIOA
|
||||
#define BUTTON_PIN GPIO_Pin_1
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,5 +0,0 @@
|
|||
CFLAGS += -DCFG_EXAMPLE_MSC_DUAL_READONLY
|
||||
|
||||
LDFLAGS += \
|
||||
-Wl,--defsym=__FLASH_SIZE=64K \
|
||||
-Wl,--defsym=__RAM_SIZE=20K \
|
|
@ -1,37 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v10x_conf.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2020/04/30
|
||||
* Description : Library configuration file.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V10x_CONF_H
|
||||
#define __CH32V10x_CONF_H
|
||||
|
||||
#include "ch32v10x_adc.h"
|
||||
#include "ch32v10x_bkp.h"
|
||||
#include "ch32v10x_crc.h"
|
||||
#include "ch32v10x_dbgmcu.h"
|
||||
#include "ch32v10x_dma.h"
|
||||
#include "ch32v10x_exti.h"
|
||||
#include "ch32v10x_flash.h"
|
||||
#include "ch32v10x_gpio.h"
|
||||
#include "ch32v10x_i2c.h"
|
||||
#include "ch32v10x_iwdg.h"
|
||||
#include "ch32v10x_pwr.h"
|
||||
#include "ch32v10x_rcc.h"
|
||||
#include "ch32v10x_rtc.h"
|
||||
#include "ch32v10x_spi.h"
|
||||
#include "ch32v10x_tim.h"
|
||||
#include "ch32v10x_usart.h"
|
||||
#include "ch32v10x_wwdg.h"
|
||||
#include "ch32v10x_usb.h"
|
||||
#include "ch32v10x_usb_host.h"
|
||||
#include "ch32v10x_it.h"
|
||||
#include "ch32v10x_misc.h"
|
||||
|
||||
#endif /* __CH32V10x_CONF_H */
|
|
@ -1,15 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v10x_it.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2022/08/20
|
||||
* Description : This file contains the headers of the interrupt handlers.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V10x_IT_H
|
||||
#define __CH32V10x_IT_H
|
||||
|
||||
#endif /* __CH32V10x_IT_H */
|
|
@ -1,148 +0,0 @@
|
|||
#include <stdio.h>
|
||||
|
||||
// https://github.com/openwch/ch32v307/pull/90
|
||||
// https://github.com/openwch/ch32v20x/pull/12
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
|
||||
#endif
|
||||
|
||||
#include "ch32v10x.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USBHD_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBFS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USBWakeUp_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBFS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void SysTick_Handler(void) {
|
||||
SysTick->CNTL0 = SysTick->CNTL1 = SysTick->CNTL2 = SysTick->CNTL3 = 0;
|
||||
SysTick->CNTH0 = SysTick->CNTH1 = SysTick->CNTH2 = SysTick->CNTH3 = 0;
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t SysTick_Config(uint32_t ticks) {
|
||||
NVIC_EnableIRQ(SysTicK_IRQn);
|
||||
SysTick->CTLR = 0;
|
||||
SysTick->CNTL0 = SysTick->CNTL1 = SysTick->CNTL2 = SysTick->CNTL3 = 0;
|
||||
SysTick->CNTH0 = SysTick->CNTH1 = SysTick->CNTH2 = SysTick->CNTH3 = 0;
|
||||
|
||||
SysTick->CMPLR0 = (u8)(ticks & 0xFF);
|
||||
SysTick->CMPLR1 = (u8)(ticks >> 8);
|
||||
SysTick->CMPLR2 = (u8)(ticks >> 16);
|
||||
SysTick->CMPLR3 = (u8)(ticks >> 24);
|
||||
|
||||
SysTick->CMPHR0 = SysTick->CMPHR1 = SysTick->CMPHR2 = SysTick->CMPHR3 = 0;
|
||||
SysTick->CTLR = 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
#endif
|
||||
|
||||
void board_init(void) {
|
||||
__disable_irq();
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
#endif
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
EXTEN->EXTEN_CTR |= EXTEN_USBFS_IO_EN;
|
||||
uint8_t usb_div;
|
||||
switch (SystemCoreClock) {
|
||||
case 48000000: usb_div = RCC_USBCLKSource_PLLCLK_Div1; break;
|
||||
case 72000000: usb_div = RCC_USBCLKSource_PLLCLK_1Div5; break;
|
||||
default: TU_ASSERT(0,); break;
|
||||
}
|
||||
RCC_USBCLKConfig(usb_div);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_USBFS, ENABLE);
|
||||
|
||||
#ifdef LED_PIN
|
||||
GPIO_InitTypeDef led_init = {
|
||||
.GPIO_Pin = LED_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_Out_OD,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
};
|
||||
GPIO_Init(LED_PORT, &led_init);
|
||||
#endif
|
||||
|
||||
#ifdef BUTTON_PIN
|
||||
GPIO_InitTypeDef button_init = {
|
||||
.GPIO_Pin = BUTTON_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
};
|
||||
GPIO_Init(BUTTON_PORT, &button_init);
|
||||
#endif
|
||||
|
||||
// UART TX is PA9
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
GPIO_InitTypeDef usart_init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
};
|
||||
GPIO_Init(GPIOA, &usart_init);
|
||||
|
||||
USART_InitTypeDef usart = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_Mode = USART_Mode_Tx,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
};
|
||||
USART_Init(USART1, &usart);
|
||||
USART_Cmd(USART1, ENABLE);
|
||||
|
||||
__enable_irq();
|
||||
|
||||
board_led_write(true);
|
||||
}
|
||||
|
||||
void board_led_write(bool state) {
|
||||
GPIO_WriteBit(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return BUTTON_STATE_ACTIVE == GPIO_ReadInputDataBit(BUTTON_PORT, BUTTON_PIN);
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t *buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const *buf, int len) {
|
||||
const char *bufc = (const char *) buf;
|
||||
for (int i = 0; i < len; i++) {
|
||||
while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET);
|
||||
USART_SendData(USART1, *bufc++);
|
||||
}
|
||||
|
||||
return len;
|
||||
}
|
|
@ -1,117 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
#set(UF2_FAMILY_ID 0x699b62ec)
|
||||
set(CH32_FAMILY ch32v10x)
|
||||
set(SDK_DIR ${TOP}/hw/mcu/wch/ch32v103)
|
||||
set(SDK_SRC_DIR ${SDK_DIR}/EVT/EXAM/SRC)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
set(CMAKE_SYSTEM_PROCESSOR rv32imac-ilp32 CACHE INTERNAL "System Processor")
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/riscv_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS CH32V103 CACHE INTERNAL "")
|
||||
set(OPENOCD_OPTION "-f ${CMAKE_CURRENT_LIST_DIR}/wch-riscv.cfg")
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/${CH32_FAMILY}.ld)
|
||||
endif ()
|
||||
set(LD_FILE_Clang ${LD_FILE_GNU})
|
||||
|
||||
if (NOT DEFINED STARTUP_FILE_GNU)
|
||||
set(STARTUP_FILE_GNU ${SDK_SRC_DIR}/Startup/startup_${CH32_FAMILY}.S)
|
||||
endif ()
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${SDK_SRC_DIR}/Core/core_riscv.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_gpio.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_misc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_rcc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_usart.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/system_${CH32_FAMILY}.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${SDK_SRC_DIR}/Core
|
||||
${SDK_SRC_DIR}/Peripheral/inc
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
)
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
-mcmodel=medany
|
||||
)
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-Wl,--defsym=__FLASH_SIZE=${LD_FLASH_SIZE}
|
||||
-Wl,--defsym=__RAM_SIZE=${LD_RAM_SIZE}
|
||||
-nostartfiles
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
message(FATAL_ERROR "Clang is not supported for MSP432E4")
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_CH32V103 ${RTOS})
|
||||
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/wch/dcd_ch32_usbfs.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_openocd_wch(${TARGET})
|
||||
|
||||
#family_add_uf2(${TARGET} ${UF2_FAMILY_ID})
|
||||
#family_flash_uf2(${TARGET} ${UF2_FAMILY_ID})
|
||||
endfunction()
|
|
@ -1,53 +0,0 @@
|
|||
# https://www.embecosm.com/resources/tool-chain-downloads/#riscv-stable
|
||||
#CROSS_COMPILE ?= riscv32-unknown-elf-
|
||||
|
||||
# Toolchain from https://nucleisys.com/download.php
|
||||
#CROSS_COMPILE ?= riscv-nuclei-elf-
|
||||
|
||||
# Toolchain from https://github.com/xpack-dev-tools/riscv-none-elf-gcc-xpack
|
||||
CROSS_COMPILE ?= riscv-none-elf-
|
||||
|
||||
CH32_FAMILY = ch32v10x
|
||||
SDK_DIR = hw/mcu/wch/ch32v103
|
||||
SDK_SRC_DIR = $(SDK_DIR)/EVT/EXAM/SRC
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
CPU_CORE ?= rv32imac-ilp32
|
||||
|
||||
# Port0 use FSDev, Port1 use USBFS
|
||||
PORT ?= 0
|
||||
|
||||
CFLAGS += \
|
||||
-mcmodel=medany \
|
||||
-ffat-lto-objects \
|
||||
-flto \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_CH32V103
|
||||
|
||||
# https://github.com/openwch/ch32v20x/pull/12
|
||||
CFLAGS += -Wno-error=strict-prototypes
|
||||
|
||||
LDFLAGS_GCC += \
|
||||
-nostdlib -nostartfiles \
|
||||
--specs=nosys.specs --specs=nano.specs \
|
||||
|
||||
LD_FILE = $(FAMILY_PATH)/linker/${CH32_FAMILY}.ld
|
||||
|
||||
SRC_C += \
|
||||
src/portable/wch/dcd_ch32_usbfs.c \
|
||||
$(SDK_SRC_DIR)/Core/core_riscv.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_gpio.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_misc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_rcc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_usart.c \
|
||||
|
||||
SRC_S += $(SDK_SRC_DIR)/Startup/startup_${CH32_FAMILY}.S
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Core \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Peripheral/inc \
|
||||
|
||||
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/RISC-V
|
||||
|
||||
OPENOCD_WCH_OPTION=-f $(TOP)/$(FAMILY_PATH)/wch-riscv.cfg
|
||||
flash: flash-openocd-wch
|
|
@ -1,165 +0,0 @@
|
|||
/* Define default values if not already defined */
|
||||
__FLASH_SIZE = DEFINED(__flash_size) ? __flash_size : 64K;
|
||||
__RAM_SIZE = DEFINED(__ram_size) ? __ram_size : 20K;
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = __FLASH_SIZE
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = __RAM_SIZE
|
||||
}
|
||||
|
||||
ENTRY( _start )
|
||||
|
||||
__stack_size = 2048;
|
||||
|
||||
PROVIDE( _stack_size = __stack_size );
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.init :
|
||||
{
|
||||
_sinit = .;
|
||||
. = ALIGN(4);
|
||||
KEEP(*(SORT_NONE(.init)))
|
||||
. = ALIGN(4);
|
||||
_einit = .;
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.vector :
|
||||
{
|
||||
*(.vector);
|
||||
. = ALIGN(64);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.rodata)
|
||||
*(.rodata*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini :
|
||||
{
|
||||
KEEP(*(SORT_NONE(.fini)))
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
PROVIDE( _etext = . );
|
||||
PROVIDE( _eitcm = . );
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
|
||||
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
|
||||
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.ctors :
|
||||
{
|
||||
/* gcc uses crtbegin.o to find the start of
|
||||
the constructors, so we make sure it is
|
||||
first. Because this is a wildcard, it
|
||||
doesn't matter if the user does not
|
||||
actually link against crtbegin.o; the
|
||||
linker won't look for a file to match a
|
||||
wildcard. The wildcard also means that it
|
||||
doesn't matter which directory crtbegin.o
|
||||
is in. */
|
||||
KEEP (*crtbegin.o(.ctors))
|
||||
KEEP (*crtbegin?.o(.ctors))
|
||||
/* We don't want to include the .ctor section from
|
||||
the crtend.o file until after the sorted ctors.
|
||||
The .ctor section from the crtend file contains the
|
||||
end of ctors marker and it must be last */
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
|
||||
KEEP (*(SORT(.ctors.*)))
|
||||
KEEP (*(.ctors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dtors :
|
||||
{
|
||||
KEEP (*crtbegin.o(.dtors))
|
||||
KEEP (*crtbegin?.o(.dtors))
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
|
||||
KEEP (*(SORT(.dtors.*)))
|
||||
KEEP (*(.dtors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_vma = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.dlalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_lma = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.data :
|
||||
{
|
||||
*(.gnu.linkonce.r.*)
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
. = ALIGN(8);
|
||||
PROVIDE( __global_pointer$ = . + 0x800 );
|
||||
*(.sdata .sdata.*)
|
||||
*(.sdata2.*)
|
||||
*(.gnu.linkonce.s.*)
|
||||
. = ALIGN(8);
|
||||
*(.srodata.cst16)
|
||||
*(.srodata.cst8)
|
||||
*(.srodata.cst4)
|
||||
*(.srodata.cst2)
|
||||
*(.srodata .srodata.*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _edata = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _sbss = .);
|
||||
*(.sbss*)
|
||||
*(.gnu.linkonce.sb.*)
|
||||
*(.bss*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _ebss = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
PROVIDE( _end = _ebss);
|
||||
PROVIDE( end = . );
|
||||
|
||||
.stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size :
|
||||
{
|
||||
PROVIDE( _heap_end = . );
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_susrstack = . );
|
||||
. = . + __stack_size;
|
||||
PROVIDE( _eusrstack = .);
|
||||
} >RAM
|
||||
|
||||
}
|
|
@ -1,600 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v10x.c
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2020/04/30
|
||||
* Description : CH32V10x Device Peripheral Access Layer System Source File.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#include "ch32v10x.h"
|
||||
|
||||
/*
|
||||
* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after
|
||||
* reset the HSI is used as SYSCLK source).
|
||||
* If none of the define below is enabled, the HSI is used as System clock source.
|
||||
*/
|
||||
//#define SYSCLK_FREQ_HSE HSE_VALUE
|
||||
//#define SYSCLK_FREQ_48MHz_HSE 48000000
|
||||
//#define SYSCLK_FREQ_56MHz_HSE 56000000
|
||||
#define SYSCLK_FREQ_72MHz_HSE 72000000
|
||||
//#define SYSCLK_FREQ_HSI HSI_VALUE
|
||||
//#define SYSCLK_FREQ_48MHz_HSI 48000000
|
||||
//#define SYSCLK_FREQ_56MHz_HSI 56000000
|
||||
//#define SYSCLK_FREQ_72MHz_HSI 72000000
|
||||
|
||||
/* Clock Definitions */
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#else
|
||||
uint32_t SystemCoreClock = HSI_VALUE; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
#endif
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/* ch32v10x_system_private_function_proto_types */
|
||||
static void SetSysClock(void);
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
static void SetSysClockToHSE( void );
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
static void SetSysClockTo48_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
static void SetSysClockTo56_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
static void SetSysClockTo72_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
static void SetSysClockTo48_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
static void SetSysClockTo56_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
static void SetSysClockTo72_HSI( void );
|
||||
|
||||
#endif
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemInit
|
||||
*
|
||||
* @brief Setup the microcontroller system Initialize the Embedded Flash Interface,
|
||||
* the PLL and update the SystemCoreClock variable.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemInit(void)
|
||||
{
|
||||
RCC->CTLR |= (uint32_t)0x00000001;
|
||||
RCC->CFGR0 &= (uint32_t)0xF8FF0000;
|
||||
RCC->CTLR &= (uint32_t)0xFEF6FFFF;
|
||||
RCC->CTLR &= (uint32_t)0xFFFBFFFF;
|
||||
RCC->CFGR0 &= (uint32_t)0xFF80FFFF;
|
||||
RCC->INTR = 0x009F0000;
|
||||
SetSysClock();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemCoreClockUpdate
|
||||
*
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0;
|
||||
|
||||
tmp = RCC->CFGR0 & RCC_SWS;
|
||||
|
||||
switch(tmp)
|
||||
{
|
||||
case 0x00:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04:
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08:
|
||||
pllmull = RCC->CFGR0 & RCC_PLLMULL;
|
||||
pllsource = RCC->CFGR0 & RCC_PLLSRC;
|
||||
pllmull = (pllmull >> 18) + 2;
|
||||
if(pllsource == 0x00)
|
||||
{
|
||||
if( EXTEN->EXTEN_CTR & EXTEN_PLL_HSI_PRE )
|
||||
{
|
||||
SystemCoreClock = ( HSI_VALUE ) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
SystemCoreClock = ( HSI_VALUE >> 1 ) * pllmull;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if((RCC->CFGR0 & RCC_PLLXTPRE) != (uint32_t)RESET)
|
||||
{
|
||||
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
SystemCoreClock = HSE_VALUE * pllmull;
|
||||
}
|
||||
}
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
|
||||
tmp = AHBPrescTable[((RCC->CFGR0 & RCC_HPRE) >> 4)];
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClock
|
||||
*
|
||||
* @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClock(void)
|
||||
{
|
||||
//GPIO_IPD_Unused();
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
SetSysClockToHSE();
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
SetSysClockTo48_HSE();
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
SetSysClockTo56_HSE();
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
SetSysClockTo72_HSE();
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
SetSysClockTo48_HSI();
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
SetSysClockTo56_HSI();
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
SetSysClockTo72_HSI();
|
||||
|
||||
#endif
|
||||
|
||||
/* If none of the define above is enabled, the HSI is used as System clock
|
||||
* source (default after reset)
|
||||
*/
|
||||
}
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockToHSE
|
||||
*
|
||||
* @brief Sets HSE as System clock source and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockToHSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if(HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
/* Flash 0 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_0;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1;
|
||||
|
||||
/* Select HSE as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_HSE;
|
||||
|
||||
/* Wait till HSE is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo48_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo48_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if(HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 1 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL6);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo56_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo56_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if(HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 2 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_2;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL7);
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo72_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo72_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if(HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 2 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_2;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL9);
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo48_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo48_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 1 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 6 = 48 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo56_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo56_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 1 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 7 = 56 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo72_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo72_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
|
||||
|
||||
/* Flash 1 wait state */
|
||||
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
|
||||
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 9 = 72 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,29 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v10x.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2020/04/30
|
||||
* Description : CH32V10x Device Peripheral Access Layer System Header File.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __SYSTEM_CH32V10x_H
|
||||
#define __SYSTEM_CH32V10x_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
/* System_Exported_Functions */
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__CH32V10x_SYSTEM_H */
|
|
@ -1,17 +0,0 @@
|
|||
adapter driver wlinke
|
||||
adapter speed 6000
|
||||
transport select sdi
|
||||
|
||||
wlink_set_address 0x00000000
|
||||
set _CHIPNAME wch_riscv
|
||||
sdi newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x00001
|
||||
|
||||
set _TARGETNAME $_CHIPNAME.cpu
|
||||
|
||||
target create $_TARGETNAME.0 wch_riscv -chain-position $_TARGETNAME
|
||||
$_TARGETNAME.0 configure -work-area-phys 0x20000000 -work-area-size 10000 -work-area-backup 1
|
||||
set _FLASHNAME $_CHIPNAME.flash
|
||||
|
||||
flash bank $_FLASHNAME wch_riscv 0x00000000 0 0 0 $_TARGETNAME.0
|
||||
|
||||
echo "Ready for Remote Connections"
|
|
@ -1,15 +0,0 @@
|
|||
set(MCU_VARIANT D6)
|
||||
|
||||
# 64KB zero-wait, 224KB total flash
|
||||
#set(LD_FLASH_SIZE 64K)
|
||||
set(LD_FLASH_SIZE 224K)
|
||||
set(LD_RAM_SIZE 20K)
|
||||
|
||||
# set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/../../linker/${CH32_FAMILY}_tinyuf2.ld)
|
||||
|
||||
function(update_board TARGET)
|
||||
target_compile_definitions(${TARGET} PUBLIC
|
||||
SYSCLK_FREQ_144MHz_HSE=144000000
|
||||
CFG_EXAMPLE_MSC_DUAL_READONLY
|
||||
)
|
||||
endfunction()
|
|
@ -1,21 +0,0 @@
|
|||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define LED_PORT GPIOA
|
||||
#define LED_PIN GPIO_Pin_0
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
#define UART_DEV USART1
|
||||
#define UART_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
|
||||
#define UART_TX_PIN GPIO_Pin_9
|
||||
#define UART_RX_PIN GPIO_Pin_10
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,11 +0,0 @@
|
|||
MCU_VARIANT = D6
|
||||
|
||||
CFLAGS += \
|
||||
-DSYSCLK_FREQ_144MHz_HSE=144000000 \
|
||||
-DCH32_FLASH_ENHANCE_READ_MODE=1 \
|
||||
-DCFG_EXAMPLE_MSC_DUAL_READONLY \
|
||||
|
||||
# 64KB zero-wait, 224KB total flash
|
||||
LDFLAGS += \
|
||||
-Wl,--defsym=__FLASH_SIZE=224K \
|
||||
-Wl,--defsym=__RAM_SIZE=20K \
|
|
@ -1,13 +0,0 @@
|
|||
set(MCU_VARIANT D6)
|
||||
|
||||
# 32KB zero-wait, 224KB total flash
|
||||
#set(LD_FLASH_SIZE 32K)
|
||||
set(LD_FLASH_SIZE 224K)
|
||||
set(LD_RAM_SIZE 10K)
|
||||
|
||||
function(update_board TARGET)
|
||||
target_compile_definitions(${TARGET} PUBLIC
|
||||
SYSCLK_FREQ_144MHz_HSI=144000000
|
||||
CFG_EXAMPLE_MSC_DUAL_READONLY
|
||||
)
|
||||
endfunction()
|
|
@ -1,21 +0,0 @@
|
|||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define LED_PORT GPIOA
|
||||
#define LED_PIN GPIO_Pin_0
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
#define UART_DEV USART2
|
||||
#define UART_CLOCK_EN() RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE)
|
||||
#define UART_TX_PIN GPIO_Pin_2
|
||||
#define UART_RX_PIN GPIO_Pin_3
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,11 +0,0 @@
|
|||
MCU_VARIANT = D6
|
||||
|
||||
CFLAGS += \
|
||||
-DSYSCLK_FREQ_144MHz_HSI=144000000 \
|
||||
-DCH32_FLASH_ENHANCE_READ_MODE=1 \
|
||||
-DCFG_EXAMPLE_MSC_DUAL_READONLY \
|
||||
|
||||
# 32KB zero-wait, 224KB total flash
|
||||
LDFLAGS += \
|
||||
-Wl,--defsym=__FLASH_SIZE=224K \
|
||||
-Wl,--defsym=__RAM_SIZE=10K \
|
|
@ -1,13 +0,0 @@
|
|||
set(MCU_VARIANT D6)
|
||||
|
||||
# 64KB zero-wait, 224KB total flash
|
||||
set(LD_FLASH_SIZE 64K)
|
||||
#set(LD_FLASH_SIZE 224K)
|
||||
set(LD_RAM_SIZE 20K)
|
||||
|
||||
function(update_board TARGET)
|
||||
target_compile_definitions(${TARGET} PUBLIC
|
||||
SYSCLK_FREQ_144MHz_HSE=144000000
|
||||
CFG_EXAMPLE_MSC_DUAL_READONLY
|
||||
)
|
||||
endfunction()
|
|
@ -1,21 +0,0 @@
|
|||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define LED_PORT GPIOA
|
||||
#define LED_PIN GPIO_Pin_15
|
||||
#define LED_STATE_ON 0
|
||||
|
||||
#define UART_DEV USART1
|
||||
#define UART_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
|
||||
#define UART_TX_PIN GPIO_Pin_9
|
||||
#define UART_RX_PIN GPIO_Pin_10
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,11 +0,0 @@
|
|||
MCU_VARIANT = D6
|
||||
|
||||
CFLAGS += \
|
||||
-DSYSCLK_FREQ_144MHz_HSE=144000000 \
|
||||
-DCH32_FLASH_ENHANCE_READ_MODE=1 \
|
||||
-DCFG_EXAMPLE_MSC_DUAL_READONLY \
|
||||
|
||||
# 64KB zero-wait , 224KB total flash
|
||||
LDFLAGS += \
|
||||
-Wl,--defsym=__FLASH_SIZE=224K \
|
||||
-Wl,--defsym=__RAM_SIZE=20K \
|
|
@ -1,36 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v20x_conf.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : Library configuration file.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V20x_CONF_H
|
||||
#define __CH32V20x_CONF_H
|
||||
|
||||
#include "ch32v20x_adc.h"
|
||||
#include "ch32v20x_bkp.h"
|
||||
#include "ch32v20x_can.h"
|
||||
#include "ch32v20x_crc.h"
|
||||
#include "ch32v20x_dbgmcu.h"
|
||||
#include "ch32v20x_dma.h"
|
||||
#include "ch32v20x_exti.h"
|
||||
#include "ch32v20x_flash.h"
|
||||
#include "ch32v20x_gpio.h"
|
||||
#include "ch32v20x_i2c.h"
|
||||
#include "ch32v20x_iwdg.h"
|
||||
#include "ch32v20x_pwr.h"
|
||||
#include "ch32v20x_rcc.h"
|
||||
#include "ch32v20x_rtc.h"
|
||||
#include "ch32v20x_spi.h"
|
||||
#include "ch32v20x_tim.h"
|
||||
#include "ch32v20x_usart.h"
|
||||
#include "ch32v20x_wwdg.h"
|
||||
#include "ch32v20x_it.h"
|
||||
#include "ch32v20x_misc.h"
|
||||
|
||||
#endif /* __CH32V20x_CONF_H */
|
|
@ -1,15 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v20x_it.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : This file contains the headers of the interrupt handlers.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V20x_IT_H
|
||||
#define __CH32V20x_IT_H
|
||||
|
||||
#endif /* __CH32V20x_IT_H */
|
|
@ -1,209 +0,0 @@
|
|||
#include <stdio.h>
|
||||
|
||||
// https://github.com/openwch/ch32v307/pull/90
|
||||
// https://github.com/openwch/ch32v20x/pull/12
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
|
||||
#endif
|
||||
|
||||
#include "ch32v20x.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
/* CH32v203 depending on variants can support 2 USB IPs: FSDEV and USBFS.
|
||||
* By default, we use FSDEV, but you can explicitly select by define:
|
||||
* - CFG_TUD_WCH_USBIP_FSDEV
|
||||
* - CFG_TUD_WCH_USBIP_USBFS
|
||||
*/
|
||||
|
||||
// USBFS
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USBHD_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBFS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USBHDWakeUp_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBFS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
// USBD (fsdev)
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USB_LP_CAN1_RX0_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_FSDEV
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USB_HP_CAN1_TX_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_FSDEV
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
__attribute__((interrupt)) __attribute__((used))
|
||||
void USBWakeUp_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_FSDEV
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
__attribute__((interrupt))
|
||||
void SysTick_Handler(void) {
|
||||
SysTick->SR = 0;
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t SysTick_Config(uint32_t ticks) {
|
||||
NVIC_EnableIRQ(SysTicK_IRQn);
|
||||
SysTick->CTLR = 0;
|
||||
SysTick->SR = 0;
|
||||
SysTick->CNT = 0;
|
||||
SysTick->CMP = ticks - 1;
|
||||
SysTick->CTLR = 0xF;
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
#endif
|
||||
|
||||
void board_init(void) {
|
||||
__disable_irq();
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
#endif
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure = {
|
||||
.GPIO_Pin = LED_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_Out_OD,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
};
|
||||
GPIO_Init(LED_PORT, &GPIO_InitStructure);
|
||||
|
||||
#ifdef UART_DEV
|
||||
UART_CLOCK_EN();
|
||||
GPIO_InitTypeDef usart_init = {
|
||||
.GPIO_Pin = UART_TX_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
};
|
||||
GPIO_Init(GPIOA, &usart_init);
|
||||
|
||||
USART_InitTypeDef usart = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_Mode = USART_Mode_Tx,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
};
|
||||
USART_Init(UART_DEV, &usart);
|
||||
USART_Cmd(UART_DEV, ENABLE);
|
||||
#endif
|
||||
|
||||
// USB init
|
||||
uint8_t usb_div;
|
||||
switch (SystemCoreClock) {
|
||||
case 48000000: usb_div = RCC_USBCLKSource_PLLCLK_Div1; break;
|
||||
case 96000000: usb_div = RCC_USBCLKSource_PLLCLK_Div2; break;
|
||||
case 144000000: usb_div = RCC_USBCLKSource_PLLCLK_Div3; break;
|
||||
default: TU_ASSERT(0,); break;
|
||||
}
|
||||
RCC_USBCLKConfig(usb_div);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE); // FSDEV
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_OTG_FS, ENABLE); // USB FS
|
||||
|
||||
__enable_irq();
|
||||
}
|
||||
|
||||
void board_reset_to_bootloader(void) {
|
||||
// board_led_write(true);
|
||||
//
|
||||
// __disable_irq();
|
||||
//
|
||||
// #if CFG_TUD_ENABLED
|
||||
// tud_deinit(0);
|
||||
// RCC_APB1PeriphResetCmd(RCC_APB1Periph_USB, ENABLE);
|
||||
// RCC_APB1PeriphResetCmd(RCC_APB1Periph_USB, DISABLE);
|
||||
// #endif
|
||||
//
|
||||
// SysTick->CTLR = 0;
|
||||
// for (int i = WWDG_IRQn; i< DMA1_Channel8_IRQn; i++) {
|
||||
// NVIC_DisableIRQ(i);
|
||||
// }
|
||||
//
|
||||
// __enable_irq();
|
||||
//
|
||||
// // define function pointer to BOOT ROM address
|
||||
// void (*bootloader_entry)(void) = (void (*)(void))0x1FFF8000;
|
||||
//
|
||||
// bootloader_entry();
|
||||
//
|
||||
// board_led_write(false);
|
||||
|
||||
// while(1) { }
|
||||
}
|
||||
|
||||
void board_led_write(bool state) {
|
||||
GPIO_WriteBit(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t board_get_unique_id(uint8_t id[], size_t max_len) {
|
||||
(void) max_len;
|
||||
volatile uint32_t* ch32_uuid = ((volatile uint32_t*) 0x1FFFF7E8UL);
|
||||
uint32_t* serial_32 = (uint32_t*) (uintptr_t) id;
|
||||
serial_32[0] = ch32_uuid[0];
|
||||
serial_32[1] = ch32_uuid[1];
|
||||
serial_32[2] = ch32_uuid[2];
|
||||
|
||||
return 12;
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t *buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const *buf, int len) {
|
||||
#ifdef UART_DEV
|
||||
const char *bufc = (const char *) buf;
|
||||
for (int i = 0; i < len; i++) {
|
||||
while (USART_GetFlagStatus(UART_DEV, USART_FLAG_TC) == RESET);
|
||||
USART_SendData(UART_DEV, *bufc++);
|
||||
}
|
||||
#else
|
||||
(void) buf; (void) len;
|
||||
#endif
|
||||
|
||||
return len;
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------
|
||||
// Neopixel
|
||||
//--------------------------------------------------------------------
|
|
@ -1,144 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
set(UF2_FAMILY_ID 0x699b62ec)
|
||||
set(CH32_FAMILY ch32v20x)
|
||||
set(SDK_DIR ${TOP}/hw/mcu/wch/${CH32_FAMILY})
|
||||
set(SDK_SRC_DIR ${SDK_DIR}/EVT/EXAM/SRC)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
set(CMAKE_SYSTEM_PROCESSOR rv32imac-ilp32 CACHE INTERNAL "System Processor")
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/riscv_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS CH32V20X CACHE INTERNAL "")
|
||||
set(OPENOCD_OPTION "-f ${CMAKE_CURRENT_LIST_DIR}/wch-riscv.cfg")
|
||||
|
||||
# Port0 use FSDev, Port1 use USBFS
|
||||
if (NOT DEFINED PORT)
|
||||
set(PORT 0)
|
||||
endif()
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/${CH32_FAMILY}.ld)
|
||||
endif ()
|
||||
set(LD_FILE_Clang ${LD_FILE_GNU})
|
||||
|
||||
if (NOT DEFINED STARTUP_FILE_GNU)
|
||||
set(STARTUP_FILE_GNU ${SDK_SRC_DIR}/Startup/startup_${CH32_FAMILY}_${MCU_VARIANT}.S)
|
||||
endif ()
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${SDK_SRC_DIR}/Core/core_riscv.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_flash.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_gpio.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_misc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_rcc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_usart.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/system_${CH32_FAMILY}.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${SDK_SRC_DIR}/Core
|
||||
${SDK_SRC_DIR}/Peripheral/inc
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CH32V20x_${MCU_VARIANT}
|
||||
)
|
||||
|
||||
if (PORT EQUAL 0)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CFG_TUD_WCH_USBIP_FSDEV=1
|
||||
)
|
||||
elseif (PORT EQUAL 1)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CFG_TUD_WCH_USBIP_USBFS=1
|
||||
)
|
||||
else()
|
||||
message(FATAL_ERROR "Invalid PORT ${PORT}")
|
||||
endif()
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (LD_FLASH_SIZE STREQUAL 224K)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CH32_FLASH_ENHANCE_READ_MODE=1
|
||||
)
|
||||
endif()
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
-mcmodel=medany
|
||||
)
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
-nostartfiles
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
-Wl,--defsym=__FLASH_SIZE=${LD_FLASH_SIZE}
|
||||
-Wl,--defsym=__RAM_SIZE=${LD_RAM_SIZE}
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
message(FATAL_ERROR "Clang is not supported for CH32v")
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_CH32V20X ${RTOS})
|
||||
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/wch/dcd_ch32_usbfs.c
|
||||
${TOP}/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_openocd_wch(${TARGET})
|
||||
family_flash_wlink_rs(${TARGET})
|
||||
|
||||
#family_add_uf2(${TARGET} ${UF2_FAMILY_ID})
|
||||
#family_flash_uf2(${TARGET} ${UF2_FAMILY_ID})
|
||||
endfunction()
|
|
@ -1,64 +0,0 @@
|
|||
# https://www.embecosm.com/resources/tool-chain-downloads/#riscv-stable
|
||||
#CROSS_COMPILE ?= riscv32-unknown-elf-
|
||||
|
||||
# Toolchain from https://nucleisys.com/download.php
|
||||
#CROSS_COMPILE ?= riscv-nuclei-elf-
|
||||
|
||||
# Toolchain from https://github.com/xpack-dev-tools/riscv-none-elf-gcc-xpack
|
||||
CROSS_COMPILE ?= riscv-none-elf-
|
||||
|
||||
CH32_FAMILY = ch32v20x
|
||||
SDK_DIR = hw/mcu/wch/ch32v20x
|
||||
SDK_SRC_DIR = $(SDK_DIR)/EVT/EXAM/SRC
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
CPU_CORE ?= rv32imac-ilp32
|
||||
|
||||
# Port0 use FSDev, Port1 use USBFS
|
||||
PORT ?= 0
|
||||
|
||||
CFLAGS += \
|
||||
-mcmodel=medany \
|
||||
-ffat-lto-objects \
|
||||
-flto \
|
||||
-DCH32V20x_${MCU_VARIANT} \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_CH32V20X
|
||||
|
||||
# https://github.com/openwch/ch32v20x/pull/12
|
||||
CFLAGS += -Wno-error=strict-prototypes
|
||||
|
||||
ifeq ($(PORT),0)
|
||||
$(info "Using FSDEV driver")
|
||||
CFLAGS += -DCFG_TUD_WCH_USBIP_FSDEV=1
|
||||
else
|
||||
$(info "Using USBFS driver")
|
||||
CFLAGS += -DCFG_TUD_WCH_USBIP_USBFS=1
|
||||
endif
|
||||
|
||||
LDFLAGS_GCC += \
|
||||
-nostdlib -nostartfiles \
|
||||
--specs=nosys.specs --specs=nano.specs \
|
||||
|
||||
LD_FILE = $(FAMILY_PATH)/linker/${CH32_FAMILY}.ld
|
||||
|
||||
SRC_C += \
|
||||
src/portable/wch/dcd_ch32_usbfs.c \
|
||||
src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c \
|
||||
$(SDK_SRC_DIR)/Core/core_riscv.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_gpio.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_misc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_rcc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_usart.c \
|
||||
|
||||
SRC_S += $(SDK_SRC_DIR)/Startup/startup_${CH32_FAMILY}_${MCU_VARIANT}.S
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Core \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Peripheral/inc \
|
||||
|
||||
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/RISC-V
|
||||
|
||||
OPENOCD_WCH_OPTION=-f $(TOP)/$(FAMILY_PATH)/wch-riscv.cfg
|
||||
flash: flash-wlink-rs
|
||||
#flash: flash-openocd-wch
|
|
@ -1,164 +0,0 @@
|
|||
/* Define default values if not already defined */
|
||||
__flash_size = DEFINED(__FLASH_SIZE) ? __FLASH_SIZE : 64K;
|
||||
__ram_size = DEFINED(__RAM_SIZE) ? __RAM_SIZE : 20K;
|
||||
__stack_size = DEFINED(__STACK_SIZE) ? __STACK_SIZE : 2048;
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = __flash_size
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = __ram_size
|
||||
}
|
||||
|
||||
ENTRY( _start )
|
||||
|
||||
PROVIDE( _stack_size = __stack_size );
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.init :
|
||||
{
|
||||
_sinit = .;
|
||||
. = ALIGN(4);
|
||||
KEEP(*(SORT_NONE(.init)))
|
||||
. = ALIGN(4);
|
||||
_einit = .;
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.vector :
|
||||
{
|
||||
*(.vector);
|
||||
. = ALIGN(64);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.rodata)
|
||||
*(.rodata*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini :
|
||||
{
|
||||
KEEP(*(SORT_NONE(.fini)))
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
PROVIDE( _etext = . );
|
||||
PROVIDE( _eitcm = . );
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
|
||||
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
|
||||
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.ctors :
|
||||
{
|
||||
/* gcc uses crtbegin.o to find the start of
|
||||
the constructors, so we make sure it is
|
||||
first. Because this is a wildcard, it
|
||||
doesn't matter if the user does not
|
||||
actually link against crtbegin.o; the
|
||||
linker won't look for a file to match a
|
||||
wildcard. The wildcard also means that it
|
||||
doesn't matter which directory crtbegin.o
|
||||
is in. */
|
||||
KEEP (*crtbegin.o(.ctors))
|
||||
KEEP (*crtbegin?.o(.ctors))
|
||||
/* We don't want to include the .ctor section from
|
||||
the crtend.o file until after the sorted ctors.
|
||||
The .ctor section from the crtend file contains the
|
||||
end of ctors marker and it must be last */
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
|
||||
KEEP (*(SORT(.ctors.*)))
|
||||
KEEP (*(.ctors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dtors :
|
||||
{
|
||||
KEEP (*crtbegin.o(.dtors))
|
||||
KEEP (*crtbegin?.o(.dtors))
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
|
||||
KEEP (*(SORT(.dtors.*)))
|
||||
KEEP (*(.dtors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_vma = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.dlalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_lma = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.data :
|
||||
{
|
||||
*(.gnu.linkonce.r.*)
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
. = ALIGN(8);
|
||||
PROVIDE( __global_pointer$ = . + 0x800 );
|
||||
*(.sdata .sdata.*)
|
||||
*(.sdata2.*)
|
||||
*(.gnu.linkonce.s.*)
|
||||
. = ALIGN(8);
|
||||
*(.srodata.cst16)
|
||||
*(.srodata.cst8)
|
||||
*(.srodata.cst4)
|
||||
*(.srodata.cst2)
|
||||
*(.srodata .srodata.*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _edata = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _sbss = .);
|
||||
*(.sbss*)
|
||||
*(.gnu.linkonce.sb.*)
|
||||
*(.bss*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _ebss = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
PROVIDE( _end = _ebss);
|
||||
PROVIDE( end = . );
|
||||
|
||||
.stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size :
|
||||
{
|
||||
PROVIDE( _heap_end = . );
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_susrstack = . );
|
||||
. = . + __stack_size;
|
||||
PROVIDE( _eusrstack = .);
|
||||
} >RAM
|
||||
|
||||
}
|
|
@ -1,986 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v20x.c
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : CH32V20x Device Peripheral Access Layer System Source File.
|
||||
* For HSE = 32Mhz (CH32V208x/CH32V203RBT6)
|
||||
* For HSE = 8Mhz (other CH32V203x)
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#include "ch32v20x.h"
|
||||
|
||||
/*
|
||||
* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after
|
||||
* reset the HSI is used as SYSCLK source).
|
||||
* If none of the define below is enabled, the HSI is used as System clock source.
|
||||
*/
|
||||
//#define SYSCLK_FREQ_HSE HSE_VALUE
|
||||
// #define SYSCLK_FREQ_48MHz_HSE 48000000
|
||||
//#define SYSCLK_FREQ_56MHz_HSE 56000000
|
||||
// #define SYSCLK_FREQ_72MHz_HSE 72000000
|
||||
// #define SYSCLK_FREQ_96MHz_HSE 96000000
|
||||
//#define SYSCLK_FREQ_120MHz_HSE 120000000
|
||||
//#define SYSCLK_FREQ_144MHz_HSE 144000000
|
||||
//#define SYSCLK_FREQ_HSI HSI_VALUE
|
||||
//#define SYSCLK_FREQ_48MHz_HSI 48000000
|
||||
//#define SYSCLK_FREQ_56MHz_HSI 56000000
|
||||
//#define SYSCLK_FREQ_72MHz_HSI 72000000
|
||||
//#define SYSCLK_FREQ_96MHz_HSI 96000000
|
||||
//#define SYSCLK_FREQ_120MHz_HSI 120000000
|
||||
//#define SYSCLK_FREQ_144MHz_HSI 144000000
|
||||
|
||||
/* Clock Definitions */
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_96MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_120MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_144MHz_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_96MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_120MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSI
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_144MHz_HSI; /* System Clock Frequency (Core Clock) */
|
||||
#else
|
||||
uint32_t SystemCoreClock = HSI_VALUE; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
#endif
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/* system_private_function_proto_types */
|
||||
static void SetSysClock(void);
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
static void SetSysClockToHSE( void );
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
static void SetSysClockTo48_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
static void SetSysClockTo56_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
static void SetSysClockTo72_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSE
|
||||
static void SetSysClockTo96_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSE
|
||||
static void SetSysClockTo120_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSE
|
||||
static void SetSysClockTo144_HSE( void );
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
static void SetSysClockTo48_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
static void SetSysClockTo56_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
static void SetSysClockTo72_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSI
|
||||
static void SetSysClockTo96_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSI
|
||||
static void SetSysClockTo120_HSI( void );
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSI
|
||||
static void SetSysClockTo144_HSI( void );
|
||||
|
||||
#endif
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemInit
|
||||
*
|
||||
* @brief Setup the microcontroller system Initialize the Embedded Flash Interface,
|
||||
* the PLL and update the SystemCoreClock variable.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemInit (void)
|
||||
{
|
||||
// Enable Flash enhance read mode for full 224KB
|
||||
#if defined(CH32_FLASH_ENHANCE_READ_MODE) && CH32_FLASH_ENHANCE_READ_MODE == 1
|
||||
FLASH->KEYR = 0x45670123; // FLASH_Unlock_Fast();
|
||||
FLASH->KEYR = 0xCDEF89AB;
|
||||
|
||||
FLASH->CTLR |= (1 << 24); // Enhanced Read Mode
|
||||
|
||||
FLASH->CTLR |= (1 << 15); // FLASH_Lock_Fast();
|
||||
#endif
|
||||
|
||||
RCC->CTLR |= (uint32_t)0x00000001;
|
||||
RCC->CFGR0 &= (uint32_t)0xF8FF0000;
|
||||
RCC->CTLR &= (uint32_t)0xFEF6FFFF;
|
||||
RCC->CTLR &= (uint32_t)0xFFFBFFFF;
|
||||
RCC->CFGR0 &= (uint32_t)0xFF80FFFF;
|
||||
RCC->INTR = 0x009F0000;
|
||||
SetSysClock();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemCoreClockUpdate
|
||||
*
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, Pll_6_5 = 0;
|
||||
|
||||
tmp = RCC->CFGR0 & RCC_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04:
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08:
|
||||
pllmull = RCC->CFGR0 & RCC_PLLMULL;
|
||||
pllsource = RCC->CFGR0 & RCC_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
if(pllmull == 17) pllmull = 18;
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
if(EXTEN->EXTEN_CTR & EXTEN_PLL_HSI_PRE){
|
||||
SystemCoreClock = HSI_VALUE * pllmull;
|
||||
}
|
||||
else{
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
#if defined (CH32V20x_D8W)
|
||||
if((RCC->CFGR0 & (3<<22)) == (3<<22))
|
||||
{
|
||||
SystemCoreClock = ((HSE_VALUE>>1)) * pllmull;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
if ((RCC->CFGR0 & RCC_PLLXTPRE) != (uint32_t)RESET)
|
||||
{
|
||||
#if defined (CH32V20x_D8) || defined (CH32V20x_D8W)
|
||||
SystemCoreClock = ((HSE_VALUE>>2) >> 1) * pllmull;
|
||||
#else
|
||||
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
#if defined (CH32V20x_D8) || defined (CH32V20x_D8W)
|
||||
SystemCoreClock = (HSE_VALUE>>2) * pllmull;
|
||||
#else
|
||||
SystemCoreClock = HSE_VALUE * pllmull;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if(Pll_6_5 == 1) SystemCoreClock = (SystemCoreClock / 2);
|
||||
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
|
||||
tmp = AHBPrescTable[((RCC->CFGR0 & RCC_HPRE) >> 4)];
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClock
|
||||
*
|
||||
* @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClock(void)
|
||||
{
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
SetSysClockToHSE();
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
SetSysClockTo48_HSE();
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
SetSysClockTo56_HSE();
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
SetSysClockTo72_HSE();
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSE
|
||||
SetSysClockTo96_HSE();
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSE
|
||||
SetSysClockTo120_HSE();
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSE
|
||||
SetSysClockTo144_HSE();
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
SetSysClockTo48_HSI();
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
SetSysClockTo56_HSI();
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
SetSysClockTo72_HSI();
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSI
|
||||
SetSysClockTo96_HSI();
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSI
|
||||
SetSysClockTo120_HSI();
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSI
|
||||
SetSysClockTo144_HSI();
|
||||
|
||||
#endif
|
||||
|
||||
/* If none of the define above is enabled, the HSI is used as System clock
|
||||
* source (default after reset)
|
||||
*/
|
||||
}
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockToHSE
|
||||
*
|
||||
* @brief Sets HSE as System clock source and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockToHSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1;
|
||||
|
||||
/* Select HSE as system clock source
|
||||
* CH32V20x_D6 (HSE=8MHZ)
|
||||
* CH32V20x_D8 (HSE=32MHZ)
|
||||
* CH32V20x_D8W (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_HSE;
|
||||
|
||||
/* Wait till HSE is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo48_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo48_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 6 = 48 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 6 = 48 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 6 = 48 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo56_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo56_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 7 = 56 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 7 = 56 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 7 = 56 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL7);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo72_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo72_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 9 = 72 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 9 = 72 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 9 = 72 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo96_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 96MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo96_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 12 = 96 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo120_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 120MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo120_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if(HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
#if defined (CH32V20x_D8W)
|
||||
RCC->CFGR0 |= (uint32_t)(3<<22);
|
||||
/* HCLK = SYSCLK/2 */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV2;
|
||||
#else
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
#endif
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 15 = 120 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 15 = 120 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/2 * 15 = 240 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo144_HSE
|
||||
*
|
||||
* @brief Sets System clock frequency to 144MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo144_HSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 18 = 144 MHz (HSE=8MHZ)
|
||||
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 18 = 144 MHz (HSE=32MHZ)
|
||||
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 18 = 144 MHz (HSE=32MHZ)
|
||||
*/
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_48MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo48_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo48_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 6 = 48 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_56MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo56_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo56_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 7 = 48 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_72MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo72_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo72_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 9 = 72 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_96MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo96_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 96MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo96_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 12 = 96 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL12);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_120MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo120_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 120MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo120_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 15 = 120 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL15);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
#elif defined SYSCLK_FREQ_144MHz_HSI
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo144_HSI
|
||||
*
|
||||
* @brief Sets System clock frequency to 144MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo144_HSI(void)
|
||||
{
|
||||
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
|
||||
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSI * 18 = 144 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL18);
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,29 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v20x.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : CH32V20x Device Peripheral Access Layer System Header File.
|
||||
*********************************************************************************
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* Attention: This software (modified or not) and binary are used for
|
||||
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
|
||||
*******************************************************************************/
|
||||
#ifndef __SYSTEM_ch32v20x_H
|
||||
#define __SYSTEM_ch32v20x_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
/* System_Exported_Functions */
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__CH32V20x_SYSTEM_H */
|
|
@ -1,17 +0,0 @@
|
|||
adapter driver wlinke
|
||||
adapter speed 6000
|
||||
transport select sdi
|
||||
|
||||
wlink_set_address 0x00000000
|
||||
set _CHIPNAME wch_riscv
|
||||
sdi newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x00001
|
||||
|
||||
set _TARGETNAME $_CHIPNAME.cpu
|
||||
|
||||
target create $_TARGETNAME.0 wch_riscv -chain-position $_TARGETNAME
|
||||
$_TARGETNAME.0 configure -work-area-phys 0x20000000 -work-area-size 10000 -work-area-backup 1
|
||||
set _FLASHNAME $_CHIPNAME.flash
|
||||
|
||||
flash bank $_FLASHNAME wch_riscv 0x00000000 0 0 0 $_TARGETNAME.0
|
||||
|
||||
echo "Ready for Remote Connections"
|
|
@ -1,4 +0,0 @@
|
|||
function(update_board TARGET)
|
||||
# target_compile_definitions(${TARGET} PUBLIC
|
||||
# )
|
||||
endfunction()
|
|
@ -1,50 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2023 Ha Thach (tinyusb.org) for Adafruit Industries
|
||||
*
|
||||
* 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 BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// LED: need to wire pin LED1 to PC0 in the J3 header
|
||||
#define LED_PORT GPIOC
|
||||
#define LED_PIN GPIO_Pin_0
|
||||
#define LED_STATE_ON 0
|
||||
#define LED_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE)
|
||||
|
||||
// Button: need to wire pin KEY to PC1 in the J3 header
|
||||
#define BUTTON_PORT GPIOC
|
||||
#define BUTTON_PIN GPIO_Pin_1
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
#define BUTTON_CLOCK_EN() do { } while(0) // same as LED clock, no need to do anything
|
||||
|
||||
// TODO UART port
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1 +0,0 @@
|
|||
LD_FILE = $(FAMILY_PATH)/ch32v307.ld
|
|
@ -1,167 +0,0 @@
|
|||
ENTRY( _start )
|
||||
|
||||
__stack_size = 4096;
|
||||
|
||||
PROVIDE( _stack_size = __stack_size );
|
||||
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 288K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K
|
||||
}
|
||||
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
|
||||
.init :
|
||||
{
|
||||
_sinit = .;
|
||||
. = ALIGN(4);
|
||||
KEEP(*(SORT_NONE(.init)))
|
||||
. = ALIGN(4);
|
||||
_einit = .;
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.vector :
|
||||
{
|
||||
*(.vector);
|
||||
. = ALIGN(64);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.rodata)
|
||||
*(.rodata*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.gnu.linkonce.t.*)
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini :
|
||||
{
|
||||
KEEP(*(SORT_NONE(.fini)))
|
||||
. = ALIGN(4);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
PROVIDE( _etext = . );
|
||||
PROVIDE( _eitcm = . );
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
|
||||
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
|
||||
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.ctors :
|
||||
{
|
||||
/* gcc uses crtbegin.o to find the start of
|
||||
the constructors, so we make sure it is
|
||||
first. Because this is a wildcard, it
|
||||
doesn't matter if the user does not
|
||||
actually link against crtbegin.o; the
|
||||
linker won't look for a file to match a
|
||||
wildcard. The wildcard also means that it
|
||||
doesn't matter which directory crtbegin.o
|
||||
is in. */
|
||||
KEEP (*crtbegin.o(.ctors))
|
||||
KEEP (*crtbegin?.o(.ctors))
|
||||
/* We don't want to include the .ctor section from
|
||||
the crtend.o file until after the sorted ctors.
|
||||
The .ctor section from the crtend file contains the
|
||||
end of ctors marker and it must be last */
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
|
||||
KEEP (*(SORT(.ctors.*)))
|
||||
KEEP (*(.ctors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dtors :
|
||||
{
|
||||
KEEP (*crtbegin.o(.dtors))
|
||||
KEEP (*crtbegin?.o(.dtors))
|
||||
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
|
||||
KEEP (*(SORT(.dtors.*)))
|
||||
KEEP (*(.dtors))
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.dalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_vma = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.dlalign :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_data_lma = .);
|
||||
} >FLASH AT>FLASH
|
||||
|
||||
.data :
|
||||
{
|
||||
*(.gnu.linkonce.r.*)
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
. = ALIGN(8);
|
||||
PROVIDE( __global_pointer$ = . + 0x800 );
|
||||
*(.sdata .sdata.*)
|
||||
*(.sdata2.*)
|
||||
*(.gnu.linkonce.s.*)
|
||||
. = ALIGN(8);
|
||||
*(.srodata.cst16)
|
||||
*(.srodata.cst8)
|
||||
*(.srodata.cst4)
|
||||
*(.srodata.cst2)
|
||||
*(.srodata .srodata.*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _edata = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _sbss = .);
|
||||
*(.sbss*)
|
||||
*(.gnu.linkonce.sb.*)
|
||||
*(.bss*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON*)
|
||||
. = ALIGN(4);
|
||||
PROVIDE( _ebss = .);
|
||||
} >RAM AT>FLASH
|
||||
|
||||
PROVIDE( _end = _ebss);
|
||||
PROVIDE( end = . );
|
||||
|
||||
.stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size :
|
||||
{
|
||||
PROVIDE( _heap_end = . );
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_susrstack = . );
|
||||
. = . + __stack_size;
|
||||
PROVIDE( _eusrstack = .);
|
||||
__freertos_irq_stack_top = .;
|
||||
} >RAM
|
||||
|
||||
}
|
|
@ -1,38 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v30x_conf.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : Library configuration file.
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V30x_CONF_H
|
||||
#define __CH32V30x_CONF_H
|
||||
|
||||
#include "ch32v30x_adc.h"
|
||||
#include "ch32v30x_bkp.h"
|
||||
#include "ch32v30x_can.h"
|
||||
#include "ch32v30x_crc.h"
|
||||
#include "ch32v30x_dac.h"
|
||||
#include "ch32v30x_dbgmcu.h"
|
||||
#include "ch32v30x_dma.h"
|
||||
#include "ch32v30x_exti.h"
|
||||
#include "ch32v30x_flash.h"
|
||||
#include "ch32v30x_fsmc.h"
|
||||
#include "ch32v30x_gpio.h"
|
||||
#include "ch32v30x_i2c.h"
|
||||
#include "ch32v30x_iwdg.h"
|
||||
#include "ch32v30x_pwr.h"
|
||||
#include "ch32v30x_rcc.h"
|
||||
#include "ch32v30x_rtc.h"
|
||||
#include "ch32v30x_sdio.h"
|
||||
#include "ch32v30x_spi.h"
|
||||
#include "ch32v30x_tim.h"
|
||||
#include "ch32v30x_usart.h"
|
||||
#include "ch32v30x_wwdg.h"
|
||||
#include "ch32v30x_it.h"
|
||||
#include "ch32v30x_misc.h"
|
||||
|
||||
|
||||
#endif /* __CH32V30x_CONF_H */
|
|
@ -1,47 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v30x_it.c
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : Main Interrupt Service Routines.
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*******************************************************************************/
|
||||
#include "ch32v30x_it.h"
|
||||
|
||||
void NMI_Handler(void) __attribute__((naked));
|
||||
void HardFault_Handler(void) __attribute__((naked));
|
||||
|
||||
/*********************************************************************
|
||||
* @fn NMI_Handler
|
||||
*
|
||||
* @brief This function handles NMI exception.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void NMI_Handle(void){
|
||||
__asm volatile ("call NMI_Handler_impl; mret");
|
||||
}
|
||||
|
||||
__attribute__((used)) void NMI_Handler_impl(void)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn HardFault_Handler
|
||||
*
|
||||
* @brief This function handles Hard Fault exception.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void HardFault_Handler(void){
|
||||
__asm volatile ("call HardFault_Handler_impl; mret");
|
||||
}
|
||||
|
||||
__attribute__((used)) void HardFault_Handler_impl(void)
|
||||
{
|
||||
while (1)
|
||||
{
|
||||
}
|
||||
}
|
|
@ -1,16 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : ch32v30x_it.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : This file contains the headers of the interrupt handlers.
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*******************************************************************************/
|
||||
#ifndef __CH32V30x_IT_H
|
||||
#define __CH32V30x_IT_H
|
||||
|
||||
// #include "debug.h"
|
||||
|
||||
|
||||
#endif /* __CH32V30x_IT_H */
|
|
@ -1,119 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2022 Greg Davill
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "debug_uart.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
|
||||
#endif
|
||||
|
||||
#include <ch32v30x.h>
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
#define UART_RINGBUFFER_SIZE_TX 128
|
||||
#define UART_RINGBUFFER_MASK_TX (UART_RINGBUFFER_SIZE_TX-1)
|
||||
|
||||
static char tx_buf[UART_RINGBUFFER_SIZE_TX];
|
||||
static unsigned int tx_produce;
|
||||
static volatile unsigned int tx_consume;
|
||||
|
||||
void USART1_IRQHandler(void) __attribute__((naked));
|
||||
void USART1_IRQHandler(void) {
|
||||
__asm volatile ("call USART1_IRQHandler_impl; mret");
|
||||
}
|
||||
|
||||
__attribute__((used)) void USART1_IRQHandler_impl(void)
|
||||
{
|
||||
if(USART_GetITStatus(USART1, USART_IT_TC) != RESET)
|
||||
{
|
||||
USART_ClearITPendingBit(USART1, USART_IT_TC);
|
||||
|
||||
if(tx_consume != tx_produce) {
|
||||
USART_SendData(USART1, tx_buf[tx_consume]);
|
||||
tx_consume = (tx_consume + 1) & UART_RINGBUFFER_MASK_TX;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void uart_write(char c)
|
||||
{
|
||||
unsigned int tx_produce_next = (tx_produce + 1) & UART_RINGBUFFER_MASK_TX;
|
||||
|
||||
NVIC_DisableIRQ(USART1_IRQn);
|
||||
if((tx_consume != tx_produce) || (USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET)) {
|
||||
tx_buf[tx_produce] = c;
|
||||
tx_produce = tx_produce_next;
|
||||
} else {
|
||||
USART_SendData(USART1, c);
|
||||
}
|
||||
NVIC_EnableIRQ(USART1_IRQn);
|
||||
}
|
||||
|
||||
|
||||
void uart_sync(void)
|
||||
{
|
||||
while(tx_consume != tx_produce);
|
||||
}
|
||||
|
||||
|
||||
void usart_printf_init(uint32_t baudrate)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
||||
tx_produce = 0;
|
||||
tx_consume = 0;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baudrate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_InitStructure.USART_Mode = USART_Mode_Tx;
|
||||
|
||||
USART_Init(USART1, &USART_InitStructure);
|
||||
USART_ITConfig(USART1, USART_IT_TC, ENABLE);
|
||||
USART_Cmd(USART1, ENABLE);
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure = { 0 };
|
||||
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 3;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
|
@ -1,31 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2022 Greg Davill
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
void uart_write(char c);
|
||||
void uart_sync(void);
|
||||
void usart_printf_init(uint32_t baudrate);
|
|
@ -1,191 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2022 Greg Davill
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "stdio.h"
|
||||
|
||||
// https://github.com/openwch/ch32v307/pull/90
|
||||
// https://github.com/openwch/ch32v20x/pull/12
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
|
||||
#endif
|
||||
|
||||
#include "debug_uart.h"
|
||||
#include "ch32v30x.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// TODO maybe having FS as port0, HS as port1
|
||||
|
||||
__attribute__((interrupt)) void USBHS_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBHS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
__attribute__((interrupt)) void OTG_FS_IRQHandler(void) {
|
||||
#if CFG_TUD_WCH_USBIP_USBFS
|
||||
tud_int_handler(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
uint32_t SysTick_Config(uint32_t ticks) {
|
||||
NVIC_EnableIRQ(SysTicK_IRQn);
|
||||
SysTick->CTLR = 0;
|
||||
SysTick->SR = 0;
|
||||
SysTick->CNT = 0;
|
||||
SysTick->CMP = ticks - 1;
|
||||
SysTick->CTLR = 0xF;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
|
||||
/* Disable interrupts during init */
|
||||
__disable_irq();
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
#endif
|
||||
|
||||
usart_printf_init(CFG_BOARD_UART_BAUDRATE);
|
||||
|
||||
#ifdef CH32V30x_D8C
|
||||
// v305/v307: Highspeed USB
|
||||
RCC_USBCLK48MConfig(RCC_USBCLK48MCLKSource_USBPHY);
|
||||
RCC_USBHSPLLCLKConfig(RCC_HSBHSPLLCLKSource_HSE);
|
||||
RCC_USBHSConfig(RCC_USBPLL_Div2);
|
||||
RCC_USBHSPLLCKREFCLKConfig(RCC_USBHSPLLCKREFCLK_4M);
|
||||
RCC_USBHSPHYPLLALIVEcmd(ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_USBHS, ENABLE);
|
||||
#endif
|
||||
|
||||
// Fullspeed USB
|
||||
uint8_t otg_div;
|
||||
switch (SystemCoreClock) {
|
||||
case 48000000: otg_div = RCC_OTGFSCLKSource_PLLCLK_Div1; break;
|
||||
case 96000000: otg_div = RCC_OTGFSCLKSource_PLLCLK_Div2; break;
|
||||
case 144000000: otg_div = RCC_OTGFSCLKSource_PLLCLK_Div3; break;
|
||||
default: TU_ASSERT(0,); break;
|
||||
}
|
||||
RCC_OTGFSCLKConfig(otg_div);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_OTG_FS, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure = {0};
|
||||
|
||||
// LED
|
||||
LED_CLOCK_EN();
|
||||
GPIO_InitStructure.GPIO_Pin = LED_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(LED_PORT, &GPIO_InitStructure);
|
||||
|
||||
// Button
|
||||
BUTTON_CLOCK_EN();
|
||||
GPIO_InitStructure.GPIO_Pin = BUTTON_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(BUTTON_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* Enable interrupts globally */
|
||||
__enable_irq();
|
||||
|
||||
board_delay(2);
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
__attribute__((interrupt)) void SysTick_Handler(void) {
|
||||
SysTick->SR = 0;
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_led_write(bool state) {
|
||||
GPIO_WriteBit(LED_PORT, LED_PIN, state);
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return BUTTON_STATE_ACTIVE == GPIO_ReadInputDataBit(BUTTON_PORT, BUTTON_PIN);
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const* buf, int len) {
|
||||
int txsize = len;
|
||||
const char* bufc = (const char*) buf;
|
||||
while (txsize--) {
|
||||
uart_write(*bufc++);
|
||||
}
|
||||
uart_sync();
|
||||
return len;
|
||||
}
|
||||
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief Reports the name of the source file and the source line number
|
||||
* where the assert_param error has occurred.
|
||||
* @param file: pointer to the source file name
|
||||
* @param line: assert_param error line source number
|
||||
* @retval None
|
||||
*/
|
||||
void assert_failed(char* file, uint32_t line) {
|
||||
/* USER CODE BEGIN 6 */
|
||||
/* User can add his own implementation to report the file name and line
|
||||
number,
|
||||
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line)
|
||||
*/
|
||||
/* USER CODE END 6 */
|
||||
}
|
||||
#endif /* USE_FULL_ASSERT */
|
|
@ -1,129 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
set(CH32_FAMILY ch32v30x)
|
||||
set(SDK_DIR ${TOP}/hw/mcu/wch/ch32v307)
|
||||
set(SDK_SRC_DIR ${SDK_DIR}/EVT/EXAM/SRC)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
# toolchain set up
|
||||
set(CMAKE_SYSTEM_PROCESSOR rv32imac-ilp32 CACHE INTERNAL "System Processor")
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/riscv_${TOOLCHAIN}.cmake)
|
||||
|
||||
set(FAMILY_MCUS CH32V307 CACHE INTERNAL "")
|
||||
set(OPENOCD_OPTION "-f ${CMAKE_CURRENT_LIST_DIR}/wch-riscv.cfg")
|
||||
|
||||
# default to highspeed, used to select USBFS / USBHS driver
|
||||
if (NOT DEFINED SPEED)
|
||||
set(SPEED high)
|
||||
endif()
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/ch32v307.ld)
|
||||
endif ()
|
||||
set(LD_FILE_Clang ${LD_FILE_GNU})
|
||||
|
||||
if (NOT DEFINED STARTUP_FILE_GNU)
|
||||
set(STARTUP_FILE_GNU ${SDK_SRC_DIR}/Startup/startup_${CH32_FAMILY}_D8C.S)
|
||||
endif ()
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${SDK_SRC_DIR}/Core/core_riscv.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_gpio.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_misc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_rcc.c
|
||||
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_usart.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/${CH32_FAMILY}_it.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/system_${CH32_FAMILY}.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${SDK_SRC_DIR}/Core
|
||||
${SDK_SRC_DIR}/Peripheral/inc
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
)
|
||||
if (SPEED STREQUAL high)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CFG_TUD_WCH_USBIP_USBHS=1
|
||||
# BOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED
|
||||
)
|
||||
else ()
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CFG_TUD_WCH_USBIP_USBFS=1
|
||||
)
|
||||
endif ()
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC
|
||||
-msmall-data-limit=8
|
||||
-mno-save-restore
|
||||
-fmessage-length=0
|
||||
-fsigned-char
|
||||
)
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-nostartfiles
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
message(FATAL_ERROR "Clang is not supported for MSP432E4")
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/debug_uart.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_CH32V307 ${RTOS})
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/wch/dcd_ch32_usbhs.c
|
||||
${TOP}/src/portable/wch/dcd_ch32_usbfs.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_openocd_wch(${TARGET})
|
||||
endfunction()
|
|
@ -1,64 +0,0 @@
|
|||
# https://www.embecosm.com/resources/tool-chain-downloads/#riscv-stable
|
||||
#CROSS_COMPILE ?= riscv32-unknown-elf-
|
||||
|
||||
# Toolchain from https://nucleisys.com/download.php
|
||||
#CROSS_COMPILE ?= riscv-nuclei-elf-
|
||||
|
||||
# Toolchain from https://github.com/xpack-dev-tools/riscv-none-elf-gcc-xpack
|
||||
CROSS_COMPILE ?= riscv-none-elf-
|
||||
|
||||
CH32_FAMILY = ch32v30x
|
||||
SDK_DIR = hw/mcu/wch/ch32v307
|
||||
SDK_SRC_DIR = $(SDK_DIR)/EVT/EXAM/SRC
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
CPU_CORE ?= rv32imac-ilp32
|
||||
|
||||
# default to use high speed port, unless specified in board.mk or command line
|
||||
SPEED ?= high
|
||||
|
||||
CFLAGS += \
|
||||
-flto \
|
||||
-msmall-data-limit=8 \
|
||||
-mno-save-restore \
|
||||
-fmessage-length=0 \
|
||||
-fsigned-char \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_CH32V307 \
|
||||
|
||||
# https://github.com/openwch/ch32v307/pull/90
|
||||
CFLAGS += -Wno-error=strict-prototypes
|
||||
|
||||
ifeq ($(SPEED),high)
|
||||
$(info "Using USBHS driver for HighSpeed mode")
|
||||
CFLAGS += -DCFG_TUD_WCH_USBIP_USBHS=1
|
||||
else
|
||||
$(info "Using USBFS driver for FullSpeed mode")
|
||||
CFLAGS += -DCFG_TUD_WCH_USBIP_USBFS=1
|
||||
endif
|
||||
|
||||
LDFLAGS_GCC += \
|
||||
-nostdlib -nostartfiles \
|
||||
--specs=nosys.specs --specs=nano.specs \
|
||||
|
||||
SRC_C += \
|
||||
src/portable/wch/dcd_ch32_usbhs.c \
|
||||
src/portable/wch/dcd_ch32_usbfs.c \
|
||||
$(SDK_SRC_DIR)/Core/core_riscv.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_gpio.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_misc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_rcc.c \
|
||||
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_usart.c
|
||||
|
||||
SRC_S += \
|
||||
$(SDK_SRC_DIR)/Startup/startup_${CH32_FAMILY}_D8C.S
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Core \
|
||||
$(TOP)/$(SDK_SRC_DIR)/Peripheral/inc
|
||||
|
||||
# For freeRTOS port source
|
||||
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/RISC-V
|
||||
|
||||
OPENOCD_WCH_OPTION=-f $(TOP)/$(FAMILY_PATH)/wch-riscv.cfg
|
||||
flash: flash-openocd-wch
|
|
@ -1,776 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v30x.c
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : CH32V30x Device Peripheral Access Layer System Source File.
|
||||
* For HSE = 8Mhz
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*********************************************************************************/
|
||||
#include "ch32v30x.h"
|
||||
|
||||
/*
|
||||
* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after
|
||||
* reset the HSI is used as SYSCLK source).
|
||||
* If none of the define below is enabled, the HSI is used as System clock source.
|
||||
*/
|
||||
// #define SYSCLK_FREQ_HSE HSE_VALUE
|
||||
/* #define SYSCLK_FREQ_24MHz 24000000 */
|
||||
//#define SYSCLK_FREQ_48MHz 48000000
|
||||
/* #define SYSCLK_FREQ_56MHz 56000000 */
|
||||
//#define SYSCLK_FREQ_72MHz 72000000
|
||||
//#define SYSCLK_FREQ_96MHz 96000000
|
||||
//#define SYSCLK_FREQ_120MHz 120000000
|
||||
#define SYSCLK_FREQ_144MHz 144000000
|
||||
|
||||
/* Clock Definitions */
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_HSE; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_24MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_24MHz; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_48MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_56MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_72MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
#elif defined SYSCLK_FREQ_96MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_96MHz; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_120MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_120MHz; /* System Clock Frequency (Core Clock) */
|
||||
#elif defined SYSCLK_FREQ_144MHz
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_144MHz; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
#else /* HSI Selected as System Clock source */
|
||||
uint32_t SystemCoreClock = HSI_VALUE; /* System Clock Frequency (Core Clock) */
|
||||
#endif
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
|
||||
/* system_private_function_proto_types */
|
||||
static void SetSysClock(void);
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
static void SetSysClockToHSE(void);
|
||||
#elif defined SYSCLK_FREQ_24MHz
|
||||
static void SetSysClockTo24(void);
|
||||
#elif defined SYSCLK_FREQ_48MHz
|
||||
static void SetSysClockTo48(void);
|
||||
#elif defined SYSCLK_FREQ_56MHz
|
||||
static void SetSysClockTo56(void);
|
||||
#elif defined SYSCLK_FREQ_72MHz
|
||||
static void SetSysClockTo72(void);
|
||||
|
||||
#elif defined SYSCLK_FREQ_96MHz
|
||||
static void SetSysClockTo96(void);
|
||||
#elif defined SYSCLK_FREQ_120MHz
|
||||
static void SetSysClockTo120(void);
|
||||
#elif defined SYSCLK_FREQ_144MHz
|
||||
static void SetSysClockTo144(void);
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemInit
|
||||
*
|
||||
* @brief Setup the microcontroller system Initialize the Embedded Flash Interface,
|
||||
* the PLL and update the SystemCoreClock variable.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemInit (void)
|
||||
{
|
||||
RCC->CTLR |= (uint32_t)0x00000001;
|
||||
|
||||
#ifdef CH32V30x_D8C
|
||||
RCC->CFGR0 &= (uint32_t)0xF8FF0000;
|
||||
#else
|
||||
RCC->CFGR0 &= (uint32_t)0xF0FF0000;
|
||||
#endif
|
||||
|
||||
RCC->CTLR &= (uint32_t)0xFEF6FFFF;
|
||||
RCC->CTLR &= (uint32_t)0xFFFBFFFF;
|
||||
RCC->CFGR0 &= (uint32_t)0xFF80FFFF;
|
||||
|
||||
#ifdef CH32V30x_D8C
|
||||
RCC->CTLR &= (uint32_t)0xEBFFFFFF;
|
||||
RCC->INTR = 0x00FF0000;
|
||||
RCC->CFGR2 = 0x00000000;
|
||||
#else
|
||||
RCC->INTR = 0x009F0000;
|
||||
#endif
|
||||
SetSysClock();
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SystemCoreClockUpdate
|
||||
*
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
void SystemCoreClockUpdate (void)
|
||||
{
|
||||
uint32_t tmp = 0, pllmull = 0, pllsource = 0, Pll_6_5 = 0;
|
||||
|
||||
tmp = RCC->CFGR0 & RCC_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04:
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08:
|
||||
pllmull = RCC->CFGR0 & RCC_PLLMULL;
|
||||
pllsource = RCC->CFGR0 & RCC_PLLSRC;
|
||||
pllmull = ( pllmull >> 18) + 2;
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
if(pllmull == 17) pllmull = 18;
|
||||
#else
|
||||
if(pllmull == 2) pllmull = 18;
|
||||
if(pllmull == 15){
|
||||
pllmull = 13; /* *6.5 */
|
||||
Pll_6_5 = 1;
|
||||
}
|
||||
if(pllmull == 16) pllmull = 15;
|
||||
if(pllmull == 17) pllmull = 16;
|
||||
#endif
|
||||
|
||||
if (pllsource == 0x00)
|
||||
{
|
||||
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
if ((RCC->CFGR0 & RCC_PLLXTPRE) != (uint32_t)RESET)
|
||||
{
|
||||
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
|
||||
}
|
||||
else
|
||||
{
|
||||
SystemCoreClock = HSE_VALUE * pllmull;
|
||||
}
|
||||
}
|
||||
|
||||
if(Pll_6_5 == 1) SystemCoreClock = (SystemCoreClock / 2);
|
||||
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
|
||||
tmp = AHBPrescTable[((RCC->CFGR0 & RCC_HPRE) >> 4)];
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClock
|
||||
*
|
||||
* @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClock(void)
|
||||
{
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
SetSysClockToHSE();
|
||||
#elif defined SYSCLK_FREQ_24MHz
|
||||
SetSysClockTo24();
|
||||
#elif defined SYSCLK_FREQ_48MHz
|
||||
SetSysClockTo48();
|
||||
#elif defined SYSCLK_FREQ_56MHz
|
||||
SetSysClockTo56();
|
||||
#elif defined SYSCLK_FREQ_72MHz
|
||||
SetSysClockTo72();
|
||||
#elif defined SYSCLK_FREQ_96MHz
|
||||
SetSysClockTo96();
|
||||
#elif defined SYSCLK_FREQ_120MHz
|
||||
SetSysClockTo120();
|
||||
#elif defined SYSCLK_FREQ_144MHz
|
||||
SetSysClockTo144();
|
||||
|
||||
#endif
|
||||
|
||||
/* If none of the define above is enabled, the HSI is used as System clock
|
||||
* source (default after reset)
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
#ifdef SYSCLK_FREQ_HSE
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockToHSE
|
||||
*
|
||||
* @brief Sets HSE as System clock source and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockToHSE(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1;
|
||||
|
||||
/* Select HSE as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_HSE;
|
||||
|
||||
/* Wait till HSE is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_24MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo24
|
||||
*
|
||||
* @brief Sets System clock frequency to 24MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo24(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1;
|
||||
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL3);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL3_EXTEN);
|
||||
#endif
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_48MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo48
|
||||
*
|
||||
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo48(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_56MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo56
|
||||
*
|
||||
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo56(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL7);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL7_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined SYSCLK_FREQ_72MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo72
|
||||
*
|
||||
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo72(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#elif defined SYSCLK_FREQ_96MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo96
|
||||
*
|
||||
* @brief Sets System clock frequency to 96MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo96(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 12 = 96 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#elif defined SYSCLK_FREQ_120MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo120
|
||||
*
|
||||
* @brief Sets System clock frequency to 120MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo120(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 15 = 120 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#elif defined SYSCLK_FREQ_144MHz
|
||||
|
||||
/*********************************************************************
|
||||
* @fn SetSysClockTo144
|
||||
*
|
||||
* @brief Sets System clock frequency to 144MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
|
||||
*
|
||||
* @return none
|
||||
*/
|
||||
static void SetSysClockTo144(void)
|
||||
{
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
RCC->CTLR |= ((uint32_t)RCC_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CTLR & RCC_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CTLR & RCC_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* HCLK = SYSCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
|
||||
/* PCLK2 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
|
||||
/* PCLK1 = HCLK */
|
||||
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
|
||||
|
||||
/* PLL configuration: PLLCLK = HSE * 18 = 144 MHz */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE |
|
||||
RCC_PLLMULL));
|
||||
|
||||
#ifdef CH32V30x_D8
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18);
|
||||
#else
|
||||
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18_EXTEN);
|
||||
#endif
|
||||
|
||||
/* Enable PLL */
|
||||
RCC->CTLR |= RCC_PLLON;
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CTLR & RCC_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Select PLL as system clock source */
|
||||
RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_SW));
|
||||
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
|
||||
/* Wait till PLL is used as system clock source */
|
||||
while ((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/*
|
||||
* If HSE fails to start-up, the application will have wrong clock
|
||||
* configuration. User can add here some code to deal with this error
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -1,27 +0,0 @@
|
|||
/********************************** (C) COPYRIGHT *******************************
|
||||
* File Name : system_ch32v30x.h
|
||||
* Author : WCH
|
||||
* Version : V1.0.0
|
||||
* Date : 2021/06/06
|
||||
* Description : CH32V30x Device Peripheral Access Layer System Header File.
|
||||
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*******************************************************************************/
|
||||
#ifndef __SYSTEM_CH32V30x_H
|
||||
#define __SYSTEM_CH32V30x_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
|
||||
|
||||
/* System_Exported_Functions */
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__CH32V30x_SYSTEM_H */
|
|
@ -1,17 +0,0 @@
|
|||
adapter driver wlinke
|
||||
adapter speed 6000
|
||||
transport select sdi
|
||||
|
||||
wlink_set_address 0x00000000
|
||||
set _CHIPNAME wch_riscv
|
||||
sdi newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x00001
|
||||
|
||||
set _TARGETNAME $_CHIPNAME.cpu
|
||||
|
||||
target create $_TARGETNAME.0 wch_riscv -chain-position $_TARGETNAME
|
||||
$_TARGETNAME.0 configure -work-area-phys 0x20000000 -work-area-size 10000 -work-area-backup 1
|
||||
set _FLASHNAME $_CHIPNAME.flash
|
||||
|
||||
flash bank $_FLASHNAME wch_riscv 0x00000000 0 0 0 $_TARGETNAME.0
|
||||
|
||||
echo "Ready for Remote Connections"
|
|
@ -1,150 +0,0 @@
|
|||
/*
|
||||
* FreeRTOS Kernel V10.0.0
|
||||
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
|
||||
*
|
||||
* 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. If you wish to use our Amazon
|
||||
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* http://www.FreeRTOS.org
|
||||
* http://aws.amazon.com/freertos
|
||||
*
|
||||
* 1 tab == 4 spaces!
|
||||
*/
|
||||
|
||||
|
||||
#ifndef FREERTOS_CONFIG_H
|
||||
#define FREERTOS_CONFIG_H
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Application specific definitions.
|
||||
*
|
||||
* These definitions should be adjusted for your particular hardware and
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
|
||||
// skip if included from IAR assembler
|
||||
#ifndef __IASMARM__
|
||||
#include "DA1469xAB.h"
|
||||
#endif
|
||||
|
||||
/* Cortex M23/M33 port configuration. */
|
||||
#define configENABLE_MPU 0
|
||||
#define configENABLE_FPU 1
|
||||
#define configENABLE_TRUSTZONE 0
|
||||
#define configMINIMAL_SECURE_STACK_SIZE (1024)
|
||||
#define configRUN_FREERTOS_SECURE_ONLY 1
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
|
||||
#define configCPU_CLOCK_HZ SystemCoreClock
|
||||
#define configTICK_RATE_HZ ( 1000 )
|
||||
#define configMAX_PRIORITIES ( 5 )
|
||||
#define configMINIMAL_STACK_SIZE ( 128 )
|
||||
#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 )
|
||||
#define configMAX_TASK_NAME_LEN 16
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 1
|
||||
#define configUSE_MUTEXES 1
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 1
|
||||
#define configQUEUE_REGISTRY_SIZE 4
|
||||
#define configUSE_QUEUE_SETS 0
|
||||
#define configUSE_TIME_SLICING 0
|
||||
#define configUSE_NEWLIB_REENTRANT 0
|
||||
#define configENABLE_BACKWARD_COMPATIBILITY 1
|
||||
#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0
|
||||
|
||||
#define configSUPPORT_STATIC_ALLOCATION 1
|
||||
#define configSUPPORT_DYNAMIC_ALLOCATION 0
|
||||
|
||||
/* Hook function related definitions. */
|
||||
#define configUSE_IDLE_HOOK 0
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#define configCHECK_HANDLER_INSTALLATION 0
|
||||
|
||||
/* Run time and task stats gathering related definitions. */
|
||||
#define configGENERATE_RUN_TIME_STATS 0
|
||||
#define configRECORD_STACK_HIGH_ADDRESS 1
|
||||
#define configUSE_TRACE_FACILITY 1 // legacy trace
|
||||
#define configUSE_STATS_FORMATTING_FUNCTIONS 0
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES 2
|
||||
|
||||
/* Software timer related definitions. */
|
||||
#define configUSE_TIMERS 1
|
||||
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2)
|
||||
#define configTIMER_QUEUE_LENGTH 32
|
||||
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
|
||||
|
||||
/* Optional functions - most linkers will remove unused functions anyway. */
|
||||
#define INCLUDE_vTaskPrioritySet 0
|
||||
#define INCLUDE_uxTaskPriorityGet 0
|
||||
#define INCLUDE_vTaskDelete 0
|
||||
#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY
|
||||
#define INCLUDE_xResumeFromISR 0
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 0
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 0
|
||||
#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
|
||||
#define INCLUDE_pcTaskGetTaskName 0
|
||||
#define INCLUDE_eTaskGetState 0
|
||||
#define INCLUDE_xEventGroupSetBitFromISR 0
|
||||
#define INCLUDE_xTimerPendFunctionCall 0
|
||||
|
||||
/* FreeRTOS hooks to NVIC vectors */
|
||||
#define xPortPendSVHandler PendSV_Handler
|
||||
#define xPortSysTickHandler SysTick_Handler
|
||||
#define vPortSVCHandler SVC_Handler
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Interrupt nesting behavior configuration.
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header
|
||||
#define configPRIO_BITS 4
|
||||
|
||||
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
||||
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<<configPRIO_BITS) - 1)
|
||||
|
||||
/* The highest interrupt priority that can be used by any interrupt service
|
||||
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
|
||||
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
|
||||
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
|
||||
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 2
|
||||
|
||||
/* Interrupt priorities used by the kernel port layer itself. These are generic
|
||||
to all Cortex-M ports, and do not rely on any particular library functions. */
|
||||
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
|
||||
|
||||
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
|
||||
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
|
||||
|
||||
#endif
|
|
@ -1,4 +0,0 @@
|
|||
set(JLINK_DEVICE DA14695)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -1,10 +0,0 @@
|
|||
#ifndef BOARD_H
|
||||
#define BOARD_H
|
||||
|
||||
#define LED_PIN 33 // P1.1
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
#define BUTTON_PIN 6
|
||||
#define BUTTON_STATE_ACTIVE 1
|
||||
|
||||
#endif
|
|
@ -1 +0,0 @@
|
|||
JLINK_DEVICE = DA14695
|
|
@ -1,34 +0,0 @@
|
|||
/**
|
||||
* This file was generated by Apache newt version: 1.9.0-dev
|
||||
*/
|
||||
|
||||
#ifndef H_MYNEWT_SYSCFG_
|
||||
#define H_MYNEWT_SYSCFG_
|
||||
|
||||
/**
|
||||
* This macro exists to ensure code includes this header when needed. If code
|
||||
* checks the existence of a setting directly via ifdef without including this
|
||||
* header, the setting macro will silently evaluate to 0. In contrast, an
|
||||
* attempt to use these macros without including this header will result in a
|
||||
* compiler error.
|
||||
*/
|
||||
#define MYNEWT_VAL(_name) MYNEWT_VAL_ ## _name
|
||||
#define MYNEWT_VAL_CHOICE(_name, _val) MYNEWT_VAL_ ## _name ## __ ## _val
|
||||
|
||||
#ifndef MYNEWT_VAL_RAM_RESIDENT
|
||||
#define MYNEWT_VAL_RAM_RESIDENT (0)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_GPIO_MAX_IRQ
|
||||
#define MYNEWT_VAL_MCU_GPIO_MAX_IRQ (4)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM
|
||||
#define MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM (-1)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US
|
||||
#define MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US (2000)
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,4 +0,0 @@
|
|||
set(JLINK_DEVICE DA14699)
|
||||
|
||||
function(update_board TARGET)
|
||||
endfunction()
|
|
@ -1,12 +0,0 @@
|
|||
#ifndef BOARD_H
|
||||
#define BOARD_H
|
||||
|
||||
#define LED_PIN 33
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
#define BUTTON_PIN 6
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
#define NEED_VBUS_MONITOR
|
||||
|
||||
#endif
|
|
@ -1,2 +0,0 @@
|
|||
# For flash-jlink target
|
||||
JLINK_DEVICE = DA14699
|
|
@ -1,34 +0,0 @@
|
|||
/**
|
||||
* This file was generated by Apache newt version: 1.9.0-dev
|
||||
*/
|
||||
|
||||
#ifndef H_MYNEWT_SYSCFG_
|
||||
#define H_MYNEWT_SYSCFG_
|
||||
|
||||
/**
|
||||
* This macro exists to ensure code includes this header when needed. If code
|
||||
* checks the existence of a setting directly via ifdef without including this
|
||||
* header, the setting macro will silently evaluate to 0. In contrast, an
|
||||
* attempt to use these macros without including this header will result in a
|
||||
* compiler error.
|
||||
*/
|
||||
#define MYNEWT_VAL(_name) MYNEWT_VAL_ ## _name
|
||||
#define MYNEWT_VAL_CHOICE(_name, _val) MYNEWT_VAL_ ## _name ## __ ## _val
|
||||
|
||||
#ifndef MYNEWT_VAL_RAM_RESIDENT
|
||||
#define MYNEWT_VAL_RAM_RESIDENT (0)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_GPIO_MAX_IRQ
|
||||
#define MYNEWT_VAL_MCU_GPIO_MAX_IRQ (4)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM
|
||||
#define MYNEWT_VAL_MCU_GPIO_RETAINABLE_NUM (-1)
|
||||
#endif
|
||||
|
||||
#ifndef MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US
|
||||
#define MYNEWT_VAL_MCU_CLOCK_XTAL32M_SETTLE_TIME_US (2000)
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1,142 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jerzy Kasenberg
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#include "bsp/board_api.h"
|
||||
#include "board.h"
|
||||
#include <hal/hal_gpio.h>
|
||||
#include <mcu/mcu.h>
|
||||
|
||||
#define LED_STATE_OFF (1-LED_STATE_ON)
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||
//--------------------------------------------------------------------+
|
||||
void USB_IRQHandler(void) {
|
||||
tud_int_handler(0);
|
||||
}
|
||||
|
||||
// DA146xx driver function that must be called whenever VBUS changes.
|
||||
extern void tusb_vbus_changed(bool present);
|
||||
|
||||
#if defined(NEED_VBUS_MONITOR) && CFG_TUD_ENABLED
|
||||
// VBUS change interrupt handler
|
||||
void VBUS_IRQHandler(void) {
|
||||
bool present = (CRG_TOP->ANA_STATUS_REG & CRG_TOP_ANA_STATUS_REG_VBUS_AVAILABLE_Msk) != 0;
|
||||
// Clear VBUS interrupt
|
||||
CRG_TOP->VBUS_IRQ_CLEAR_REG = 1;
|
||||
|
||||
tusb_vbus_changed(present);
|
||||
}
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM
|
||||
//--------------------------------------------------------------------+
|
||||
void UnhandledIRQ(void) {
|
||||
CRG_TOP->SYS_CTRL_REG = 0x80;
|
||||
__BKPT(1);
|
||||
while (1);
|
||||
}
|
||||
|
||||
void board_init(void) {
|
||||
// LED
|
||||
hal_gpio_init_out(LED_PIN, LED_STATE_ON);
|
||||
|
||||
hal_gpio_init_out(1, 0);
|
||||
hal_gpio_init_out(2, 0);
|
||||
hal_gpio_init_out(3, 0);
|
||||
hal_gpio_init_out(4, 0);
|
||||
hal_gpio_init_out(5, 0);
|
||||
|
||||
// Button
|
||||
hal_gpio_init_in(BUTTON_PIN, BUTTON_STATE_ACTIVE ? HAL_GPIO_PULL_DOWN : HAL_GPIO_PULL_UP);
|
||||
|
||||
// 1ms tick timer
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
|
||||
#if CFG_TUD_ENABLED
|
||||
#ifdef NEED_VBUS_MONITOR
|
||||
// Setup interrupt for both connect and disconnect
|
||||
CRG_TOP->VBUS_IRQ_MASK_REG = CRG_TOP_VBUS_IRQ_MASK_REG_VBUS_IRQ_EN_FALL_Msk |
|
||||
CRG_TOP_VBUS_IRQ_MASK_REG_VBUS_IRQ_EN_RISE_Msk;
|
||||
NVIC_SetPriority(VBUS_IRQn, 2);
|
||||
// Trigger interrupt at the start to inform driver about VBUS state at start
|
||||
// otherwise it could go unnoticed.
|
||||
NVIC_SetPendingIRQ(VBUS_IRQn);
|
||||
NVIC_EnableIRQ(VBUS_IRQn);
|
||||
#else
|
||||
// This board is USB powered there is no need to monitor VBUS line. Notify driver that VBUS is present.
|
||||
tusb_vbus_changed(true);
|
||||
#endif
|
||||
|
||||
/* Setup USB IRQ */
|
||||
NVIC_SetPriority(USB_IRQn, 2);
|
||||
NVIC_EnableIRQ(USB_IRQn);
|
||||
|
||||
/* Use PLL96 / 2 clock not HCLK */
|
||||
CRG_TOP->CLK_CTRL_REG &= ~CRG_TOP_CLK_CTRL_REG_USB_CLK_SRC_Msk;
|
||||
|
||||
mcu_gpio_set_pin_function(14, MCU_GPIO_MODE_INPUT, MCU_GPIO_FUNC_USB);
|
||||
mcu_gpio_set_pin_function(15, MCU_GPIO_MODE_INPUT, MCU_GPIO_FUNC_USB);
|
||||
#endif
|
||||
}
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// Board porting API
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
void board_led_write(bool state) {
|
||||
hal_gpio_write(LED_PIN, state ? LED_STATE_ON : LED_STATE_OFF);
|
||||
}
|
||||
|
||||
uint32_t board_button_read(void) {
|
||||
return BUTTON_STATE_ACTIVE == hal_gpio_read(BUTTON_PIN);
|
||||
}
|
||||
|
||||
int board_uart_read(uint8_t* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int board_uart_write(void const* buf, int len) {
|
||||
(void) buf;
|
||||
(void) len;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||
volatile uint32_t system_ticks = 0;
|
||||
|
||||
void SysTick_Handler(void) {
|
||||
system_ticks++;
|
||||
}
|
||||
|
||||
uint32_t board_millis(void) {
|
||||
return system_ticks;
|
||||
}
|
||||
#endif
|
|
@ -1,141 +0,0 @@
|
|||
include_guard()
|
||||
|
||||
set(MCU_DIR ${TOP}/hw/mcu/dialog/da1469x)
|
||||
|
||||
# include board specific
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
|
||||
|
||||
set(CMAKE_SYSTEM_PROCESSOR cortex-m33-nodsp CACHE INTERNAL "System Processor")
|
||||
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
|
||||
set(FAMILY_MCUS DA1469X CACHE INTERNAL "")
|
||||
|
||||
#------------------------------------
|
||||
# BOARD_TARGET
|
||||
#------------------------------------
|
||||
# only need to be built ONCE for all examples
|
||||
function(add_board_target BOARD_TARGET)
|
||||
if (TARGET ${BOARD_TARGET})
|
||||
return()
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED LD_FILE_GNU)
|
||||
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/da1469x.ld)
|
||||
endif ()
|
||||
|
||||
if (NOT DEFINED STARTUP_FILE_${CMAKE_C_COMPILER_ID})
|
||||
set(STARTUP_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/gcc_startup_da1469x.S)
|
||||
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
|
||||
endif ()
|
||||
|
||||
add_library(${BOARD_TARGET} STATIC
|
||||
${MCU_DIR}/src/system_da1469x.c
|
||||
${MCU_DIR}/src/da1469x_clock.c
|
||||
${MCU_DIR}/src/hal_gpio.c
|
||||
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
|
||||
)
|
||||
target_compile_options(${BOARD_TARGET} PUBLIC -mthumb-interwork)
|
||||
target_compile_definitions(${BOARD_TARGET} PUBLIC
|
||||
CORE_M33
|
||||
CFG_TUD_ENDPOINT0_SIZE=8
|
||||
)
|
||||
target_include_directories(${BOARD_TARGET} PUBLIC
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
${MCU_DIR}/include
|
||||
${MCU_DIR}/SDK_10.0.8.105/sdk/bsp/include
|
||||
)
|
||||
|
||||
update_board(${BOARD_TARGET})
|
||||
|
||||
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-L${NRFX_DIR}/mdk
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
-nostartfiles
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--script=${LD_FILE_GNU}"
|
||||
-L${NRFX_DIR}/mdk
|
||||
)
|
||||
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
|
||||
target_link_options(${BOARD_TARGET} PUBLIC
|
||||
"LINKER:--config=${LD_FILE_IAR}"
|
||||
)
|
||||
endif ()
|
||||
endfunction()
|
||||
|
||||
|
||||
#------------------------------------
|
||||
# Functions
|
||||
#------------------------------------
|
||||
|
||||
function(family_flash_jlink_dialog TARGET)
|
||||
set(JLINKEXE JLinkExe)
|
||||
set(JLINK_IF swd)
|
||||
|
||||
# mkimage from sdk
|
||||
set(MKIMAGE $ENV{HOME}/code/tinyusb-mcu-driver/dialog/SDK_10.0.8.105/binaries/mkimage)
|
||||
|
||||
file(GENERATE OUTPUT $<TARGET_FILE_DIR:${TARGET}>/version.h
|
||||
CONTENT "#define SW_VERSION \"v_1.0.0.1\"
|
||||
#define SW_VERSION_DATE \"2024-07-17 17:55\""
|
||||
)
|
||||
|
||||
file(GENERATE OUTPUT $<TARGET_FILE_DIR:${TARGET}>/${TARGET}.jlink
|
||||
CONTENT "r
|
||||
halt
|
||||
loadfile $<TARGET_FILE_DIR:${TARGET}>/${TARGET}-image.bin 0x16000000
|
||||
r
|
||||
go
|
||||
exit"
|
||||
)
|
||||
|
||||
add_custom_target(${TARGET}-image
|
||||
DEPENDS ${TARGET}
|
||||
COMMAND ${MKIMAGE} da1469x $<TARGET_FILE_DIR:${TARGET}>/${TARGET}.bin $<TARGET_FILE_DIR:${TARGET}>/version.h $<TARGET_FILE_DIR:${TARGET}>/${TARGET}.bin.img
|
||||
COMMAND cp ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/product_header.dump $<TARGET_FILE_DIR:${TARGET}>/${TARGET}-image.bin
|
||||
COMMAND cat $<TARGET_FILE_DIR:${TARGET}>/${TARGET}.bin.img >> $<TARGET_FILE_DIR:${TARGET}>/${TARGET}-image.bin
|
||||
)
|
||||
add_custom_target(${TARGET}-jlink
|
||||
DEPENDS ${TARGET}-image
|
||||
COMMAND ${JLINKEXE} -device ${JLINK_DEVICE} -if ${JLINK_IF} -JTAGConf -1,-1 -speed auto -CommandFile $<TARGET_FILE_DIR:${TARGET}>/${TARGET}.jlink
|
||||
)
|
||||
endfunction()
|
||||
|
||||
|
||||
function(family_configure_example TARGET RTOS)
|
||||
family_configure_common(${TARGET} ${RTOS})
|
||||
|
||||
# Board target
|
||||
add_board_target(board_${BOARD})
|
||||
|
||||
#---------- Port Specific ----------
|
||||
# These files are built for each example since it depends on example's tusb_config.h
|
||||
target_sources(${TARGET} PUBLIC
|
||||
# BSP
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
|
||||
)
|
||||
target_include_directories(${TARGET} PUBLIC
|
||||
# family, hw, board
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
|
||||
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
|
||||
)
|
||||
|
||||
# Add TinyUSB target and port source
|
||||
family_add_tinyusb(${TARGET} OPT_MCU_DA1469X ${RTOS})
|
||||
target_sources(${TARGET}-tinyusb PUBLIC
|
||||
${TOP}/src/portable/dialog/da146xx/dcd_da146xx.c
|
||||
)
|
||||
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
|
||||
|
||||
# Link dependencies
|
||||
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
|
||||
|
||||
# Flashing
|
||||
family_add_bin_hex(${TARGET})
|
||||
family_flash_jlink_dialog(${TARGET})
|
||||
endfunction()
|
|
@ -1,62 +0,0 @@
|
|||
MCU_DIR = hw/mcu/dialog/da1469x
|
||||
|
||||
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||
|
||||
CFLAGS += \
|
||||
-flto \
|
||||
-mthumb \
|
||||
-mthumb-interwork \
|
||||
-mabi=aapcs \
|
||||
-mcpu=cortex-m33+nodsp \
|
||||
-mfloat-abi=hard \
|
||||
-mfpu=fpv5-sp-d16 \
|
||||
-DCORE_M33 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_DA1469X \
|
||||
-DCFG_TUD_ENDPOINT0_SIZE=8\
|
||||
|
||||
LDFLAGS_GCC += \
|
||||
-nostdlib \
|
||||
--specs=nosys.specs --specs=nano.specs
|
||||
|
||||
# All source paths should be relative to the top level.
|
||||
LD_FILE = $(FAMILY_PATH)/linker/da1469x.ld
|
||||
|
||||
# While this is for da1469x chip, there is chance that da1468x chip family will also work
|
||||
SRC_C += \
|
||||
src/portable/dialog/da146xx/dcd_da146xx.c \
|
||||
${MCU_DIR}/src/system_da1469x.c \
|
||||
${MCU_DIR}/src/da1469x_clock.c \
|
||||
${MCU_DIR}/src/hal_gpio.c \
|
||||
|
||||
SRC_S += $(FAMILY_PATH)/gcc_startup_da1469x.S
|
||||
|
||||
INC += \
|
||||
$(TOP)/$(BOARD_PATH) \
|
||||
$(TOP)/${MCU_DIR}/include \
|
||||
$(TOP)/${MCU_DIR}/SDK_10.0.8.105/sdk/bsp/include
|
||||
|
||||
# For freeRTOS port source
|
||||
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM33_NTZ/non_secure
|
||||
|
||||
# flash using jlink but with some twists
|
||||
flash: flash-dialog
|
||||
|
||||
# SDK_BINARY_PATH is the path to the SDK binary files
|
||||
SDK_BINARY_PATH = $(HOME)/code/tinyusb-mcu-driver/dialog/SDK_10.0.8.105/binaries
|
||||
MKIMAGE = $(SDK_BINARY_PATH)/mkimage
|
||||
|
||||
$(BUILD)/$(PROJECT)-image.bin: $(BUILD)/$(PROJECT).bin
|
||||
@echo '#define SW_VERSION "v_1.0.0.1"' >$(BUILD)/version.h
|
||||
@echo '#define SW_VERSION_DATE "'`date +"%Y-%m-%d %H:%M"`'"' >> $(BUILD)/version.h
|
||||
$(MKIMAGE) da1469x $^ $(BUILD)/version.h $^.img
|
||||
cp $(TOP)/$(FAMILY_PATH)/product_header.dump $(BUILD)/$(PROJECT)-image.bin
|
||||
cat $^.img >> $(BUILD)/$(PROJECT)-image.bin
|
||||
|
||||
flash-dialog: $(BUILD)/$(PROJECT)-image.bin
|
||||
@echo r > $(BUILD)/$(BOARD).jlink
|
||||
@echo halt >> $(BUILD)/$(BOARD).jlink
|
||||
@echo loadfile $^ 0x16000000 >> $(BUILD)/$(BOARD).jlink
|
||||
@echo r >> $(BUILD)/$(BOARD).jlink
|
||||
@echo go >> $(BUILD)/$(BOARD).jlink
|
||||
@echo exit >> $(BUILD)/$(BOARD).jlink
|
||||
$(JLINKEXE) -device $(JLINK_DEVICE) -if $(JLINK_IF) -JTAGConf -1,-1 -speed auto -CommandFile $(BUILD)/$(BOARD).jlink
|
|
@ -1,301 +0,0 @@
|
|||
/*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one
|
||||
* or more contributor license agreements. See the NOTICE file
|
||||
* distributed with this work for additional information
|
||||
* regarding copyright ownership. The ASF licenses this file
|
||||
* to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance
|
||||
* with the License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing,
|
||||
* software distributed under the License is distributed on an
|
||||
* "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
|
||||
* KIND, either express or implied. See the License for the
|
||||
* specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*/
|
||||
|
||||
#include "syscfg/syscfg.h"
|
||||
|
||||
.syntax unified
|
||||
.arch armv7-m
|
||||
|
||||
.section .stack
|
||||
.align 3
|
||||
#ifdef __STACK_SIZE
|
||||
.equ Stack_Size, __STACK_SIZE
|
||||
#else
|
||||
.equ Stack_Size, 0xC00
|
||||
#endif
|
||||
.equ SYS_CTRL_REG, 0x50000024
|
||||
.equ CACHE_FLASH_REG, 0x100C0040
|
||||
.equ RESET_STAT_REG, 0x500000BC
|
||||
|
||||
.globl __StackTop
|
||||
.globl __StackLimit
|
||||
__StackLimit:
|
||||
.space Stack_Size
|
||||
.size __StackLimit, . - __StackLimit
|
||||
__StackTop:
|
||||
.size __StackTop, . - __StackTop
|
||||
|
||||
.section .heap
|
||||
.align 3
|
||||
#ifdef __HEAP_SIZE
|
||||
.equ Heap_Size, __HEAP_SIZE
|
||||
#else
|
||||
.equ Heap_Size, 0
|
||||
#endif
|
||||
.globl __HeapBase
|
||||
.globl __HeapLimit
|
||||
__HeapBase:
|
||||
.if Heap_Size
|
||||
.space Heap_Size
|
||||
.endif
|
||||
.size __HeapBase, . - __HeapBase
|
||||
__HeapLimit:
|
||||
.size __HeapLimit, . - __HeapLimit
|
||||
|
||||
.section .isr_vector
|
||||
.align 2
|
||||
.globl __isr_vector
|
||||
__isr_vector:
|
||||
.long __StackTop
|
||||
.long Reset_Handler
|
||||
/* Cortex-M33 interrupts */
|
||||
.long NMI_Handler
|
||||
.long HardFault_Handler
|
||||
.long MemoryManagement_Handler
|
||||
.long BusFault_Handler
|
||||
.long UsageFault_Handler
|
||||
.long SecureFault_Handler
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long SVC_Handler
|
||||
.long DebugMonitor_Handler
|
||||
.long 0 /* Reserved */
|
||||
.long PendSV_Handler
|
||||
.long SysTick_Handler
|
||||
/* DA1469x interrupts */
|
||||
.long SENSOR_NODE_IRQHandler
|
||||
.long DMA_IRQHandler
|
||||
.long CHARGER_STATE_IRQHandler
|
||||
.long CHARGER_ERROR_IRQHandler
|
||||
.long CMAC2SYS_IRQHandler
|
||||
.long UART_IRQHandler
|
||||
.long UART2_IRQHandler
|
||||
.long UART3_IRQHandler
|
||||
.long I2C_IRQHandler
|
||||
.long I2C2_IRQHandler
|
||||
.long SPI_IRQHandler
|
||||
.long SPI2_IRQHandler
|
||||
.long PCM_IRQHandler
|
||||
.long SRC_IN_IRQHandler
|
||||
.long SRC_OUT_IRQHandler
|
||||
.long USB_IRQHandler
|
||||
.long TIMER_IRQHandler
|
||||
.long TIMER2_IRQHandler
|
||||
.long RTC_IRQHandler
|
||||
.long KEY_WKUP_GPIO_IRQHandler
|
||||
.long PDC_IRQHandler
|
||||
.long VBUS_IRQHandler
|
||||
.long MRM_IRQHandler
|
||||
.long MOTOR_CONTROLLER_IRQHandler
|
||||
.long TRNG_IRQHandler
|
||||
.long DCDC_IRQHandler
|
||||
.long XTAL32M_RDY_IRQHandler
|
||||
.long ADC_IRQHandler
|
||||
.long ADC2_IRQHandler
|
||||
.long CRYPTO_IRQHandler
|
||||
.long CAPTIMER1_IRQHandler
|
||||
.long RFDIAG_IRQHandler
|
||||
.long LCD_CONTROLLER_IRQHandler
|
||||
.long PLL_LOCK_IRQHandler
|
||||
.long TIMER3_IRQHandler
|
||||
.long TIMER4_IRQHandler
|
||||
.long LRA_IRQHandler
|
||||
.long RTC_EVENT_IRQHandler
|
||||
.long GPIO_P0_IRQHandler
|
||||
.long GPIO_P1_IRQHandler
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.long 0 /* Reserved */
|
||||
.size __isr_vector, . - __isr_vector
|
||||
|
||||
.text
|
||||
.thumb
|
||||
.thumb_func
|
||||
.align 2
|
||||
.globl Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
/* Make sure interrupt vector is remapped at 0x0 */
|
||||
ldr r1, =SYS_CTRL_REG
|
||||
ldrh r2, [r1, #0]
|
||||
orrs r2, r2, #8
|
||||
strh r2, [r1, #0]
|
||||
|
||||
#if !MYNEWT_VAL(RAM_RESIDENT)
|
||||
/*
|
||||
* Flash is remapped at 0x0 with an offset, i.e. 0x0 does not correspond to
|
||||
* 0x16000000 but to start of an image on flash. This is calculated from product
|
||||
* header by 1st state bootloader and configured in CACHE_FLASH_REG. We need to
|
||||
* retrieve proper offset value for calculations later.
|
||||
*/
|
||||
ldr r1, =CACHE_FLASH_REG
|
||||
ldr r4, [r1, #0]
|
||||
mov r2, r4
|
||||
mov r3, #0xFFFF
|
||||
bic r4, r4, r3 /* CACHE_FLASH_REG[FLASH_REGION_BASE] */
|
||||
mov r3, #0xFFF0
|
||||
and r2, r2, r3 /* CACHE_FLASH_REG[FLASH_REGION_OFFSET] */
|
||||
lsr r2, r2, #2
|
||||
orr r4, r4, r2
|
||||
|
||||
/* Copy ISR vector from flash to RAM */
|
||||
ldr r1, =__isr_vector_start /* src ptr */
|
||||
ldr r2, =__isr_vector_end /* src end */
|
||||
ldr r3, =__intvect_start__ /* dst ptr */
|
||||
/* Make sure we copy from QSPIC address range, not from remapped range */
|
||||
cmp r1, r4
|
||||
itt lt
|
||||
addlt r1, r1, r4
|
||||
addlt r2, r2, r4
|
||||
.loop_isr_copy:
|
||||
cmp r1, r2
|
||||
ittt lt
|
||||
ldrlt r0, [r1], #4
|
||||
strlt r0, [r3], #4
|
||||
blt .loop_isr_copy
|
||||
|
||||
/* Copy QSPI code from flash to RAM */
|
||||
ldr r1, =__text_ram_addr /* src ptr */
|
||||
ldr r2, =__text_ram_start__ /* ptr */
|
||||
ldr r3, =__text_ram_end__ /* dst end */
|
||||
.loop_code_text_ram_copy:
|
||||
cmp r2, r3
|
||||
ittt lt
|
||||
ldrlt r0, [r1], #4
|
||||
strlt r0, [r2], #4
|
||||
blt .loop_code_text_ram_copy
|
||||
|
||||
/* Copy data from flash to RAM */
|
||||
ldr r1, =__etext /* src ptr */
|
||||
ldr r2, =__data_start__ /* dst ptr */
|
||||
ldr r3, =__data_end__ /* dst end */
|
||||
.loop_data_copy:
|
||||
cmp r2, r3
|
||||
ittt lt
|
||||
ldrlt r0, [r1], #4
|
||||
strlt r0, [r2], #4
|
||||
blt .loop_data_copy
|
||||
#endif
|
||||
|
||||
/* Clear BSS */
|
||||
movs r0, 0
|
||||
ldr r1, =__bss_start__
|
||||
ldr r2, =__bss_end__
|
||||
.loop_bss_clear:
|
||||
cmp r1, r2
|
||||
itt lt
|
||||
strlt r0, [r1], #4
|
||||
blt .loop_bss_clear
|
||||
|
||||
ldr r0, =__HeapBase
|
||||
ldr r1, =__HeapLimit
|
||||
/* Call static constructors */
|
||||
bl __libc_init_array
|
||||
|
||||
bl SystemInit
|
||||
bl main
|
||||
|
||||
.pool
|
||||
.size Reset_Handler, . - Reset_Handler
|
||||
|
||||
/* Default interrupt handler */
|
||||
.type Default_Handler, %function
|
||||
Default_Handler:
|
||||
ldr r1, =SYS_CTRL_REG
|
||||
ldrh r2, [r1, #0]
|
||||
orrs r2, r2, #0x80 /* DEBUGGER_ENABLE */
|
||||
strh r2, [r1, #0]
|
||||
b .
|
||||
|
||||
.size Default_Handler, . - Default_Handler
|
||||
|
||||
/* Default handlers for all interrupts */
|
||||
.macro IRQ handler
|
||||
.weak \handler
|
||||
.set \handler, Default_Handler
|
||||
.endm
|
||||
|
||||
/* Cortex-M33 interrupts */
|
||||
IRQ NMI_Handler
|
||||
IRQ HardFault_Handler
|
||||
IRQ MemoryManagement_Handler
|
||||
IRQ BusFault_Handler
|
||||
IRQ UsageFault_Handler
|
||||
IRQ SecureFault_Handler
|
||||
IRQ SVC_Handler
|
||||
IRQ DebugMonitor_Handler
|
||||
IRQ PendSV_Handler
|
||||
IRQ SysTick_Handler
|
||||
/* DA1469x interrupts */
|
||||
IRQ SENSOR_NODE_IRQHandler
|
||||
IRQ DMA_IRQHandler
|
||||
IRQ CHARGER_STATE_IRQHandler
|
||||
IRQ CHARGER_ERROR_IRQHandler
|
||||
IRQ CMAC2SYS_IRQHandler
|
||||
IRQ UART_IRQHandler
|
||||
IRQ UART2_IRQHandler
|
||||
IRQ UART3_IRQHandler
|
||||
IRQ I2C_IRQHandler
|
||||
IRQ I2C2_IRQHandler
|
||||
IRQ SPI_IRQHandler
|
||||
IRQ SPI2_IRQHandler
|
||||
IRQ PCM_IRQHandler
|
||||
IRQ SRC_IN_IRQHandler
|
||||
IRQ SRC_OUT_IRQHandler
|
||||
IRQ USB_IRQHandler
|
||||
IRQ TIMER_IRQHandler
|
||||
IRQ TIMER2_IRQHandler
|
||||
IRQ RTC_IRQHandler
|
||||
IRQ KEY_WKUP_GPIO_IRQHandler
|
||||
IRQ PDC_IRQHandler
|
||||
IRQ VBUS_IRQHandler
|
||||
IRQ MRM_IRQHandler
|
||||
IRQ MOTOR_CONTROLLER_IRQHandler
|
||||
IRQ TRNG_IRQHandler
|
||||
IRQ DCDC_IRQHandler
|
||||
IRQ XTAL32M_RDY_IRQHandler
|
||||
IRQ ADC_IRQHandler
|
||||
IRQ ADC2_IRQHandler
|
||||
IRQ CRYPTO_IRQHandler
|
||||
IRQ CAPTIMER1_IRQHandler
|
||||
IRQ RFDIAG_IRQHandler
|
||||
IRQ LCD_CONTROLLER_IRQHandler
|
||||
IRQ PLL_LOCK_IRQHandler
|
||||
IRQ TIMER3_IRQHandler
|
||||
IRQ TIMER4_IRQHandler
|
||||
IRQ LRA_IRQHandler
|
||||
IRQ RTC_EVENT_IRQHandler
|
||||
IRQ GPIO_P0_IRQHandler
|
||||
IRQ GPIO_P1_IRQHandler
|
||||
IRQ RESERVED40_IRQHandler
|
||||
IRQ RESERVED41_IRQHandler
|
||||
IRQ RESERVED42_IRQHandler
|
||||
IRQ RESERVED43_IRQHandler
|
||||
IRQ RESERVED44_IRQHandler
|
||||
IRQ RESERVED45_IRQHandler
|
||||
IRQ RESERVED46_IRQHandler
|
||||
IRQ RESERVED47_IRQHandler
|
||||
|
||||
.end
|
|
@ -1,244 +0,0 @@
|
|||
/*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one
|
||||
* or more contributor license agreements. See the NOTICE file
|
||||
* distributed with this work for additional information
|
||||
* regarding copyright ownership. The ASF licenses this file
|
||||
* to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance
|
||||
* with the License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing,
|
||||
* software distributed under the License is distributed on an
|
||||
* "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
|
||||
* KIND, either express or implied. See the License for the
|
||||
* specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
/*
|
||||
* Flash is remapped at 0x0 by 1st stage bootloader, but this is done with
|
||||
* an offset derived from image header thus it is safer to use remapped
|
||||
* address space at 0x0 instead of QSPI_M address space at 0x16000000.
|
||||
* Bootloader partition is 32K, but 9K is currently reserved for product
|
||||
* header (8K) and image header (1K).
|
||||
* First 512 bytes of SYSRAM are remapped at 0x0 and used as ISR vector
|
||||
* (there's no need to reallocate ISR vector) and thus cannot be used by
|
||||
* application.
|
||||
*/
|
||||
|
||||
FLASH (r) : ORIGIN = (0x00000000), LENGTH = (1024 * 1024)
|
||||
RAM (rw) : ORIGIN = (0x20000000), LENGTH = (512 * 1024)
|
||||
}
|
||||
|
||||
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
|
||||
|
||||
/* Linker script to place sections and symbol values. Should be used together
|
||||
* with other linker script that defines memory regions FLASH and RAM.
|
||||
* It references following symbols, which must be defined in code:
|
||||
* Reset_Handler : Entry of reset handler
|
||||
*
|
||||
* It defines following symbols, which code can use without definition:
|
||||
* __exidx_start
|
||||
* __exidx_end
|
||||
* __etext
|
||||
* __data_start__
|
||||
* __preinit_array_start
|
||||
* __preinit_array_end
|
||||
* __init_array_start
|
||||
* __init_array_end
|
||||
* __fini_array_start
|
||||
* __fini_array_end
|
||||
* __data_end__
|
||||
* __bss_start__
|
||||
* __bss_end__
|
||||
* __HeapBase
|
||||
* __HeapLimit
|
||||
* __StackLimit
|
||||
* __StackTop
|
||||
* __stack
|
||||
* __bssnz_start__
|
||||
* __bssnz_end__
|
||||
*/
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
__text = .;
|
||||
|
||||
.text :
|
||||
{
|
||||
__isr_vector_start = .;
|
||||
KEEP(*(.isr_vector))
|
||||
/* ISR vector shall have exactly 512 bytes */
|
||||
. = __isr_vector_start + 0x200;
|
||||
__isr_vector_end = .;
|
||||
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
|
||||
*(.libcmac.rom)
|
||||
|
||||
KEEP(*(.init))
|
||||
KEEP(*(.fini))
|
||||
|
||||
/* .ctors */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
|
||||
/* .dtors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
*(.rodata*)
|
||||
|
||||
*(.eh_frame*)
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
.intvect :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__intvect_start__ = .;
|
||||
. = . + (__isr_vector_end - __isr_vector_start);
|
||||
. = ALIGN(4);
|
||||
} > RAM
|
||||
|
||||
.sleep_state (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(sleep_state)
|
||||
} > RAM
|
||||
|
||||
/* This section will be zeroed by RTT package init */
|
||||
.rtt (NOLOAD):
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.rtt)
|
||||
. = ALIGN(4);
|
||||
} > RAM
|
||||
|
||||
__text_ram_addr = LOADADDR(.text_ram);
|
||||
|
||||
.text_ram :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__text_ram_start__ = .;
|
||||
*(.text_ram*)
|
||||
. = ALIGN(4);
|
||||
__text_ram_end__ = .;
|
||||
} > RAM AT > FLASH
|
||||
|
||||
__etext = LOADADDR(.data);
|
||||
|
||||
.data :
|
||||
{
|
||||
__data_start__ = .;
|
||||
*(vtable)
|
||||
*(.data*)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
*(.preinit_array)
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
*(SORT(.init_array.*))
|
||||
*(.init_array)
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
*(SORT(.fini_array.*))
|
||||
*(.fini_array)
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
*(.jcr)
|
||||
. = ALIGN(4);
|
||||
/* All data end */
|
||||
__data_end__ = .;
|
||||
} > RAM AT > FLASH
|
||||
|
||||
.bssnz :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__bssnz_start__ = .;
|
||||
*(.bss.core.nz*)
|
||||
. = ALIGN(4);
|
||||
__bssnz_end__ = .;
|
||||
} > RAM
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__bss_start__ = .;
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
__bss_end__ = .;
|
||||
} > RAM
|
||||
|
||||
.cmac (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(0x400);
|
||||
*(.libcmac.ram)
|
||||
} > RAM
|
||||
|
||||
/* Heap starts after BSS */
|
||||
. = ALIGN(8);
|
||||
__HeapBase = .;
|
||||
|
||||
/* .stack_dummy section doesn't contains any symbols. It is only
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later */
|
||||
.stack_dummy (COPY):
|
||||
{
|
||||
*(.stack*)
|
||||
} > RAM
|
||||
|
||||
_ram_start = ORIGIN(RAM);
|
||||
|
||||
/* Set stack top to end of RAM, and stack limit move down by
|
||||
* size of stack_dummy section */
|
||||
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
|
||||
PROVIDE(__stack = __StackTop);
|
||||
|
||||
/* Top of head is the bottom of the stack */
|
||||
__HeapLimit = __StackLimit;
|
||||
end = __HeapLimit;
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__HeapBase <= __HeapLimit, "region RAM overflowed with stack")
|
||||
|
||||
/* Check that intvect is at the beginning of RAM */
|
||||
ASSERT(__intvect_start__ == ORIGIN(RAM), "intvect is not at beginning of RAM")
|
||||
}
|
Binary file not shown.
|
@ -1,6 +0,0 @@
|
|||
set(hw_dir "${CMAKE_CURRENT_LIST_DIR}/../../../")
|
||||
|
||||
idf_component_register(SRCS family.c
|
||||
INCLUDE_DIRS "." ${BOARD} ${hw_dir}
|
||||
PRIV_REQUIRES driver usb
|
||||
REQUIRES led_strip src tinyusb_src)
|
|
@ -1,3 +0,0 @@
|
|||
# Apply board specific content here
|
||||
set(IDF_TARGET "esp32")
|
||||
set(MAX3421_HOST 1)
|
|
@ -1,53 +0,0 @@
|
|||
/*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020, Ha Thach (tinyusb.org)
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* This file is part of the TinyUSB stack.
|
||||
*/
|
||||
|
||||
#ifndef BOARD_H_
|
||||
#define BOARD_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define NEOPIXEL_PIN 0
|
||||
#define NEOPIXEL_POWER_PIN 2
|
||||
#define NEOPIXEL_POWER_STATE 1
|
||||
|
||||
#define BUTTON_PIN 38
|
||||
#define BUTTON_STATE_ACTIVE 0
|
||||
|
||||
// SPI for USB host shield
|
||||
#define MAX3421_SPI_HOST SPI3_HOST
|
||||
#define MAX3421_SCK_PIN 5
|
||||
#define MAX3421_MOSI_PIN 19
|
||||
#define MAX3421_MISO_PIN 21
|
||||
#define MAX3421_CS_PIN 33
|
||||
#define MAX3421_INTR_PIN 15
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* BOARD_H_ */
|
|
@ -1,3 +0,0 @@
|
|||
# Apply board specific content here
|
||||
set(IDF_TARGET "esp32s2")
|
||||
set(MAX3421_HOST 1)
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue