提交 d79898a9 编写于 作者: B Bernard Xiong 提交者: GitHub

Merge pull request #850 from Quintin-Z/master

[BSP] add nv32f100x bsp.
# for module compiling
import os
Import('RTT_ROOT')
cwd = str(Dir('#'))
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
from building import *
TARGET = 'rtthread-nv32f100x.' + rtconfig.TARGET_EXT
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM == 'iar':
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = ['$LINK $SOURCES $LINKFLAGS -o $TARGET --map project.map'])
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# make a building
DoBuilding(TARGET, objs)
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'app')
src = Glob('./src/*.c')
path = [cwd + '/inc',
cwd + '/..',
]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = path)
Return('group')
/*
* File : ledapp.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2017-09-19 Quintin.Z the first version
*/
#include <stdio.h>
#include <rthw.h>
#include <rtdevice.h>
#include "board.h"
#include <rtthread.h>
#ifdef RT_USING_COMPONENTS_INIT
#include <components.h>
#endif /* RT_USING_COMPONENTS_INIT */
#include "gpio.h"
void led_thread_entry(void* parameter)
{
GPIO_Init (GPIOA, GPIO_PTB5_MASK, GPIO_PinOutput);
while(1)
{
GPIO_Toggle (GPIOA, GPIO_PTB5_MASK);
rt_thread_delay(RT_TICK_PER_SECOND / 10);
}
}
/*
* File : _main.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2008 - 2012, RT-Thread Development Team
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2015-11-19 Urey the first version
* 2017-09-20 Quintin.Z modify for nv32
*/
#include "rtthread.h"
#include "finsh.h"
extern void led_thread_entry(void* parameter);
int main(void)
{
rt_thread_t thread;
#ifdef RT_USING_FINSH
finsh_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
/* Create led thread */
thread = rt_thread_create("led",
led_thread_entry, RT_NULL,
256, 20, 20);
if(thread != RT_NULL)
rt_thread_startup(thread);
return 0;
}
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'board')
src = Glob('./src/*.c')
path = [cwd + '/inc'
]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = path)
Return('group')
/*
* File : board.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006-2017, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2017-09-19 Quintin.Z the first version
*/
// <<< Use Configuration Wizard in Context Menu >>>
#ifndef __BOARD_H__
#define __BOARD_H__
#include <stdint.h>
#include <stdbool.h>
// <o> Internal SRAM memory size[Kbytes] <8>
#define NV32_SRAM_SIZE 8
#define NV32_SRAM_END (0x1FFFF800 + NV32_SRAM_SIZE * 1024)
void rt_hw_board_init(void);
#endif
/*
* File : drv_uart.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006-2017, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2017-09-19 Quintin.Z the first version
*/
#ifndef __DRV_UART_H__
#define __DRV_UART_H__
#include <rthw.h>
#include <rtthread.h>
void rt_hw_uart_init(void);
#endif
/******************************************************************************
* @brief provide high-level startup routines for NV32Fxx.
*
*******************************************************************************/
/* Function prototypes */
void cpu_identify(void);
void flash_identify(void);
void start(void);
/******************************************************************************
* @brief provide system init routine/configuration for KExx.
*
*******************************************************************************/
/********************************************************************/
#ifndef SYSINIT_H_
#define SYSINIT_H_
/******************************************************************************
* Includes
******************************************************************************/
/******************************************************************************
* Constants
******************************************************************************/
/******************************************************************************
* Macros
******************************************************************************/
#define SIM_SCGC_VALUE 0x00003000L
/******************************************************************************
* Global variables
******************************************************************************/
/******************************************************************************
* Global functions
******************************************************************************/
void sysinit (void);
void enable_abort_button(void);
void end_test(void);
/********************************************************************/
#endif /* SYSINIT_H_ */
/*
* File : board.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006-2017, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2017-09-19 Quintin.Z the first version
*/
#include <rthw.h>
#include <rtthread.h>
#include "sysinit.h"
#include "board.h"
#include "drv_uart.h"
#include "nv32.h"
/* RT_USING_COMPONENTS_INIT */
#ifdef RT_USING_COMPONENTS_INIT
#include <components.h>
#endif
#define portNVIC_SYSTICK_CTRL ( ( volatile uint32_t *) 0xe000e010 )
#define portNVIC_SYSTICK_LOAD ( ( volatile uint32_t *) 0xe000e014 )
#define portNVIC_INT_CTRL ( ( volatile uint32_t *) 0xe000ed04 )
#define portNVIC_SYSPRI2 ( ( volatile uint32_t *) 0xe000ed20 )
#define portNVIC_SYSTICK_CLK 0x00000004
#define portNVIC_SYSTICK_INT 0x00000002
#define portNVIC_SYSTICK_ENABLE 0x00000001
#define portNVIC_PENDSVSET 0x10000000
#define portMIN_INTERRUPT_PRIORITY ( 255UL )
#define portNVIC_PENDSV_PRI ( portMIN_INTERRUPT_PRIORITY << 16UL )
#define portNVIC_SYSTICK_PRI ( portMIN_INTERRUPT_PRIORITY << 24UL )
#ifdef __CC_ARM
extern int Image$$RW_IRAM1$$ZI$$Limit;
#define NV32_SRAM_BEGIN (&Image$$RW_IRAM1$$ZI$$Limit)
#elif __ICCARM__
#pragma section="HEAP"
#define NV32_SRAM_BEGIN (__segment_end("HEAP"))
#else
extern int __bss_end;
#define NV32_SRAM_BEGIN (&__bss_end)
#endif
/*******************************************************************************
* Function Name : assert_failed
* Description : Reports the name of the source file and the source line number
* where the assert error has occurred.
* Input : - file: pointer to the source file name
* - line: assert error line source number
* Output : None
* Return : None
*******************************************************************************/
void assert_failed(uint8_t* file, uint32_t line)
{
rt_kprintf("\n\r Wrong parameter value detected on\r\n");
rt_kprintf(" file %s\r\n", file);
rt_kprintf(" line %d\r\n", line);
while (1) ;
}
/**
* This is the timer interrupt service routine.
*
*/
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
/**
* This function will initial STM32 board.
*/
void rt_hw_board_init()
{
/* Configure the SysTick */
*(portNVIC_SYSTICK_LOAD) = ( 40000000 / RT_TICK_PER_SECOND ) - 1UL;
*(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE;
rt_hw_uart_init();
/* Call components board initial (use INIT_BOARD_EXPORT()) */
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef RT_USING_HEAP
rt_system_heap_init((void*)NV32_SRAM_BEGIN, (void*)NV32_SRAM_END);
#endif
}
long cmd_reset(int argc, char** argv)
{
NVIC_SystemReset();
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_reset, __cmd_reset, Reset Board.);
/*@}*/
/*
* File : drv_uart.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006-2017, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2017-09-19 Quintin.Z the first version
*/
#include <rtdevice.h>
#include <board.h>
#include "drv_uart.h"
#include "nv32.h"
#include "uart.h"
#include "sim.h"
/* NV32 uart driver */
struct nv32_uart
{
UART_Type* uart_device;
IRQn_Type irq;
};
static rt_err_t nv32_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
struct nv32_uart* uart;
UART_ConfigBaudrateType uart_config;
RT_ASSERT(serial != RT_NULL);
RT_ASSERT(cfg != RT_NULL);
uart = (struct nv32_uart *)serial->parent.user_data;
uart_config.u32SysClkHz = BUS_CLK_HZ;
uart_config.u32Baudrate = cfg->baud_rate;
UART_SetBaudrate(uart->uart_device, &uart_config);
if (cfg->data_bits == DATA_BITS_8)
{
UART_Set8BitMode(uart->uart_device);
}
else if(cfg->data_bits == DATA_BITS_9)
{
UART_Set9BitMode(uart->uart_device);
}
if (cfg->stop_bits == STOP_BITS_1)
{
uart->uart_device->BDH &= (~UART_BDH_SBNS_MASK);
}
else if (cfg->stop_bits == STOP_BITS_2)
{
uart->uart_device->BDH |= UART_BDH_SBNS_MASK;
}
/* Enable receiver and transmitter */
uart->uart_device->C2 |= (UART_C2_TE_MASK | UART_C2_RE_MASK );
UART_EnableInterrupt(UART0, UART_RxBuffFullInt);
NVIC_EnableIRQ(UART0_IRQn);
return RT_EOK;
}
static rt_err_t nv32_control(struct rt_serial_device *serial, int cmd, void *arg)
{
struct nv32_uart* uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct nv32_uart *)serial->parent.user_data;
switch (cmd)
{
case RT_DEVICE_CTRL_CLR_INT:
/* disable rx irq */
NVIC_DisableIRQ(uart->irq);
break;
case RT_DEVICE_CTRL_SET_INT:
/* enable rx irq */
NVIC_EnableIRQ(uart->irq);
break;
}
return RT_EOK;
}
static int nv32_putc(struct rt_serial_device *serial, char c)
{
struct nv32_uart* uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct nv32_uart *)serial->parent.user_data;
while (!(uart->uart_device->S1 & UART_S1_TDRE_MASK));
uart->uart_device->D = (uint8_t)c;
return 1;
}
static int nv32_getc(struct rt_serial_device *serial)
{
int ch;
struct nv32_uart* uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct nv32_uart *)serial->parent.user_data;
ch = -1;
if (uart->uart_device->S1 & UART_S1_RDRF_MASK)
{
ch = uart->uart_device->D;
}
return ch;
}
static const struct rt_uart_ops nv32_uart_ops =
{
nv32_configure,
nv32_control,
nv32_putc,
nv32_getc,
};
#ifdef RT_USING_UART0
struct nv32_uart uart0 =
{
UART0,
UART0_IRQn,
};
struct rt_serial_device serial0;
void UART0_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
if(UART0->S1 & UART_S1_RDRF_MASK)
{
rt_hw_serial_isr(&serial0, RT_SERIAL_EVENT_RX_IND);
}
/* leave interrupt */
rt_interrupt_leave();
}
#endif
void rt_hw_uart_init(void)
{
struct nv32_uart* uart;
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
#ifdef RT_USING_UART0
uart = &uart0;
serial0.ops = &nv32_uart_ops;
serial0.config = config;
SIM->PINSEL |= SIM_PINSEL_UART0PS_MASK;
SIM->SCGC |= SIM_SCGC_UART0_MASK;
uart->uart_device->C2 &= ~(UART_C2_TE_MASK | UART_C2_RE_MASK );
/* Configure the UART for 8-bit mode, no parity */
uart->uart_device->C1 = 0;
rt_hw_serial_register(&serial0, "uart0", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, uart);
#endif
}
/******************************************************************************
* @brief provide high-level startup routines for NV32Fxx.
*
*******************************************************************************/
#include "start.h"
#include "common.h"
#include "wdog.h"
#include "sysinit.h"
/********************************************************************/
/********************************************************************/
/*!
* \brief flash SystemInit
* \return None
*
* this is a system initialization function which dediu16Cated in Keil
* others complier don't use it.
* it is similar to start function
*/
void SystemInit( void )
{
#if !defined(ENABLE_WDOG)
/* Disable the watchdog ETMer */
WDOG_Disable();
#else
/* Disable the watchdog ETMer but enable update */
WDOG_DisableWDOGEnableUpdate();
#endif
sysinit();
}
/*****************************************************************************
* @brief provide system init routine/configuration for NV32Fxx.
*
*******************************************************************************/
#include "common.h"
#include "sysinit.h"
#include "sim.h"
#include "uart.h"
#include "ics.h"
/********************************************************************/
uint16_t global_pass_count = 0;
uint16_t global_fail_count = 0;
void print_sys_log(void);
void UART_InitPrint(void);
/*****************************************************************************//*!
+FUNCTION----------------------------------------------------------------
* @function name: sysinit
*
* @brief initalize system including SIM, ICS, UART, etc
*
* @param none
*
* @return none
*
* @ Pass/ Fail criteria: none
*****************************************************************************/
void sysinit (void)
{
SIM_ConfigType sSIMConfig = {{0}, 0};
ICS_ConfigType sICSConfig = {0};
/* initialize the Pass/Fail counts to 0 */
global_pass_count = 0;
global_fail_count = 0;
EFMCR &= 0xFFFF0001; // set wait state 1
#if defined(TRIM_IRC)
/* if not trimmed, do trim first */
ICS_Trim(ICS_TRIM_VALUE);
#endif
/*
* Enable SWD pin, RESET pin
*/
/*
* NOTE: please make sure other register bits are also write-once and
* need add other bit mask here if needed.
*/
#if defined(SPI0_PINREMAP)
sSIMConfig.u32PinSel |= SIM_PINSEL_SPI0PS_MASK;
#endif
#if defined(OUTPUT_BUSCLK)
sSIMConfig.sBits.bEnableCLKOUT = 1; /* output bus clock if enabled */
#endif
#if defined(DISABLE_NMI)
sSIMConfig.sBits.bDisableNMI = 1;
#endif
#if !defined(CPU_NV32M3)
/* make sure clocks to peripheral modules are enabled */
sSIMConfig.u32SCGC |= SIM_SCGC_SWD_MASK | SIM_SCGC_FLASH_MASK |
SIM_SCGC_UART0_MASK | SIM_SCGC_UART1_MASK |
SIM_SCGC_UART2_MASK
;
#else
sSIMConfig.u32SCGC |= SIM_SCGC_SWD_MASK | SIM_SCGC_FLASH_MASK |
SIM_SCGC_UART0_MASK
;
#endif
#if !defined(CPU_NV32)
/* bus clock divided by 2 */
// sSIMConfig.u32BusDiv |= SIM_CLKDIV_OUTDIV2_MASK;
#endif
// sSIMConfig.sBits.bBusDiv |= SIM_BUSDIV_BUSDIV_MASK;
SIM_Init(&sSIMConfig); /* initialize SIM */
#if defined(XOSC_STOP_ENABLE)
sICSConfig.oscConfig.bStopEnable = 1; /* enabled in stop mode */
#endif
#if defined(CRYST_HIGH_GAIN)
sICSConfig.oscConfig.bGain = 1; /* high gain */
#endif
#if (EXT_CLK_FREQ_KHZ >=4000)
sICSConfig.oscConfig.bRange = 1; /* high range */
#endif
sICSConfig.oscConfig.bEnable = 1; /* enable OSC */
sICSConfig.u32ClkFreq = EXT_CLK_FREQ_KHZ;
#if defined(USE_FEE)
sICSConfig.u8ClkMode = ICS_CLK_MODE_FEE;
#elif defined(USE_FBE_OSC)
sICSConfig.u8ClkMode = ICS_CLK_MODE_FBE_OSC;
#elif defined(USE_FEE_OSC)
sICSConfig.u8ClkMode = ICS_CLK_MODE_FEE_OSC;
#elif defined(USE_FBILP)
sICSConfig.u8ClkMode = ICS_CLK_MODE_FBILP;
#elif defined(USE_FBELP)
sICSConfig.u8ClkMode = ICS_CLK_MODE_FBELP;
#endif
ICS_Init(&sICSConfig); /* initialize ICS */
}
void NMI_Handler(void)
{
while(1);
}
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'lib')
src = Glob('./src/*.c')
src += Glob('./src/*.s')
path = [cwd + '/inc'
]
CPPDEFINES = ['NV32', 'KEIL']
group = DefineGroup('Lib', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')
此差异已折叠。
此差异已折叠。
/******************************************************************************
*
* NOTE:系统所使用的一些宏定义,以及时钟模式的选择。
******************************************************************************/
#ifndef _NVxx_CONFIG_H_
#define _NVxx_CONFIG_H_
#include <stdint.h>
#define CPU_NV32
#define TEST
//#define TRIM_IRC /*!< 是否使用定义的TRIM值来校准内部IRC,若注释则使用出厂校准的TRIM值出厂校准至37.5K--48M */
//#define SPI0_PINREMAP /*!< SPI0的管脚映射定义 */
//#define ENABLE_WDOG /*!< 使能看门狗 */
//#define DISABLE_NMI /*!< 禁用NMI中断输入引脚 */
/*! 定义是否打印系统信息 */
//#define PRINT_SYS_LOG
#if !defined(BOOT_LOADER)
#endif
//#define OUTPUT_BUSCLK /*!< 定义是否输出系统时钟,输出引脚为PH2 */
#define ICS_TRIM_VALUE 0x2c
/*! 定义时钟的时钟模式以及频率
*/
//#define USE_FEE /*!< 使用外部时钟FEE模式 */
//#define USE_FEE_OSC /*!< 使用外部时钟输入OSC模式 */
#define USE_FEI /*!< 使用系统内部时钟IRC */
// #define USE_FBELP
//#define USE_FBE_OSC
/*! 定义外部晶振频率. */
//#define EXT_CLK_FREQ_KHZ 32 /* in KHz */
//#define EXT_CLK_FREQ_KHZ 4000 /* in KHz */
//#define EXT_CLK_FREQ_KHZ 4000 /* in KHz */
//#define EXT_CLK_FREQ_KHZ 1000 /* in KHz */
#define EXT_CLK_FREQ_KHZ 10000 /* in KHz */
/*! 定义所使用的UART口 */
#define TERM_PORT UART1 /*!< 定义使用UART1口,开发板上默认使用UART1口 */
/* 定义总线时钟主频 */
#if defined(USE_FEI)
#define BUS_CLK_HZ 40000000L
#elif (EXT_CLK_FREQ_KHZ == 10000)
#define BUS_CLK_HZ 50000000L
#elif (EXT_CLK_FREQ_KHZ == 12000)
#define BUS_CLK_HZ 30000000L
#elif (EXT_CLK_FREQ_KHZ == 8000)
#define BUS_CLK_HZ 24000000L
#elif (EXT_CLK_FREQ_KHZ == 4000)
#define BUS_CLK_HZ 40000000L
#elif (EXT_CLK_FREQ_KHZ == 32)
#define BUS_CLK_HZ 16777216L
#else
#define BUS_CLK_HZ 60000000L
#endif
/*! define UART baud rate */
#define UART_PRINT_BITRATE 115200 /*! UART波特率 */
#endif /* NVxx_CONFIG_H_ */
/******************************************************************************
* @brief header file for ACMP utilities.
*
*******************************************************************************
*
* provide APIs for accessing ACMP
******************************************************************************/
#ifndef _MY_ACMP_H_
#define _MY_ACMP_H_
#ifdef __cplusplus
extern "C" {
#endif
/******************************************************************************
* Includes
******************************************************************************/
/******************************************************************************
* Constants
******************************************************************************/
/* DAC reference select */
enum
{
DAC_REF_BANDGAP = 0,
DAC_REF_VDDA
};
/******************************************************************************
* Macros
******************************************************************************/
/******************************************************************************
* ACMP module number definition *
******************************************************************************/
#define MAX_ACMP_NO 2
/******************************************************************************
* ACMP positive and negative pin select definition
*
*//*! @addtogroup acmp_pinsel_list
* @{
*******************************************************************************/
#define ACMP_INPUT_P_EXT0 (0<<4) /*!< positive pin select external pin 0 */
#define ACMP_INPUT_P_EXT1 (1<<4) /*!< positive pin select external pin 1 */
#define ACMP_INPUT_P_EXT2 (2<<4) /*!< positive pin select external pin 2 */
#define ACMP_INPUT_P_DAC (3<<4) /*!< positive pin select internal DAC */
#define ACMP_INPUT_N_EXT0 0 /*!< positive pin select external pin 0 */
#define ACMP_INPUT_N_EXT1 1 /*!< positive pin select external pin 1 */
#define ACMP_INPUT_N_EXT2 2 /*!< positive pin select external pin 2 */
#define ACMP_INPUT_N_DAC 3 /*!< positive pin select internal DAC */
/*! @} End of acmp_pinsel_list */
/******************************************************************************
* ACMP interrupt sensitivity edge definition
*
*//*! @addtogroup acmp_intedgesel
* @{
*******************************************************************************/
#define ACMP_SENSITIVITYMODE_FALLING 0 /*!< interrupt on falling edge */
#define ACMP_SENSITIVITYMODE_RISING 1 /*!< interrupt on rising edge */
#define ACMP_SENSITIVITYMODE_ANY 3 /*!< interrupt on falling or rising edge */
/*! @} End of acmp_intedgesel */
/******************************************************************************
* ACMP hysterisis selection definition
*
*//*! @addtogroup acmp_hyst
* @{
*******************************************************************************/
#define ACMP_HYST_20MV (0<<6) /*!< 20mv hyst */
#define ACMP_HYST_30MV (1<<6) /*!< 30mv hyst */
/*! @} End of acmp_hyst */
/******************************************************************************
* ACMP internal DAC reference selection definition
*
*//*! @addtogroup acmp_dacref
* @{
*******************************************************************************/
#define ACMP_DAC_REFERENCE_BANDGAP (0<<6) /*!< select bandgap as refference */
#define ACMP_DAC_REFERENCE_VDDA (1<<6) /*!< select VDDA as refference */
/*! @} End of acmp_dacref */
/******************************************************************************
* Types
******************************************************************************/
/*! @brief ACMP_CALLBACK function declaration */
typedef void (*ACMP_CallbackPtr)(void);
/*! @} End of acmp_callback */
/******************************************************************************
* ACMP control status struct
*
*//*! @addtogroup acmp_ctrlstatusstruct
* @{
*******************************************************************************/
/*!
* @brief ACMP control and status fields type.
*
*/
typedef union
{
uint8_t byte; /*!< byte field of union type */
struct
{
uint8_t bMod : 2; /*!< Sensitivity modes of the interrupt trigger */
uint8_t bOutEn : 1; /*!< Output can be placed onto an external pin */
uint8_t bOutState : 1; /*!< The current value of the analog comparator output */
uint8_t bIntEn : 1; /*!< ACMP interrupt enable */
uint8_t bIntFlag : 1; /*!< ACMP Interrupt Flag Bit */
uint8_t bHyst : 1; /*!< Selects ACMP hystersis */
uint8_t bEn : 1; /*!< Enables the ACMP module */
}bits; /*!< bitfield of union type */
}ACMP_CtrlStatusType, *ACMP_CtrlStatusPtr; /*!< ACMP Control/Status reg structure */
/*! @} End of acmp_ctrlstatusstruct */
/******************************************************************************
* ACMP pin select struct
*
*//*! @addtogroup acmp_pinselectstruct
* @{
*******************************************************************************/
/*!
* @brief ACMP external pins control struct.
*
*/
typedef union
{
uint8_t byte; /*!< byte field of union type */
struct
{
uint8_t bNegPin : 2; /*!< Negative pin select */
uint8_t : 2;
uint8_t bPosPin : 2; /*!< Positive pin select */
uint8_t : 2;
}bits; /*!< bitfield of union type */
}ACMP_PinSelType, *ACMP_PinSelPtr; /*!< ACMP Pin select structure */
/*! @} End of acmp_pinselectstruct */
/******************************************************************************
* ACMP DAC control struct
*
*//*! @addtogroup acmp_dacctrlstruct
* @{
*******************************************************************************/
/*!
* @brief ACMP internal ADC control struct.
*
*/
typedef union
{
uint8_t byte; /*!< byte field of union type */
struct
{
uint8_t bVal : 6; /*!< 6 bit DAC value */
uint8_t bRef : 1; /*!< 6 bit DAC reference select */
uint8_t bEn : 1; /*!< 6 bit DAC enable bit */
}bits; /*!< bitfield of union type */
}ACMP_DACType, *ACMP_DACPtr; /*!< ACMP DAC control structure */
/*! @} End of acmp_dacctrlstruct */
/******************************************************************************
* ACMP pin enable union
*
*//*! @addtogroup acmp_pinenunion
* @{
*******************************************************************************/
/*!
* @brief ACMP external input pin enable control struct.
*
*/
typedef union
{
uint8_t byte; /*!< byte field of union type */
struct
{
uint8_t bEn : 3; /*!< ACMP external input pin enable */
uint8_t bRsvd : 5;
}bits; /*!< bitfield of union type */
}ACMP_PinEnType, *ACMP_PinEnPtr; /*!< ACMP Pin enable structure */
/*! @} End of acmp_pinenunion */
/******************************************************************************
* ACMP config struct
*
*//*! @addtogroup acmp_configstruct
* @{
*******************************************************************************/
/*!
* @brief ACMP module configuration struct.
*
*/
typedef struct
{
ACMP_CtrlStatusType sCtrlStatus; /*!< ACMP control and status */
ACMP_PinSelType sPinSelect; /*!< ACMP pin select */
ACMP_DACType sDacSet; /*!< ACMP internal dac set */
ACMP_PinEnType sPinEnable; /*!< ACMP external pin control */
}ACMP_ConfigType, *ACMP_ConfigPtr;
/*! @} End of acmp_configstruct */
/******************************************************************************
* Global variables
******************************************************************************/
/*!
* inline functions
*/
/******************************************************************************
* ACMP api list.
*
*//*! @addtogroup acmp_api_list
* @{
*******************************************************************************/
/*****************************************************************************//*!
*
* @brief enable the acmp module.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_Disable.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_Enable(ACMP_Type *pACMPx)
{
pACMPx->CS |= ACMP_CS_ACE_MASK;
}
/*****************************************************************************//*!
*
* @brief disable the acmp module.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_Enable.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_Disable(ACMP_Type *pACMPx)
{
pACMPx->CS &= ~ACMP_CS_ACE_MASK;
}
/*****************************************************************************//*!
*
* @brief select sensitivity modes of the interrupt trigger.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8EdgeSelect falling or rising selction, 0~3.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_SelectIntMode(ACMP_Type *pACMPx, uint8_t u8EdgeSelect)
{
pACMPx->CS &= ~ACMP_CS_ACMOD_MASK;
pACMPx->CS |= ACMP_CS_ACMOD(u8EdgeSelect & 0x3);
}
/*****************************************************************************//*!
*
* @brief enable the ACMP module analog comparator output.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_DisablePinOut.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_EnablePinOut(ACMP_Type *pACMPx)
{
pACMPx->CS |= ACMP_CS_ACOPE_MASK;
}
/*****************************************************************************//*!
*
* @brief disable the ACMP module analog comparator output.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_EnablePinOut.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DisablePinOut(ACMP_Type *pACMPx)
{
pACMPx->CS &= ~ACMP_CS_ACOPE_MASK;
}
/*****************************************************************************//*!
*
* @brief select ACMP hystersis.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8HystSelect ACMP_HYST_20MV or ACMP_HYST_30MV.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_SelectHyst(ACMP_Type *pACMPx, uint8_t u8HystSelect)
{
pACMPx->CS &= ~ACMP_CS_HYST_MASK;
pACMPx->CS |= u8HystSelect;
}
/*****************************************************************************//*!
*
* @brief enable the acmp module interrupt.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_DisableInterrupt.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_EnableInterrupt(ACMP_Type *pACMPx)
{
pACMPx->CS |= ACMP_CS_ACIE_MASK;
}
/*****************************************************************************//*!
*
* @brief disable the acmp module interrupt.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_EnableInterrupt.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DisableInterrupt(ACMP_Type *pACMPx)
{
pACMPx->CS &= ~ACMP_CS_ACIE_MASK;
}
/*****************************************************************************//*!
*
* @brief get the interrupt flag bit.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_ClrFlag.
*
*****************************************************************************/
__STATIC_INLINE uint8_t ACMP_GetFlag(ACMP_Type *pACMPx)
{
return (pACMPx->CS & ACMP_CS_ACF_MASK);
}
/*****************************************************************************//*!
*
* @brief clear the interrupt flag bit.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_GetFlag.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_ClrFlag(ACMP_Type *pACMPx)
{
pACMPx->CS &= ~ACMP_CS_ACF_MASK;
}
/*****************************************************************************//*!
*
* @brief ACMP Positive Input Select.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8PosPinSel positive input select, ACMP_INPUT_P_EXT0~2 or ACMP_INPUT_P_DAC.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_NegativeInputSelect.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_PositiveInputSelect(ACMP_Type *pACMPx, uint8_t u8PosPinSel)
{
pACMPx->C0 &= ~ACMP_C0_ACPSEL_MASK;
pACMPx->C0 |= u8PosPinSel;
}
/*****************************************************************************//*!
*
* @brief ACMP Negative Input Select.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8NegPinSel negative input select, ACMP_INPUT_N_EXT0~2 or ACMP_INPUT_N_DAC.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_PositiveInputSelect.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_NegativeInputSelect(ACMP_Type *pACMPx, uint8_t u8NegPinSel)
{
pACMPx->C0 &= ~ACMP_C0_ACNSEL_MASK;
pACMPx->C0 |= u8NegPinSel;
}
/*****************************************************************************//*!
*
* @brief Enable 6 bit DAC in ACMP module.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_DacDisable.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DacEnable(ACMP_Type *pACMPx)
{
pACMPx->C1 |= ACMP_C1_DACEN_MASK;
}
/*****************************************************************************//*!
*
* @brief Disable 6 bit DAC in ACMP module.
*
* @param[in] pACMPx pointer to an ACMP module.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
* @see ACMP_DacEnable.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DacDisable(ACMP_Type *pACMPx)
{
pACMPx->C1 &= ~ACMP_C1_DACEN_MASK;
}
/*****************************************************************************//*!
*
* @brief ACMP 6 bit DAC Reference Select.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8RefSelect dac reference select:ACMP_DAC_REFERENCE_BANDGAP or ACMP_DAC_REFERENCE_VDDA.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DacReferenceSelect(ACMP_Type *pACMPx, uint8_t u8RefSelect)
{
pACMPx->C1 &= ~ACMP_C1_DACREF_MASK;
pACMPx->C1 |= u8RefSelect;
}
/*****************************************************************************//*!
*
* @brief ACMP 6 bit DAC Output Value Set.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8DacValue dac output set, Voutput= (Vin/64)x(DACVAL[5:0]+1).
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_DacOutputSet(ACMP_Type *pACMPx, uint8_t u8DacValue)
{
ASSERT(!(u8DacValue & (~ACMP_C1_DACVAL_MASK)));
pACMPx->C1 &= ~ACMP_C1_DACVAL_MASK;
pACMPx->C1 |= ACMP_C1_DACVAL(u8DacValue);
}
/*****************************************************************************//*!
*
* @brief Enable ACMP input pin.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8InputPin ACMP external pin, 0~2.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_InputPinEnable(ACMP_Type *pACMPx, uint8_t u8InputPin)
{
ASSERT(!(u8InputPin & (~ACMP_C2_ACIPE_MASK)));
pACMPx->C2 |= ACMP_C2_ACIPE(u8InputPin);
}
/*****************************************************************************//*!
*
* @brief Disable ACMP input pin.
*
* @param[in] pACMPx pointer to an ACMP module.
* @param[in] u8InputPin ACMP external pin, 0~2.
*
* @return none.
*
* @ Pass/ Fail criteria: none.
*
*****************************************************************************/
__STATIC_INLINE void ACMP_InputPinDisable(ACMP_Type *pACMPx, uint8_t u8InputPin)
{
ASSERT(!(u8InputPin & (~ACMP_C2_ACIPE_MASK)));
pACMPx->C2 &= ~ACMP_C2_ACIPE(u8InputPin);
}
/*! @} End of acmp_api_list */
/******************************************************************************
* Global functions
******************************************************************************/
void ACMP_Init(ACMP_Type *pACMPx, ACMP_ConfigType *pConfig);
void ACMP_DeInit(ACMP_Type *pACMPx);
void ACMP_ConfigDAC(ACMP_Type *pACMPx, ACMP_DACType *pDACConfig);
void ACMP_SetCallback(ACMP_Type *pACMPx, ACMP_CallbackPtr pfnCallback);
#ifdef __cplusplus
}
#endif
#endif /* _MY_ACMP_H_ */
此差异已折叠。
/******************************************************************************
*
* @brief provide generic high-level routines for ARM Cortex M0/M0+ processors.
*
*******************************************************************************/
#ifndef _CPU_ARM_CM0_H
#define _CPU_ARM_CM0_H
/*ARM Cortex M0 implementation for interrupt priority shift*/
#define ARM_INTERRUPT_LEVEL_BITS 2
/***********************************************************************/
/*!< Macro to enable all interrupts. */
#ifndef KEIL
#define EnableInterrupts asm(" CPSIE i");
#else
#define EnableInterrupts __enable_irq()
#endif
/*!< Macro to disable all interrupts. */
#ifndef KEIL
#define DisableInterrupts asm(" CPSID i");
#else
#define DisableInterrupts __disable_irq()
#endif
#define disable_irq(irq) NVIC_DisableIRQ(irq)
#define enable_irq(irq) NVIC_EnableIRQ(irq)
#define set_irq_priority(irq, prio) NVIC_SetPriority(irq, prio)
/***********************************************************************/
/*
* Misc. Defines
*/
#ifdef FALSE
#undef FALSE
#endif
#define FALSE (0)
#ifdef TRUE
#undef TRUE
#endif
#define TRUE (1)
#ifdef NULL
#undef NULL
#endif
#define NULL (0)
#ifdef ON
#undef ON
#endif
#define ON (1)
#ifdef OFF
#undef OFF
#endif
#define OFF (0)
#undef ENABLE
#define ENABLE (1)
#undef DISABLE
#define DISABLE (0)
/***********************************************************************/
/*
* The basic data types
*/
typedef unsigned char uint8; /* 8 bits */
typedef unsigned short int uint16; /* 16 bits */
typedef unsigned long int uint32; /* 32 bits */
typedef char int8; /* 8 bits */
typedef short int int16; /* 16 bits */
typedef int int32; /* 32 bits */
typedef volatile int8 vint8; /* 8 bits */
typedef volatile int16 vint16; /* 16 bits */
typedef volatile int32 vint32; /* 32 bits */
typedef volatile uint8 vuint8; /* 8 bits */
typedef volatile uint16 vuint16; /* 16 bits */
typedef volatile uint32 vuint32; /* 32 bits */
// function prototype for main function
int main(void);
/***********************************************************************/
// function prototypes for arm_cm0.c
void stop (void);
void wait (void);
void write_vtor (int);
/***********************************************************************/
#endif /* _CPU_ARM_CM4_H */
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
#ifndef EEPROM_H_
#define EEPROM_H_
/******************************************************************************
* Includes
******************************************************************************/
#include "common.h"
#define EERPOM_SIZE 1024 // in bytes
#define EEPROM_START_ADR 0x00401000
#define EEPROM_ERR_SUCCESS 0x01
#define EEPROM_ADR_OverFlow 0x02
#define EEPROM_ERR_INVALID_PARAM 0x04
#define EEPROM_BLANK 0xffffffff
#define EEPROM_SECTOR_MASK 0x00401200
#define EEPROM_ARRAY_ADR_MASK 0x1ff
uint16_t Adress_Js(uint32_t adr);
uint16_t EEPROM_Erase(uint32_t adr);
uint32_t EEPROM_Read(uint32_t adr);
uint8_t EEPROM_ReadByte(uint32_t adr);
uint16_t EEPROM_Write(uint32_t adr, uint32_t Data);
uint16_t EEPROM_WriteByte(uint32_t adr, uint8_t Data);
uint16_t EERPOM_Writeup4byte(uint32_t adr, uint8_t *pData,uint32_t length);
#endif
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册