4
0
mirror of https://github.com/RT-Thread/rt-thread.git synced 2025-02-14 23:39:21 +08:00

[bsp][mm32f526x] 1.add mm32f526x bsp; (#9940)

[bsp][mm32f526x] 1.add a bsp for mm32f526x;
This commit is contained in:
Chasel 2025-02-03 23:29:27 +08:00 committed by GitHub
parent 562e15b118
commit 94952b18fc
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
45 changed files with 11541 additions and 0 deletions

View File

@ -93,6 +93,7 @@ jobs:
- "hc32l196"
- "mm32/mm32f3270-100ask-pitaya"
- "mm32f327x"
- "mm32f526x"
- "mm32l07x"
- "sam7x"
- "hk32/hk32f030c8-mini"

View File

@ -0,0 +1,22 @@
scons.args: &scons
scons_arg:
- '--strict'
devices.gpio:
<<: *scons
kconfig:
- CONFIG_RT_USING_PIN=y
- CONFIG_BSP_USING_GPIO=y
devices.uart:
kconfig:
- CONFIG_RT_USING_SERIAL=y
- CONFIG_RT_USING_SERIAL_V1=y
- CONFIG_BSP_USING_UART1=y
- CONFIG_BSP_USING_UART2=y
- CONFIG_BSP_USING_UART3=y
devices.adc:
kconfig:
- CONFIG_RT_USING_ADC=y
- CONFIG_BSP_USING_ADC=y
- CONFIG_BSP_USING_ADC1=y
- CONFIG_BSP_USING_ADC2=y

1314
bsp/mm32f526x/.config Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,6 @@
# files format check exclude path, please follow the instructions below to modify;
# If you need to exclude an entire folder, add the folder path in dir_path;
# If you need to exclude a file, add the path to the file in file_path.
dir_path:
- Libraries

17
bsp/mm32f526x/Kconfig Normal file
View File

@ -0,0 +1,17 @@
mainmenu "RT-Thread Configuration"
BSP_DIR := .
RTT_DIR := ../..
PKGS_DIR := packages
source "$(RTT_DIR)/Kconfig"
osource "$PKGS_DIR/Kconfig"
rsource "board/Kconfig"
config SOC_MM32F526x
bool
select RT_USING_COMPONENTS_INIT
select RT_USING_USER_MAIN
default y

20
bsp/mm32f526x/Makefile Normal file
View File

@ -0,0 +1,20 @@
ifeq ($(shell uname), Linux)
# Linux-specific settings
toolchain=/home/mhy/gcc-arm-none-eabi-10.3-2021.10/bin
else
# Windows-specific settings
# toolchain=F:\work\TOOLS\sdk-toolchain-RISC-V-GCC-WCH\bin
ifndef toolchain
$(warning Please rewrite the toolchain in windows local directory")
exit 0
endif
endif
all:
scons -j 8 --exec-path=$(toolchain)
PHONY: clean
clean:
scons -c --exec-path=$(toolchain)
rm -f *.bin *.hex *.map > /dev/null 2>&1

154
bsp/mm32f526x/README.md Normal file
View File

@ -0,0 +1,154 @@
# MM32F5265-OB开发板BSP 说明
标签: MM32、Cortex-M33、MM32F5265、国产MCU
---
## 1. 简介
本文档为MM32F5265-OB 评估板bsp适配说明
### 1.1 开发板介绍
MM32F5265-OB 是为了用户快速上手、了解学习MM32系列MCU的一块入门级开发板可满足基础测试及高端开发需求。
开发板外观如下图所示:
MM32F5265-OB
![Mini-F5265-OB](figures/Mini-F5265-OB.jpg)
#### MM32F5265-OB 开发板特性:
#### 内核与系统
- 工作频率可达 120MHz
- 搭载 “星辰”STAR-MC1 (兼容 Cortex-M33处理器采用 Armv8-M Mainline 架构内置单精度浮点运算单元FPU支持 DSP 扩展
- 4KB L1 指令缓存I-Cache和 4KB L1 数据缓存D-Cache
- 三角函数加速单元CORDIC支持 SinCos 和 Atan 操作
- 外设互联矩阵 MindSwitch支持定时器、GPIOs、EXTI、ADC、DAC 和比较器等模块信号间的直接连接或触发连接
- 2 个 8 通道 DMA 控制器支持外设类型包括定时器、ADC、DAC、UART、LPUART、I2C、SPI、QSPI 和 FlexCAN
#### 存储器
- 多达 256KB 的 Flash 存储器
- 多达 128KB 的 SRAM
- Boot loader 支持片内 Flash 在线系统编程ISP
- QSPI 接口,支持扩展外部 NOR Flash 存储支持在线执行模式eXecute-In-PlaceXIP
- FSMC 接口,支持外扩 SRAM/PSRAM/NOR Flash 类型,兼容 8080/6800 通信总线模式
#### 时钟、复位和电源管理
- 2.0V 5.5V 供电
- 上电/断电复位POR/PDR、可编程电压监测器PVD
- 外部 4 24MHz 高速晶体振荡器
- 内置经出厂调校的 8MHz 高速 RC 振荡器
- 内置的 PLL1 可产生系统时钟,支持多种分频模式,为总线矩阵和外设提供时钟
- 内置的 PLL2 可产生最高 100MHz 的系统时钟,支持多种分频模式,为 USB 和ADC 提供时钟
- 内置 40KHz 低速振荡器
- 外部 32.768KHz 低速振荡器,支持旁路功能
#### 低功耗
- 多种低功耗模式包括低功耗运行Lower Power Run、睡眠Sleep、低功耗睡眠Low Power Sleep、停机Stop、深度停机Deep Stop和待机模式Standby
- VBAT 为 RTC 和后备寄存器20 x 16 位)供电
- 内置LPUART、LPTimer支持从低功耗模式下触发唤醒
#### 多达 14 个通信接口
- 5 个 UART 接口
- 1 个 LPUART 接口
- 2 个 I2C 接口
- 3 个 SPI 接口(支持 I2S 模式)
- 1 个 USB 2.0,支持 Device & Host 模式
- 2 个 FlexCAN 接口,兼容 CAN 2.0B 协议
#### 13 个定时器
- 2 个 16 位 4 通道高级定时器TIM1 / TIM8有 4 组包含互补输出功能的 PWM输出通道并支持硬件死区插入和故障检测后的紧急停止功能
- 2 个 16 位 4 通道通用定时器TIM3 / TIM4和 2 个 32 位 4 通道通用定时器TIM2 / TIM5每个通道配有 1 个 PWM 输出,并支持输入捕捉和输出比较,可用于红外、霍尔传感器或者编码器信号的解码
- 2 个 16 位基础定时器TIM6 / TIM7可用作通用定时和产生中断
- 1 个 16 位低功耗定时器LPTIM能在除了 Standby 以外的所有低功耗模式下唤醒处理器
- 2 个看门狗定时器,包括独立型的 IWDG 和窗口型的 WWDG
- 1 个 24 位 Systick 定时器
- 1 个 RTC 实时时钟
#### 2 个 12 位 ADC共支持 19 个外部输入通道和 2 个内部输入通道,其中每个 ADC 支持最快 3MSPS 转换率,硬件支持过采样到 16 位分辨率
- 转换范围0 VDDA
- 支持采样时间和分辨率配置
- 支持硬件过采样,过采样次数从 2 到 256 次可选
- 片上温度传感器
- 片上电压传感器
- VBAT 电压传感器
#### 2 个 12 位 DAC
#### 3 个 高速模拟比较器
#### 多达 86 个快速 I/O 端口
- 所有 I/O 口可以映像到 16 个外部中断
- 所有端口均可输入输出电压不高于 VDD 的信号
- 多达 61 个 5V 容忍 I/O 端口
#### CRC 计算单元
#### 96 位芯片唯一 IDUID
#### 调试模式
- 串行调试接口SWD
- JTAG 接口
#### 采用 LQFP100、LQFP64 和 LQFP48 封装
#### 全系列支持 -40℃ +105℃ 扩展工业型工作温度范围
#### 板载主控MM32F5265E7PV
板载资源:
- 2 个用户LED
- 2 个用户按键
- 1 个复位按键
- 1 个可调电位器
- 8M SPI FLASH 和 2K EEPROM
板载接口:
- 1 x USB Type-C (USB-DBG)
供电方式:
- USB TYPE-C
更多详细信息请咨询[上海灵动微电子](https://www.mindmotion.com.cn/)
## 2. 编译说明
推荐熟悉 RT_Thread 的用户使用[env工具](https://www.rt-thread.org/download.html#download-rt-thread-env-tool)可以在console下进入到 `bsp/mm32f526x` 目录中,运行以下命令:
```
pkgs --update
make
```
来编译这个板级支持包。如果编译正确无误会产生rtthread.elf、rtthread.bin、rtthread.hex文件。其中 rtthread.bin、rtthread.hex 都可以烧写到设备中运行。
## 3. 驱动支持情况及计划
| 驱动 | 支持情况 | 备注 |
| ---------- | :------: | :--------------------------: |
| UART | 支持 | UART1/2/3 |
| GPIO | 支持 | / |
| ADC | 支持 | ADC1/2 |
| FLASH | 支持 | / |
## 4. 联系人信息
维护人:
- [Chasel](https://github.com/Maihuanyi) email: m19825309307@163.com
## 5. 参考
- [MM32F5260系列产品手册](https://www.mindmotion.com.cn/download/products/DS_MM32F5260_SC.pdf)
- [MM32F5260系列用户手册](https://www.mindmotion.com.cn/download/products/UM_MM32F5260_SC.pdf)
- [MiniBoard(MM32F5260)资料包](https://www.mindmotion.com.cn/support/development_tools/evaluation_boards/miniboard/mm32f5265e7pv/)
- [KEIL Pack 设备支持包](https://www.mindmotion.com.cn/support/software/keil_pack/)
- [IAR Pack 设备支持包](https://www.mindmotion.com.cn/support/software/iar_pack/)
- [J-Link Pack 设备支持包](https://www.mindmotion.com.cn/support/software/jlink_pack/)

11
bsp/mm32f526x/SConscript Normal file
View File

@ -0,0 +1,11 @@
from building import *
cwd = GetCurrentDir()
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')

48
bsp/mm32f526x/SConstruct Normal file
View File

@ -0,0 +1,48 @@
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
try:
from building import *
except:
print('Cannot found RT-Thread root directory, please check RTT_ROOT')
print(RTT_ROOT)
exit(-1)
TARGET = 'rtthread.' + rtconfig.TARGET_EXT
DefaultEnvironment(tools=[])
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM in ['iccarm']:
env.Replace(CCCOM = ['$CC $CFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = env["LINKCOM"] + ' --map project.map')
Export('RTT_ROOT')
Export('rtconfig')
SDK_ROOT = os.path.abspath('./')
if os.path.exists(SDK_ROOT + '/libraries'):
libraries_path_prefix = SDK_ROOT + '/libraries'
else:
libraries_path_prefix = os.path.dirname(SDK_ROOT) + '/libraries'
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# make a building
DoBuilding(TARGET, objs)

View File

@ -0,0 +1,15 @@
from building import *
import os
cwd = GetCurrentDir()
src = Glob('*.c')
CPPPATH = [cwd]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
list = os.listdir(cwd)
for item in list:
if os.path.isfile(os.path.join(cwd, item, 'SConscript')):
group = group + SConscript(os.path.join(item, 'SConscript'))
Return('group')

View File

@ -0,0 +1,38 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include "hal_rcc.h"
#include "hal_gpio.h"
#define LED1_PIN 31
#define LED2_PIN 30
int main(void)
{
/* set LED1 pin mode to output */
rt_pin_mode(LED1_PIN, PIN_MODE_OUTPUT);
/* set LED2 pin mode to output */
rt_pin_mode(LED2_PIN, PIN_MODE_OUTPUT);
while (1) {
rt_pin_write(LED1_PIN, PIN_HIGH);
rt_pin_write(LED2_PIN, PIN_HIGH);
rt_thread_mdelay(500);
rt_pin_write(LED1_PIN, PIN_LOW);
rt_pin_write(LED2_PIN, PIN_LOW);
rt_thread_mdelay(500);
}
return RT_EOK;
}

View File

@ -0,0 +1,58 @@
menu "Hardware Drivers Config"
menu "On-chip Peripheral Drivers"
menu "GPIO Drivers"
config BSP_USING_GPIO
bool "Enable GPIO"
select RT_USING_PIN
default n
endmenu
menu "UART Drivers"
config BSP_USING_UART1
bool "Enable UART1 PA9/10(T/R)"
select RT_USING_SERIAL
default n
config BSP_USING_UART2
bool "Enable UART2 PA2/3(T/R)"
select RT_USING_SERIAL
default n
config BSP_USING_UART3
bool "Enable UART3 PC10/11(T/R)"
select RT_USING_SERIAL
default y
endmenu
menuconfig BSP_USING_ADC
bool "Enable ADC"
default n
select RT_USING_ADC
if BSP_USING_ADC
config BSP_USING_ADC1
bool "Enable ADC1"
default n
config BSP_USING_ADC2
bool "Enable ADC2"
default n
endif
menu "Flash Drivers"
config BSP_USING_OCFLASH
bool "Enable On Chip Flash"
default n
config OCFLASH_USE_FAL
bool "Enable On Chip Flash FAL Driver"
depends on BSP_USING_OCFLASH
select RT_USING_FAL
default n
config OCFLASH_USE_LFS
bool "Enable On Chip Flash DFS Driver"
depends on OCFLASH_USE_FAL
select RT_USING_DFS
select RT_USING_MTD_NOR
select PKG_USING_LITTLEFS
default n
endmenu
endmenu
endmenu

View File

@ -0,0 +1,18 @@
# RT-Thread building script for component
import os
import rtconfig
from building import *
cwd = GetCurrentDir()
# add the general drivers.
src = ['board.c']
src += ['mm32_msp.c']
CPPPATH = [cwd]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
Return('group')

View File

@ -0,0 +1,87 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <board.h>
extern uint32_t SystemCoreClock;
extern void SystemInit(void);
/**
* this function will delay for some us.
*
* @param us the delay time of us
*/
void rt_hw_us_delay(rt_uint32_t us)
{
rt_uint32_t ticks;
rt_uint32_t told, tnow, tcnt = 0;
rt_uint32_t reload = SysTick->LOAD;
ticks = us * reload / (1000000 / RT_TICK_PER_SECOND);
told = SysTick->VAL;
while (1) {
tnow = SysTick->VAL;
if (tnow != told) {
if (tnow < told) {
tcnt += told - tnow;
} else {
tcnt += reload - tnow + told;
}
told = tnow;
if (tcnt >= ticks) {
break;
}
}
}
}
static void bsp_clock_config(void)
{
SystemInit();
SysTick_Config(SystemCoreClock / RT_TICK_PER_SECOND);
SysTick->CTRL |= 0x00000004UL;
}
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
void rt_hw_board_init()
{
bsp_clock_config();
#if defined(RT_USING_HEAP)
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
#endif
#ifdef RT_USING_PIN
extern int rt_hw_pin_init(void);
rt_hw_pin_init();
#endif
#ifdef RT_USING_SERIAL
extern int rt_hw_uart_init(void);
rt_hw_uart_init();
#endif
#if defined(RT_USING_CONSOLE) && defined(RT_USING_DEVICE)
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
}

View File

@ -0,0 +1,42 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#include <rtthread.h>
#include <rtdevice.h>
#include <rthw.h>
#include "mm32_device.h"
#include <hal_common.h>
#include "mm32_msp.h"
#define SRAM_SIZE 0x1C000
#define SRAM_BASE (0x30000000)
#define SRAM_END (SRAM_BASE + SRAM_SIZE)
#ifdef __CC_ARM
extern int Image$$RW_IRAM1$$ZI$$Limit;
#define HEAP_BEGIN ((void *)&Image$$RW_IRAM1$$ZI$$Limit)
#elif __ICCARM__
#pragma section = "HEAP"
#define HEAP_BEGIN (__segment_end("HEAP"))
#else
extern int __bss_end__;
#define HEAP_BEGIN ((void *)&__bss_end__)
#endif
#define HEAP_END SRAM_END
#define HEAP_SIZE (HEAP_END - (rt_uint32_t)HEAP_BEGIN)
extern void rt_hw_board_init(void);
#define CLOCK_SYS_FREQ 120000000u
#define CLOCK_SYSTICK_FREQ (CLOCK_SYS_FREQ/8u)
#endif

View File

@ -0,0 +1,34 @@
/*###ICF### Section handled by ICF editor, don't touch! ****/
/*-Editor annotation file-*/
/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_4.xml" */
/*-Specials-*/
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
define symbol __ICFEDIT_region_IROM_start__ = 0x08000000;
define symbol __ICFEDIT_region_IROM_end__ = 0x0003FFFF;
define symbol __ICFEDIT_region_IRAM_start__ = 0x30000000;
define symbol __ICFEDIT_region_IRAM_end__ = 0x3001FFFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_cstack__ = 0x0800;
define symbol __ICFEDIT_size_proc_stack__ = 0x0;
define symbol __ICFEDIT_size_heap__ = 0x0800;
/**** End of ICF editor section. ###ICF###*/
define memory mem with size = 4G;
define region IROM_region = mem:[from __ICFEDIT_region_IROM_start__ to __ICFEDIT_region_IROM_end__];
define region IRAM_region = mem:[from __ICFEDIT_region_IRAM_start__ to __ICFEDIT_region_IRAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
define block PROC_STACK with alignment = 8, size = __ICFEDIT_size_proc_stack__ { };
define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
do not initialize { section .noinit };
initialize by copy { readwrite };
if (isdefinedsymbol(__USE_DLIB_PERTHREAD))
{
// Required in a multi-threaded application
initialize by copy with packing = none { section __DLIB_PERTHREAD };
}
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place in IROM_region { readonly };
place in IRAM_region { readwrite, block CSTACK, block PROC_STACK, block HEAP };

View File

@ -0,0 +1,268 @@
/*
*-------- <<< Use Configuration Wizard in Context Menu >>> -------------------
*/
/*---------------------- Flash Configuration ----------------------------------
<h> Flash Configuration
<o0> Flash Base Address <0x0-0xFFFFFFFF:8>
<o1> Flash Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__ROM_BASE = 0x08000000;
__ROM_SIZE = 0x00040000;
/*--------------------- Embedded RAM Configuration ----------------------------
<h> RAM Configuration
<o0> RAM Base Address <0x0-0xFFFFFFFF:8>
<o1> RAM Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__RAM_BASE = 0x30000000;
__RAM_SIZE = 0x0001C000;
/*--------------------- Stack / Heap Configuration ----------------------------
<h> Stack / Heap Configuration
<o0> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
<o1> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__STACK_SIZE = 0x00001000;
/*__HEAP_SIZE = 0x00001000;*/
/*
*-------------------- <<< end of configuration section >>> -------------------
*/
/* ARMv8-M stack sealing:
to use ARMv8-M stack sealing set __STACKSEAL_SIZE to 8 otherwise keep 0
*/
__STACKSEAL_SIZE = 0;
MEMORY
{
FLASH (rx) : ORIGIN = __ROM_BASE, LENGTH = __ROM_SIZE
RAM (rwx) : ORIGIN = __RAM_BASE, LENGTH = __RAM_SIZE
}
/* 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
* __copy_table_start__
* __copy_table_end__
* __zero_table_start__
* __zero_table_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__
* __end__
* end
* __HeapLimit
* __StackLimit
* __StackTop
* __stack
* __StackSeal (only if ARMv8-M stack sealing is used)
*/
ENTRY(Reset_Handler)
SECTIONS
{
.text :
{
. = ALIGN(4);
KEEP(*(.vectors))
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
. = ALIGN(4);
PROVIDE(__ctors_start__ = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
PROVIDE(__ctors_end__ = .);
. = ALIGN(4);
_etext = .;
} > FLASH
/*
* SG veneers:
* All SG veneers are placed in the special output section .gnu.sgstubs. Its start address
* must be set, either with the command line option <20><>--section-start<72><74> or in a linker script,
* to indicate where to place these veneers in memory.
*/
/*
.gnu.sgstubs :
{
. = ALIGN(32);
} > FLASH
*/
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > FLASH
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
/* This is used by the startup in order to initialize the .data secion */
_sidata = .;
} > FLASH
__exidx_end = .;
__etext = ALIGN (4);
.data : AT (__etext)
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
*(.gnu.linkonce.d*)
PROVIDE(__dtors_start__ = .);
KEEP(*(SORT(.dtors.*)))
KEEP(*(.dtors))
PROVIDE(__dtors_end__ = .);
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} > RAM
/*
* Secondary data section, optional
*
* Remember to add each additional data section
* to the .copy.table above to asure proper
* initialization during startup.
*/
/*
__etext2 = ALIGN (4);
.data2 : AT (__etext2)
{
. = ALIGN(4);
__data2_start__ = .;
*(.data2)
*(.data2.*)
. = ALIGN(4);
__data2_end__ = .;
} > RAM2
*/
/*
.heap (COPY) :
{
. = ALIGN(8);
__end__ = .;
PROVIDE(end = .);
. = . + __HEAP_SIZE;
. = ALIGN(8);
__HeapLimit = .;
} > RAM
*/
/* ARMv8-M stack sealing:
to use ARMv8-M stack sealing uncomment '.stackseal' section
*/
/*
.stackseal :
{
. = ALIGN(8);
__StackSeal = .;
. = . + 8;
. = ALIGN(8);
} > RAM
*/
.stack :
{
. = ALIGN(8);
_sstack = .;
. = . + __STACK_SIZE;
. = ALIGN(8);
_estack = .;
} > RAM
__bss_start__ = .;
.bss :
{
. = ALIGN(4);
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_ebss = . ;
*(.bss.init)
} > RAM
__bss_end__ = .;
/*
* Secondary bss section, optional
*
* Remember to add each additional bss section
* to the .zero.table above to asure proper
* initialization during startup.
*/
/*
.bss2 :
{
. = ALIGN(4);
__bss2_start__ = .;
*(.bss2)
*(.bss2.*)
. = ALIGN(4);
__bss2_end__ = .;
} > RAM2 AT > RAM2
*/
}

View File

@ -0,0 +1,114 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
#! armclang -E --target=arm-arm-none-eabi -mcpu=cortex-m33 -xc
; command above MUST be in first line (no comment above!)
/*
;-------- <<< Use Configuration Wizard in Context Menu >>> -------------------
*/
/*--------------------- Flash Configuration ----------------------------------
; <h> Flash Configuration
; <o0> Flash Base Address <0x0-0xFFFFFFFF:8>
; <o1> Flash Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __ROM_BASE 0x008000000
#define __ROM_SIZE 0x000040000
/*---------------------------- ITCM Configuration -----------------------------
; <h> ITCM Configuration
; <o0> ITCM Base Address <0x0-0xFFFFFFFF:8>
; <o1> ITCM Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __ITCM_BASE 0x00000000
#define __ITCM_SIZE 0x00008000
/*---------------------------- DTCM Configuration -----------------------------
; <h> DTCM Configuration
; <o0> DTCM Base Address <0x0-0xFFFFFFFF:8>
; <o1> DTCM Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __DTCM_BASE 0x20000000
#define __DTCM_SIZE 0x00008000
/*--------------------- Embedded RAM1 Configuration ---------------------------
; <h> RAM Configuration
; <o0> RAM1 Base Address <0x0-0xFFFFFFFF:8>
; <o1> RAM1 Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __RAM1_BASE 0x30000000
#define __RAM1_SIZE 0x0001C000
/*--------------------- Embedded RAM2 Configuration ---------------------------
; <h> RAM Configuration
; <o0> RAM2 Base Address <0x0-0xFFFFFFFF:8>
; <o1> RAM2 Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __RAM2_BASE 0x3001C000
#define __RAM2_SIZE 0x00004000
/*--------------------- Stack / Heap Configuration ---------------------------
; <h> Stack / Heap Configuration
; <o0> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; <o1> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __STACK_SIZE 0x00000800
#define __HEAP_SIZE 0x00000C00
/*----------------------------------------------------------------------------
User Stack & Heap boundary definition
*----------------------------------------------------------------------------*/
#define __STACK_TOP (__RAM1_BASE + __RAM1_SIZE) /* starts at end of RAM */
#define __HEAP_BASE (AlignExpr(+0, 8)) /* starts after RW_RAM section, 8 byte aligned */
/*----------------------------------------------------------------------------
Scatter File Definitions definition
*----------------------------------------------------------------------------*/
#define __RO_BASE __ROM_BASE
#define __RO_SIZE __ROM_SIZE
LR_ROM __RO_BASE __RO_SIZE { ; load region size_region
ER_ROM __RO_BASE __RO_SIZE { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
; *(Veneer$$CMSE) ; uncomment for secure applications
.ANY (+RO)
.ANY (+XO)
}
RW_ITCM __ITCM_BASE __ITCM_SIZE { ; RW data
.ANY (+RW +ZI)
}
RW_DTCM __DTCM_BASE __DTCM_SIZE { ; RW data
.ANY (+RW +ZI)
}
RW_RAM1 __RAM1_BASE (__RAM1_SIZE - __STACK_SIZE - __HEAP_SIZE) { ; RW data
.ANY (+RW +ZI)
}
RW_RAM2 __RAM2_BASE __RAM2_SIZE { ; RW data
.ANY (+RW +ZI)
}
#if __HEAP_SIZE > 0
ARM_LIB_HEAP __HEAP_BASE EMPTY __HEAP_SIZE { ; Reserve empty region for heap
}
#endif
ARM_LIB_STACK __STACK_TOP EMPTY -__STACK_SIZE { ; Reserve empty region for stack
}
}

View File

@ -0,0 +1,121 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <rtthread.h>
#include "mm32_device.h"
#include "mm32_msp.h"
void mm32_msp_uart_init(void *instance)
{
GPIO_InitTypeDef GPIO_InitStructure;
UART_TypeDef *uart_x = (UART_TypeDef *)instance;
#ifdef BSP_USING_UART1
if(UART1 == uart_x)
{
/* Enable UART clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_UART1, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
/* Configure USART Rx/tx PIN */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_High;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource9, GPIO_AF_7);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource10, GPIO_AF_7);
}
#endif
#ifdef BSP_USING_UART2
if(UART2 == uart_x)
{
/* Enable UART clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART2, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
/* Configure USART Rx/tx PIN */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_High;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource2, GPIO_AF_7);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource3, GPIO_AF_7);
}
#endif
#ifdef BSP_USING_UART3
if(UART3 == uart_x)
{
/* Enable UART clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART3, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOC, ENABLE);
GPIO_InitTypeDef GPIO_InitStructure;
/* Configure USART Rx/tx PIN */
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_High;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource10, GPIO_AF_7);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource11, GPIO_AF_7);
}
#endif
/* add others */
}
#ifdef BSP_USING_ADC
void mm32_msp_adc_init(void *instance)
{
GPIO_InitTypeDef GPIO_InitStruct;
ADC_TypeDef *adc_x = (ADC_TypeDef *)instance;
#ifdef BSP_USING_ADC1
if(adc_x == ADC1)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE); //Enable ADC1 clock
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
/* configure adc channel as analog input */
GPIO_StructInit(&GPIO_InitStruct);
GPIO_InitStruct.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_High;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AIN;
GPIO_Init(GPIOA, &GPIO_InitStruct);
}
#endif
#ifdef BSP_USING_ADC2
if(adc_x == ADC2)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, ENABLE); //Enable ADC2 clock
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
/* configure adc channel as analog input */
GPIO_StructInit(&GPIO_InitStruct);
GPIO_InitStruct.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_High;
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_AIN;
GPIO_Init(GPIOA, &GPIO_InitStruct);
}
#endif
}
#endif /* BSP_USING_ADC */

View File

@ -0,0 +1,17 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __MM32_MSP_H__
#define __MM32_MSP_H__
void mm32_msp_uart_init(void *instance);
void mm32_msp_adc_init(void *instance);
#endif /* __MM32_MSP_H__ */

View File

@ -0,0 +1,33 @@
# RT-Thread building script for component
import os
import rtconfig
from building import *
cwd = GetCurrentDir()
# add the general drivers.
src = []
# add serial driver code
if GetDepend('BSP_USING_UART1') or GetDepend('BSP_USING_UART2') or GetDepend('BSP_USING_UART3'):
src += ['drv_uart.c']
# add gpio driver code
if GetDepend(['BSP_USING_GPIO']):
src += ['drv_gpio.c']
# add adc driver code
if GetDepend(['BSP_USING_ADC']):
src += ['drv_adc.c']
# add flash driver code
if GetDepend(['BSP_USING_OCFLASH']):
src += ['drv_flash.c']
CPPPATH = [cwd]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
Return('group')

View File

@ -0,0 +1,163 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <rtdevice.h>
#include "board.h"
#include "drv_adc.h"
#include <hal_gpio.h>
#include <hal_adc.h>
#include <hal_rcc.h>
#include <hal_misc.h>
#if defined(BSP_USING_ADC)
struct mm32_adc
{
struct rt_adc_device mm32_adc_device;
ADC_TypeDef *adc_x;
char *name;
};
#if defined(BSP_USING_ADC1)
struct mm32_adc mm32_adc1_config = {
.adc_x = ADC1,
.name = "adc1",
};
#endif /* BSP_USING_ADC1 */
#if defined(BSP_USING_ADC2)
struct mm32_adc mm32_adc2_config = {
.adc_x = ADC2,
.name = "adc2",
};
#endif /* BSP_USING_ADC2 */
static void ADCxChannelEnable(ADC_TypeDef* ADCn, rt_uint32_t channel)
{
ADCn->ADCHS &= ~(1 << channel);
ADCn->ADCHS |= (1 << channel);
}
static rt_err_t mm32_adc_init(struct rt_adc_device *device, rt_int8_t channel, rt_bool_t enabled)
{
ADC_InitTypeDef ADC_InitStruct;
ADC_TypeDef *adc_x;
RT_ASSERT(device != RT_NULL);
adc_x = device->parent.user_data;
if (enabled) {
mm32_msp_adc_init((void *)adc_x);
ADC_CalibrationConfig(adc_x, 0x1FE);
ADC_StructInit(&ADC_InitStruct);
ADC_InitStruct.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStruct.ADC_Prescaler = ADC_Prescaler_16; //ADC prescale factor
ADC_InitStruct.ADC_Mode = ADC_Mode_Scan; //Set ADC mode to scan conversion mode
ADC_InitStruct.ADC_DataAlign = ADC_DataAlign_Right; //AD data right-justified
ADC_Init(adc_x, &ADC_InitStruct);
ADC_SampleTimeConfig(adc_x, channel, ADC_SampleTime_240_5);
ADC_ChannelCmd(adc_x, channel, ENABLE);
ADC_DifferentialConversionConfig(adc_x, ADC_Pseudo_Differential_Conversion_4_5);
ADC_Cmd(adc_x, ENABLE);
} else {
#if defined(BSP_USING_ADC1)
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, DISABLE); //disable ADC1 clock
#endif /* BSP_USING_ADC1 */
#if defined(BSP_USING_ADC2)
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, DISABLE); //disable ADC2 clock
#endif /* BSP_USING_ADC2 */
ADC_DeInit(adc_x);
ADC_Cmd(adc_x, DISABLE);
}
return RT_EOK;
}
static rt_err_t mm32_get_adc_value(struct rt_adc_device *device, rt_int8_t channel, rt_uint32_t *value)
{
ADC_TypeDef *adc_x;
RT_ASSERT(device != RT_NULL);
adc_x = device->parent.user_data;
ADC_SoftwareStartConvCmd(adc_x, ENABLE);
rt_uint32_t cnt = 0;
/* @warning There is a bug here, please fix me. */
while(ADC_GetFlagStatus(adc_x, ADC_FLAG_EOS) == 0) {
rt_thread_mdelay(1);
if (cnt++ > 5)
break;
}
ADC_ClearFlag(adc_x, ADC_FLAG_EOS);
*value = ADC_GetChannelConvertedValue(adc_x, channel);
return RT_EOK;
}
static rt_uint8_t mm32_adc_get_resolution(struct rt_adc_device *device)
{
ADC_TypeDef *adc_x = device->parent.user_data;
RT_ASSERT(device != RT_NULL);
switch( ((adc_x->ADCFG)&(0x00000380)) )
{
case ADC_Resolution_12b:
return 12;
case ADC_Resolution_11b:
return 11;
case ADC_Resolution_10b:
return 10;
case ADC_Resolution_9b:
return 9;
case ADC_Resolution_8b:
return 8;
default:
return 12;
}
}
static rt_int16_t mm32_adc_get_vref(struct rt_adc_device *device)
{
if(device == RT_NULL)
return -RT_ERROR;
return 3300;
}
static const struct rt_adc_ops mm32_adc_ops =
{
.enabled = mm32_adc_init,
.convert = mm32_get_adc_value,
.get_resolution = mm32_adc_get_resolution,
.get_vref = mm32_adc_get_vref,
};
int rt_hw_adc_init(void)
{
#if defined(BSP_USING_ADC1)
rt_hw_adc_register(&mm32_adc1_config.mm32_adc_device, mm32_adc1_config.name, &mm32_adc_ops, mm32_adc1_config.adc_x);
#endif /* BSP_USING_ADC1 */
#if defined(BSP_USING_ADC2)
rt_hw_adc_register(&mm32_adc2_config.mm32_adc_device, mm32_adc2_config.name, &mm32_adc_ops, mm32_adc2_config.adc_x);
#endif /* BSP_USING_ADC2 */
return RT_EOK;
}
INIT_BOARD_EXPORT(rt_hw_adc_init);
#endif /* BSP_USING_ADC */

View File

@ -0,0 +1,16 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __DRV_ADC_H__
#define __DRV_ADC_H__
int rt_hw_adc_init(void);
#endif

View File

@ -0,0 +1,145 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <rtthread.h>
#include "hal_flash.h"
#include "drv_flash.h"
#define OCFLASH_BLK_SIZE 1024
#define OCFLASH_LEN 1024*256
#define OCFLASH_ADDR 0x08000000
#ifdef OCFLASH_USE_FAL
#include <fal.h>
#endif
#ifdef OCFLASH_USE_LFS
#include <dfs_fs.h>
#define FS_PARTITION_NAME "filesystem"
#endif
static int init(void)
{
/* do nothing now */
return 0;
}
static int read(long offset, uint8_t *buf, size_t size)
{
size_t i;
uint32_t addr = OCFLASH_ADDR + offset;
for (i = 0; i < size; i++)
{
*buf = *(__IO uint8_t *)addr;
buf++;
addr++;
}
return size;
}
static int write(long offset, const uint8_t *buf, size_t size)
{
size_t i;
uint32_t addr = OCFLASH_ADDR + offset;
FLASH->KEYR = 0x45670123;
FLASH->KEYR = 0xCDEF89AB;
FLASH->SR = 0x00000001 | 0x00000004 | 0x00000010;
FLASH->CR |= 0x1;
i = 0;
while (i < size)
{
*(__IO uint16_t *)addr = *buf | *(buf + 1) << 8;
addr = addr + 2;
buf += 2;
i += 2;
}
//Lock flash
FLASH->CR |= 0x00000080;
return size;
}
static int erase(long offset, size_t size)
{
int len;
RT_ASSERT(offset > 0 && offset < OCFLASH_LEN);
int page_addr = (offset >> 10) << 10;
len = size + (offset - page_addr);
while (len > 0)
{
FLASH_Unlock();
FLASH_ErasePage(page_addr);
FLASH_Lock();
len -= OCFLASH_BLK_SIZE;
page_addr += OCFLASH_BLK_SIZE;
}
return size;
}
#ifdef OCFLASH_USE_FAL
const struct fal_flash_dev mm32_onchip_flash =
{
.name = "mm32_onchip",
.addr = 0x08000000,
.len = 1024 * 512,
.blk_size = 1024,
.ops = {init, read, write, erase},
.write_gran = 2
};
#endif
int flash_init(void)
{
#ifdef OCFLASH_USE_FAL
fal_init();
#endif
#ifdef OCFLASH_USE_LFS
struct rt_device *flash_dev = fal_mtd_nor_device_create(FS_PARTITION_NAME);
if (flash_dev == NULL)
{
rt_kprintf("Can't create a mtd device on '%s' partition.\n", FS_PARTITION_NAME);
}
else
{
rt_kprintf("Create a mtd device on the %s partition of flash successful.\n", FS_PARTITION_NAME);
}
if (rt_device_find(FS_PARTITION_NAME) != RT_NULL)
{
if (dfs_mount(FS_PARTITION_NAME, "/", "lfs", 0, 0) == RT_EOK)
{
rt_kprintf("onchip lfs filesystem mount to '/'\n");
}
else
{
dfs_mkfs("lfs", FS_PARTITION_NAME);
if (dfs_mount(FS_PARTITION_NAME, "/", "lfs", 0, 0) == RT_EOK)
{
rt_kprintf("onchip lfs filesystem mount to '/' with mkfs\n");
}
else
{
rt_kprintf("onchip lfs filesystem mount to '/' failed!\n");
}
}
}
else
{
rt_kprintf("find filesystem portion failed\r\n");
}
#endif
return 0;
}
INIT_APP_EXPORT(flash_init);

View File

@ -0,0 +1,27 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __DRV_FLASH_H__
#define __DRV_FLASH_H__
#include <rtdevice.h>
struct spi_flash_device
{
struct rt_device flash_device;
struct rt_device_blk_geometry geometry;
struct rt_spi_device *rt_spi_device;
struct rt_mutex lock;
void *user_data;
};
int flash_init(void);
#endif

View File

@ -0,0 +1,489 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include "drv_gpio.h"
#include <board.h>
#include <rthw.h>
#include <hal_gpio.h>
#include <hal_exti.h>
#include <hal_misc.h>
#include <hal_rcc.h>
#define PIN_NUM(port, no) (((((port) & 0xFu) << 4) | ((no) & 0xFu)))
#define PIN_PORT(pin) ((uint8_t)(((pin) >> 4) & 0xFu))
#define PIN_NO(pin) ((uint8_t)((pin) & 0xFu))
#define RCC_PIN_PORT(pin) ((uint32_t)(0x01u << (PIN_PORT(pin))))
#define PIN_ATPORTSOURCE(pin) ((uint8_t)(((pin) & 0xF0u) >> 4))
#define PIN_ATPINSOURCE(pin) ((uint8_t)((pin) & 0xFu))
#define PIN_ATPORT(pin) ((GPIO_TypeDef *)(GPIOA_BASE + (0x400u * PIN_PORT(pin))))
#define PIN_ATPIN(pin) ((uint16_t)(1u << PIN_NO(pin)))
/* mm32f5265 pin port */
#define __MM32_PORT_MAX 6u
#define PIN_ATPORT_MAX __MM32_PORT_MAX
struct pin_irq_map
{
rt_uint16_t pinbit;
rt_uint32_t irqbit;
enum IRQn irqno;
};
const struct pin_irq_map mm32_pin_irq_map[] =
{
{GPIO_Pin_0, EXTI_Line0, EXTI0_IRQn},
{GPIO_Pin_1, EXTI_Line1, EXTI1_IRQn},
{GPIO_Pin_2, EXTI_Line2, EXTI2_IRQn},
{GPIO_Pin_3, EXTI_Line3, EXTI3_IRQn},
{GPIO_Pin_4, EXTI_Line4, EXTI4_IRQn},
{GPIO_Pin_5, EXTI_Line5, EXTI9_5_IRQn},
{GPIO_Pin_6, EXTI_Line6, EXTI9_5_IRQn},
{GPIO_Pin_7, EXTI_Line7, EXTI9_5_IRQn},
{GPIO_Pin_8, EXTI_Line8, EXTI9_5_IRQn},
{GPIO_Pin_9, EXTI_Line9, EXTI9_5_IRQn},
{GPIO_Pin_10, EXTI_Line10, EXTI15_10_IRQn},
{GPIO_Pin_11, EXTI_Line11, EXTI15_10_IRQn},
{GPIO_Pin_12, EXTI_Line12, EXTI15_10_IRQn},
{GPIO_Pin_13, EXTI_Line13, EXTI15_10_IRQn},
{GPIO_Pin_14, EXTI_Line14, EXTI15_10_IRQn},
{GPIO_Pin_15, EXTI_Line15, EXTI15_10_IRQn},
};
struct rt_pin_irq_hdr mm32_pin_irq_hdr_tab[] =
{
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
};
#define ITEM_NUM(items) sizeof(items) / sizeof(items[0])
static rt_base_t mm32_pin_get(const char *name)
{
rt_base_t pin = 0;
int hw_port_num, hw_pin_num = 0;
int i, name_len;
name_len = rt_strlen(name);
if ((name_len < 4) || (name_len >= 6)) {
return -RT_EINVAL;
}
if ((name[0] != 'P') || (name[2] != '.')) {
return -RT_EINVAL;
}
if ((name[1] >= 'A') && (name[1] <= 'Z')) {
hw_port_num = (int)(name[1] - 'A');
} else {
return -RT_EINVAL;
}
for (i = 3; i < name_len; i++) {
hw_pin_num *= 10;
hw_pin_num += name[i] - '0';
}
pin = PIN_NUM(hw_port_num, hw_pin_num);
return pin;
}
void mm32_pin_write(rt_device_t dev, rt_base_t pin, rt_uint8_t value)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_port = PIN_ATPORT(pin);
gpio_pin = PIN_ATPIN(pin);
} else {
return;
}
GPIO_WriteBit(gpio_port, gpio_pin, (PIN_LOW == value) ? Bit_RESET : Bit_SET);
}
rt_ssize_t mm32_pin_read(rt_device_t dev, rt_base_t pin)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
int value;
value = PIN_LOW;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_port = PIN_ATPORT(pin);
gpio_pin = PIN_ATPIN(pin);
value = GPIO_ReadInputDataBit(gpio_port, gpio_pin);
} else {
return -RT_EINVAL;
}
return value;
}
void mm32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
GPIO_InitTypeDef GPIO_InitStructure;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_port = PIN_ATPORT(pin);
gpio_pin = PIN_ATPIN(pin);
} else {
return;
}
/* GPIO Periph clock enable */
RCC_AHBPeriphClockCmd(RCC_PIN_PORT(pin), ENABLE);
/* Configure GPIO_InitStructure */
GPIO_InitStructure.GPIO_Pin = gpio_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_High;
if (mode == PIN_MODE_OUTPUT) {
/* output setting */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
} else if (mode == PIN_MODE_OUTPUT_OD) {
/* output setting: od. */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
} else if (mode == PIN_MODE_INPUT) {
/* input setting: not pull. */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_FLOATING;
} else if (mode == PIN_MODE_INPUT_PULLUP) {
/* input setting: pull up. */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
} else {
/* input setting:default. */
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;
}
GPIO_Init(gpio_port, &GPIO_InitStructure);
}
rt_inline rt_int32_t bit2bitno(rt_uint32_t bit)
{
int i;
for (i = 0; i < 32; i++) {
if ((0x01 << i) == bit) {
return i;
}
}
return -1;
}
rt_inline const struct pin_irq_map *get_pin_irq_map(uint32_t pinbit)
{
rt_int32_t mapindex = bit2bitno(pinbit);
if (mapindex < 0 || mapindex >= ITEM_NUM(mm32_pin_irq_map)) {
return RT_NULL;
}
return &mm32_pin_irq_map[mapindex];
};
rt_err_t mm32_pin_attach_irq(struct rt_device *device, rt_base_t pin,
rt_uint8_t mode, void (*hdr)(void *args), void *args)
{
uint16_t gpio_pin;
rt_base_t level;
rt_int32_t irqindex = -1;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_pin = PIN_ATPIN(pin);
} else {
return -RT_EINVAL;
}
irqindex = bit2bitno(gpio_pin);
if (irqindex < 0 || irqindex >= ITEM_NUM(mm32_pin_irq_map)) {
return -RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (mm32_pin_irq_hdr_tab[irqindex].pin == pin &&
mm32_pin_irq_hdr_tab[irqindex].hdr == hdr &&
mm32_pin_irq_hdr_tab[irqindex].mode == mode &&
mm32_pin_irq_hdr_tab[irqindex].args == args)
{
rt_hw_interrupt_enable(level);
return RT_EOK;
}
if (mm32_pin_irq_hdr_tab[irqindex].pin != -1) {
rt_hw_interrupt_enable(level);
return -RT_EBUSY;
}
mm32_pin_irq_hdr_tab[irqindex].pin = pin;
mm32_pin_irq_hdr_tab[irqindex].hdr = hdr;
mm32_pin_irq_hdr_tab[irqindex].mode = mode;
mm32_pin_irq_hdr_tab[irqindex].args = args;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
rt_err_t mm32_pin_detach_irq(struct rt_device *device, rt_base_t pin)
{
uint16_t gpio_pin;
rt_base_t level;
rt_int32_t irqindex = -1;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_pin = PIN_ATPIN(pin);
} else {
return -RT_EINVAL;
}
irqindex = bit2bitno(gpio_pin);
if (irqindex < 0 || irqindex >= ITEM_NUM(mm32_pin_irq_map)) {
return -RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (mm32_pin_irq_hdr_tab[irqindex].pin == -1) {
rt_hw_interrupt_enable(level);
return RT_EOK;
}
mm32_pin_irq_hdr_tab[irqindex].pin = -1;
mm32_pin_irq_hdr_tab[irqindex].hdr = RT_NULL;
mm32_pin_irq_hdr_tab[irqindex].mode = 0;
mm32_pin_irq_hdr_tab[irqindex].args = RT_NULL;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
rt_err_t mm32_pin_irq_enable(struct rt_device *device, rt_base_t pin,
rt_uint8_t enabled)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
const struct pin_irq_map *irqmap;
rt_base_t level;
rt_int32_t irqindex = -1;
GPIO_InitTypeDef GPIO_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
if (PIN_PORT(pin) < PIN_ATPORT_MAX) {
gpio_port = PIN_ATPORT(pin);
gpio_pin = PIN_ATPIN(pin);
} else {
return -RT_EINVAL;
}
if (enabled == PIN_IRQ_ENABLE)
{
irqindex = bit2bitno(gpio_pin);
if (irqindex < 0 || irqindex >= ITEM_NUM(mm32_pin_irq_map)) {
return -RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (mm32_pin_irq_hdr_tab[irqindex].pin == -1) {
rt_hw_interrupt_enable(level);
return -RT_ENOSYS;
}
irqmap = &mm32_pin_irq_map[irqindex];
/* GPIO Periph clock enable */
RCC_AHBPeriphClockCmd(RCC_PIN_PORT(pin), ENABLE);
/* Configure GPIO_InitStructure */
GPIO_InitStructure.GPIO_Pin = gpio_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_High;
GPIO_Init(gpio_port, &GPIO_InitStructure);
NVIC_InitStructure.NVIC_IRQChannel = irqmap->irqno;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
EXTI_InitStructure.EXTI_Line = irqmap->irqbit;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
switch (mm32_pin_irq_hdr_tab[irqindex].mode) {
case PIN_IRQ_MODE_RISING:
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
break;
case PIN_IRQ_MODE_FALLING:
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
break;
case PIN_IRQ_MODE_RISING_FALLING:
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
break;
}
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
rt_hw_interrupt_enable(level);
} else if (enabled == PIN_IRQ_DISABLE) {
irqmap = get_pin_irq_map(gpio_pin);
if (irqmap == RT_NULL) {
return -RT_ENOSYS;
}
EXTI_InitStructure.EXTI_Line = irqmap->irqbit;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
EXTI_Init(&EXTI_InitStructure);
} else {
return -RT_ENOSYS;
}
return RT_EOK;
}
const static struct rt_pin_ops _mm32_pin_ops =
{
mm32_pin_mode,
mm32_pin_write,
mm32_pin_read,
mm32_pin_attach_irq,
mm32_pin_detach_irq,
mm32_pin_irq_enable,
mm32_pin_get,
};
int rt_hw_pin_init(void)
{
int result;
result = rt_device_pin_register("pin", &_mm32_pin_ops, RT_NULL);
return result;
}
rt_inline void pin_irq_hdr(int irqno)
{
EXTI_ClearITPendingBit(mm32_pin_irq_map[irqno].irqbit);
if (mm32_pin_irq_hdr_tab[irqno].hdr)
{
mm32_pin_irq_hdr_tab[irqno].hdr(mm32_pin_irq_hdr_tab[irqno].args);
}
}
void EXTI0_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
pin_irq_hdr(0);
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI1_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
pin_irq_hdr(1);
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI2_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
pin_irq_hdr(2);
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI3_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
pin_irq_hdr(3);
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI4_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
pin_irq_hdr(4);
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI9_5_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
if (EXTI_GetITStatus(EXTI_Line5) != RESET)
{
pin_irq_hdr(5);
}
if (EXTI_GetITStatus(EXTI_Line6) != RESET)
{
pin_irq_hdr(6);
}
if (EXTI_GetITStatus(EXTI_Line7) != RESET)
{
pin_irq_hdr(7);
}
if (EXTI_GetITStatus(EXTI_Line8) != RESET)
{
pin_irq_hdr(8);
}
if (EXTI_GetITStatus(EXTI_Line9) != RESET)
{
pin_irq_hdr(9);
}
/* leave interrupt */
rt_interrupt_leave();
}
void EXTI15_10_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
if (EXTI_GetITStatus(EXTI_Line10) != RESET)
{
pin_irq_hdr(10);
}
if (EXTI_GetITStatus(EXTI_Line11) != RESET)
{
pin_irq_hdr(11);
}
if (EXTI_GetITStatus(EXTI_Line12) != RESET)
{
pin_irq_hdr(12);
}
if (EXTI_GetITStatus(EXTI_Line13) != RESET)
{
pin_irq_hdr(13);
}
if (EXTI_GetITStatus(EXTI_Line14) != RESET)
{
pin_irq_hdr(14);
}
if (EXTI_GetITStatus(EXTI_Line15) != RESET)
{
pin_irq_hdr(15);
}
/* leave interrupt */
rt_interrupt_leave();
}

View File

@ -0,0 +1,17 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __DRV_GPIO_H__
#define __DRV_GPIO_H__
int rt_hw_pin_init(void);
#endif

View File

@ -0,0 +1,231 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#include "board.h"
#include <mm32_device.h>
#include <rtdevice.h>
#include "drv_uart.h"
#include <hal_gpio.h>
#include <hal_uart.h>
#include <hal_rcc.h>
#include <hal_misc.h>
/* uart driver */
struct mm32_uart
{
UART_TypeDef *uart;
IRQn_Type irq;
};
static rt_err_t mm32_uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
struct mm32_uart *uart;
UART_InitTypeDef UART_InitStructure;
RT_ASSERT(serial != RT_NULL);
RT_ASSERT(cfg != RT_NULL);
uart = (struct mm32_uart *)serial->parent.user_data;
UART_InitStructure.BaudRate = cfg->baud_rate;
if (cfg->data_bits == DATA_BITS_8)
UART_InitStructure.WordLength = UART_WordLength_8b;
if (cfg->stop_bits == STOP_BITS_1)
UART_InitStructure.StopBits = UART_StopBits_1;
else if (cfg->stop_bits == STOP_BITS_2)
UART_InitStructure.StopBits = UART_StopBits_2;
UART_InitStructure.Parity = UART_Parity_No;
UART_InitStructure.HWFlowControl = UART_HWFlowControl_None;
UART_InitStructure.Mode = UART_Mode_Rx | UART_Mode_Tx;
UART_Init(uart->uart, &UART_InitStructure);
/* Enable UART */
UART_Cmd(uart->uart, ENABLE);
return RT_EOK;
}
static rt_err_t mm32_uart_control(struct rt_serial_device *serial, int cmd, void *arg)
{
struct mm32_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct mm32_uart *)serial->parent.user_data;
switch (cmd)
{
case RT_DEVICE_CTRL_CLR_INT:
/* disable rx irq */
NVIC_DisableIRQ(uart->irq);
UART_ITConfig(uart->uart, UART_IT_RX, DISABLE);
break;
case RT_DEVICE_CTRL_SET_INT:
/* enable rx irq */
NVIC_EnableIRQ(uart->irq);
/* enable interrupt */
UART_ITConfig(uart->uart, UART_IT_RX, ENABLE);
break;
}
return RT_EOK;
}
static int mm32_uart_putc(struct rt_serial_device *serial, char c)
{
struct mm32_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct mm32_uart *)serial->parent.user_data;
while ((uart->uart->CSR & UART_CSR_TXC_Msk) == 0)
;
uart->uart->TDR = c;
return 1;
}
static int mm32_uart_getc(struct rt_serial_device *serial)
{
int ch;
struct mm32_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct mm32_uart *)serial->parent.user_data;
ch = -1;
if (uart->uart->CSR & UART_FLAG_RXAVL)
{
ch = uart->uart->RDR & 0xff;
}
return ch;
}
static const struct rt_uart_ops mm32_uart_ops =
{
mm32_uart_configure,
mm32_uart_control,
mm32_uart_putc,
mm32_uart_getc,
};
#if defined(BSP_USING_UART1)
/* UART1 device driver structure */
static struct mm32_uart uart1;
struct rt_serial_device serial1;
void UART1_IRQHandler(void)
{
struct mm32_uart *uart;
uart = &uart1;
/* enter interrupt */
rt_interrupt_enter();
if (UART_GetITStatus(uart->uart, UART_IT_RX) != RESET)
{
UART_ClearITPendingBit(uart->uart, UART_IT_RX);
rt_hw_serial_isr(&serial1, RT_SERIAL_EVENT_RX_IND);
}
if (UART_GetITStatus(uart->uart, UART_IT_TX) != RESET)
{
/* clear interrupt */
UART_ClearITPendingBit(uart->uart, UART_IT_TX);
}
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART1 */
#if defined(BSP_USING_UART2)
/* UART2 device driver structure */
static struct mm32_uart uart2;
struct rt_serial_device serial2;
void UART2_IRQHandler(void)
{
struct mm32_uart *uart;
uart = &uart2;
/* enter interrupt */
rt_interrupt_enter();
if (UART_GetITStatus(uart->uart, UART_IT_RX) != RESET)
{
UART_ClearITPendingBit(uart->uart, UART_IT_RX);
rt_hw_serial_isr(&serial2, RT_SERIAL_EVENT_RX_IND);
}
if (UART_GetITStatus(uart->uart, UART_IT_TX) != RESET)
{
/* clear interrupt */
UART_ClearITPendingBit(uart->uart, UART_IT_TX);
}
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART2 */
#if defined(BSP_USING_UART3)
/* UART3 device driver structure */
static struct mm32_uart uart3;
struct rt_serial_device serial3;
void UART3_IRQHandler(void)
{
struct mm32_uart *uart;
uart = &uart3;
/* enter interrupt */
rt_interrupt_enter();
if (UART_GetITStatus(uart->uart, UART_IT_RX) != RESET)
{
UART_ClearITPendingBit(uart->uart, UART_IT_RX);
rt_hw_serial_isr(&serial3, RT_SERIAL_EVENT_RX_IND);
}
if (UART_GetITStatus(uart->uart, UART_IT_TX) != RESET)
{
/* clear interrupt */
UART_ClearITPendingBit(uart->uart, UART_IT_TX);
}
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART3 */
int rt_hw_uart_init(void)
{
struct mm32_uart *uart;
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
#ifdef BSP_USING_UART1
mm32_msp_uart_init((void *)UART1);
uart = &uart1;
uart->uart = UART1;
uart->irq = UART1_IRQn;
config.baud_rate = BAUD_RATE_115200;
serial1.ops = &mm32_uart_ops;
serial1.config = config;
/* register UART1 device */
rt_hw_serial_register(&serial1, "uart1",
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX,
uart);
#endif /* BSP_USING_UART1 */
#ifdef BSP_USING_UART2
mm32_msp_uart_init((void *)UART2);
uart = &uart2;
uart->uart = UART2;
uart->irq = UART2_IRQn;
config.baud_rate = BAUD_RATE_115200;
serial2.ops = &mm32_uart_ops;
serial2.config = config;
/* register UART2 device */
rt_hw_serial_register(&serial2, "uart2",
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX,
uart);
#endif /* BSP_USING_UART2 */
#ifdef BSP_USING_UART3
mm32_msp_uart_init((void *)UART3);
uart = &uart3;
uart->uart = UART3;
uart->irq = UART3_IRQn;
config.baud_rate = BAUD_RATE_115200;
serial3.ops = &mm32_uart_ops;
serial3.config = config;
/* register UART2 device */
rt_hw_serial_register(&serial3, "uart3",
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX,
uart);
#endif /* BSP_USING_UART3 */
return 0;
}

View File

@ -0,0 +1,16 @@
/*
* Copyright (c) 2022-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-01-22 chasel first version
*/
#ifndef __DRV_UART_H__
#define __DRV_UART_H__
int rt_hw_uart_init(void);
#endif

View File

@ -0,0 +1,37 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-08-05 mazhiyuan first version
*/
#ifndef _FAL_CFG_H_
#define _FAL_CFG_H_
#include <rtconfig.h>
#include <board.h>
/* ===================== Flash device Configuration ========================= */
extern const struct fal_flash_dev mm32_onchip_flash;
extern struct fal_flash_dev nor_flash0;
/* flash device table */
#define FAL_FLASH_DEV_TABLE \
{ \
&mm32_onchip_flash, \
}
/* ====================== Partition Configuration ========================== */
#ifdef FAL_PART_HAS_TABLE_CFG
/* partition table */
#define FAL_PART_TABLE \
{ \
{FAL_PART_MAGIC_WORD, "bl", "mm32_onchip", 0, 128*1024, 0}, \
{FAL_PART_MAGIC_WORD, "filesystem", "mm32_onchip", 128*1024, 255*1024, 0}, \
}
#endif /* FAL_PART_HAS_TABLE_CFG */
#endif /* _FAL_CFG_H_ */

View File

@ -0,0 +1,34 @@
/*###ICF### Section handled by ICF editor, don't touch! ****/
/*-Editor annotation file-*/
/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_4.xml" */
/*-Specials-*/
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
define symbol __ICFEDIT_region_IROM_start__ = 0x08000000;
define symbol __ICFEDIT_region_IROM_end__ = 0x0003FFFF;
define symbol __ICFEDIT_region_IRAM_start__ = 0x30000000;
define symbol __ICFEDIT_region_IRAM_end__ = 0x3001FFFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_cstack__ = 0x0800;
define symbol __ICFEDIT_size_proc_stack__ = 0x0;
define symbol __ICFEDIT_size_heap__ = 0x0800;
/**** End of ICF editor section. ###ICF###*/
define memory mem with size = 4G;
define region IROM_region = mem:[from __ICFEDIT_region_IROM_start__ to __ICFEDIT_region_IROM_end__];
define region IRAM_region = mem:[from __ICFEDIT_region_IRAM_start__ to __ICFEDIT_region_IRAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
define block PROC_STACK with alignment = 8, size = __ICFEDIT_size_proc_stack__ { };
define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
do not initialize { section .noinit };
initialize by copy { readwrite };
if (isdefinedsymbol(__USE_DLIB_PERTHREAD))
{
// Required in a multi-threaded application
initialize by copy with packing = none { section __DLIB_PERTHREAD };
}
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place in IROM_region { readonly };
place in IRAM_region { readwrite, block CSTACK, block PROC_STACK, block HEAP };

View File

@ -0,0 +1,268 @@
/*
*-------- <<< Use Configuration Wizard in Context Menu >>> -------------------
*/
/*---------------------- Flash Configuration ----------------------------------
<h> Flash Configuration
<o0> Flash Base Address <0x0-0xFFFFFFFF:8>
<o1> Flash Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__ROM_BASE = 0x08000000;
__ROM_SIZE = 0x00040000;
/*--------------------- Embedded RAM Configuration ----------------------------
<h> RAM Configuration
<o0> RAM Base Address <0x0-0xFFFFFFFF:8>
<o1> RAM Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__RAM_BASE = 0x30000000;
__RAM_SIZE = 0x0001C000;
/*--------------------- Stack / Heap Configuration ----------------------------
<h> Stack / Heap Configuration
<o0> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
<o1> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
</h>
-----------------------------------------------------------------------------*/
__STACK_SIZE = 0x00001000;
/*__HEAP_SIZE = 0x00001000;*/
/*
*-------------------- <<< end of configuration section >>> -------------------
*/
/* ARMv8-M stack sealing:
to use ARMv8-M stack sealing set __STACKSEAL_SIZE to 8 otherwise keep 0
*/
__STACKSEAL_SIZE = 0;
MEMORY
{
FLASH (rx) : ORIGIN = __ROM_BASE, LENGTH = __ROM_SIZE
RAM (rwx) : ORIGIN = __RAM_BASE, LENGTH = __RAM_SIZE
}
/* 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
* __copy_table_start__
* __copy_table_end__
* __zero_table_start__
* __zero_table_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__
* __end__
* end
* __HeapLimit
* __StackLimit
* __StackTop
* __stack
* __StackSeal (only if ARMv8-M stack sealing is used)
*/
ENTRY(Reset_Handler)
SECTIONS
{
.text :
{
. = ALIGN(4);
KEEP(*(.vectors))
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
. = ALIGN(4);
PROVIDE(__ctors_start__ = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
PROVIDE(__ctors_end__ = .);
. = ALIGN(4);
_etext = .;
} > FLASH
/*
* SG veneers:
* All SG veneers are placed in the special output section .gnu.sgstubs. Its start address
* must be set, either with the command line option <20><>--section-start<72><74> or in a linker script,
* to indicate where to place these veneers in memory.
*/
/*
.gnu.sgstubs :
{
. = ALIGN(32);
} > FLASH
*/
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > FLASH
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
/* This is used by the startup in order to initialize the .data secion */
_sidata = .;
} > FLASH
__exidx_end = .;
__etext = ALIGN (4);
.data : AT (__etext)
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
*(.gnu.linkonce.d*)
PROVIDE(__dtors_start__ = .);
KEEP(*(SORT(.dtors.*)))
KEEP(*(.dtors))
PROVIDE(__dtors_end__ = .);
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} > RAM
/*
* Secondary data section, optional
*
* Remember to add each additional data section
* to the .copy.table above to asure proper
* initialization during startup.
*/
/*
__etext2 = ALIGN (4);
.data2 : AT (__etext2)
{
. = ALIGN(4);
__data2_start__ = .;
*(.data2)
*(.data2.*)
. = ALIGN(4);
__data2_end__ = .;
} > RAM2
*/
/*
.heap (COPY) :
{
. = ALIGN(8);
__end__ = .;
PROVIDE(end = .);
. = . + __HEAP_SIZE;
. = ALIGN(8);
__HeapLimit = .;
} > RAM
*/
/* ARMv8-M stack sealing:
to use ARMv8-M stack sealing uncomment '.stackseal' section
*/
/*
.stackseal :
{
. = ALIGN(8);
__StackSeal = .;
. = . + 8;
. = ALIGN(8);
} > RAM
*/
.stack :
{
. = ALIGN(8);
_sstack = .;
. = . + __STACK_SIZE;
. = ALIGN(8);
_estack = .;
} > RAM
__bss_start__ = .;
.bss :
{
. = ALIGN(4);
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_ebss = . ;
*(.bss.init)
} > RAM
__bss_end__ = .;
/*
* Secondary bss section, optional
*
* Remember to add each additional bss section
* to the .zero.table above to asure proper
* initialization during startup.
*/
/*
.bss2 :
{
. = ALIGN(4);
__bss2_start__ = .;
*(.bss2)
*(.bss2.*)
. = ALIGN(4);
__bss2_end__ = .;
} > RAM2 AT > RAM2
*/
}

View File

@ -0,0 +1,114 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
#! armclang -E --target=arm-arm-none-eabi -mcpu=cortex-m33 -xc
; command above MUST be in first line (no comment above!)
/*
;-------- <<< Use Configuration Wizard in Context Menu >>> -------------------
*/
/*--------------------- Flash Configuration ----------------------------------
; <h> Flash Configuration
; <o0> Flash Base Address <0x0-0xFFFFFFFF:8>
; <o1> Flash Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __ROM_BASE 0x008000000
#define __ROM_SIZE 0x000040000
/*---------------------------- ITCM Configuration -----------------------------
; <h> ITCM Configuration
; <o0> ITCM Base Address <0x0-0xFFFFFFFF:8>
; <o1> ITCM Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __ITCM_BASE 0x00000000
#define __ITCM_SIZE 0x00008000
/*---------------------------- DTCM Configuration -----------------------------
; <h> DTCM Configuration
; <o0> DTCM Base Address <0x0-0xFFFFFFFF:8>
; <o1> DTCM Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __DTCM_BASE 0x20000000
#define __DTCM_SIZE 0x00008000
/*--------------------- Embedded RAM1 Configuration ---------------------------
; <h> RAM Configuration
; <o0> RAM1 Base Address <0x0-0xFFFFFFFF:8>
; <o1> RAM1 Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __RAM1_BASE 0x30000000
#define __RAM1_SIZE 0x0001C000
/*--------------------- Embedded RAM2 Configuration ---------------------------
; <h> RAM Configuration
; <o0> RAM2 Base Address <0x0-0xFFFFFFFF:8>
; <o1> RAM2 Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __RAM2_BASE 0x3001C000
#define __RAM2_SIZE 0x00004000
/*--------------------- Stack / Heap Configuration ---------------------------
; <h> Stack / Heap Configuration
; <o0> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; <o1> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
*----------------------------------------------------------------------------*/
#define __STACK_SIZE 0x00000800
#define __HEAP_SIZE 0x00000C00
/*----------------------------------------------------------------------------
User Stack & Heap boundary definition
*----------------------------------------------------------------------------*/
#define __STACK_TOP (__RAM1_BASE + __RAM1_SIZE) /* starts at end of RAM */
#define __HEAP_BASE (AlignExpr(+0, 8)) /* starts after RW_RAM section, 8 byte aligned */
/*----------------------------------------------------------------------------
Scatter File Definitions definition
*----------------------------------------------------------------------------*/
#define __RO_BASE __ROM_BASE
#define __RO_SIZE __ROM_SIZE
LR_ROM __RO_BASE __RO_SIZE { ; load region size_region
ER_ROM __RO_BASE __RO_SIZE { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
; *(Veneer$$CMSE) ; uncomment for secure applications
.ANY (+RO)
.ANY (+XO)
}
RW_ITCM __ITCM_BASE __ITCM_SIZE { ; RW data
.ANY (+RW +ZI)
}
RW_DTCM __DTCM_BASE __DTCM_SIZE { ; RW data
.ANY (+RW +ZI)
}
RW_RAM1 __RAM1_BASE (__RAM1_SIZE - __STACK_SIZE - __HEAP_SIZE) { ; RW data
.ANY (+RW +ZI)
}
RW_RAM2 __RAM2_BASE __RAM2_SIZE { ; RW data
.ANY (+RW +ZI)
}
#if __HEAP_SIZE > 0
ARM_LIB_HEAP __HEAP_BASE EMPTY __HEAP_SIZE { ; Reserve empty region for heap
}
#endif
ARM_LIB_STACK __STACK_TOP EMPTY -__STACK_SIZE { ; Reserve empty region for stack
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 555 KiB

2489
bsp/mm32f526x/project.ewp Normal file

File diff suppressed because it is too large Load Diff

10
bsp/mm32f526x/project.eww Normal file
View File

@ -0,0 +1,10 @@
<?xml version="1.0" encoding="iso-8859-1"?>
<workspace>
<project>
<path>$WS_DIR$\project.ewp</path>
</project>
<batchBuild/>
</workspace>

View File

@ -0,0 +1,177 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_optx.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj; *.o</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc; *.md</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
<nMigrate>0</nMigrate>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>rtthread</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>12000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
<RunAbUc>0</RunAbUc>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\build\keil\List\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>255</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>1</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<bEvRecOn>1</bEvRecOn>
<bSchkAxf>0</bSchkAxf>
<bTchkAxf>0</bTchkAxf>
<nTsel>19</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>BIN\MM32LINKCM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 ) -FN1 -FC1000 -FD20000000 -FF0MM32F3270_512 -FL080000 -FS08000000 -FP0($$Device:MM32F3277G9P$Flash\MM32F3270_512.FLM)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>MM32LINKCM3</Key>
<Name>-U0028089 -O206 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC1000 -FN1 -FF0MM32L3xx_128.FLM -FS08000000 -FL020000 -FP0($$Device:MM32L373PF$Flash\MM32L3xx_128.FLM)</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
<bLintAuto>0</bLintAuto>
<bAutoGenD>0</bAutoGenD>
<LntExFlags>0</LntExFlags>
<pMisraName></pMisraName>
<pszMrule></pszMrule>
<pSingCmds></pSingCmds>
<pMultCmds></pMultCmds>
<pMisraNamep></pMisraNamep>
<pszMrulep></pszMrulep>
<pSingCmdsp></pSingCmdsp>
<pMultCmdsp></pMultCmdsp>
</TargetOption>
</Target>
</ProjectOpt>

File diff suppressed because it is too large Load Diff

409
bsp/mm32f526x/rtconfig.h Normal file
View File

@ -0,0 +1,409 @@
#ifndef RT_CONFIG_H__
#define RT_CONFIG_H__
/* RT-Thread Kernel */
/* klibc options */
/* rt_vsnprintf options */
/* end of rt_vsnprintf options */
/* rt_vsscanf options */
/* end of rt_vsscanf options */
/* rt_memset options */
/* end of rt_memset options */
/* rt_memcpy options */
/* end of rt_memcpy options */
/* rt_memmove options */
/* end of rt_memmove options */
/* rt_memcmp options */
/* end of rt_memcmp options */
/* rt_strstr options */
/* end of rt_strstr options */
/* rt_strcasecmp options */
/* end of rt_strcasecmp options */
/* rt_strncpy options */
/* end of rt_strncpy options */
/* rt_strcpy options */
/* end of rt_strcpy options */
/* rt_strncmp options */
/* end of rt_strncmp options */
/* rt_strcmp options */
/* end of rt_strcmp options */
/* rt_strlen options */
/* end of rt_strlen options */
/* rt_strnlen options */
/* end of rt_strnlen options */
/* end of klibc options */
#define RT_NAME_MAX 8
#define RT_CPUS_NR 1
#define RT_ALIGN_SIZE 8
#define RT_THREAD_PRIORITY_32
#define RT_THREAD_PRIORITY_MAX 32
#define RT_TICK_PER_SECOND 1000
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_HOOK
#define RT_HOOK_USING_FUNC_PTR
#define RT_USING_IDLE_HOOK
#define RT_IDLE_HOOK_LIST_SIZE 4
#define IDLE_THREAD_STACK_SIZE 512
#define RT_USING_TIMER_SOFT
#define RT_TIMER_THREAD_PRIO 4
#define RT_TIMER_THREAD_STACK_SIZE 512
/* kservice options */
/* end of kservice options */
#define RT_USING_DEBUG
#define RT_DEBUGING_ASSERT
#define RT_DEBUGING_COLOR
#define RT_DEBUGING_CONTEXT
/* Inter-Thread communication */
#define RT_USING_SEMAPHORE
#define RT_USING_MUTEX
#define RT_USING_EVENT
#define RT_USING_MAILBOX
#define RT_USING_MESSAGEQUEUE
/* end of Inter-Thread communication */
/* Memory Management */
#define RT_USING_MEMPOOL
#define RT_USING_SMALL_MEM
#define RT_USING_SMALL_MEM_AS_HEAP
#define RT_USING_HEAP
/* end of Memory Management */
#define RT_USING_DEVICE
#define RT_USING_CONSOLE
#define RT_CONSOLEBUF_SIZE 128
#define RT_CONSOLE_DEVICE_NAME "uart3"
#define RT_VER_NUM 0x50200
#define RT_BACKTRACE_LEVEL_MAX_NR 32
/* end of RT-Thread Kernel */
/* RT-Thread Components */
#define RT_USING_COMPONENTS_INIT
#define RT_USING_USER_MAIN
#define RT_MAIN_THREAD_STACK_SIZE 2048
#define RT_MAIN_THREAD_PRIORITY 10
#define RT_USING_MSH
#define RT_USING_FINSH
#define FINSH_USING_MSH
#define FINSH_THREAD_NAME "tshell"
#define FINSH_THREAD_PRIORITY 20
#define FINSH_THREAD_STACK_SIZE 4096
#define FINSH_USING_HISTORY
#define FINSH_HISTORY_LINES 5
#define FINSH_USING_SYMTAB
#define FINSH_CMD_SIZE 80
#define MSH_USING_BUILT_IN_COMMANDS
#define FINSH_USING_DESCRIPTION
#define FINSH_ARG_MAX 10
#define FINSH_USING_OPTION_COMPLETION
/* DFS: device virtual file system */
/* end of DFS: device virtual file system */
/* Device Drivers */
#define RT_USING_DEVICE_IPC
#define RT_UNAMED_PIPE_NUMBER 64
#define RT_USING_SERIAL
#define RT_USING_SERIAL_V1
#define RT_SERIAL_USING_DMA
#define RT_SERIAL_RB_BUFSZ 64
#define RT_USING_I2C
#define RT_USING_I2C_BITOPS
#define RT_USING_SOFT_I2C
#define RT_USING_SOFT_I2C1
#define RT_SOFT_I2C1_SCL_PIN 38
#define RT_SOFT_I2C1_SDA_PIN 39
#define RT_SOFT_I2C1_BUS_NAME "i2c1"
#define RT_SOFT_I2C1_TIMING_DELAY 10
#define RT_SOFT_I2C1_TIMING_TIMEOUT 10
#define RT_USING_ADC
#define RT_USING_PIN
/* end of Device Drivers */
/* C/C++ and POSIX layer */
/* ISO-ANSI C layer */
/* Timezone and Daylight Saving Time */
#define RT_LIBC_USING_LIGHT_TZ_DST
#define RT_LIBC_TZ_DEFAULT_HOUR 8
#define RT_LIBC_TZ_DEFAULT_MIN 0
#define RT_LIBC_TZ_DEFAULT_SEC 0
/* end of Timezone and Daylight Saving Time */
/* end of ISO-ANSI C layer */
/* POSIX (Portable Operating System Interface) layer */
/* Interprocess Communication (IPC) */
/* Socket is in the 'Network' category */
/* end of Interprocess Communication (IPC) */
/* end of POSIX (Portable Operating System Interface) layer */
/* end of C/C++ and POSIX layer */
/* Network */
/* end of Network */
/* Memory protection */
/* end of Memory protection */
/* Utilities */
/* end of Utilities */
/* Using USB legacy version */
/* end of Using USB legacy version */
/* end of RT-Thread Components */
/* RT-Thread Utestcases */
/* end of RT-Thread Utestcases */
/* RT-Thread online packages */
/* IoT - internet of things */
/* Wi-Fi */
/* Marvell WiFi */
/* end of Marvell WiFi */
/* Wiced WiFi */
/* end of Wiced WiFi */
/* CYW43012 WiFi */
/* end of CYW43012 WiFi */
/* BL808 WiFi */
/* end of BL808 WiFi */
/* CYW43439 WiFi */
/* end of CYW43439 WiFi */
/* end of Wi-Fi */
/* IoT Cloud */
/* end of IoT Cloud */
/* end of IoT - internet of things */
/* security packages */
/* end of security packages */
/* language packages */
/* JSON: JavaScript Object Notation, a lightweight data-interchange format */
/* end of JSON: JavaScript Object Notation, a lightweight data-interchange format */
/* XML: Extensible Markup Language */
/* end of XML: Extensible Markup Language */
/* end of language packages */
/* multimedia packages */
/* LVGL: powerful and easy-to-use embedded GUI library */
/* end of LVGL: powerful and easy-to-use embedded GUI library */
/* u8g2: a monochrome graphic library */
/* end of u8g2: a monochrome graphic library */
/* end of multimedia packages */
/* tools packages */
/* end of tools packages */
/* system packages */
/* enhanced kernel services */
/* end of enhanced kernel services */
/* acceleration: Assembly language or algorithmic acceleration packages */
/* end of acceleration: Assembly language or algorithmic acceleration packages */
/* CMSIS: ARM Cortex-M Microcontroller Software Interface Standard */
/* end of CMSIS: ARM Cortex-M Microcontroller Software Interface Standard */
/* Micrium: Micrium software products porting for RT-Thread */
/* end of Micrium: Micrium software products porting for RT-Thread */
/* end of system packages */
/* peripheral libraries and drivers */
/* HAL & SDK Drivers */
/* STM32 HAL & SDK Drivers */
/* end of STM32 HAL & SDK Drivers */
/* Infineon HAL Packages */
/* end of Infineon HAL Packages */
/* Kendryte SDK */
/* end of Kendryte SDK */
/* end of HAL & SDK Drivers */
/* sensors drivers */
/* end of sensors drivers */
/* touch drivers */
/* end of touch drivers */
#define PKG_USING_AT24CXX
#define PKG_USING_AT24CXX_LATEST_VERSION
#define PKG_AT24CXX_FINSH
#define PKG_USING_MM32
#define PKG_USING_MM32_LATEST_VERSION
/* end of peripheral libraries and drivers */
/* AI packages */
/* end of AI packages */
/* Signal Processing and Control Algorithm Packages */
/* end of Signal Processing and Control Algorithm Packages */
/* miscellaneous packages */
/* project laboratory */
/* end of project laboratory */
/* samples: kernel and components samples */
/* end of samples: kernel and components samples */
/* entertainment: terminal games and other interesting software packages */
/* end of entertainment: terminal games and other interesting software packages */
/* end of miscellaneous packages */
/* Arduino libraries */
/* Projects and Demos */
/* end of Projects and Demos */
/* Sensors */
/* end of Sensors */
/* Display */
/* end of Display */
/* Timing */
/* end of Timing */
/* Data Processing */
/* end of Data Processing */
/* Data Storage */
/* Communication */
/* end of Communication */
/* Device Control */
/* end of Device Control */
/* Other */
/* end of Other */
/* Signal IO */
/* end of Signal IO */
/* Uncategorized */
/* end of Arduino libraries */
/* end of RT-Thread online packages */
/* Hardware Drivers Config */
/* On-chip Peripheral Drivers */
/* GPIO Drivers */
#define BSP_USING_GPIO
/* end of GPIO Drivers */
/* UART Drivers */
#define BSP_USING_UART3
/* end of UART Drivers */
#define BSP_USING_ADC
#define BSP_USING_ADC1
/* Flash Drivers */
/* end of Flash Drivers */
/* end of On-chip Peripheral Drivers */
/* end of Hardware Drivers Config */
#define SOC_MM32F526x
#endif

144
bsp/mm32f526x/rtconfig.py Normal file
View File

@ -0,0 +1,144 @@
# BSP Note: For TI EK-TM4C1294XL Tiva C Series Connected LancuhPad (REV D)
import os
import sys
# toolchains options
CROSS_TOOL = 'gcc'
if os.getenv('RTT_CC'):
CROSS_TOOL = os.getenv('RTT_CC')
# device options
ARCH = 'arm'
CPU = 'cortex-m33'
# cross_tool provides the cross compiler
# EXEC_PATH is the compiler execute path, for example, CodeSourcery, Keil MDK, IAR
if CROSS_TOOL == 'gcc':
PLATFORM = 'gcc'
EXEC_PATH = r'C:\Users\XXYYZZ'
elif CROSS_TOOL == 'keil':
PLATFORM = 'armcc'
EXEC_PATH = 'C:/Keil_v5'
elif CROSS_TOOL == 'iar':
PLATFORM = 'iccarm'
EXEC_PATH = 'C:/Program Files (x86)/IAR Systems/Embedded Workbench 7.2'
if os.getenv('RTT_EXEC_PATH'):
EXEC_PATH = os.getenv('RTT_EXEC_PATH')
BUILD = 'debug'
#BUILD = 'release'
if PLATFORM == 'gcc':
# toolchains
PREFIX = 'arm-none-eabi-'
CC = PREFIX + 'gcc'
AS = PREFIX + 'gcc'
AR = PREFIX + 'ar'
CXX = PREFIX + 'g++'
LINK = PREFIX + 'gcc'
TARGET_EXT = 'elf'
SIZE = PREFIX + 'size'
OBJDUMP = PREFIX + 'objdump'
OBJCPY = PREFIX + 'objcopy'
DEVICE = ' -mcpu=cortex-m33 -mthumb -mfpu=fpv5-sp-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections'
CFLAGS = DEVICE + ' -Dgcc'
AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -Wa,-mimplicit-it=thumb '
LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=rt-thread.map,-cref,-u,Reset_Handler -T board/linker_scripts/link.lds'
CPATH = ''
LPATH = ''
if BUILD == 'debug':
CFLAGS += ' -O0 -gdwarf-2 -g'
AFLAGS += ' -gdwarf-2'
else:
CFLAGS += ' -O2'
CXXFLAGS = CFLAGS
POST_ACTION = OBJCPY + ' -O binary $TARGET rtthread.bin\n'
POST_ACTION += OBJCPY + ' -O ihex $TARGET rtthread.hex\n'
POST_ACTION += SIZE + ' $TARGET\n'
elif PLATFORM == 'armcc':
# toolchains
CC = 'armcc'
AS = 'armasm'
AR = 'armar'
LINK = 'armlink'
TARGET_EXT = 'axf'
DEVICE = ' --cpu ' + CPU
CFLAGS = '-c ' + DEVICE + ' --apcs=interwork --c99'
CFLAGS += ' -mfpu=fpv5-sp-d16 -mfloat-abi=hard '
AFLAGS = DEVICE + ' --apcs=interwork '
LFLAGS = DEVICE + ' --scatter "board/linker_scripts/link.sct" --info sizes --info totals --info unused --info veneers --list rtthread.map --strict'
CFLAGS += ' -I' + EXEC_PATH + '/ARM/ARMCC/INC'
LFLAGS += ' --libpath ' + EXEC_PATH + '/ARM/ARMCC/LIB'
CFLAGS += ' -D__MICROLIB '
AFLAGS += ' --pd "__MICROLIB SETA 1" '
LFLAGS += ' --library_type=microlib '
EXEC_PATH += '/arm/armcc/bin/'
if BUILD == 'debug':
CFLAGS += ' -g -O0'
AFLAGS += ' -g'
else:
CFLAGS += ' -O2'
POST_ACTION = 'fromelf --bin $TARGET --output rtthread.bin \nfromelf -z $TARGET'
elif PLATFORM == 'iccarm':
# toolchains
CC = 'iccarm'
AS = 'iasmarm'
AR = 'iarchive'
LINK = 'ilinkarm'
TARGET_EXT = 'out'
DEVICE = '-Dewarm' # + ' -D' + PART_TYPE
CFLAGS = DEVICE
CFLAGS += ' --diag_suppress Pa050'
CFLAGS += ' --no_cse'
CFLAGS += ' --no_unroll'
CFLAGS += ' --no_inline'
CFLAGS += ' --no_code_motion'
CFLAGS += ' --no_tbaa'
CFLAGS += ' --no_clustering'
CFLAGS += ' --no_scheduling'
CFLAGS += ' --endian=little'
CFLAGS += ' --cpu=Cortex-M33'
CFLAGS += ' -e'
CFLAGS += ' --fpu=VFPv4_sp'
CFLAGS += ' --dlib_config "' + EXEC_PATH + '/arm/INC/c/DLib_Config_Normal.h"'
CFLAGS += ' --silent'
AFLAGS = DEVICE
AFLAGS += ' -s+'
AFLAGS += ' -w+'
AFLAGS += ' -r'
AFLAGS += ' --cpu ' + CPU
AFLAGS += ' --fpu VFPv5_sp'
AFLAGS += ' -S'
if BUILD == 'debug':
CFLAGS += ' --debug'
CFLAGS += ' -On'
else:
CFLAGS += ' -Oh'
LFLAGS = ' --config "board/linker_scripts/link.icf"'
LFLAGS += ' --entry __iar_program_start'
#LFLAGS += ' --silent'
EXEC_PATH = EXEC_PATH + '/arm/bin/'
POST_ACTION = ''

2088
bsp/mm32f526x/template.ewp Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,10 @@
<?xml version="1.0" encoding="iso-8859-1"?>
<workspace>
<project>
<path>$WS_DIR$\template.ewp</path>
</project>
<batchBuild/>
</workspace>

View File

@ -0,0 +1,184 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_opt.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>rtthread</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>25000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>1</RunSim>
<RunTarget>0</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\build\keil\List\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>255</CpuCode>
<Books>
<Book>
<Number>0</Number>
<Title>Datasheet</Title>
<Path>DATASHTS\ST\STM32F4xx\DM00053488.pdf</Path>
</Book>
<Book>
<Number>1</Number>
<Title>Reference Manual</Title>
<Path>DATASHTS\ST\STM32F4xx\DM00031020.pdf</Path>
</Book>
<Book>
<Number>2</Number>
<Title>Technical Reference Manual</Title>
<Path>datashts\arm\cortex_m4\r0p1\DDI0439C_CORTEX_M4_R0P1_TRM.PDF</Path>
</Book>
<Book>
<Number>3</Number>
<Title>Generic User Guide</Title>
<Path>datashts\arm\cortex_m4\r0p1\DUI0553A_CORTEX_M4_DGUG.PDF</Path>
</Book>
</Books>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<tPdscDbg>0</tPdscDbg>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>6</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>Segger\JL2CM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>JL2CM3</Key>
<Name>-U20090928 -O207 -S0 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -TO18 -TC10000000 -TP21 -TDS8001 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC800 -FN1 -FF0STM32F4xx_1024 -FS08000000 -FL0100000</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-O207 -S0 -C0 -FO7 -FN1 -FC800 -FD20000000 -FF0STM32F4xx_1024 -FL0100000 -FS08000000</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
</ProjectOpt>

View File

@ -0,0 +1,177 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_optx.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj; *.o</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc; *.md</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
<nMigrate>0</nMigrate>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>rtthread</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>12000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
<RunAbUc>0</RunAbUc>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\build\keil\List\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>255</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>1</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<bEvRecOn>1</bEvRecOn>
<bSchkAxf>0</bSchkAxf>
<bTchkAxf>0</bTchkAxf>
<nTsel>19</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>BIN\MM32LINKCM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 ) -FN1 -FC1000 -FD20000000 -FF0MM32F3270_512 -FL080000 -FS08000000 -FP0($$Device:MM32F3277G9P$Flash\MM32F3270_512.FLM)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>MM32LINKCM3</Key>
<Name>-U0028089 -O206 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC1000 -FN1 -FF0MM32L3xx_128.FLM -FS08000000 -FL020000 -FP0($$Device:MM32L373PF$Flash\MM32L3xx_128.FLM)</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
<bLintAuto>0</bLintAuto>
<bAutoGenD>0</bAutoGenD>
<LntExFlags>0</LntExFlags>
<pMisraName></pMisraName>
<pszMrule></pszMrule>
<pSingCmds></pSingCmds>
<pMultCmds></pMultCmds>
<pMisraNamep></pMisraNamep>
<pszMrulep></pszMrulep>
<pSingCmdsp></pSingCmdsp>
<pMultCmdsp></pMultCmdsp>
</TargetOption>
</Target>
</ProjectOpt>

View File

@ -0,0 +1,391 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_projx.xsd">
<SchemaVersion>2.1</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Targets>
<Target>
<TargetName>rtthread</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5060960::V5.06 update 7 (build 960)::.\ARMCC</pCCUsed>
<uAC6>0</uAC6>
<TargetOption>
<TargetCommonOption>
<Device>MM32F3277G9P</Device>
<Vendor>MindMotion</Vendor>
<PackID>MindMotion.MM32F3270_DFP.1.0.4</PackID>
<PackURL>http://www.mindmotion.com.cn/Download/MDK_KEIL/</PackURL>
<Cpu>IRAM(0x20000000,0x20000) IROM(0x08000000,0x80000) CPUTYPE("Cortex-M3") CLOCK(12000000) ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile></StartupFile>
<FlashDriverDll>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0MM32F3270_512 -FS08000000 -FL080000 -FP0($$Device:MM32F3277G9P$Flash\MM32F3270_512.FLM))</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>$$Device:MM32F3277G9P$Device\MM32F327x\Include\mm32_device.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>$$Device:MM32F3277G9P$SVD\MM32F3270.svd</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath></RegisterFilePath>
<DBRegisterFilePath></DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\build\keil\Obj\</OutputDirectory>
<OutputName>rtthread</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>1</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>0</BrowseInformation>
<ListingPath>.\build\keil\List\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopB1X>0</nStopB1X>
<nStopB2X>0</nStopB2X>
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name>fromelf --bin !L --output rtthread.bin</UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
<nStopA2X>0</nStopA2X>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments> -REMAP</SimDllArguments>
<SimDlgDll>DCM.DLL</SimDlgDll>
<SimDlgDllArguments>-pCM3</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments></TargetDllArguments>
<TargetDlgDll>TCM.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM3</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4096</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>BIN\UL2CM3.DLL</Flash2>
<Flash3></Flash3>
<Flash4></Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M3"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<RvdsMve>0</RvdsMve>
<RvdsCdeCp>0</RvdsCdeCp>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<EndSel>0</EndSel>
<uLtcg>0</uLtcg>
<nSecure>0</nSecure>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>1</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>1</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x20000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x8000000</StartAddress>
<Size>0x80000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x8000000</StartAddress>
<Size>0x80000</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x20000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>1</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>1</OneElfS>
<Strict>0</Strict>
<EnumInt>0</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>0</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>1</uC99>
<uGnu>0</uGnu>
<useXO>0</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>0</vShortEn>
<vShortWch>0</vShortWch>
<v6Lto>0</v6Lto>
<v6WtE>0</v6WtE>
<v6Rtti>0</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define>USE_STDPERIPH_DRIVER</Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<ClangAsOpt>4</ClangAsOpt>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>0</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>1</RepFail>
<useFile>0</useFile>
<TextAddressRange>0x00000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\drivers\linker_scripts\link.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc></Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
</Target>
</Targets>
<RTE>
<apis/>
<components/>
<files/>
</RTE>
</Project>