This commit is contained in:
cfif 2025-06-02 13:26:42 +03:00
commit adf5d5e66b
15 changed files with 2239 additions and 0 deletions

199
APP/AT32F437xM_FLASH.ld Normal file
View File

@ -0,0 +1,199 @@
/*
*****************************************************************************
**
** File : AT32F437xM_FLASH.ld
**
** Abstract : Linker script for AT32F437xM Device with
** 4096KByte FLASH, 384KByte 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 : Artery Tek AT32
**
** Environment : Arm gcc toolchain
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20060000; /* 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 */
_MetadataSize = 256;
_BootloaderSize = 64K;
_BootloaderBegin = 0x08000000;
_FirmwareMainSize = 320K;
_FirmwareMainBegin = _BootloaderBegin + _BootloaderSize;
_FirmwareRecoverySize = 320K;
_FirmwareRecoveryBegin = _FirmwareMainBegin + _FirmwareMainSize;
_FirmwareMainTelematicaSize = 192K;
_FirmwareMainTelematicaBegin = _FirmwareRecoveryBegin + _FirmwareRecoverySize;
_SettingsMainSize = 16K;
_SettingsMainBegin = _FirmwareMainTelematicaBegin + _FirmwareMainTelematicaSize;
_SettingsRecoverySize = 16K;
_SettingsRecoveryBegin = _SettingsMainBegin + _SettingsMainSize;
_FileSystemSize = 96K;
_FileSystemBegin = _SettingsRecoveryBegin + _SettingsRecoverySize;
/* Specify the memory areas */
MEMORY
{
BOOTLOADER (rx) : ORIGIN = _BootloaderBegin, LENGTH = _BootloaderSize
FLASH (rx) : ORIGIN = _FirmwareMainBegin, LENGTH = _FirmwareMainSize - _MetadataSize
META (rx) : ORIGIN = _FirmwareMainBegin + _FirmwareMainSize - _MetadataSize, LENGTH = _MetadataSize
UPDATE_FIRMWARE (rx) : ORIGIN = _FirmwareRecoveryBegin, LENGTH = _FirmwareRecoverySize
MAIN_TELE_FIRM (rx) : ORIGIN = _FirmwareMainTelematicaBegin, LENGTH = _FirmwareMainTelematicaSize
SETTINGS_MAIN (rx) : ORIGIN = _SettingsMainBegin, LENGTH = _SettingsMainSize
SETTINGS_RECOVERY (rx) : ORIGIN = _SettingsRecoveryBegin, LENGTH = _SettingsRecoverySize
FILE_SYSTEM (rx) : ORIGIN = _FileSystemBegin, LENGTH = _FileSystemSize
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
.metaaaa : SUBALIGN(1)
{
KEEP(*(.meta_fw_crc))
LONG(_FirmwareMainSize - _MetadataSize) ; /* word with firmware_size */
KEEP(*(.meta_fw_name_size))
KEEP(*(.meta_fw_name))
KEEP(*(.meta_hw_name_size))
KEEP(*(.meta_hw_name))
KEEP(*(.meta_interface_name_size))
KEEP(*(.meta_interface_name))
. = ALIGN(256);
} >META
/* 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(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

178
APP/FreeRTOSConfig.h Normal file
View File

@ -0,0 +1,178 @@
/* USER CODE BEGIN Header */
/*
* FreeRTOS Kernel V10.3.1
* Portion Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
* Portion Copyright (C) 2019 StMicroelectronics, Inc. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/* USER CODE END Header */
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* These parameters and more are described within the 'configuration' section of the
* FreeRTOS API documentation available on the FreeRTOS.org web site.
*
* See http://www.freertos.org/a00110.html
*----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* Section where include file can be added */
/* USER CODE END Includes */
/* Ensure definitions are only used by the compiler, and not by the assembler. */
#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
#include <stdint.h>
extern uint32_t SystemCoreClock;
#endif
#ifndef CMSIS_device_header
//#define CMSIS_device_header "niietcm4.h"
#define CMSIS_device_header "at32f435_437.h"
#endif /* CMSIS_device_header */
//#include "niietcm4.h"
#include "at32f435_437.h"
#define configCHECK_FOR_STACK_OVERFLOW 1
#define configENABLE_FPU 1
#define configENABLE_MPU 0
#define configUSE_PREEMPTION 1
#define configSUPPORT_STATIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ ( system_core_clock )
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES ( 56 )
#define configMINIMAL_STACK_SIZE ((uint16_t)64)
#define configTOTAL_HEAP_SIZE ((size_t)52000)
#define configMAX_TASK_NAME_LEN ( 16 )
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
/* USER CODE BEGIN MESSAGE_BUFFER_LENGTH_TYPE */
/* Defaults to size_t for backward compatibility, but can be changed
if lengths will always be less than the number of bytes in a size_t. */
#define configMESSAGE_BUFFER_LENGTH_TYPE size_t
/* USER CODE END MESSAGE_BUFFER_LENGTH_TYPE */
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Software timer definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY ( 2 )
#define configTIMER_QUEUE_LENGTH 10
#define configTIMER_TASK_STACK_DEPTH 128
/* CMSIS-RTOS V2 flags */
#define configUSE_OS2_THREAD_SUSPEND_RESUME 1
#define configUSE_OS2_THREAD_ENUMERATE 1
#define configUSE_OS2_EVENTFLAGS_FROM_ISR 1
#define configUSE_OS2_THREAD_FLAGS 1
#define configUSE_OS2_TIMER 1
#define configUSE_OS2_MUTEX 1
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTimerPendFunctionCall 1
#define INCLUDE_xQueueGetMutexHolder 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_eTaskGetState 1
/*
* The CMSIS-RTOS V2 FreeRTOS wrapper is dependent on the heap implementation used
* by the application thus the correct define need to be enabled below
*/
#define USE_FreeRTOS_HEAP_4
/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
/* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 4
#endif
/* The lowest interrupt priority that can be used in a call to a "set priority"
function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
/* USER CODE BEGIN 1 */
#define configASSERT(x) if ((x) == 0) {nvic_system_reset();}
//#define configASSERT(x) if ((x) == 0) {taskDISABLE_INTERRUPTS(); for( ;; );}
/* USER CODE END 1 */
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
standard names. */
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
/* IMPORTANT: After 10.3.1 update, Systick_Handler comes from NVIC (if SYS timebase = systick), otherwise from cmsis_os2.c */
#define USE_CUSTOM_SYSTICK_HANDLER_IMPLEMENTATION 0
#endif /* FREERTOS_CONFIG_H */

191
APP/at32f435_437_conf.h Normal file
View File

@ -0,0 +1,191 @@
/**
**************************************************************************
* @file at32f435_437_conf.h
* @version v2.0.4
* @date 2021-12-31
* @brief at32f435_437 config header file
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __AT32F435_437_CONF_H
#define __AT32F435_437_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup AT32F435_periph_template
* @{
*/
/** @addtogroup 435_Library_configuration Library_configuration
* @{
*/
/**
* @brief in the following line adjust the value of high speed exernal crystal (hext)
* used in your application
*
* tip: to avoid modifying this file each time you need to use different hext, you
* can define the hext value in your toolchain compiler preprocessor.
*
*/
#if !defined HEXT_VALUE
#define HEXT_VALUE ((uint32_t)25000000) /*!< value of the high speed exernal crystal in hz */
#endif
/**
* @brief in the following line adjust the high speed exernal crystal (hext) startup
* timeout value
*/
#define HEXT_STARTUP_TIMEOUT ((uint16_t)0x3000) /*!< time out for hext start up */
#define HICK_VALUE ((uint32_t)8000000) /*!< value of the high speed internal clock in hz */
/* module define -------------------------------------------------------------*/
#define CRM_MODULE_ENABLED
#define TMR_MODULE_ENABLED
#define ERTC_MODULE_ENABLED
#define GPIO_MODULE_ENABLED
#define I2C_MODULE_ENABLED
#define USART_MODULE_ENABLED
#define PWC_MODULE_ENABLED
#define CAN_MODULE_ENABLED
#define ADC_MODULE_ENABLED
#define DAC_MODULE_ENABLED
#define SPI_MODULE_ENABLED
#define EDMA_MODULE_ENABLED
#define DMA_MODULE_ENABLED
#define DEBUG_MODULE_ENABLED
#define FLASH_MODULE_ENABLED
#define CRC_MODULE_ENABLED
#define WWDT_MODULE_ENABLED
#define WDT_MODULE_ENABLED
#define EXINT_MODULE_ENABLED
#define SDIO_MODULE_ENABLED
#define XMC_MODULE_ENABLED
#define USB_MODULE_ENABLED
#define ACC_MODULE_ENABLED
#define MISC_MODULE_ENABLED
#define QSPI_MODULE_ENABLED
#define DVP_MODULE_ENABLED
#define SCFG_MODULE_ENABLED
#define EMAC_MODULE_ENABLED
/* includes ------------------------------------------------------------------*/
#ifdef CRM_MODULE_ENABLED
#include "at32f435_437_crm.h"
#endif
#ifdef TMR_MODULE_ENABLED
#include "at32f435_437_tmr.h"
#endif
#ifdef ERTC_MODULE_ENABLED
#include "at32f435_437_ertc.h"
#endif
#ifdef GPIO_MODULE_ENABLED
#include "at32f435_437_gpio.h"
#endif
#ifdef I2C_MODULE_ENABLED
#include "at32f435_437_i2c.h"
#endif
#ifdef USART_MODULE_ENABLED
#include "at32f435_437_usart.h"
#endif
#ifdef PWC_MODULE_ENABLED
#include "at32f435_437_pwc.h"
#endif
#ifdef CAN_MODULE_ENABLED
#include "at32f435_437_can.h"
#endif
#ifdef ADC_MODULE_ENABLED
#include "at32f435_437_adc.h"
#endif
#ifdef DAC_MODULE_ENABLED
#include "at32f435_437_dac.h"
#endif
#ifdef SPI_MODULE_ENABLED
#include "at32f435_437_spi.h"
#endif
#ifdef DMA_MODULE_ENABLED
#include "at32f435_437_dma.h"
#endif
#ifdef DEBUG_MODULE_ENABLED
#include "at32f435_437_debug.h"
#endif
#ifdef FLASH_MODULE_ENABLED
#include "at32f435_437_flash.h"
#endif
#ifdef CRC_MODULE_ENABLED
#include "at32f435_437_crc.h"
#endif
#ifdef WWDT_MODULE_ENABLED
#include "at32f435_437_wwdt.h"
#endif
#ifdef WDT_MODULE_ENABLED
#include "at32f435_437_wdt.h"
#endif
#ifdef EXINT_MODULE_ENABLED
#include "at32f435_437_exint.h"
#endif
#ifdef SDIO_MODULE_ENABLED
#include "at32f435_437_sdio.h"
#endif
#ifdef XMC_MODULE_ENABLED
#include "at32f435_437_xmc.h"
#endif
#ifdef ACC_MODULE_ENABLED
#include "at32f435_437_acc.h"
#endif
#ifdef MISC_MODULE_ENABLED
#include "at32f435_437_misc.h"
#endif
#ifdef EDMA_MODULE_ENABLED
#include "at32f435_437_edma.h"
#endif
#ifdef QSPI_MODULE_ENABLED
#include "at32f435_437_qspi.h"
#endif
#ifdef SCFG_MODULE_ENABLED
#include "at32f435_437_scfg.h"
#endif
#ifdef EMAC_MODULE_ENABLED
#include "at32f435_437_emac.h"
#endif
#ifdef DVP_MODULE_ENABLED
#include "at32f435_437_dvp.h"
#endif
#ifdef USB_MODULE_ENABLED
#include "at32f435_437_usb.h"
#endif
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,113 @@
/**
**************************************************************************
* @file at32f435_437_clock.c
* @version v2.0.4
* @date 2021-12-31
* @brief system clock config program
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* includes ------------------------------------------------------------------*/
#include "at32f435_437_clock.h"
/**
* @brief system clock config program
* @note the system clock is configured as follow:
* - system clock = (hext * pll_ns)/(pll_ms * pll_fr)
* - system clock source = pll (hext)
* - hext = 8000000
* - sclk = 250000000
* - ahbdiv = 1
* - ahbclk = 250000000
* - apb2div = 2
* - apb2clk = 125000000
* - apb1div = 2
* - apb1clk = 125000000
* - pll_ns = 125
* - pll_ms = 1
* - pll_fr = 4
* @param none
* @retval none
*/
void system_clock_config(void)
{
/* enable pwc periph clock */
crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE);
/* config ldo voltage */
pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3);
/* set the flash clock divider */
flash_clock_divider_set(FLASH_CLOCK_DIV_3);
/* reset crm */
crm_reset();
crm_clock_source_enable(CRM_CLOCK_SOURCE_HEXT, TRUE);
/* wait till hext is ready */
while(crm_hext_stable_wait() == ERROR)
{
}
#if defined PLL_NS
/* config pll clock resource */
crm_pll_config(CRM_PLL_SOURCE_HEXT, PLL_NS, 1, CRM_PLL_FR_4);
#endif
#if !defined PLL_NS
/* config pll clock resource */
crm_pll_config(CRM_PLL_SOURCE_HEXT, 40, 1, CRM_PLL_FR_4);
#endif
/* enable pll */
crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE);
/* wait till pll is ready */
while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET)
{
}
/* config ahbclk */
crm_ahb_div_set(CRM_AHB_DIV_1);
/* config apb2clk */
crm_apb2_div_set(CRM_APB2_DIV_2);
/* config apb1clk */
crm_apb1_div_set(CRM_APB1_DIV_2);
/* enable auto step mode */
crm_auto_step_mode_enable(TRUE);
/* select pll as system clock source */
crm_sysclk_switch(CRM_SCLK_PLL);
/* wait till pll is used as system clock source */
while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL)
{
}
/* disable auto step mode */
crm_auto_step_mode_enable(FALSE);
/* update system_core_clock global variable */
system_core_clock_update();
}

View File

@ -0,0 +1,46 @@
/**
**************************************************************************
* @file at32f435_437_clock.h
* @version v2.0.4
* @date 2021-12-31
* @brief header file of clock program
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __AT32F435_437_CLOCK_H
#define __AT32F435_437_CLOCK_H
#ifdef __cplusplus
extern "C" {
#endif
/* includes ------------------------------------------------------------------*/
#include "at32f435_437.h"
/* exported functions ------------------------------------------------------- */
void system_clock_config(void);
#ifdef __cplusplus
}
#endif
#endif

91
APP/delay_sec.c Normal file
View File

@ -0,0 +1,91 @@
//
// Created by cfif on 09.02.23.
//
#include "at32f435_437_clock.h"
#include "at32f435_437.h"
/* delay macros */
#define STEP_DELAY_MS 50
/* delay variable */
static __IO uint32_t fac_us;
static __IO uint32_t fac_ms;
/**
* @brief initialize delay function
* @param none
* @retval none
*/
void delay_init()
{
/* configure systick */
systick_clock_source_config(SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV);
fac_us = system_core_clock / (1000000U);
fac_ms = fac_us * (1000U);
}
/**
* @brief inserts a delay time.
* @param nus: specifies the delay time length, in microsecond.
* @retval none
*/
void delay_us(uint32_t nus)
{
uint32_t temp = 0;
SysTick->LOAD = (uint32_t)(nus * fac_us);
SysTick->VAL = 0x00;
SysTick->CTRL |= SysTick_CTRL_ENABLE_Msk ;
do
{
temp = SysTick->CTRL;
}while((temp & 0x01) && !(temp & (1 << 16)));
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
SysTick->VAL = 0x00;
}
/**
* @brief inserts a delay time.
* @param nms: specifies the delay time length, in milliseconds.
* @retval none
*/
void delay_ms(uint16_t nms)
{
uint32_t temp = 0;
while(nms)
{
if(nms > STEP_DELAY_MS)
{
SysTick->LOAD = (uint32_t)(STEP_DELAY_MS * fac_ms);
nms -= STEP_DELAY_MS;
}
else
{
SysTick->LOAD = (uint32_t)(nms * fac_ms);
nms = 0;
}
SysTick->VAL = 0x00;
SysTick->CTRL |= SysTick_CTRL_ENABLE_Msk;
do
{
temp = SysTick->CTRL;
}while((temp & 0x01) && !(temp & (1 << 16)));
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
SysTick->VAL = 0x00;
}
}
/**
* @brief inserts a delay time.
* @param sec: specifies the delay time, in seconds.
* @retval none
*/
void delay_sec(uint16_t sec)
{
uint16_t index;
for(index = 0; index < sec; index++)
{
delay_ms(500);
delay_ms(500);
}
}

14
APP/delay_sec.h Normal file
View File

@ -0,0 +1,14 @@
//
// Created by cfif on 18.02.23.
//
#ifndef GONEC_GSM_DELAY_SEC_H
#define GONEC_GSM_DELAY_SEC_H
#include "inttypes.h"
void delay_init();
void delay_ms(uint16_t nms);
void delay_us(uint32_t nus);
#endif //GONEC_GSM_DELAY_SEC_H

149
APP/int/at32f435_437_int.c Normal file
View File

@ -0,0 +1,149 @@
/**
**************************************************************************
* @file at32f435_437_int.c
* @version v2.0.4
* @date 2021-12-31
* @brief main interrupt service routines.
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* includes ------------------------------------------------------------------*/
#include "at32f435_437_int.h"
/** @addtogroup AT32F437_periph_examples
* @{
*/
/** @addtogroup 437_EMAC_tcp_server
* @{
*/
/**
* @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)
// {
// }
nvic_system_reset();
}
/**
* @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 debug monitor exception.
* @param none
* @retval none
*/
//void DebugMon_Handler(void)
//{
//}
/**
* @brief this function handles pendsv_handler 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 emac handler.
* @param none
* @retval none
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,58 @@
/**
**************************************************************************
* @file at32f435_437_int.h
* @version v2.0.4
* @date 2021-12-31
* @brief header file of main interrupt service routines.
**************************************************************************
* Copyright notice & Disclaimer
*
* The software Board Support Package (BSP) that is made available to
* download from Artery official website is the copyrighted work of Artery.
* Artery authorizes customers to use, copy, and distribute the BSP
* software and its related documentation for the purpose of design and
* development in conjunction with Artery microcontrollers. Use of the
* software is governed by this copyright notice and the following disclaimer.
*
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
* GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
* TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
* STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
**************************************************************************
*/
/* define to prevent recursive inclusion -------------------------------------*/
#ifndef __AT32F435_437_INT_H
#define __AT32F435_437_INT_H
#ifdef __cplusplus
extern "C" {
#endif
/* includes ------------------------------------------------------------------*/
#include "at32f435_437.h"
/* exported types ------------------------------------------------------------*/
/* exported constants --------------------------------------------------------*/
/* exported macro ------------------------------------------------------------*/
/* exported functions ------------------------------------------------------- */
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 DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
#ifdef __cplusplus
}
#endif
#endif

93
APP/main.c Normal file
View File

@ -0,0 +1,93 @@
#include "cmsis_os.h"
#include "MainModesArbiter.h"
#include "at32f435_437_clock.h"
#include "PeripheralInterfaces.h"
#include "wdt_timer.h"
/// не проебать
//XTT316300S1012671
//XTT316300S1012862
//XTT316300S1012157
//XTT316300S1012191
// INTELCOM_BILD_FOR_SOUND_TEST
//подготовка не горит
// AT+CCMXPLAYWAV="E:/ecall_on.wav", 2
// bot +79418100029
// testNum sms +79418100025
// +79418100013 smsCener
/// +79043490000
// ecall_on
// 2.1.7
/// 79043490000 tele2 smscentr
//AT+CCMXPLAYWAV="E:/ant_error.wav", 2
// AT+CCMXPLAY="E:/tets_call_timeuot.mp3", 0, 0
// LE11B01SIM7600M22_CUS_AS
// 00000000000000000
_Noreturn void stop() {
while (1) {
asm("nop");
}
}
#define STOP stop();
// Переполнение стека
void vApplicationStackOverflowHook(TaskHandle_t xTask, signed char *pcTaskName) {
STOP
}
tMma MAIN_ENV;
#define sts(STR) STR, sizeof(STR)-1
void main_SetAccessProtection(){
flash_status_type status = FLASH_OPERATE_DONE;
if(flash_fap_status_get() == RESET) {
flash_unlock();
status = flash_operation_wait_for(OPERATION_TIMEOUT);
if (status != FLASH_OPERATE_TIMEOUT) {
if ((status == FLASH_PROGRAM_ERROR) || (status == FLASH_EPP_ERROR))
flash_flag_clear(FLASH_PRGMERR_FLAG | FLASH_EPPERR_FLAG);
status = flash_fap_enable(TRUE);
if (status == FLASH_OPERATE_DONE){
//nvic_system_reset();
}
flash_lock();
}
flash_lock();
}
}
#ifdef SET_ACCESS_PROTECTION
#define SetAccessProtection main_SetAccessProtection();
#else
#define SetAccessProtection //
#endif
#ifdef SET_WDT
#define SetWdt Wdt_Start();
#else
#define SetWdt //
#endif
int main(void) {
SetAccessProtection
system_clock_config();
osKernelInitialize();
InitPeripheralInterfaces();
Mma_Init(&MAIN_ENV, &GPIOS, &SERIAL_PORTS, &I2C_PORTS, &SPI_PORTS, &ADCS, &NVM_STORAGE, &RTCS, &CAN_PORTS);
Mma_StartThread(&MAIN_ENV);
SetWdt
osKernelStart();
STOP
}
#undef SetAccessProtection

15
APP/modular.json Normal file
View File

@ -0,0 +1,15 @@
{
"cmake": {
"inc_dirs": [
"./",
"./clock",
"./int"
],
"srcs": [
"./**.c",
"./clock/**.c",
"./int/**.c",
"./**.s"
]
}
}

571
APP/startup_at32f435_437.s Normal file
View File

@ -0,0 +1,571 @@
/**
******************************************************************************
* @file startup_at32f435_437.s
* @version v2.0.4
* @date 2021-12-31
* @brief at32f435_437 devices vector table for gcc 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 and the external sram 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-m4 processor is in thread mode,
* priority is privileged, and the stack is set to main.
******************************************************************************
*/
.syntax unified
.cpu cortex-m4
.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
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
/**
* @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:
movs r1, #0
b LoopCopyDataInit
CopyDataInit:
ldr r3, =_sidata
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobss
/* Call the clock system intitialization function.*/
bl SystemInit
/* 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
/* External Interrupts */
.word WWDT_IRQHandler /* Window Watchdog Timer */
.word PVM_IRQHandler /* PVM through EXINT Line detect */
.word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXINT line */
.word ERTC_WKUP_IRQHandler /* ERTC Wakeup through the EXINT line */
.word FLASH_IRQHandler /* Flash */
.word CRM_IRQHandler /* CRM */
.word EXINT0_IRQHandler /* EXINT Line 0 */
.word EXINT1_IRQHandler /* EXINT Line 1 */
.word EXINT2_IRQHandler /* EXINT Line 2 */
.word EXINT3_IRQHandler /* EXINT Line 3 */
.word EXINT4_IRQHandler /* EXINT Line 4 */
.word EDMA_Stream1_IRQHandler /* EDMA Stream 1 */
.word EDMA_Stream2_IRQHandler /* EDMA Stream 2 */
.word EDMA_Stream3_IRQHandler /* EDMA Stream 3 */
.word EDMA_Stream4_IRQHandler /* EDMA Stream 4 */
.word EDMA_Stream5_IRQHandler /* EDMA Stream 5 */
.word EDMA_Stream6_IRQHandler /* EDMA Stream 6 */
.word EDMA_Stream7_IRQHandler /* EDMA Stream 7 */
.word ADC1_2_3_IRQHandler /* ADC1 & ADC2 & ADC3 */
.word CAN1_TX_IRQHandler /* CAN1 TX */
.word CAN1_RX0_IRQHandler /* CAN1 RX0 */
.word CAN1_RX1_IRQHandler /* CAN1 RX1 */
.word CAN1_SE_IRQHandler /* CAN1 SE */
.word EXINT9_5_IRQHandler /* EXINT Line [9:5] */
.word TMR1_BRK_TMR9_IRQHandler /* TMR1 Brake and TMR9 */
.word TMR1_OVF_TMR10_IRQHandler /* TMR1 Overflow and TMR10 */
.word TMR1_TRG_HALL_TMR11_IRQHandler /* TMR1 Trigger and hall and TMR11 */
.word TMR1_CH_IRQHandler /* TMR1 Channel */
.word TMR2_GLOBAL_IRQHandler /* TMR2 */
.word TMR3_GLOBAL_IRQHandler /* TMR3 */
.word TMR4_GLOBAL_IRQHandler /* TMR4 */
.word I2C1_EVT_IRQHandler /* I2C1 Event */
.word I2C1_ERR_IRQHandler /* I2C1 Error */
.word I2C2_EVT_IRQHandler /* I2C2 Event */
.word I2C2_ERR_IRQHandler /* I2C2 Error */
.word SPI1_IRQHandler /* SPI1 */
.word SPI2_I2S2EXT_IRQHandler /* SPI2 */
.word USART1_IRQHandler /* USART1 */
.word USART2_IRQHandler /* USART2 */
.word USART3_IRQHandler /* USART3 */
.word EXINT15_10_IRQHandler /* EXINT Line [15:10] */
.word ERTCAlarm_IRQHandler /* RTC Alarm through EXINT Line */
.word OTGFS1_WKUP_IRQHandler /* OTGFS1 Wakeup from suspend */
.word TMR8_BRK_TMR12_IRQHandler /* TMR8 Brake and TMR12 */
.word TMR8_OVF_TMR13_IRQHandler /* TMR8 Overflow and TMR13 */
.word TMR8_TRG_HALL_TMR14_IRQHandler /* TMR8 Trigger and hall and TMR14 */
.word TMR8_CH_IRQHandler /* TMR8 Channel */
.word EDMA_Stream8_IRQHandler /* EDMA Stream 8 */
.word XMC_IRQHandler /* XMC */
.word SDIO1_IRQHandler /* SDIO1 */
.word TMR5_GLOBAL_IRQHandler /* TMR5 */
.word SPI3_I2S3EXT_IRQHandler /* SPI3 */
.word UART4_IRQHandler /* UART4 */
.word UART5_IRQHandler /* UART5 */
.word TMR6_DAC_GLOBAL_IRQHandler /* TMR6 & DAC */
.word TMR7_GLOBAL_IRQHandler /* TMR7 */
.word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
.word DMA1_Channel2_IRQHandler /* DMA1 Channel 2 */
.word DMA1_Channel3_IRQHandler /* DMA1 Channel 3 */
.word DMA1_Channel4_IRQHandler /* DMA1 Channel 4 */
.word DMA1_Channel5_IRQHandler /* DMA1 Channel 5 */
.word EMAC_IRQHandler /* EMAC */
.word EMAC_WKUP_IRQHandler /* EMAC Wakeup */
.word CAN2_TX_IRQHandler /* CAN2 TX */
.word CAN2_RX0_IRQHandler /* CAN2 RX0 */
.word CAN2_RX1_IRQHandler /* CAN2 RX1 */
.word CAN2_SE_IRQHandler /* CAN2 SE */
.word OTGFS1_IRQHandler /* OTGFS1 */
.word DMA1_Channel6_IRQHandler /* DMA1 Channel 6 */
.word DMA1_Channel7_IRQHandler /* DMA1 Channel 7 */
.word 0 /* Reserved */
.word USART6_IRQHandler /* USART6 */
.word I2C3_EVT_IRQHandler /* I2C3 Event */
.word I2C3_ERR_IRQHandler /* I2C3 Error */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word OTGFS2_WKUP_IRQHandler /* OTGFS2 Wakeup from suspend */
.word OTGFS2_IRQHandler /* OTGFS2 */
.word DVP_IRQHandler /* DVP */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word FPU_IRQHandler /* FPU */
.word UART7_IRQHandler /* UART7 */
.word UART8_IRQHandler /* UART8 */
.word SPI4_IRQHandler /* SPI4 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word QSPI2_IRQHandler /* QSPI2 */
.word QSPI1_IRQHandler /* QSPI1 */
.word 0 /* Reserved */
.word DMAMUX_IRQHandler /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SDIO2_IRQHandler /* SDIO2 */
.word ACC_IRQHandler /* ACC */
.word TMR20_BRK_IRQHandler /* TMR20 Brake */
.word TMR20_OVF_IRQHandler /* TMR20 Overflow */
.word TMR20_TRG_HALL_IRQHandler /* TMR20 Trigger and hall */
.word TMR20_CH_IRQHandler /* TMR20 Channel */
.word DMA2_Channel1_IRQHandler /* DMA2 Channel 1 */
.word DMA2_Channel2_IRQHandler /* DMA2 Channel 2 */
.word DMA2_Channel3_IRQHandler /* DMA2 Channel 3 */
.word DMA2_Channel4_IRQHandler /* DMA2 Channel 4 */
.word DMA2_Channel5_IRQHandler /* DMA2 Channel 5 */
.word DMA2_Channel6_IRQHandler /* DMA2 Channel 6 */
.word DMA2_Channel7_IRQHandler /* DMA2 Channel 7 */
/*******************************************************************************
*
* 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 WWDT_IRQHandler
.thumb_set WWDT_IRQHandler,Default_Handler
.weak PVM_IRQHandler
.thumb_set PVM_IRQHandler,Default_Handler
.weak TAMP_STAMP_IRQHandler
.thumb_set TAMP_STAMP_IRQHandler,Default_Handler
.weak ERTC_WKUP_IRQHandler
.thumb_set ERTC_WKUP_IRQHandler,Default_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler,Default_Handler
.weak CRM_IRQHandler
.thumb_set CRM_IRQHandler,Default_Handler
.weak EXINT0_IRQHandler
.thumb_set EXINT0_IRQHandler,Default_Handler
.weak EXINT1_IRQHandler
.thumb_set EXINT1_IRQHandler,Default_Handler
.weak EXINT2_IRQHandler
.thumb_set EXINT2_IRQHandler,Default_Handler
.weak EXINT3_IRQHandler
.thumb_set EXINT3_IRQHandler,Default_Handler
.weak EXINT4_IRQHandler
.thumb_set EXINT4_IRQHandler,Default_Handler
.weak EDMA_Stream1_IRQHandler
.thumb_set EDMA_Stream1_IRQHandler,Default_Handler
.weak EDMA_Stream2_IRQHandler
.thumb_set EDMA_Stream2_IRQHandler,Default_Handler
.weak EDMA_Stream3_IRQHandler
.thumb_set EDMA_Stream3_IRQHandler,Default_Handler
.weak EDMA_Stream4_IRQHandler
.thumb_set EDMA_Stream4_IRQHandler,Default_Handler
.weak EDMA_Stream5_IRQHandler
.thumb_set EDMA_Stream5_IRQHandler,Default_Handler
.weak EDMA_Stream6_IRQHandler
.thumb_set EDMA_Stream6_IRQHandler,Default_Handler
.weak EDMA_Stream7_IRQHandler
.thumb_set EDMA_Stream7_IRQHandler,Default_Handler
.weak ADC1_2_3_IRQHandler
.thumb_set ADC1_2_3_IRQHandler,Default_Handler
.weak CAN1_TX_IRQHandler
.thumb_set CAN1_TX_IRQHandler,Default_Handler
.weak CAN1_RX0_IRQHandler
.thumb_set CAN1_RX0_IRQHandler,Default_Handler
.weak CAN1_RX1_IRQHandler
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
.weak CAN1_SE_IRQHandler
.thumb_set CAN1_SE_IRQHandler,Default_Handler
.weak EXINT9_5_IRQHandler
.thumb_set EXINT9_5_IRQHandler,Default_Handler
.weak TMR1_BRK_TMR9_IRQHandler
.thumb_set TMR1_BRK_TMR9_IRQHandler,Default_Handler
.weak TMR1_OVF_TMR10_IRQHandler
.thumb_set TMR1_OVF_TMR10_IRQHandler,Default_Handler
.weak TMR1_TRG_HALL_TMR11_IRQHandler
.thumb_set TMR1_TRG_HALL_TMR11_IRQHandler,Default_Handler
.weak TMR1_CH_IRQHandler
.thumb_set TMR1_CH_IRQHandler,Default_Handler
.weak TMR2_GLOBAL_IRQHandler
.thumb_set TMR2_GLOBAL_IRQHandler,Default_Handler
.weak TMR3_GLOBAL_IRQHandler
.thumb_set TMR3_GLOBAL_IRQHandler,Default_Handler
.weak TMR4_GLOBAL_IRQHandler
.thumb_set TMR4_GLOBAL_IRQHandler,Default_Handler
.weak I2C1_EVT_IRQHandler
.thumb_set I2C1_EVT_IRQHandler,Default_Handler
.weak I2C1_ERR_IRQHandler
.thumb_set I2C1_ERR_IRQHandler,Default_Handler
.weak I2C2_EVT_IRQHandler
.thumb_set I2C2_EVT_IRQHandler,Default_Handler
.weak I2C2_ERR_IRQHandler
.thumb_set I2C2_ERR_IRQHandler,Default_Handler
.weak SPI1_IRQHandler
.thumb_set SPI1_IRQHandler,Default_Handler
.weak SPI2_I2S2EXT_IRQHandler
.thumb_set SPI2_I2S2EXT_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 EXINT15_10_IRQHandler
.thumb_set EXINT15_10_IRQHandler,Default_Handler
.weak ERTCAlarm_IRQHandler
.thumb_set ERTCAlarm_IRQHandler,Default_Handler
.weak OTGFS1_WKUP_IRQHandler
.thumb_set OTGFS1_WKUP_IRQHandler,Default_Handler
.weak TMR8_BRK_TMR12_IRQHandler
.thumb_set TMR8_BRK_TMR12_IRQHandler,Default_Handler
.weak TMR8_OVF_TMR13_IRQHandler
.thumb_set TMR8_OVF_TMR13_IRQHandler,Default_Handler
.weak TMR8_TRG_HALL_TMR14_IRQHandler
.thumb_set TMR8_TRG_HALL_TMR14_IRQHandler,Default_Handler
.weak TMR8_CH_IRQHandler
.thumb_set TMR8_CH_IRQHandler,Default_Handler
.weak EDMA_Stream8_IRQHandler
.thumb_set EDMA_Stream8_IRQHandler,Default_Handler
.weak XMC_IRQHandler
.thumb_set XMC_IRQHandler,Default_Handler
.weak SDIO1_IRQHandler
.thumb_set SDIO1_IRQHandler,Default_Handler
.weak TMR5_GLOBAL_IRQHandler
.thumb_set TMR5_GLOBAL_IRQHandler,Default_Handler
.weak SPI3_I2S3EXT_IRQHandler
.thumb_set SPI3_I2S3EXT_IRQHandler,Default_Handler
.weak UART4_IRQHandler
.thumb_set UART4_IRQHandler,Default_Handler
.weak UART5_IRQHandler
.thumb_set UART5_IRQHandler,Default_Handler
.weak TMR6_DAC_GLOBAL_IRQHandler
.thumb_set TMR6_DAC_GLOBAL_IRQHandler,Default_Handler
.weak TMR7_GLOBAL_IRQHandler
.thumb_set TMR7_GLOBAL_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 EMAC_IRQHandler
.thumb_set EMAC_IRQHandler,Default_Handler
.weak EMAC_WKUP_IRQHandler
.thumb_set EMAC_WKUP_IRQHandler,Default_Handler
.weak CAN2_TX_IRQHandler
.thumb_set CAN2_TX_IRQHandler,Default_Handler
.weak CAN2_RX0_IRQHandler
.thumb_set CAN2_RX0_IRQHandler ,Default_Handler
.weak CAN2_RX1_IRQHandler
.thumb_set CAN2_RX1_IRQHandler ,Default_Handler
.weak CAN2_SE_IRQHandler
.thumb_set CAN2_SE_IRQHandler,Default_Handler
.weak OTGFS1_IRQHandler
.thumb_set OTGFS1_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 USART6_IRQHandler
.thumb_set USART6_IRQHandler,Default_Handler
.weak I2C3_EVT_IRQHandler
.thumb_set I2C3_EVT_IRQHandler,Default_Handler
.weak I2C3_ERR_IRQHandler
.thumb_set I2C3_ERR_IRQHandler,Default_Handler
.weak OTGFS2_WKUP_IRQHandler
.thumb_set OTGFS2_WKUP_IRQHandler,Default_Handler
.weak OTGFS2_IRQHandler
.thumb_set OTGFS2_IRQHandler,Default_Handler
.weak DVP_IRQHandler
.thumb_set DVP_IRQHandler,Default_Handler
.weak FPU_IRQHandler
.thumb_set FPU_IRQHandler,Default_Handler
.weak UART7_IRQHandler
.thumb_set UART7_IRQHandler,Default_Handler
.weak UART8_IRQHandler
.thumb_set UART8_IRQHandler,Default_Handler
.weak SPI4_IRQHandler
.thumb_set SPI4_IRQHandler,Default_Handler
.weak QSPI2_IRQHandler
.thumb_set QSPI2_IRQHandler,Default_Handler
.weak QSPI1_IRQHandler
.thumb_set QSPI1_IRQHandler,Default_Handler
.weak DMAMUX_IRQHandler
.thumb_set DMAMUX_IRQHandler ,Default_Handler
.weak SDIO2_IRQHandler
.thumb_set SDIO2_IRQHandler ,Default_Handler
.weak ACC_IRQHandler
.thumb_set ACC_IRQHandler,Default_Handler
.weak TMR20_BRK_IRQHandler
.thumb_set TMR20_BRK_IRQHandler,Default_Handler
.weak TMR20_OVF_IRQHandler
.thumb_set TMR20_OVF_IRQHandler,Default_Handler
.weak TMR20_TRG_HALL_IRQHandler
.thumb_set TMR20_TRG_HALL_IRQHandler,Default_Handler
.weak TMR20_CH_IRQHandler
.thumb_set TMR20_CH_IRQHandler,Default_Handler
.weak DMA2_Channel1_IRQHandler
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
.weak DMA2_Channel2_IRQHandler
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
.weak DMA2_Channel3_IRQHandler
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
.weak DMA2_Channel4_IRQHandler
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
.weak DMA2_Channel5_IRQHandler
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
.weak DMA2_Channel6_IRQHandler
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
.weak DMA2_Channel7_IRQHandler
.thumb_set DMA2_Channel7_IRQHandler,Default_Handler

94
CMakeLists.txt Normal file
View File

@ -0,0 +1,94 @@
#-- Service --------------------------------------------------------------------
SET(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/MODULES/CmakeConfig_GCC_CortexM4/gcc_cm4f.cmake)
ENABLE_LANGUAGE(ASM)
CMAKE_MINIMUM_REQUIRED(VERSION 3.8.0)
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -O1")
set(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -O1")
IF (${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR})
MESSAGE(
FATAL_ERROR
"In-source builds not allowed.
Please make a new directory (called a build directory) and run CMake from there.
You may need to remove CMakeCache.txt."
)
ENDIF ()
SET(CMAKE_EXPORT_COMPILE_COMMANDS ON)
#-- Project config -------------------------------------------------------------
PROJECT(SMART_COMPONENTS_AURUS_V2) # Project name
SET(HARDWARE_REVISION 2.1.7) #
SET(VERSION \"2.1.7_UVEOS\") #
SET(VERSION_INTERFACE \"1.0_INTERFACE\") #
SET(HARDWARE_USER_NAME "SMART_COMPONENTS")
#SET(VECT_TAB_OFFSET "0x100000")
SET(VECT_TAB_OFFSET "0x10000")
SET(HEXT_VALUE "8000000")
SET(PLL_NS "125")
#-- Defines --------------------------------------------------------------------
#ADD_DEFINITIONS(-DSET_ACCESS_PROTECTION) # Выставление защиты доступа к памяти
#ADD_DEFINITIONS(-DSET_WDT) # Выставление сторожевого таймера
ADD_DEFINITIONS(-DAURUS_CAR_UI=0)
ADD_DEFINITIONS(-DUART_DMA_SEND)
ADD_DEFINITIONS(-DDEBUG -DAT32F435VGT7 -DAT_START_F435_V1)
ADD_DEFINITIONS(-DFIRMWARE_TEST=1)
ADD_DEFINITIONS(-DFIRMWARE_VERSION=${VERSION})
ADD_DEFINITIONS(-DHARDWARE_REVISION=\"${HARDWARE_REVISION}\")
ADD_DEFINITIONS(-DFIRMWARE_INTERFACE_VERSION=${VERSION_INTERFACE})
ADD_DEFINITIONS(-DVECT_TAB_OFFSET=${VECT_TAB_OFFSET})
ADD_DEFINITIONS(-DHEXT_VALUE=${HEXT_VALUE})
ADD_DEFINITIONS(-DPLL_NS=${PLL_NS})
ADD_DEFINITIONS(-DCMSIS_device_header="at32f435_437.h")
ADD_DEFINITIONS(-DFLASH_PAGE_SIZE=2048)
ADD_DEFINITIONS(-DAMPL_MAX9768_AddrResist=11)
ADD_DEFINITIONS(-DCOM_INT_BIG_BUFFERS)
ADD_DEFINITIONS(-DVARIABLE_TABLE_WITH_ID)
ADD_DEFINITIONS(-DLFS_THREADSAFE=1)
ADD_DEFINITIONS(-DHALF_DUPLEX_NO_DELAY=1)
ADD_DEFINITIONS(-DACCESS_ADC=1)
ADD_DEFINITIONS(-DACCESS_RTC=1)
ADD_DEFINITIONS(-DSTORAGE_ARTERY_CHECK_CLEAR=1)
#ADD_DEFINITIONS(-DSTORAGE_ARTERY_CHECK_WRITE_SECTORS=1) # Включение записи по секторам (Тестово, закоментированно)
#-- Project paths, Include dirs, Sources list ---------------------------------
#ADD_FILES(SOURCES "MODULES/DeviceStartup_ARTERY_AT32F437ZMT7/ld/startup_at32f435_437.s")
include(modular.cmake)
#-- Options --------------------------------------------------------------------
IF (PRINTF_FLOAT STREQUAL "1")
SET(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -u_printf_float")
ENDIF ()
IF (SCANF_FLOAT STREQUAL "1")
SET(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -u_scanf_float")
ENDIF ()
#-- Linker script --------------------------------------------------------------
SET(LDSCRIPT ${CMAKE_SOURCE_DIR}/APP/AT32F437xM_FLASH.ld)
SET(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -T ${LDSCRIPT} -Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -Wl,--print-memory-usage")
#-- Random BuildId Generation ------------------------------------------------------------
SET(RANDOM_BUILD_ID_GEN_FILE ${CMAKE_SOURCE_DIR}/MODULES/CmakeConfig_RandomBuildIdGenerator/version.cmake)
add_custom_target(GEN_RANDOM_BUILD_ID)
ADD_CUSTOM_COMMAND(TARGET GEN_RANDOM_BUILD_ID POST_BUILD
COMMAND ${CMAKE_COMMAND} -P ${RANDOM_BUILD_ID_GEN_FILE})
#-- Project linking ------------------------------------------------------------
ADD_EXECUTABLE(${PROJECT_NAME}.elf ${SOURCES})
TARGET_LINK_LIBRARIES(${PROJECT_NAME}.elf)
add_dependencies(${PROJECT_NAME}.elf GEN_RANDOM_BUILD_ID)
#-- Custom commands ------------------------------------------------------------
ADD_CUSTOM_COMMAND(TARGET ${PROJECT_NAME}.elf POST_BUILD
COMMAND ${CMAKE_OBJCOPY} "-Oihex" ${PROJECT_NAME}.elf ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.hex
COMMAND ${CMAKE_OBJCOPY} "-Obinary" ${PROJECT_NAME}.elf ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.bin
# COMMAND ${CMAKE_OBJDUMP} "-DS" ${PROJECT_NAME}.elf > ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.dasm
COMMAND ${CMAKE_SIZE} ${PROJECT_NAME}.elf)

27
artery_f437.cfg Normal file
View File

@ -0,0 +1,27 @@
#
# This is an STM32F429 discovery board with a single STM32F429ZI chip.
# http://www.st.com/web/catalog/tools/FM116/SC959/SS1532/PF259090
#
source [find interface/stlink.cfg]
transport select hla_swd
source [find target/at32f435xx.cfg]
#reset_config trst_only
#reset_config srst_only
#reset_config trst_and_srst
#reset_config srst_pulls_trst
#reset_config combined
#reset_config srst_gates_jtag
#reset_config trst_push_pull
#reset_config trst_push_pull
reset_config none
#reset_config [none|trst_only|srst_only|trst_and_srst]
#[srst_pulls_trst|trst_pulls_srst|combined|separate]
#[srst_gates_jtag|srst_nogate] [trst_push_pull|trst_open_drain]
#[srst_push_pull|srst_open_drain]
#[connect_deassert_srst|connect_assert_srst]

400
modular.json Normal file
View File

@ -0,0 +1,400 @@
{
"dep": [
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "DeviceStartup_ARTERY_AT32F435_437"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CmakeConfig_GCC_CortexM4"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "FreeRTOSHeap4_CM4_CMSIS"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SystemDelay_CMSIS_RTOS"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SystemSync_CMSIS_RTOS"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SystemDelayInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CmsisCore5"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CmsisRtosThreadUtils"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "GpioPin_ARTERY_AT32F435_437"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SerialPort_ARTERY_AT32"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SerialPort_P2P_CmsisRtos"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SerialPortHalfDuplexInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "Rtc_ARTERY_AT32F435_437"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SpiPort_ARTERY_AT32"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "I2cPort_ARTERY_At32f435_437_v2"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "Adc_ARTERY_AT32"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "Accel_QMA6100P"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AccelDataFlowInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AtGsmCommon"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AtCmdCommon"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "BaseTypes"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "LoggerToSerialPort"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AudioCodec_NAU88U10YG"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "Nmea0183Parser"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "UserInputWatchButtons"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_PowerManagment"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_GpioPins"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Adcs"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_SerialPorts"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Rtcs"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_SpiPorts"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_I2cPorts"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Accel"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_ComInt"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Indication"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_AudioCodec"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_DeviceTesting"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_UserInput"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_StorageOnFlash"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_CrashDetection"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AudioRecorderInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_CLI"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_PWM_SIM7600E"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "EraGlonassUveos"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_AccelCalibration"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AudioPlayerSimcomSim7600E"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AudioRecorderSimcomSim7600E"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CliCmd_Vars"
},
{
"type": "local",
"dir": "APP"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AtCmdSignaturePduSpecific"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SerialPortFrameTpInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SerialPortFrameInterface"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "FirmwareLoader_ARTERY_AT32"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "Amplifier_AW87579"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_Amplifier"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_Codec"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_Test"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_PowerManager"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_DeviceStorage"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Amplifier"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Gsm_Sim7600E"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_MainModesArbiter"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_ADR"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_CanPorts"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CanSerialPortFrame_ARTERY_F435"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_CanUdsUazStatus"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_EXTERNAL_TELEMATICA"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "AtGsmSimCom7600_CA"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_SubsystemSwitcher"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_ModemDataCollector"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_SystemSelector"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "PointEvent"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "ComIntCmd_ThisSubSystem"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_META_UVEOS"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "CmakeConfig_RandomBuildIdGenerator"
},
{
"type": "git",
"provider": "Smart_Components_Aurus",
"repo": "SMART_COMPONENTS_Wdt"
}
]
}