diff --git a/build/envsetup.sh b/build/envsetup.sh index cad9db2..47c4dcc 100644 --- a/build/envsetup.sh +++ b/build/envsetup.sh @@ -15,3 +15,15 @@ if [ $? -ne 0 ]; then export PATH="$PATH:$TREMO_SDK_PATH/tools/toolchain/bin/" fi fi + +if [ `uname` = "Darwin" ];then + echo "your operation system is osx,please select your default device" + DEVICES=($(ls /dev/cu.*)) + echo $DEVICES + read index + export SERIAL_PORT=${DEVICES[index]} + echo $SERIAL_PORT +elif [ `uname` = "Linux" ];then + echo "your operation system is linux, default device is /dev/ttyUSB0 " +fi + diff --git a/build/make/common.mk b/build/make/common.mk index cd148db..a64c5a7 100644 --- a/build/make/common.mk +++ b/build/make/common.mk @@ -9,6 +9,8 @@ export HOST_ARCH := Cortex-M4F ifeq ($(shell uname), Linux) export EXECUTABLE_SUFFIX := +else ifeq ($(shell uname), Darwin) +export EXECUTABLE_SUFFIX := else export EXECUTABLE_SUFFIX := .exe endif @@ -67,10 +69,13 @@ $(foreach src,$(CXX_SOURCES),$(eval $(call BUILD_CXX_PROCESS,$(PROJECT),$(src))) # flash settings TREMO_LOADER := $(SCRIPTS_PATH)/tremo_loader.py + SERIAL_PORT ?= /dev/ttyUSB0 SERIAL_BAUDRATE ?= 921600 $(PROJECT)_ADDRESS ?= 0x08000000 + + ################################################################################################## ifeq ($(IDE),keil) all: keil_project diff --git a/build/make/gen_3rd_project.mk b/build/make/gen_3rd_project.mk index bdda3d0..120c724 100644 --- a/build/make/gen_3rd_project.mk +++ b/build/make/gen_3rd_project.mk @@ -5,10 +5,18 @@ keil_gen_script := $(SCRIPTS_PATH)/keil.py FILE_CREATE = $(file >$(1),$(2)) FILE_APPEND = $(file >>$(1),$(2)) -PATH_PREFIX := $(shell realpath $(TREMO_SDK_PATH) --relative-to=.)/ -SRC_PATH := $(foreach src, $($(PROJECT)_SOURCE),'$(addprefix $(PATH_PREFIX),$(shell realpath $(src) --relative-to=$(TREMO_SDK_PATH)))'$(comma)) -LIB_PATH := $(foreach lib, $($(PROJECT)_LIBS),'$(addprefix $(PATH_PREFIX),$(shell realpath $(lib) --relative-to=$(TREMO_SDK_PATH)))'$(comma)) -INC_PATH := $(foreach inc, $($(PROJECT)_INC_PATH),$(addprefix $(PATH_PREFIX),$(shell realpath $(inc) --relative-to=$(TREMO_SDK_PATH)))$(semi)) +RP := realpath + +ifeq ($(shell uname), Linux) +export RP := realpath +else ifeq ($(shell uname), Darwin) +export RP := grealpath +endif + +PATH_PREFIX := $(shell $(RP) $(TREMO_SDK_PATH) --relative-to=.)/ +SRC_PATH := $(foreach src, $($(PROJECT)_SOURCE),'$(addprefix $(PATH_PREFIX),$(shell $(RP) $(src) --relative-to=$(TREMO_SDK_PATH)))'$(comma)) +LIB_PATH := $(foreach lib, $($(PROJECT)_LIBS),'$(addprefix $(PATH_PREFIX),$(shell $(RP) $(lib) --relative-to=$(TREMO_SDK_PATH)))'$(comma)) +INC_PATH := $(foreach inc, $($(PROJECT)_INC_PATH),$(addprefix $(PATH_PREFIX),$(shell $(RP) $(inc) --relative-to=$(TREMO_SDK_PATH)))$(semi)) DEFINES := $(foreach dflags, $($(PROJECT)_DEFINES), $(dflags)$(comma)) ASMDEFINES := $(foreach adflags,$($(PROJECT)_AFLAGS),$(adflags)$(comma)) C_MiscControls := $($(PROJECT)_CFLAGS) diff --git a/build/scripts/tremo_loader.py b/build/scripts/tremo_loader.py index 5d927a2..f6af5ee 100644 --- a/build/scripts/tremo_loader.py +++ b/build/scripts/tremo_loader.py @@ -1,4 +1,5 @@ import argparse +import traceback import serial import os import sys @@ -226,6 +227,7 @@ def tremo_flash(args): # flash tremo = TremoLoader(args.port) + tremo.connect() tremo.set_baudrate(args.baud) for address, filename in download_files: @@ -339,6 +341,7 @@ def tremo_read_sn(args): sn = tremo_read_sn(args) print('The SN is: %s' % binascii.hexlify(sn)) except Exception as e: + traceback.print_exc() print(str(e)) diff --git a/platform/user/init.h b/platform/user/init.h new file mode 100644 index 0000000..02af898 --- /dev/null +++ b/platform/user/init.h @@ -0,0 +1,35 @@ +#ifndef __USER_INIT_H +#define __USER_INIT_H + + +#include + +#include "tremo_rcc.h" +#include "tremo_gpio.h" +#include "tremo_uart.h" +#include "tremo_regs.h" + +void uart_log_init(void) +{ + // uart0 + gpio_set_iomux(GPIOB, GPIO_PIN_0, 1); + gpio_set_iomux(GPIOB, GPIO_PIN_1, 1); + + /* uart config struct init */ + uart_config_t uart_config; + uart_config_init(&uart_config); + + uart_config.baudrate = UART_BAUDRATE_115200; + uart_init(CONFIG_DEBUG_UART, &uart_config); + uart_cmd(CONFIG_DEBUG_UART, ENABLE); +} + +void board_init(const rcc_peripheral_t *peripheral_array, size_t length) +{ + for (size_t i = 0; i < length; i++) + { + rcc_enable_peripheral_clk(peripheral_array[i], true); + } +} + +#endif \ No newline at end of file diff --git a/projects/ASR6601CB-EVAL/examples/lora/pingpong/src/main.c b/projects/ASR6601CB-EVAL/examples/lora/pingpong/src/main.c index 573303c..f855bac 100644 --- a/projects/ASR6601CB-EVAL/examples/lora/pingpong/src/main.c +++ b/projects/ASR6601CB-EVAL/examples/lora/pingpong/src/main.c @@ -53,7 +53,7 @@ int main(void) { // Target board initialization board_init(); - + printf("......"); app_start(); } diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/Makefile b/projects/ASR6601CB-EVAL/tutorial/dht11/Makefile new file mode 100644 index 0000000..df0ca0e --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/Makefile @@ -0,0 +1,35 @@ + +PROJECT := $(notdir $(CURDIR)) + +$(PROJECT)_SOURCE := $(wildcard src/*.c) \ + $(TREMO_SDK_PATH)/platform/system/printf-stdarg.c \ + $(TREMO_SDK_PATH)/platform/system/system_cm4.c \ + $(TREMO_SDK_PATH)/platform/system/startup_cm4.S \ + $(wildcard $(TREMO_SDK_PATH)/drivers/peripheral/src/*.c) + +$(PROJECT)_INC_PATH := inc \ + $(TREMO_SDK_PATH)/platform/CMSIS \ + $(TREMO_SDK_PATH)/platform/common \ + $(TREMO_SDK_PATH)/platform/system \ + $(TREMO_SDK_PATH)/platform/user \ + $(TREMO_SDK_PATH)/drivers/peripheral/inc + +$(PROJECT)_CFLAGS := -Wall -Os -ffunction-sections -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -fsingle-precision-constant -std=gnu99 -fno-builtin-printf -fno-builtin-sprintf -fno-builtin-snprintf +$(PROJECT)_DEFINES := -DCONFIG_DEBUG_UART=UART0 -DUSE_MODEM_LORA -DREGION_CN470 + +$(PROJECT)_LDFLAGS := -Wl,--gc-sections -Wl,--wrap=printf -Wl,--wrap=sprintf -Wl,--wrap=snprintf + +$(PROJECT)_LIBS := + +$(PROJECT)_LINK_LD := cfg/gcc.ld + +# please change the settings to download the app +#SERIAL_PORT := +#SERIAL_BAUDRATE := +#$(PROJECT)_ADDRESS := + +################################################################################################## +include $(TREMO_SDK_PATH)/build/make/common.mk + + + diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/gcc.ld b/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/gcc.ld new file mode 100644 index 0000000..5b328a7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/gcc.ld @@ -0,0 +1,156 @@ +/* +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20004000; /* end of RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_HEAP_SIZE = 0x0000; /* required amount of heap */ +_STACK_SIZE = 0x1000; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K +} + +/* Define output sections */ +SECTIONS +{ + +/* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT>FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /********************************************************************************* + * Heap + *********************************************************************************/ + .heap : + { + . = ALIGN(4); + _heap_bottom = . ; + end = _heap_bottom; + _end = end; + __end = end; + . += _HEAP_SIZE ; + _heap_top = .; + } >RAM + + /********************************************************************************* + * Stack + *********************************************************************************/ + .stack : + { + . = ALIGN(4); + _stack_bottom = . ; + . += _STACK_SIZE ; + _stack_top = .; + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/ram.ini b/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/ram.ini new file mode 100644 index 0000000..ccb5019 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/cfg/ram.ini @@ -0,0 +1,11 @@ +FUNC void Setup (void) { + SP = _RDWORD(0x08000000); // Setup Stack Pointer + PC = _RDWORD(0x08000004); // Setup Program Counter + _WDWORD(0xE000ED08, 0x08000000); // Setup Vector Table Offset Register +} + +load ./Objects/project.elf incremental + +Setup(); // Setup for Running + +g, main \ No newline at end of file diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/inc/dht11.h b/projects/ASR6601CB-EVAL/tutorial/dht11/inc/dht11.h new file mode 100644 index 0000000..20ef175 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/inc/dht11.h @@ -0,0 +1,14 @@ + +#ifndef __DHT11_DTH11_H +#define __DHT11_DTH11_H + + +#include "tremo_delay.h" + + + +void dht11_setup(uint8_t gpio_pin); + +void dht11_read(); + +#endif \ No newline at end of file diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/inc/tremo_it.h b/projects/ASR6601CB-EVAL/tutorial/dht11/inc/tremo_it.h new file mode 100644 index 0000000..63e10ab --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/inc/tremo_it.h @@ -0,0 +1,21 @@ +#ifndef __TREMO_IT_H +#define __TREMO_IT_H + +#ifdef __cplusplus +extern "C" { +#endif + +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void SVC_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __TREMO_IT_H */ diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/keil.bat b/projects/ASR6601CB-EVAL/tutorial/dht11/keil.bat new file mode 100644 index 0000000..43c3191 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/keil.bat @@ -0,0 +1 @@ +..\..\..\tools\keil\KeilProjectGen.exe ..\..\..\ .\utils\keil_config.ini project project diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/src/dht11.c b/projects/ASR6601CB-EVAL/tutorial/dht11/src/dht11.c new file mode 100644 index 0000000..dbb1cc9 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/src/dht11.c @@ -0,0 +1,165 @@ +#include +#include "dht11.h" +#include "tremo_gpio.h" + +unsigned char uchar_flag; +unsigned char uchar_temp; +unsigned char uchar_com_data; + +unsigned char ucharRH_data_H_temp; +unsigned char ucharRH_data_L_temp; +unsigned char ucharT_data_H_temp; +unsigned char ucharT_data_L_temp; +unsigned char ucharcheckdata_temp; + +unsigned char ucharRH_data_H; +unsigned char ucharRH_data_L; +unsigned char ucharT_data_H; +unsigned char ucharT_data_L; +unsigned char ucharcheckdata; + +float Humi, Temp; +uint8_t dht11_pin; + +void output_low() +{ + gpio_write(GPIOA, dht11_pin, GPIO_LEVEL_LOW); +} + +void output_high() +{ + gpio_write(GPIOA, dht11_pin, GPIO_LEVEL_HIGH); +} + +void input_initial() +{ + gpio_set_iomux(GPIOA, dht11_pin, 0); + // gpio_init(GPIOA, dht11_pin, GPIO_MODE_INPUT_FLOATING); + // gpio_init(GPIOA,dht11_pin,GPIO_MODE_INPUT_PULL_UP); + + // gpio_config_interrupt(GPIOA, dht11_pin, GPIO_INTR_RISING_FALLING_EDGE); +} + +gpio_level_t read_data() +{ + return gpio_read(GPIOA, dht11_pin); +} + +void COM() +{ + unsigned char i; + for (i = 0; i < 8; i++) + { + uchar_flag = 2; + // 等待IO口变低,变低后,通过延时去判断是0还是1 + while ((read_data() != GPIO_LEVEL_HIGH) && uchar_flag++) + { + delay_us(10); + } + delay_us(35); // 延时35us + uchar_temp = 0; + // 如果这个位是1,35us后,还是1,否则为0 + if (read_data() == GPIO_LEVEL_HIGH) + { + uchar_temp = 1; + } + uchar_flag = 2; + // 等待IO口变高,变高后,表示可以读取下一位 + while ((read_data() == GPIO_LEVEL_HIGH) && uchar_flag++) + { + delay_us(10); + } + if (uchar_flag == 1) + { + printf("COM first step over time\n"); + break; + } + uchar_com_data <<= 1; + uchar_com_data |= uchar_temp; + } + printf("COM first step uchar_com_data = %x\n", uchar_com_data); +} + +void dht11_setup(uint8_t gpio_pin) +{ + printf("读取程序开始\n"); + dht11_pin = gpio_pin; + gpio_init(GPIOA,dht11_pin,GPIO_MODE_OUTPUT_PP_LOW); + output_low(); + delay_ms(20); + printf("主机拉低电平20ms\n"); + output_high(); + delay_us(30); + printf("主机拉高电平30um\n"); + input_initial(); +} + +void dht11_reset(){ + printf("发送复位信号\n"); + //设置为输出低电平 + gpio_init(GPIOA,dht11_pin,GPIO_MODE_OUTPUT_PP_LOW); + output_low(); + delay_ms(20); + printf("主机拉低电平20ms\n"); + //设置为输出高电平 + output_high(); + delay_us(30); + printf("主机拉高电平30um\n"); + //设置为输入模式 + input_initial(); +} + +void dht11_read() +{ + printf("读取DHT11响应\n"); + if (read_data() != GPIO_LEVEL_LOW) + { + printf("%s\n", "read data failed!"); + return; + } + uchar_flag = 2; + // 判断从机是否发出 80us 的低电平响应信号是否结束 + printf("现在是低电平,等待从机拉高--%d\n",read_data()); + while ((read_data() == GPIO_LEVEL_LOW) && uchar_flag++) + { + delay_us(10); + } + uchar_flag = 2; + printf("现在是高电平,等待从机拉低--%d\n",read_data()); + // 判断从机是否发出 80us 的高电平,如发出则进入数据接收状态 + while ((read_data() == GPIO_LEVEL_HIGH) && uchar_flag++) + { + printf("wait for low %d\n",uchar_flag); + delay_us(30); + } + COM(); // 读取第1字节, + ucharRH_data_H_temp = uchar_com_data; + printf("读取第一位:%x\n", uchar_com_data); + COM(); // 读取第2字节, + ucharRH_data_L_temp = uchar_com_data; + COM(); // 读取第3字节, + ucharT_data_H_temp = uchar_com_data; + COM(); // 读取第4字节, + ucharT_data_L_temp = uchar_com_data; + COM(); // 读取第5字节, + ucharcheckdata_temp = uchar_com_data; + output_high(); + // 判断校验和是否一致 + uchar_temp = (ucharT_data_H_temp + ucharT_data_L_temp + ucharRH_data_H_temp + ucharRH_data_L_temp); + if (uchar_temp == ucharcheckdata_temp) + { + // 校验和一致, + ucharRH_data_H = ucharRH_data_H_temp; + ucharRH_data_L = ucharRH_data_L_temp; + ucharT_data_H = ucharT_data_H_temp; + ucharT_data_L = ucharT_data_L_temp; + ucharcheckdata = ucharcheckdata_temp; + // 保存温度和湿度 + Humi = ucharRH_data_H; + Humi = ((unsigned short)Humi << 8 | ucharRH_data_L) / 10; + + Temp = ucharT_data_H; + Temp = ((unsigned short)Temp << 8 | ucharT_data_L) / 10; + printf("1=%f,2=%f\n", Humi, Temp); + } +} diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/src/main.c b/projects/ASR6601CB-EVAL/tutorial/dht11/src/main.c new file mode 100644 index 0000000..3ebfa8c --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/src/main.c @@ -0,0 +1,43 @@ +#include +#include "dht11.h" +#include "init.h" + +#define DTH11_PIN GPIO_PIN_6 + +void setup_board() +{ + const rcc_peripheral_t peripheral_array[] = { + RCC_PERIPHERAL_UART0, + RCC_PERIPHERAL_GPIOA, + RCC_PERIPHERAL_GPIOB}; + board_init(peripheral_array, sizeof(peripheral_array) / sizeof(rcc_peripheral_t)); + +} + +int main(void) +{ + setup_board(); + gpio_set_iomux(GPIOA,DTH11_PIN,0); + gpio_write(GPIOA,DTH11_PIN,GPIO_LEVEL_HIGH); + uart_log_init(); + delay_init(); + + printf("start read temp and hum\n"); + delay_ms(1000*5); + + while (1) { + dht11_setup(DTH11_PIN); + dht11_read(); + delay_ms(1000*20); + } +} + +#ifdef USE_FULL_ASSERT +void assert_failed(void* file, uint32_t line) +{ + (void)file; + (void)line; + + while (1) { } +} +#endif diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/src/tremo_it.c b/projects/ASR6601CB-EVAL/tutorial/dht11/src/tremo_it.c new file mode 100644 index 0000000..026cdd7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/src/tremo_it.c @@ -0,0 +1,116 @@ + +#include "tremo_it.h" + + + + +/** + * @brief This function handles NMI exception. + * @param None + * @retval None + */ +void NMI_Handler(void) +{ +} + +/** + * @brief This function handles Hard Fault exception. + * @param None + * @retval None + */ +void HardFault_Handler(void) +{ + + /* Go to infinite loop when Hard Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Memory Manage exception. + * @param None + * @retval None + */ +void MemManage_Handler(void) +{ + /* Go to infinite loop when Memory Manage exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Bus Fault exception. + * @param None + * @retval None + */ +void BusFault_Handler(void) +{ + /* Go to infinite loop when Bus Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Usage Fault exception. + * @param None + * @retval None + */ +void UsageFault_Handler(void) +{ + /* Go to infinite loop when Usage Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles SVCall exception. + * @param None + * @retval None + */ +void SVC_Handler(void) +{ +} + +/** + * @brief This function handles PendSVC exception. + * @param None + * @retval None + */ +void PendSV_Handler(void) +{ +} + +/** + * @brief This function handles SysTick Handler. + * @param None + * @retval None + */ +void SysTick_Handler(void) +{ +} + +/** + * @brief This function handles PWR Handler. + * @param None + * @retval None + */ +void PWR_IRQHandler() +{ +} + +/******************************************************************************/ +/* Tremo Peripherals Interrupt Handlers */ +/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */ +/* available peripheral interrupt handler's name please refer to the startup */ +/* file (startup_cm4.S). */ +/******************************************************************************/ + +/** + * @brief This function handles PPP interrupt request. + * @param None + * @retval None + */ +/*void PPP_IRQHandler(void) +{ +}*/ + diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/utils/genbinary.bat b/projects/ASR6601CB-EVAL/tutorial/dht11/utils/genbinary.bat new file mode 100644 index 0000000..efa3465 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/utils/genbinary.bat @@ -0,0 +1 @@ +..\..\..\tools\hex2bin\hex2bin.exe .\Objects\project.hex diff --git a/projects/ASR6601CB-EVAL/tutorial/dht11/utils/keil_config.ini b/projects/ASR6601CB-EVAL/tutorial/dht11/utils/keil_config.ini new file mode 100644 index 0000000..11add75 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/dht11/utils/keil_config.ini @@ -0,0 +1,18 @@ +[settings] +src='../../../projects/ASR6601CB-EVAL/template/src/main.c', '../../../projects/ASR6601CB-EVAL/template/src/tremo_it.c', '../../../platform/system/system_cm4.c', '../../../platform/system/startup_cm4.S', '../../../drivers/peripheral/src/tremo_adc.c', '../../../drivers/peripheral/src/tremo_bstimer.c', '../../../drivers/peripheral/src/tremo_crc.c', '../../../drivers/peripheral/src/tremo_dac.c', '../../../drivers/peripheral/src/tremo_delay.c', '../../../drivers/peripheral/src/tremo_dma.c', '../../../drivers/peripheral/src/tremo_flash.c', '../../../drivers/peripheral/src/tremo_gpio.c', '../../../drivers/peripheral/src/tremo_i2c.c', '../../../drivers/peripheral/src/tremo_i2s.c', '../../../drivers/peripheral/src/tremo_iwdg.c', '../../../drivers/peripheral/src/tremo_lcd.c', '../../../drivers/peripheral/src/tremo_lptimer.c', '../../../drivers/peripheral/src/tremo_lpuart.c', '../../../drivers/peripheral/src/tremo_pwr.c', '../../../drivers/peripheral/src/tremo_rcc.c', '../../../drivers/peripheral/src/tremo_rtc.c', '../../../drivers/peripheral/src/tremo_spi.c', '../../../drivers/peripheral/src/tremo_system.c', '../../../drivers/peripheral/src/tremo_timer.c', '../../../drivers/peripheral/src/tremo_uart.c', '../../../drivers/peripheral/src/tremo_wdg.c', +lib= +include_path='../../../projects/ASR6601CB-EVAL/template/inc; ../../../platform/CMSIS; ../../../platform/common; ../../../platform/system; ../../../drivers/peripheral/inc;' +defines='' +adefines='' +cMisc='-Wall -Os -ffunction-sections -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -fsingle-precision-constant -std=gnu99 -fno-builtin-printf -fno-builtin-sprintf -fno-builtin-snprintf' +aMisc='' +host_arch='Cortex-M4' +ld_files='./cfg/gcc.ld' +ini_files='./cfg/ram.ini' +ld_misc='-Wl,--gc-sections -Wl,--wrap=printf -Wl,--wrap=sprintf -Wl,--wrap=snprintf' +runuser1='1' +runuser2='0' +runuser1_pro='./utils/genbinary.bat' +runuser2_pro='' +createLib='0' +createexe='1' diff --git a/projects/ASR6601CB-EVAL/tutorial/light/Makefile b/projects/ASR6601CB-EVAL/tutorial/light/Makefile new file mode 100644 index 0000000..7bd13a3 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/Makefile @@ -0,0 +1,35 @@ + +PROJECT := $(notdir $(CURDIR)) + +$(PROJECT)_SOURCE := $(wildcard src/*.c) \ + $(TREMO_SDK_PATH)/platform/system/printf-stdarg.c \ + $(TREMO_SDK_PATH)/platform/system/system_cm4.c \ + $(TREMO_SDK_PATH)/platform/system/startup_cm4.S \ + $(wildcard $(TREMO_SDK_PATH)/drivers/peripheral/src/*.c) + +$(PROJECT)_INC_PATH := inc \ + $(TREMO_SDK_PATH)/platform/CMSIS \ + $(TREMO_SDK_PATH)/platform/common \ + $(TREMO_SDK_PATH)/platform/system \ + $(TREMO_SDK_PATH)/platform/user \ + $(TREMO_SDK_PATH)/drivers/peripheral/inc + +$(PROJECT)_CFLAGS := -Wall -Os -ffunction-sections -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -fsingle-precision-constant -std=gnu99 -fno-builtin-printf -fno-builtin-sprintf -fno-builtin-snprintf +$(PROJECT)_DEFINES := -DCONFIG_DEBUG_UART=UART0 -DUSE_MODEM_LORA -DREGION_CN470 + +$(PROJECT)_LDFLAGS := -Wl,--gc-sections -Wl,--wrap=printf -Wl,--wrap=sprintf -Wl,--wrap=snprintf + +$(PROJECT)_LIBS := + +$(PROJECT)_LINK_LD := cfg/gcc.ld + +# please change the settings to download the app +#SERIAL_PORT := +#SERIAL_BAUDRATE := +#$(PROJECT)_ADDRESS := + +################################################################################################## +include $(TREMO_SDK_PATH)/build/make/common.mk + + + diff --git a/projects/ASR6601CB-EVAL/tutorial/light/cfg/gcc.ld b/projects/ASR6601CB-EVAL/tutorial/light/cfg/gcc.ld new file mode 100644 index 0000000..5b328a7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/cfg/gcc.ld @@ -0,0 +1,156 @@ +/* +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20004000; /* end of RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_HEAP_SIZE = 0x0000; /* required amount of heap */ +_STACK_SIZE = 0x1000; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K +} + +/* Define output sections */ +SECTIONS +{ + +/* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT>FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /********************************************************************************* + * Heap + *********************************************************************************/ + .heap : + { + . = ALIGN(4); + _heap_bottom = . ; + end = _heap_bottom; + _end = end; + __end = end; + . += _HEAP_SIZE ; + _heap_top = .; + } >RAM + + /********************************************************************************* + * Stack + *********************************************************************************/ + .stack : + { + . = ALIGN(4); + _stack_bottom = . ; + . += _STACK_SIZE ; + _stack_top = .; + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/projects/ASR6601CB-EVAL/tutorial/light/cfg/ram.ini b/projects/ASR6601CB-EVAL/tutorial/light/cfg/ram.ini new file mode 100644 index 0000000..ccb5019 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/cfg/ram.ini @@ -0,0 +1,11 @@ +FUNC void Setup (void) { + SP = _RDWORD(0x08000000); // Setup Stack Pointer + PC = _RDWORD(0x08000004); // Setup Program Counter + _WDWORD(0xE000ED08, 0x08000000); // Setup Vector Table Offset Register +} + +load ./Objects/project.elf incremental + +Setup(); // Setup for Running + +g, main \ No newline at end of file diff --git a/projects/ASR6601CB-EVAL/tutorial/light/inc/tremo_it.h b/projects/ASR6601CB-EVAL/tutorial/light/inc/tremo_it.h new file mode 100644 index 0000000..63e10ab --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/inc/tremo_it.h @@ -0,0 +1,21 @@ +#ifndef __TREMO_IT_H +#define __TREMO_IT_H + +#ifdef __cplusplus +extern "C" { +#endif + +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void SVC_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __TREMO_IT_H */ diff --git a/projects/ASR6601CB-EVAL/tutorial/light/src/main.c b/projects/ASR6601CB-EVAL/tutorial/light/src/main.c new file mode 100644 index 0000000..21e5173 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/src/main.c @@ -0,0 +1,77 @@ +#include + +#include "init.h" +#include "tremo_delay.h" + +#define LIGHT_WARM GPIO_PIN_15 +#define LIGHT_COLD GPIO_PIN_14 + +/** + * @brief Setup the board,enable GPIO + */ +void setup_board() +{ + const rcc_peripheral_t peripheral_array[] = { + RCC_PERIPHERAL_UART0, + RCC_PERIPHERAL_GPIOA, + RCC_PERIPHERAL_GPIOB}; + board_init(peripheral_array, sizeof(peripheral_array) / sizeof(rcc_peripheral_t)); +} + +/** + * @brief Setup the warm and colde light,which will off + * + */ +void setup_light() +{ + gpio_init(GPIOA, LIGHT_COLD, GPIO_MODE_OUTPUT_PP_LOW); + gpio_init(GPIOA, LIGHT_WARM, GPIO_MODE_OUTPUT_PP_LOW); +} + +/** + * @brief turn warm light on + * + */ +void turn_warm_light_on() +{ + gpio_write(GPIOA, LIGHT_COLD, GPIO_LEVEL_LOW); + gpio_write(GPIOA, LIGHT_WARM, GPIO_LEVEL_HIGH); +} + +/** + * @brief turn cold light on + * + */ +void turn_cold_light_on() +{ + gpio_write(GPIOA, LIGHT_COLD, GPIO_LEVEL_HIGH); + gpio_write(GPIOA, LIGHT_WARM, GPIO_LEVEL_LOW); +} + +int main(void) +{ + setup_board(); + uart_log_init(); + printf("start test light\n"); + setup_light(); + //loop , cold and warm light on or off + while (1) + { + turn_cold_light_on(); + delay_ms(1000); + turn_warm_light_on(); + delay_ms(1000); + } +} + +#ifdef USE_FULL_ASSERT +void assert_failed(void *file, uint32_t line) +{ + (void)file; + (void)line; + + while (1) + { + } +} +#endif diff --git a/projects/ASR6601CB-EVAL/tutorial/light/src/tremo_it.c b/projects/ASR6601CB-EVAL/tutorial/light/src/tremo_it.c new file mode 100644 index 0000000..026cdd7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/light/src/tremo_it.c @@ -0,0 +1,116 @@ + +#include "tremo_it.h" + + + + +/** + * @brief This function handles NMI exception. + * @param None + * @retval None + */ +void NMI_Handler(void) +{ +} + +/** + * @brief This function handles Hard Fault exception. + * @param None + * @retval None + */ +void HardFault_Handler(void) +{ + + /* Go to infinite loop when Hard Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Memory Manage exception. + * @param None + * @retval None + */ +void MemManage_Handler(void) +{ + /* Go to infinite loop when Memory Manage exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Bus Fault exception. + * @param None + * @retval None + */ +void BusFault_Handler(void) +{ + /* Go to infinite loop when Bus Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Usage Fault exception. + * @param None + * @retval None + */ +void UsageFault_Handler(void) +{ + /* Go to infinite loop when Usage Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles SVCall exception. + * @param None + * @retval None + */ +void SVC_Handler(void) +{ +} + +/** + * @brief This function handles PendSVC exception. + * @param None + * @retval None + */ +void PendSV_Handler(void) +{ +} + +/** + * @brief This function handles SysTick Handler. + * @param None + * @retval None + */ +void SysTick_Handler(void) +{ +} + +/** + * @brief This function handles PWR Handler. + * @param None + * @retval None + */ +void PWR_IRQHandler() +{ +} + +/******************************************************************************/ +/* Tremo Peripherals Interrupt Handlers */ +/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */ +/* available peripheral interrupt handler's name please refer to the startup */ +/* file (startup_cm4.S). */ +/******************************************************************************/ + +/** + * @brief This function handles PPP interrupt request. + * @param None + * @retval None + */ +/*void PPP_IRQHandler(void) +{ +}*/ + diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/Makefile b/projects/ASR6601CB-EVAL/tutorial/uart/Makefile new file mode 100644 index 0000000..afb3f7b --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/Makefile @@ -0,0 +1,34 @@ + +PROJECT := $(notdir $(CURDIR)) + +$(PROJECT)_SOURCE := $(wildcard src/*.c) \ + $(TREMO_SDK_PATH)/platform/system/printf-stdarg.c \ + $(TREMO_SDK_PATH)/platform/system/system_cm4.c \ + $(TREMO_SDK_PATH)/platform/system/startup_cm4.S \ + $(wildcard $(TREMO_SDK_PATH)/drivers/peripheral/src/*.c) + +$(PROJECT)_INC_PATH := inc \ + $(TREMO_SDK_PATH)/platform/CMSIS \ + $(TREMO_SDK_PATH)/platform/common \ + $(TREMO_SDK_PATH)/platform/system \ + $(TREMO_SDK_PATH)/drivers/peripheral/inc + +$(PROJECT)_CFLAGS := -Wall -Os -ffunction-sections -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -fsingle-precision-constant -std=gnu99 -fno-builtin-printf -fno-builtin-sprintf -fno-builtin-snprintf +$(PROJECT)_DEFINES := -DCONFIG_DEBUG_UART=UART0 -DUSE_MODEM_LORA -DREGION_CN470 + +$(PROJECT)_LDFLAGS := -Wl,--gc-sections -Wl,--wrap=printf -Wl,--wrap=sprintf -Wl,--wrap=snprintf + +$(PROJECT)_LIBS := + +$(PROJECT)_LINK_LD := cfg/gcc.ld + +# please change the settings to download the app +#SERIAL_PORT := +#SERIAL_BAUDRATE := +#$(PROJECT)_ADDRESS := + +################################################################################################## +include $(TREMO_SDK_PATH)/build/make/common.mk + + + diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/cfg/gcc.ld b/projects/ASR6601CB-EVAL/tutorial/uart/cfg/gcc.ld new file mode 100644 index 0000000..5b328a7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/cfg/gcc.ld @@ -0,0 +1,156 @@ +/* +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20004000; /* end of RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_HEAP_SIZE = 0x0000; /* required amount of heap */ +_STACK_SIZE = 0x1000; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K +} + +/* Define output sections */ +SECTIONS +{ + +/* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT>FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /********************************************************************************* + * Heap + *********************************************************************************/ + .heap : + { + . = ALIGN(4); + _heap_bottom = . ; + end = _heap_bottom; + _end = end; + __end = end; + . += _HEAP_SIZE ; + _heap_top = .; + } >RAM + + /********************************************************************************* + * Stack + *********************************************************************************/ + .stack : + { + . = ALIGN(4); + _stack_bottom = . ; + . += _STACK_SIZE ; + _stack_top = .; + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/cfg/ram.ini b/projects/ASR6601CB-EVAL/tutorial/uart/cfg/ram.ini new file mode 100644 index 0000000..ccb5019 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/cfg/ram.ini @@ -0,0 +1,11 @@ +FUNC void Setup (void) { + SP = _RDWORD(0x08000000); // Setup Stack Pointer + PC = _RDWORD(0x08000004); // Setup Program Counter + _WDWORD(0xE000ED08, 0x08000000); // Setup Vector Table Offset Register +} + +load ./Objects/project.elf incremental + +Setup(); // Setup for Running + +g, main \ No newline at end of file diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/inc/tremo_it.h b/projects/ASR6601CB-EVAL/tutorial/uart/inc/tremo_it.h new file mode 100644 index 0000000..63e10ab --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/inc/tremo_it.h @@ -0,0 +1,21 @@ +#ifndef __TREMO_IT_H +#define __TREMO_IT_H + +#ifdef __cplusplus +extern "C" { +#endif + +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void SVC_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __TREMO_IT_H */ diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/src/main.c b/projects/ASR6601CB-EVAL/tutorial/uart/src/main.c new file mode 100644 index 0000000..4e3cb5b --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/src/main.c @@ -0,0 +1,48 @@ +#include + +#include "init.h" +#include "tremo_delay.h" + + +/** + * @brief Setup the board,enable GPIO + */ +void setup_board() +{ + const rcc_peripheral_t peripheral_array[] = { + RCC_PERIPHERAL_UART2, + RCC_PERIPHERAL_GPIOA, + RCC_PERIPHERAL_GPIOB + }; + board_init(peripheral_array, sizeof(peripheral_array) / sizeof(rcc_peripheral_t)); +} + + + +int main(void) +{ + setup_board(); + uart_log_init(); + printf("start test light\n"); + uart_send_data(UART2,0x01); + uart_send_data(UART2,0x01); + uart_send_data(UART2,0x01); + uart_send_data(UART2,0x01); + while (1) + { + uint8_t rec = uart_receive_data(UART2); + printf("receive data %d",rec); + } +} + +#ifdef USE_FULL_ASSERT +void assert_failed(void *file, uint32_t line) +{ + (void)file; + (void)line; + + while (1) + { + } +} +#endif diff --git a/projects/ASR6601CB-EVAL/tutorial/uart/src/tremo_it.c b/projects/ASR6601CB-EVAL/tutorial/uart/src/tremo_it.c new file mode 100644 index 0000000..026cdd7 --- /dev/null +++ b/projects/ASR6601CB-EVAL/tutorial/uart/src/tremo_it.c @@ -0,0 +1,116 @@ + +#include "tremo_it.h" + + + + +/** + * @brief This function handles NMI exception. + * @param None + * @retval None + */ +void NMI_Handler(void) +{ +} + +/** + * @brief This function handles Hard Fault exception. + * @param None + * @retval None + */ +void HardFault_Handler(void) +{ + + /* Go to infinite loop when Hard Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Memory Manage exception. + * @param None + * @retval None + */ +void MemManage_Handler(void) +{ + /* Go to infinite loop when Memory Manage exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Bus Fault exception. + * @param None + * @retval None + */ +void BusFault_Handler(void) +{ + /* Go to infinite loop when Bus Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles Usage Fault exception. + * @param None + * @retval None + */ +void UsageFault_Handler(void) +{ + /* Go to infinite loop when Usage Fault exception occurs */ + while(1){ + } +} + +/** + * @brief This function handles SVCall exception. + * @param None + * @retval None + */ +void SVC_Handler(void) +{ +} + +/** + * @brief This function handles PendSVC exception. + * @param None + * @retval None + */ +void PendSV_Handler(void) +{ +} + +/** + * @brief This function handles SysTick Handler. + * @param None + * @retval None + */ +void SysTick_Handler(void) +{ +} + +/** + * @brief This function handles PWR Handler. + * @param None + * @retval None + */ +void PWR_IRQHandler() +{ +} + +/******************************************************************************/ +/* Tremo Peripherals Interrupt Handlers */ +/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */ +/* available peripheral interrupt handler's name please refer to the startup */ +/* file (startup_cm4.S). */ +/******************************************************************************/ + +/** + * @brief This function handles PPP interrupt request. + * @param None + * @retval None + */ +/*void PPP_IRQHandler(void) +{ +}*/ + diff --git a/readme.md b/readme.md index 8a927a5..30300a4 100644 --- a/readme.md +++ b/readme.md @@ -10,7 +10,7 @@ Ra-08(H) 模组出厂内置 AT 固件程序,直接上手使用对接LoRaWAN网 # 1.目的 本文基于 linux 环境,介绍安信可 Ra-08(H) 模组二次开发点对点通讯的具体流程,供读者参考。 - + > macos可编译 # 2.硬件准备 - **linux 环境** 用来编译 & 烧写 & 运行等操作的必须环境,本文以 (Ubuntu18.04) 为例。 @@ -119,3 +119,26 @@ Sent: PONG Received: PING Sent: PONG ``` + + +# 7. mac编译 + +### 7.1 安装arm-none-eabi-gcc + +首先需要cloneArmMbed仓库,在命令行中执行 +```bash +brew tap ArmMbed/homebrew-formulae +``` +然后安装arm-none-eabi-gcc编译链 +```bash +brew install arm-none-eabi-gcc +``` + +### 7.2 安装coreutils +构建工程makefile中使用了`relativepath`命令,macos中并不支持完整的该命令,需要安装`coreutils` + +```bash +brew install coreutils +``` + +后续步骤可参考4、5、6 \ No newline at end of file