diff --git a/.gitignore b/.gitignore
index 2d9960b..d2fe1a1 100644
--- a/.gitignore
+++ b/.gitignore
@@ -19,3 +19,4 @@ quest_info.txt
*.jwt
bootcode.txt
*.uvoptx
+build/
diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index f89ebfd..2da9afd 100644
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -4,19 +4,19 @@
"name": "stm32",
"includePath": [
"${workspaceFolder}/**",
- "${workspaceFolder}/source/soft",
- "D:\\Keil_v5\\ARM\\ARMCC\\include"
+ "${workspaceFolder}/source/**",
+ "D:/GNU Arm Embedded Toolchain/10 2021.10/arm-none-eabi/include"
],
"defines": [
"STM32F40_41xxx",
"USE_STDPERIPH_DRIVER",
"RT_THREAD",
- "__CC_ARM",
- "__packed= "
+ "STM32F10X_MD"
],
"cStandard": "c99",
"cppStandard": "gnu++17",
- "intelliSenseMode": "windows-gcc-x64"
+ "intelliSenseMode": "windows-gcc-arm",
+ "compilerPath": "D:\\GNU Arm Embedded Toolchain\\10 2021.10\\bin\\arm-none-eabi-gcc"
}
],
"version": 4
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 0d25f08..5aa2e51 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -3,6 +3,7 @@
"stm32f4xx.h": "c",
"signal.h": "c",
"dev_flash.h": "c",
- "opt.h": "c"
+ "opt.h": "c",
+ "if_can.h": "c"
}
}
\ No newline at end of file
diff --git a/Makefile b/Makefile
new file mode 100644
index 0000000..dc54142
--- /dev/null
+++ b/Makefile
@@ -0,0 +1,220 @@
+##########################################################################################################################
+# File automatically-generated by tool: [projectgenerator] version: [3.17.1] date: [Tue Oct 31 22:08:45 CST 2023]
+##########################################################################################################################
+
+# ------------------------------------------------
+# Generic Makefile (based on gcc)
+#
+# ChangeLog :
+# 2017-02-10 - Several enhancements + project update mode
+# 2015-07-22 - first version
+# ------------------------------------------------
+
+######################################
+# target
+######################################
+TARGET = checker_slave_boot
+
+
+######################################
+# building variables
+######################################
+# debug build?
+DEBUG = 1
+# optimization
+OPT = -Og
+
+
+#######################################
+# paths
+#######################################
+# Build path
+BUILD_DIR = build
+
+######################################
+# source
+######################################
+# C sources
+C_SOURCES = \
+source/main/main.c \
+source/core/core_cm3.c \
+source/core/system_stm32f10x.c \
+source/stm32lib/src/misc.c \
+source/stm32lib/src/stm32f10x_adc.c \
+source/stm32lib/src/stm32f10x_bkp.c \
+source/stm32lib/src/stm32f10x_can.c \
+source/stm32lib/src/stm32f10x_cec.c \
+source/stm32lib/src/stm32f10x_crc.c \
+source/stm32lib/src/stm32f10x_dac.c \
+source/stm32lib/src/stm32f10x_dbgmcu.c \
+source/stm32lib/src/stm32f10x_dma.c \
+source/stm32lib/src/stm32f10x_exti.c \
+source/stm32lib/src/stm32f10x_flash.c \
+source/stm32lib/src/stm32f10x_fsmc.c \
+source/stm32lib/src/stm32f10x_gpio.c \
+source/stm32lib/src/stm32f10x_i2c.c \
+source/stm32lib/src/stm32f10x_iwdg.c \
+source/stm32lib/src/stm32f10x_pwr.c \
+source/stm32lib/src/stm32f10x_rcc.c \
+source/stm32lib/src/stm32f10x_rtc.c \
+source/stm32lib/src/stm32f10x_sdio.c \
+source/stm32lib/src/stm32f10x_spi.c \
+source/stm32lib/src/stm32f10x_tim.c \
+source/stm32lib/src/stm32f10x_usart.c \
+source/stm32lib/src/stm32f10x_wwdg.c \
+source/interface/if_rtt.c \
+source/interface/if_gpioout.c \
+source/dev/dev_flash.c \
+source/dev/dev_backup.c \
+source/dev/dev_watchdog.c \
+source/rtt/SEGGER_RTT.c \
+source/rtt/SEGGER_RTT_printf.c \
+source/rt_thread/board.c \
+source/rt_thread/core_delay.c \
+source/soft/buff.c \
+source/soft/debug.c \
+source/soft/crc.c \
+
+
+
+# ASM sources
+ASM_SOURCES = \
+source/core/startup_stm32f103xe.s \
+source/core/cortex_m4_gcc.s \
+
+
+#######################################
+# binaries
+#######################################
+PREFIX = arm-none-eabi-
+# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
+# either it can be added to the PATH environment variable.
+ifdef GCC_PATH
+CC = $(GCC_PATH)/$(PREFIX)gcc
+AS = $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
+CP = $(GCC_PATH)/$(PREFIX)objcopy
+SZ = $(GCC_PATH)/$(PREFIX)size
+else
+CC = $(PREFIX)gcc
+AS = $(PREFIX)gcc -x assembler-with-cpp
+CP = $(PREFIX)objcopy
+SZ = $(PREFIX)size
+endif
+HEX = $(CP) -O ihex
+BIN = $(CP) -O binary -S
+
+#######################################
+# CFLAGS
+#######################################
+# cpu
+CPU = -mcpu=cortex-m3
+
+# fpu
+# NONE for Cortex-M0/M0+/M3
+
+# float-abi
+
+
+# mcu
+MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI)
+
+# macros for gcc
+# AS defines
+AS_DEFS =
+
+# C defines
+C_DEFS = \
+-DSTM32F10X_HD \
+-DUSE_STDPERIPH_DRIVER
+
+
+# AS includes
+AS_INCLUDES =
+
+# C includes
+C_INCLUDES = \
+-Isource/codec \
+-Isource/coder \
+-Isource/core \
+-Isource/dev \
+-Isource/elec_det \
+-Isource/interface \
+-Isource/main \
+-Isource/rt_thread \
+-Isource/rt_thread/include \
+-Isource/RTT \
+-Isource/soft \
+-Isource/stm32lib/inc \
+-Isource/task \
+
+
+# compile gcc flags
+ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+CFLAGS += $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+ifeq ($(DEBUG), 1)
+CFLAGS += -g -gdwarf-2
+endif
+
+
+# Generate dependency information
+CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
+
+
+#######################################
+# LDFLAGS
+#######################################
+# link script
+LDSCRIPT = stm32_boot.ld
+
+# libraries
+LIBS = -lc -lm -lnosys
+LIBDIR =
+LDFLAGS = $(MCU) -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections
+
+# default action: build all
+all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
+
+
+#######################################
+# build the application
+#######################################
+# list of objects
+OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
+vpath %.c $(sort $(dir $(C_SOURCES)))
+# list of ASM program objects
+OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
+vpath %.s $(sort $(dir $(ASM_SOURCES)))
+
+$(BUILD_DIR)/%.o: %.c Makefile | $(BUILD_DIR)
+ $(CC) -c $(CFLAGS) -Wa,-a,-ad,-alms=$(BUILD_DIR)/$(notdir $(<:.c=.lst)) $< -o $@
+
+$(BUILD_DIR)/%.o: %.s Makefile | $(BUILD_DIR)
+ $(AS) -c $(CFLAGS) $< -o $@
+
+$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile
+ $(CC) $(OBJECTS) $(LDFLAGS) -o $@
+ $(SZ) $@
+
+$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(HEX) $< $@
+
+$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(BIN) $< $@
+
+$(BUILD_DIR):
+ mkdir $@
+
+#######################################
+# clean up
+#######################################
+clean:
+ -rm -fR $(BUILD_DIR)
+
+#######################################
+# dependencies
+#######################################
+-include $(wildcard $(BUILD_DIR)/*.d)
+
+# *** EOF ***
\ No newline at end of file
diff --git a/checher_slave.uvoptx b/checher_slave.uvoptx
index 8aeaea0..1911924 100644
--- a/checher_slave.uvoptx
+++ b/checher_slave.uvoptx
@@ -75,7 +75,7 @@
1
0
- 0
+ 1
18
@@ -523,7 +523,7 @@
1
0
- 1
+ 0
18
@@ -771,7 +771,7 @@
stm32lib
- 0
+ 1
0
0
0
@@ -1167,7 +1167,7 @@
elec_det
- 1
+ 0
0
0
0
@@ -1475,7 +1475,7 @@
rtt
- 0
+ 1
0
0
0
@@ -1507,7 +1507,7 @@
rt_thread
- 0
+ 1
0
0
0
diff --git a/checher_slave.uvprojx b/checher_slave.uvprojx
index eda6663..baac5af 100644
--- a/checher_slave.uvprojx
+++ b/checher_slave.uvprojx
@@ -10,7 +10,7 @@
boot
0x4
ARM-ADS
- 5060750::V5.06 update 6 (build 750)::ARMCC
+ 5060960::V5.06 update 7 (build 960)::.\ARMCC
0
@@ -185,6 +185,7 @@
0
0
0
+ 0
0
0
8
@@ -351,7 +352,7 @@
0
0
0
- 0
+ 4
@@ -798,7 +799,7 @@
2
2
2
- 2
+ 0
@@ -1892,7 +1893,7 @@
2
2
2
- 2
+ 0
@@ -2383,7 +2384,7 @@
2
2
2
- 2
+ 0
@@ -2482,7 +2483,7 @@
2
2
2
- 2
+ 0
@@ -2561,7 +2562,7 @@
2
2
2
- 2
+ 0
@@ -2635,7 +2636,7 @@
app
0x4
ARM-ADS
- 5060750::V5.06 update 6 (build 750)::ARMCC
+ 5060960::V5.06 update 7 (build 960)::.\ARMCC
0
@@ -2810,6 +2811,7 @@
0
0
0
+ 0
0
0
8
@@ -2976,7 +2978,7 @@
0
0
0
- 0
+ 4
@@ -4254,6 +4256,7 @@
0
0
0
+ 0
0
0
8
@@ -4420,7 +4423,7 @@
0
0
0
- 0
+ 4
diff --git a/source/core/core_cm3.c b/source/core/core_cm3.c
index fcff0d1..a01cd3d 100644
--- a/source/core/core_cm3.c
+++ b/source/core/core_cm3.c
@@ -729,13 +729,13 @@ uint32_t __LDREXW(uint32_t *addr)
*
* Exclusive STR command for 8 bit values
*/
-uint32_t __STREXB(uint8_t value, uint8_t *addr)
-{
- uint32_t result=0;
+// uint32_t __STREXB(uint8_t value, uint8_t *addr)
+// {
+// uint32_t result=0;
- __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
- return(result);
-}
+// __ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
+// return(result);
+// }
/**
* @brief STR Exclusive (16 bit)
@@ -746,13 +746,13 @@ uint32_t __STREXB(uint8_t value, uint8_t *addr)
*
* Exclusive STR command for 16 bit values
*/
-uint32_t __STREXH(uint16_t value, uint16_t *addr)
-{
- uint32_t result=0;
+// uint32_t __STREXH(uint16_t value, uint16_t *addr)
+// {
+// uint32_t result=0;
- __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
- return(result);
-}
+// __ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
+// return(result);
+// }
/**
* @brief STR Exclusive (32 bit)
@@ -763,13 +763,13 @@ uint32_t __STREXH(uint16_t value, uint16_t *addr)
*
* Exclusive STR command for 32 bit values
*/
-uint32_t __STREXW(uint32_t value, uint32_t *addr)
-{
- uint32_t result=0;
+// uint32_t __STREXW(uint32_t value, uint32_t *addr)
+// {
+// uint32_t result=0;
- __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
- return(result);
-}
+// __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
+// return(result);
+// }
#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
diff --git a/source/core/cortex_m4_gcc.s b/source/core/cortex_m4_gcc.s
new file mode 100644
index 0000000..28ec23b
--- /dev/null
+++ b/source/core/cortex_m4_gcc.s
@@ -0,0 +1,44 @@
+
+
+
+
+
+ .cpu cortex-m3
+ .fpu softvfp
+ .syntax unified
+ .thumb
+ .text
+
+
+
+
+
+ .global __interrupt_disable
+ .type __interrupt_disable, %function
+__interrupt_disable:
+ MRS R0, PRIMASK
+ CPSID I
+ BX LR
+
+
+ .global __interrupt_enable
+ .type __interrupt_enable, %function
+__interrupt_enable:
+ MSR PRIMASK, R0
+ BX LR
+
+
+ .global __set_msp
+ .type __set_msp, %function
+__set_msp:
+ MSR MSP, R0
+ BX LR
+
+
+
+
+
+
+
+
+
diff --git a/source/core/startup_stm32f103xe.s b/source/core/startup_stm32f103xe.s
new file mode 100644
index 0000000..771aa8a
--- /dev/null
+++ b/source/core/startup_stm32f103xe.s
@@ -0,0 +1,470 @@
+/**
+ *************** (C) COPYRIGHT 2017 STMicroelectronics ************************
+ * @file startup_stm32f103xe.s
+ * @author MCD Application Team
+ * @brief STM32F103xE Devices vector table for Atollic toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Configure the clock system
+ * - Configure external SRAM mounted on STM3210E-EVAL board
+ * to be used as data memory (optional, to be enabled by user)
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M3 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2017-2021 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m3
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+
+/* Call the clock system initialization function.*/
+ bl SystemInit
+
+/* Copy the data segment initializers from flash to SRAM */
+ ldr r0, =_sdata
+ ldr r1, =_edata
+ ldr r2, =_sidata
+ movs r3, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r4, [r2, r3]
+ str r4, [r0, r3]
+ adds r3, r3, #4
+
+LoopCopyDataInit:
+ adds r4, r0, r3
+ cmp r4, r1
+ bcc CopyDataInit
+
+/* Zero fill the bss segment. */
+ ldr r2, =_sbss
+ ldr r4, =_ebss
+ movs r3, #0
+ b LoopFillZerobss
+
+FillZerobss:
+ str r3, [r2]
+ adds r2, r2, #4
+
+LoopFillZerobss:
+ cmp r2, r4
+ bcc FillZerobss
+
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+ bx lr
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_IRQHandler
+ .word TAMPER_IRQHandler
+ .word RTC_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_2_IRQHandler
+ .word USB_HP_CAN1_TX_IRQHandler
+ .word USB_LP_CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_IRQHandler
+ .word TIM1_UP_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word TIM3_IRQHandler
+ .word TIM4_IRQHandler
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word USBWakeUp_IRQHandler
+ .word TIM8_BRK_IRQHandler
+ .word TIM8_UP_IRQHandler
+ .word TIM8_TRG_COM_IRQHandler
+ .word TIM8_CC_IRQHandler
+ .word ADC3_IRQHandler
+ .word FSMC_IRQHandler
+ .word SDIO_IRQHandler
+ .word TIM5_IRQHandler
+ .word SPI3_IRQHandler
+ .word UART4_IRQHandler
+ .word UART5_IRQHandler
+ .word TIM6_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word BootRAM /* @0x1E0. This is for boot in RAM mode for
+ STM32F10x High Density devices. */
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_IRQHandler
+ .thumb_set PVD_IRQHandler,Default_Handler
+
+ .weak TAMPER_IRQHandler
+ .thumb_set TAMPER_IRQHandler,Default_Handler
+
+ .weak RTC_IRQHandler
+ .thumb_set RTC_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_2_IRQHandler
+ .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+ .weak USB_HP_CAN1_TX_IRQHandler
+ .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
+
+ .weak USB_LP_CAN1_RX0_IRQHandler
+ .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_IRQHandler
+ .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_IRQHandler
+ .thumb_set TIM1_UP_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak USBWakeUp_IRQHandler
+ .thumb_set USBWakeUp_IRQHandler,Default_Handler
+
+ .weak TIM8_BRK_IRQHandler
+ .thumb_set TIM8_BRK_IRQHandler,Default_Handler
+
+ .weak TIM8_UP_IRQHandler
+ .thumb_set TIM8_UP_IRQHandler,Default_Handler
+
+ .weak TIM8_TRG_COM_IRQHandler
+ .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM8_CC_IRQHandler
+ .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+ .weak ADC3_IRQHandler
+ .thumb_set ADC3_IRQHandler,Default_Handler
+
+ .weak FSMC_IRQHandler
+ .thumb_set FSMC_IRQHandler,Default_Handler
+
+ .weak SDIO_IRQHandler
+ .thumb_set SDIO_IRQHandler,Default_Handler
+
+ .weak TIM5_IRQHandler
+ .thumb_set TIM5_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak UART4_IRQHandler
+ .thumb_set UART4_IRQHandler,Default_Handler
+
+ .weak UART5_IRQHandler
+ .thumb_set UART5_IRQHandler,Default_Handler
+
+ .weak TIM6_IRQHandler
+ .thumb_set TIM6_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_5_IRQHandler
+ .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler
+
diff --git a/source/dev/dev_flash.h b/source/dev/dev_flash.h
index 6c3576a..d27610d 100644
--- a/source/dev/dev_flash.h
+++ b/source/dev/dev_flash.h
@@ -6,13 +6,13 @@
-__packed
+#pragma pack (1)
typedef struct{
uint32_t file_size;//文件长度,不包括文件名
char name[120];
int used; // 初始值为0xffffffff,每使用一次添加一个0
}flash_file;
-
+#pragma pack ()
#define FLASH_FILE_HEAD_SIZE 128
@@ -40,7 +40,7 @@ int flash_erase_addr(uint32_t addr);
-__packed
+#pragma pack (1)
typedef struct{
uint32_t size;
char pack_time[20];
@@ -51,7 +51,7 @@ typedef struct{
char host_if[8];
char device_type[12];
}rom_head;
-
+#pragma pack ()
#define ROM_HEAD_SIZE 128
@@ -65,7 +65,7 @@ int flash_updata_boot(uint8_t *rom,uint32_t size);
// 系统参数
-__packed
+#pragma pack (1)
typedef struct{
char pack_time[20];// 打包时间
char host_if[8];// 主机接口
@@ -76,22 +76,19 @@ typedef struct{
int hard_version;// 硬件版本号
int resistor_diff;// 电阻校准值
}sys_param_def;
-
+#pragma pack ()
int flash_save_param(sys_param_def *par);
const sys_param_def *sys_param(void);
-
+#pragma pack (1)
#if 1
-__packed
typedef struct{
uint16_t max;
uint16_t min;
uint8_t err;
}scheme_range_def;
-
-__packed
typedef struct
{
uint8_t taskid;
@@ -100,18 +97,13 @@ typedef struct
uint8_t err;
scheme_range_def range[16];
}scheme_task_def;
-
#else
-
__packed
typedef struct{
uint32_t max;
uint32_t min;
uint32_t err;
}scheme_range_def;
-
-
-
__packed
typedef struct
{
@@ -121,21 +113,13 @@ typedef struct
uint32_t err;
scheme_range_def range[16];
}scheme_task_def;
-
-
#endif
-
-
-__packed
typedef struct{
uint8_t err;
uint8_t suberr_num;
uint8_t suberr[30];
}marerr_def;
-
-
// 方案参数
-__packed
typedef struct{
uint8_t slave_data[2048];
uint32_t plan_id;
@@ -145,6 +129,7 @@ typedef struct{
marerr_def marerr[21];
scheme_task_def task[0];
}scheme_def;
+#pragma pack ()
const scheme_def *check_scheme(void);
diff --git a/source/interface/if_can.c b/source/interface/if_can.c
index 7ecb4fe..044edcf 100644
--- a/source/interface/if_can.c
+++ b/source/interface/if_can.c
@@ -1,3 +1,4 @@
+#include "stm32f10x.h"
#include "if_can.h"
#include "rtthread.h"
#include "rthw.h"
diff --git a/source/main/compiler_info.h b/source/main/compiler_info.h
index 0c56131..2c9c6fa 100644
--- a/source/main/compiler_info.h
+++ b/source/main/compiler_info.h
@@ -6,7 +6,7 @@
-#define BUILD_DATE "2023-10-31 16:54:55"
+#define BUILD_DATE "2023-10-31 23:33:54"
#define SOFT_VERSION "2.03"
diff --git a/source/soft/debug.h b/source/soft/debug.h
index 467276a..16887c6 100644
--- a/source/soft/debug.h
+++ b/source/soft/debug.h
@@ -51,8 +51,9 @@
#define DBG_LOG_(type_,msg_,...)\
debug_log(__FILE__,__func__,__LINE__,type_,(msg_),##__VA_ARGS__)
-//#define DBG_LOG_(type_,msg_,...)\
-// debug_log("-","-",__LINE__,type_,(msg_),##__VA_ARGS__)
+
+// #define DBG_LOG_(type_,msg_,...)
+// debug_log("-","-",__LINE__,type_,(msg_),##__VA_ARGS__)
#ifdef DEBUG
diff --git a/stm32_boot.ld b/stm32_boot.ld
new file mode 100644
index 0000000..73fe775
--- /dev/null
+++ b/stm32_boot.ld
@@ -0,0 +1,189 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : STM32CubeMX
+**
+** Abstract : Linker script for STM32F103RCTx series
+** 256Kbytes FLASH and 48Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2019 STMicroelectronics
+**
+** Redistribution and use in source and binary forms, with or without modification,
+** are permitted provided that the following conditions are met:
+** 1. Redistributions of source code must retain the above copyright notice,
+** this list of conditions and the following disclaimer.
+** 2. Redistributions in binary form must reproduce the above copyright notice,
+** this list of conditions and the following disclaimer in the documentation
+** and/or other materials provided with the distribution.
+** 3. Neither the name of STMicroelectronics nor the names of its contributors
+** may be used to endorse or promote products derived from this software
+** without specific prior written permission.
+**
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 48K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 256K
+}
+
+/* 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
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+