From 5186c6a3e0ced52e32f293c4f765ce9f5d2c5ed6 Mon Sep 17 00:00:00 2001 From: eddyem Date: Fri, 20 Nov 2020 01:14:53 +0300 Subject: [PATCH] start adding examples --- src/Makefile | 14 + src/Makefile.include | 62 +++ src/Readme.md | 2 + src/include/adc.c | 113 +++++ src/include/adc.h | 39 ++ src/include/bootloader.h | 4 + src/include/ch554.h | 752 ++++++++++++++++++++++++++++++++++ src/include/ch554_datatypes.h | 125 ++++++ src/include/ch554_usb.h | 337 +++++++++++++++ src/include/debug.c | 125 ++++++ src/include/debug.h | 211 ++++++++++ src/include/i2c.c | 120 ++++++ src/include/i2c.h | 32 ++ src/include/pwm.h | 25 ++ src/include/spi.c | 131 ++++++ src/include/spi.h | 72 ++++ src/include/touchkey.c | 119 ++++++ src/include/touchkey.h | 49 +++ src/pwm/Makefile | 7 + src/pwm/main.c | 40 ++ src/pwm/pwm.bin | Bin 0 -> 310 bytes src/touchkey/Makefile | 8 + src/touchkey/main.c | 60 +++ src/touchkey/touchkey.bin | Bin 0 -> 3137 bytes 24 files changed, 2447 insertions(+) create mode 100644 src/Makefile create mode 100644 src/Makefile.include create mode 100644 src/Readme.md create mode 100644 src/include/adc.c create mode 100644 src/include/adc.h create mode 100644 src/include/bootloader.h create mode 100644 src/include/ch554.h create mode 100644 src/include/ch554_datatypes.h create mode 100644 src/include/ch554_usb.h create mode 100644 src/include/debug.c create mode 100644 src/include/debug.h create mode 100644 src/include/i2c.c create mode 100644 src/include/i2c.h create mode 100644 src/include/pwm.h create mode 100644 src/include/spi.c create mode 100644 src/include/spi.h create mode 100644 src/include/touchkey.c create mode 100644 src/include/touchkey.h create mode 100644 src/pwm/Makefile create mode 100644 src/pwm/main.c create mode 100644 src/pwm/pwm.bin create mode 100644 src/touchkey/Makefile create mode 100644 src/touchkey/main.c create mode 100644 src/touchkey/touchkey.bin diff --git a/src/Makefile b/src/Makefile new file mode 100644 index 0000000..ae9fee3 --- /dev/null +++ b/src/Makefile @@ -0,0 +1,14 @@ +SUBDIRS = $(shell ls -d */) + +.PHONY: $(SUBDIRS) + + +$(SUBDIRS): + $(MAKE) -C $@ + +.DEFAULT_GOAL := all +all: $(SUBDIRS) + + +print-% : ; @echo $* = $($*) + diff --git a/src/Makefile.include b/src/Makefile.include new file mode 100644 index 0000000..4bd2c66 --- /dev/null +++ b/src/Makefile.include @@ -0,0 +1,62 @@ +####################################################### + +# toolchain +CC = sdcc +OBJCOPY = objcopy +WCHISP ?= ch55tool -b + +####################################################### + +FREQ_SYS ?= 24000000 + +XRAM_SIZE ?= 0x0400 + +XRAM_LOC ?= 0x0000 + +CODE_SIZE ?= 0x3800 + +ROOT_DIR := $(dir $(abspath $(lastword $(MAKEFILE_LIST)))) + +CFLAGS := -V -mmcs51 --model-small \ + --xram-size $(XRAM_SIZE) --xram-loc $(XRAM_LOC) \ + --code-size $(CODE_SIZE) \ + -I$(ROOT_DIR)/include -DFREQ_SYS=$(FREQ_SYS) \ + $(EXTRA_FLAGS) + +LFLAGS := $(CFLAGS) + +RELS := $(C_FILES:.c=.rel) + +print-% : ; @echo $* = $($*) + +%.rel : %.c + $(CC) -c $(CFLAGS) $< + +# Note: SDCC will dump all of the temporary files into this one, so strip the paths from RELS +# For now, get around this by stripping the paths off of the RELS list. + +$(TARGET).ihx: $(RELS) + $(CC) $(notdir $(RELS)) $(LFLAGS) -o $(TARGET).ihx + +$(TARGET).bin: $(TARGET).ihx + $(OBJCOPY) -I ihex -O binary $(TARGET).ihx $(TARGET).bin + +flash: $(TARGET).bin + $(WCHISP) $(TARGET).bin + +.DEFAULT_GOAL := all +all: $(TARGET).bin + +clean: + rm -f \ + $(notdir $(RELS:.rel=.asm)) \ + $(notdir $(RELS:.rel=.lst)) \ + $(notdir $(RELS:.rel=.mem)) \ + $(notdir $(RELS:.rel=.rel)) \ + $(notdir $(RELS:.rel=.rst)) \ + $(notdir $(RELS:.rel=.sym)) \ + $(notdir $(RELS:.rel=.adb)) \ + $(TARGET).lk \ + $(TARGET).map \ + $(TARGET).mem \ + $(TARGET).ihx diff --git a/src/Readme.md b/src/Readme.md new file mode 100644 index 0000000..bbe93fa --- /dev/null +++ b/src/Readme.md @@ -0,0 +1,2 @@ +Examples [from here](https://github.com/Blinkinlabs/ch554_sdcc]. + diff --git a/src/include/adc.c b/src/include/adc.c new file mode 100644 index 0000000..d758e95 --- /dev/null +++ b/src/include/adc.c @@ -0,0 +1,113 @@ + +/********************************** (C) COPYRIGHT ******************************* +* File Name : ADC.C +* Author : WCH +* Version : V1.0 +* Date : 2019/07/22 +* Description : CH554ADC sampling clock setting, ADC channel setting function, voltage comparison mode setting +*******************************************************************************/ + +#include "ch554.h" +#include "debug.h" +#include "adc.h" +#include "stdio.h" + +#define SUCCESS 1 +#define FAIL -1 + +//uint16_t UserData; +/******************************************************************************* +* Function Name : ADCInit(uint8_t div) +* Description : ADC sampling clock setting, module is turned on, interrupt is turned on +* Input : uint8_t speed clock setting + 1 Slow 384 Fosc + 0 Fast 96 Fosc +* Output : None +* Return : None +*******************************************************************************/ +void ADCInit(uint8_t speed) +{ + ADC_CFG &= ~bADC_CLK | speed; + ADC_CFG |= bADC_EN; //ADC power enable +#if ADC_INTERRUPT + ADC_IF = 0; //Clear interrupt + IE_ADC = 1; //Enable ADC interrupt +#endif +} + +/******************************************************************************* +* Function Name : ADC_ChannelSelect(uint8_t ch) +* Description : ADC sampling enabled +* Input : uint8_t ch Use channel +* Output : None +* Return : SUCCESS + FAIL +*******************************************************************************/ +uint8_t ADC_ChannelSelect(uint8_t ch) +{ + if(ch == 0){ADC_CHAN1 =0;ADC_CHAN0=0;P1_DIR_PU &= ~bAIN0;} //AIN0 + else if(ch == 1){ADC_CHAN1 =0;ADC_CHAN0=1;P1_DIR_PU &= ~bAIN1;} //AIN1 + else if(ch == 2){ADC_CHAN1 =1;ADC_CHAN0=0;P1_DIR_PU &= ~bAIN2;} //AIN2 + else if(ch == 3){ADC_CHAN1 =1;ADC_CHAN0=1;P3_DIR_PU &= ~bAIN3;} //AIN3 + else return FAIL; + return SUCCESS; +} + +/******************************************************************************* +* Function Name : VoltageCMPModeInit() +* Description : Voltage comparator mode initialization +* Input : uint8_t fo forward port 0 \ 1 \ 2 \ 3 + uint8_t re Reverse port 1 \ 3 +* Output : None +* Return : success SUCCESS + failure FAIL +*******************************************************************************/ +uint8_t VoltageCMPModeInit(uint8_t fo,uint8_t re) +{ + ADC_CFG |= bCMP_EN; // level comparison power enable + if(re == 1){ + if(fo == 0) {ADC_CHAN1 =0;ADC_CHAN0=0;CMP_CHAN =0;} // AIN0 and AIN1 + else if(fo == 2) {ADC_CHAN1 =1;ADC_CHAN0=0;CMP_CHAN =0;} //AIN2 and AIN1 + else if(fo == 3) {ADC_CHAN1 =1;ADC_CHAN0=1;CMP_CHAN =0; } //AIN3 and AIN1 + else return FAIL; + } + else if(re == 3){ + if(fo == 0) {ADC_CHAN1 =0;ADC_CHAN0=0;CMP_CHAN =0;} //AIN0 and AIN1 + else if(fo == 1) {ADC_CHAN1 =0;ADC_CHAN0=1;CMP_CHAN =0;} //AIN1 and AIN1 + else if(fo == 2) {ADC_CHAN1 =1;ADC_CHAN0=0;CMP_CHAN =0;} //AIN2 and AIN1 + else return FAIL; + } + else return FAIL; +#if ADC_INTERRUPT + CMP_IF = 0; //Clear interrupt + IE_ADC = 1; //Enable ADC interrupt +#endif + + return SUCCESS; +} + +#if ADC_INTERRUPT + +// Must be copied into main if ADC is interrupt driven +/******************************************************************************* +* Function Name : ADCInterrupt(void) +* Description : ADC Interrupt service routine +*******************************************************************************/ +/* +void ADCInterrupt(void) __interrupt(INT_NO_ADC) //ADC interrupt service routine, using register set 1 +{ + if(ADC_IF == 1) //ADC complete interrupt + { + UserData = ADC_DATA; //Take ADC sampling data + ADC_IF = 0; //Clear ADC interrupt flag + printf(" %d ",UserData); + } + if(CMP_IF == 1) //Voltage comparison complete interrupt + { +// UserData = ADC_CTRL&0x80 >> 7); //Save comparator result + CMP_IF = 0; //Clear Comparator Complete Interrupt + } +} +*/ +#endif + diff --git a/src/include/adc.h b/src/include/adc.h new file mode 100644 index 0000000..ca05c21 --- /dev/null +++ b/src/include/adc.h @@ -0,0 +1,39 @@ + +#ifndef __ADC_H__ +#define __ADC_H__ + + + +/******************************************************************************* +* Function Name : ADCClkSet(uint8_t div) +* Description :ADC sampling clock setting, module is turned on, interrupt is turned on +* Input : uint8_t speed clock setting + 0 Slow 384 Fosc + 1 fast 96 Fosc +* Output : None +* Return : None +*******************************************************************************/ +extern void ADCInit(uint8_t speed); + +/******************************************************************************* +* Function Name : ADC_ChannelSelect(uint8_t ch) +* Description : ADC sampling channel settings +* Input : uint8_t ch uses channels 0-3 +* Output : None +* Return : success SUCCESS + failure FAIL Channel setting out of range +*******************************************************************************/ +extern uint8_t ADC_ChannelSelect(uint8_t ch); + +/******************************************************************************* +* Function Name : VoltageCMPModeInit() +* Description : Voltage comparator mode initialization +* Input : uint8_t fo Forward port 0\1\2\3 + uint8_t re Reverse port 1\3 +* Output : None +* Return : success SUCCESS + failure FAIL +*******************************************************************************/ +extern uint8_t VoltageCMPModeInit(uint8_t fo,uint8_t re); + +#endif \ No newline at end of file diff --git a/src/include/bootloader.h b/src/include/bootloader.h new file mode 100644 index 0000000..8f1e7ba --- /dev/null +++ b/src/include/bootloader.h @@ -0,0 +1,4 @@ +#pragma once + +#define BOOT_ADDR 0x3800 +void (* __data bootloader)(void) = BOOT_ADDR; diff --git a/src/include/ch554.h b/src/include/ch554.h new file mode 100644 index 0000000..bb263dd --- /dev/null +++ b/src/include/ch554.h @@ -0,0 +1,752 @@ +/*-------------------------------------------------------------------------- +CH554.H +Header file for CH554 microcontrollers. +**************************************** +** Copyright (C) W.ch 1999-2014 ** +** Web: http://wch.cn ** +**************************************** +--------------------------------------------------------------------------*/ + +#ifndef __CH554_H__ +#define __CH554_H__ + +#include + +/*----- SFR --------------------------------------------------------------*/ +/* sbit are bit addressable, others are byte addressable */ + +/* System Registers */ +SFR(PSW, 0xD0); // program status word + SBIT(CY, 0xD0, 7); // carry flag + SBIT(AC, 0xD0, 6); // auxiliary carry flag + SBIT(F0, 0xD0, 5); // bit addressable general purpose flag 0 + SBIT(RS1, 0xD0, 4); // register R0-R7 bank selection high bit + SBIT(RS0, 0xD0, 3); // register R0-R7 bank selection low bit +#define MASK_PSW_RS 0x18 // bit mask of register R0-R7 bank selection +// RS1 & RS0: register R0-R7 bank selection +// 00 - bank 0, R0-R7 @ address 0x00-0x07 +// 01 - bank 1, R0-R7 @ address 0x08-0x0F +// 10 - bank 2, R0-R7 @ address 0x10-0x17 +// 11 - bank 3, R0-R7 @ address 0x18-0x1F + SBIT(OV, 0xD0, 2); // overflow flag + SBIT(F1, 0xD0, 1); // bit addressable general purpose flag 1 + SBIT(P, 0xD0, 0); // ReadOnly: parity flag +SFR(ACC, 0xE0); // accumulator +SFR(B, 0xF0); // general purpose register B +SFR(SP, 0x81); // stack pointer +//sfr16 DPTR = 0x82; // DPTR pointer, little-endian +SFR(DPL, 0x82); // data pointer low +SFR(DPH, 0x83); // data pointer high +SFR(SAFE_MOD, 0xA1); // WriteOnly: writing safe mode +//sfr CHIP_ID = 0xA1; // ReadOnly: reading chip ID +#define CHIP_ID SAFE_MOD +SFR(GLOBAL_CFG, 0xB1); // global config, Write@SafeMode +#define bBOOT_LOAD 0x20 // ReadOnly: boot loader status for discriminating BootLoader or Application: set 1 by power on reset, clear 0 by software reset +#define bSW_RESET 0x10 // software reset bit, auto clear by hardware +#define bCODE_WE 0x08 // enable flash-ROM (include code & Data-Flash) being program or erasing: 0=writing protect, 1=enable program and erase +#define bDATA_WE 0x04 // enable Data-Flash (flash-ROM data area) being program or erasing: 0=writing protect, 1=enable program and erase +#define bLDO3V3_OFF 0x02 // disable 5V->3.3V LDO: 0=enable LDO for USB and internal oscillator under 5V power, 1=disable LDO, V33 pin input external 3.3V power +#define bWDOG_EN 0x01 // enable watch-dog reset if watch-dog timer overflow: 0=as timer only, 1=enable reset if timer overflow + +/* Clock and Sleep and Power Registers */ +SFR(PCON, 0x87); // power control and reset flag +#define SMOD 0x80 // baud rate selection for UART0 mode 1/2/3: 0=slow(Fsys/128 @mode2, TF1/32 @mode1/3, no effect for TF2), + // 1=fast(Fsys/32 @mode2, TF1/16 @mode1/3, no effect for TF2) +#define bRST_FLAG1 0x20 // ReadOnly: recent reset flag high bit +#define bRST_FLAG0 0x10 // ReadOnly: recent reset flag low bit +#define MASK_RST_FLAG 0x30 // ReadOnly: bit mask of recent reset flag +#define RST_FLAG_SW 0x00 +#define RST_FLAG_POR 0x10 +#define RST_FLAG_WDOG 0x20 +#define RST_FLAG_PIN 0x30 +// bPC_RST_FLAG1 & bPC_RST_FLAG0: recent reset flag +// 00 - software reset, by bSW_RESET=1 @(bBOOT_LOAD=0 or bWDOG_EN=1) +// 01 - power on reset +// 10 - watch-dog timer overflow reset +// 11 - external input manual reset by RST pin +#define GF1 0x08 // general purpose flag bit 1 +#define GF0 0x04 // general purpose flag bit 0 +#define PD 0x02 // power-down enable bit, auto clear by wake-up hardware +SFR(CLOCK_CFG, 0xB9); // system clock config: lower 3 bits for system clock Fsys, Write@SafeMode +#define bOSC_EN_INT 0x80 // internal oscillator enable and original clock selection: 1=enable & select internal clock, 0=disable & select external clock +#define bOSC_EN_XT 0x40 // external oscillator enable, need quartz crystal or ceramic resonator between XI and XO pins +#define bWDOG_IF_TO 0x20 // ReadOnly: watch-dog timer overflow interrupt flag, cleared by reload watch-dog count or auto cleared when MCU enter interrupt routine +#define bROM_CLK_FAST 0x10 // flash-ROM clock frequency selection: 0=normal(for Fosc>=16MHz), 1=fast(for Fosc<16MHz) +#define bRST 0x08 // ReadOnly: pin RST input +#define bT2EX_ 0x08 // alternate pin for T2EX +#define bCAP2_ 0x08 // alternate pin for CAP2 +#define MASK_SYS_CK_SEL 0x07 // bit mask of system clock Fsys selection +/* + Fxt = 24MHz(8MHz~25MHz for non-USB application), from external oscillator @XI&XO + Fosc = bOSC_EN_INT ? 24MHz : Fxt + Fpll = Fosc * 4 => 96MHz (32MHz~100MHz for non-USB application) + Fusb4x = Fpll / 2 => 48MHz (Fixed) + MASK_SYS_CK_SEL[2] [1] [0] + Fsys = Fpll/3 = 32MHz: 1 1 1 + Fsys = Fpll/4 = 24MHz: 1 1 0 + Fsys = Fpll/6 = 16MHz: 1 0 1 + Fsys = Fpll/8 = 12MHz: 1 0 0 + Fsys = Fpll/16 = 6MHz: 0 1 1 + Fsys = Fpll/32 = 3MHz: 0 1 0 + Fsys = Fpll/128 = 750KHz: 0 0 1 + Fsys = Fpll/512 =187.5KHz: 0 0 0 +*/ +SFR(WAKE_CTRL, 0xA9); // wake-up control, Write@SafeMode +#define bWAK_BY_USB 0x80 // enable wake-up by USB event +#define bWAK_RXD1_LO 0x40 // enable wake-up by RXD1 low level +#define bWAK_P1_5_LO 0x20 // enable wake-up by pin P1.5 low level +#define bWAK_P1_4_LO 0x10 // enable wake-up by pin P1.4 low level +#define bWAK_P1_3_LO 0x08 // enable wake-up by pin P1.3 low level +#define bWAK_RST_HI 0x04 // enable wake-up by pin RST high level +#define bWAK_P3_2E_3L 0x02 // enable wake-up by pin P3.2 (INT0) edge or pin P3.3 (INT1) low level +#define bWAK_RXD0_LO 0x01 // enable wake-up by RXD0 low level +SFR(RESET_KEEP, 0xFE); // value keeper during reset +SFR(WDOG_COUNT, 0xFF); // watch-dog count, count by clock frequency Fsys/65536 + +/* Interrupt Registers */ +SFR(IE, 0xA8); // interrupt enable + SBIT(EA, 0xA8, 7); // enable global interrupts: 0=disable, 1=enable if E_DIS=0 + SBIT(E_DIS, 0xA8, 6); // disable global interrupts, intend to inhibit interrupt during some flash-ROM operation: 0=enable if EA=1, 1=disable + SBIT(ET2, 0xA8, 5); // enable timer2 interrupt + SBIT(ES, 0xA8, 4); // enable UART0 interrupt + SBIT(ET1, 0xA8, 3); // enable timer1 interrupt + SBIT(EX1, 0xA8, 2); // enable external interrupt INT1 + SBIT(ET0, 0xA8, 1); // enable timer0 interrupt + SBIT(EX0, 0xA8, 0); // enable external interrupt INT0 +SFR(IP, 0xB8); // interrupt priority and current priority + SBIT(PH_FLAG, 0xB8, 7); // ReadOnly: high level priority action flag + SBIT(PL_FLAG, 0xB8, 6); // ReadOnly: low level priority action flag +// PH_FLAG & PL_FLAG: current interrupt priority +// 00 - no interrupt now +// 01 - low level priority interrupt action now +// 10 - high level priority interrupt action now +// 11 - unknown error + SBIT(PT2, 0xB8, 5); // timer2 interrupt priority level + SBIT(PS, 0xB8, 4); // UART0 interrupt priority level + SBIT(PT1, 0xB8, 3); // timer1 interrupt priority level + SBIT(PX1, 0xB8, 2); // external interrupt INT1 priority level + SBIT(PT0, 0xB8, 1); // timer0 interrupt priority level + SBIT(PX0, 0xB8, 0); // external interrupt INT0 priority level +SFR(IE_EX, 0xE8); // extend interrupt enable + SBIT(IE_WDOG, 0xE8, 7); // enable watch-dog timer interrupt + SBIT(IE_GPIO, 0xE8, 6); // enable GPIO input interrupt + SBIT(IE_PWMX, 0xE8, 5); // enable PWM1/2 interrupt + SBIT(IE_UART1, 0xE8, 4); // enable UART1 interrupt + SBIT(IE_ADC, 0xE8, 3); // enable ADC interrupt + SBIT(IE_USB, 0xE8, 2); // enable USB interrupt + SBIT(IE_TKEY, 0xE8, 1); // enable touch-key timer interrupt + SBIT(IE_SPI0, 0xE8, 0); // enable SPI0 interrupt +SFR(IP_EX, 0xE9); // extend interrupt priority +#define bIP_LEVEL 0x80 // ReadOnly: current interrupt nested level: 0=no interrupt or two levels, 1=one level +#define bIP_GPIO 0x40 // GPIO input interrupt priority level +#define bIP_PWMX 0x20 // PWM1/2 interrupt priority level +#define bIP_UART1 0x10 // UART1 interrupt priority level +#define bIP_ADC 0x08 // ADC interrupt priority level +#define bIP_USB 0x04 // USB interrupt priority level +#define bIP_TKEY 0x02 // touch-key timer interrupt priority level +#define bIP_SPI0 0x01 // SPI0 interrupt priority level +SFR(GPIO_IE, 0xC7); // GPIO interrupt enable +#define bIE_IO_EDGE 0x80 // enable GPIO edge interrupt: 0=low/high level, 1=falling/rising edge +#define bIE_RXD1_LO 0x40 // enable interrupt by RXD1 low level / falling edge +#define bIE_P1_5_LO 0x20 // enable interrupt by pin P1.5 low level / falling edge +#define bIE_P1_4_LO 0x10 // enable interrupt by pin P1.4 low level / falling edge +#define bIE_P1_3_LO 0x08 // enable interrupt by pin P1.3 low level / falling edge +#define bIE_RST_HI 0x04 // enable interrupt by pin RST high level / rising edge +#define bIE_P3_1_LO 0x02 // enable interrupt by pin P3.1 low level / falling edge +#define bIE_RXD0_LO 0x01 // enable interrupt by RXD0 low level / falling edge + +/* FlashROM and Data-Flash Registers */ +SFR16(ROM_ADDR, 0x84); // address for flash-ROM, little-endian +SFR(ROM_ADDR_L, 0x84); // address low byte for flash-ROM +SFR(ROM_ADDR_H, 0x85); // address high byte for flash-ROM +SFR16(ROM_DATA, 0x8E); // data for flash-ROM writing, little-endian +SFR(ROM_DATA_L, 0x8E); // data low byte for flash-ROM writing, data byte for Data-Flash reading/writing +SFR(ROM_DATA_H, 0x8F); // data high byte for flash-ROM writing +SFR(ROM_CTRL, 0x86); // WriteOnly: flash-ROM control +#define ROM_CMD_WRITE 0x9A // WriteOnly: flash-ROM word or Data-Flash byte write operation command +#define ROM_CMD_READ 0x8E // WriteOnly: Data-Flash byte read operation command +//sfr ROM_STATUS = 0x86; // ReadOnly: flash-ROM status +#define ROM_STATUS ROM_CTRL +#define bROM_ADDR_OK 0x40 // ReadOnly: flash-ROM writing operation address valid flag, can be reviewed before or after operation: 0=invalid parameter, 1=address valid +#define bROM_CMD_ERR 0x02 // ReadOnly: flash-ROM operation command error flag: 0=command accepted, 1=unknown command + +/* Port Registers */ +SFR(P1, 0x90); // port 1 input & output + SBIT(SCK, 0x90, 7); // serial clock for SPI0 + SBIT(TXD1, 0x90, 7); // TXD output for UART1 + SBIT(TIN5, 0x90, 7); // TIN5 for Touch-Key + SBIT(MISO, 0x90, 6); // master serial data input or slave serial data output for SPI0 + SBIT(RXD1, 0x90, 6); // RXD input for UART1 + SBIT(TIN4, 0x90, 6); // TIN4 for Touch-Key + SBIT(MOSI, 0x90, 5); // master serial data output or slave serial data input for SPI0 + SBIT(PWM1, 0x90, 5); // PWM output for PWM1 + SBIT(TIN3, 0x90, 5); // TIN3 for Touch-Key + SBIT(UCC2, 0x90, 5); // CC2 for USB type-C + SBIT(AIN2, 0x90, 5); // AIN2 for ADC + SBIT(T2_, 0x90, 4); // alternate pin for T2 + SBIT(CAP1_, 0x90, 4); // alternate pin for CAP1 + SBIT(SCS, 0x90, 4); // slave chip-selection input for SPI0 + SBIT(TIN2, 0x90, 4); // TIN2 for Touch-Key + SBIT(UCC1, 0x90, 4); // CC1 for USB type-C + SBIT(AIN1, 0x90, 4); // AIN1 for ADC + SBIT(TXD_, 0x90, 3); // alternate pin for TXD of UART0 + SBIT(RXD_, 0x90, 2); // alternate pin for RXD of UART0 + SBIT(T2EX, 0x90, 1); // external trigger input for timer2 reload & capture + SBIT(CAP2, 0x90, 1); // capture2 input for timer2 + SBIT(TIN1, 0x90, 1); // TIN1 for Touch-Key + SBIT(VBUS2, 0x90, 1); // VBUS2 for USB type-C + SBIT(AIN0, 0x90, 1); // AIN0 for ADC + SBIT(T2, 0x90, 0); // external count input + SBIT(CAP1, 0x90, 0); // capture1 input for timer2 + SBIT(TIN0, 0x90, 0); // TIN0 for Touch-Key +SFR(P1_MOD_OC, 0x92); // port 1 output mode: 0=push-pull, 1=open-drain +SFR(P1_DIR_PU, 0x93); // port 1 direction for push-pull or pullup enable for open-drain +// Pn_MOD_OC & Pn_DIR_PU: pin input & output configuration for Pn (n=1/3) +// 0 0: float input only, without pullup resistance +// 0 1: push-pull output, strong driving high level and low level +// 1 0: open-drain output and input without pullup resistance +// 1 1: quasi-bidirectional (standard 8051 mode), open-drain output and input with pullup resistance, just driving high level strongly for 2 clocks if turning output level from low to high +#define bSCK 0x80 // serial clock for SPI0 +#define bTXD1 0x80 // TXD output for UART1 +#define bMISO 0x40 // master serial data input or slave serial data output for SPI0 +#define bRXD1 0x40 // RXD input for UART1 +#define bMOSI 0x20 // master serial data output or slave serial data input for SPI0 +#define bPWM1 0x20 // PWM output for PWM1 +#define bUCC2 0x20 // CC2 for USB type-C +#define bAIN2 0x20 // AIN2 for ADC +#define bT2_ 0x10 // alternate pin for T2 +#define bCAP1_ 0x10 // alternate pin for CAP1 +#define bSCS 0x10 // slave chip-selection input for SPI0 +#define bUCC1 0x10 // CC1 for USB type-C +#define bAIN1 0x10 // AIN1 for ADC +#define bTXD_ 0x08 // alternate pin for TXD of UART0 +#define bRXD_ 0x04 // alternate pin for RXD of UART0 +#define bT2EX 0x02 // external trigger input for timer2 reload & capture +#define bCAP2 bT2EX // capture2 input for timer2 +#define bVBUS2 0x02 // VBUS2 for USB type-C +#define bAIN0 0x02 // AIN0 for ADC +#define bT2 0x01 // external count input or clock output for timer2 +#define bCAP1 bT2 // capture1 input for timer2 +SFR(P2, 0xA0); // port 2 +SFR(P3, 0xB0); // port 3 input & output + SBIT(UDM, 0xB0, 7); // ReadOnly: pin UDM input + SBIT(UDP, 0xB0, 6); // ReadOnly: pin UDP input + SBIT(T1, 0xB0, 5); // external count input for timer1 + SBIT(PWM2, 0xB0, 4); // PWM output for PWM2 + SBIT(RXD1_, 0xB0, 4); // alternate pin for RXD1 + SBIT(T0, 0xB0, 4); // external count input for timer0 + SBIT(INT1, 0xB0, 3); // external interrupt 1 input + SBIT(TXD1_, 0xB0, 2); // alternate pin for TXD1 + SBIT(INT0, 0xB0, 2); // external interrupt 0 input + SBIT(VBUS1, 0xB0, 2); // VBUS1 for USB type-C + SBIT(AIN3, 0xB0, 2); // AIN3 for ADC + SBIT(PWM2_, 0xB0, 1); // alternate pin for PWM2 + SBIT(TXD, 0xB0, 1); // TXD output for UART0 + SBIT(PWM1_, 0xB0, 0); // alternate pin for PWM1 + SBIT(RXD, 0xB0, 0); // RXD input for UART0 +SFR(P3_MOD_OC, 0x96); // port 3 output mode: 0=push-pull, 1=open-drain +SFR(P3_DIR_PU, 0x97); // port 3 direction for push-pull or pullup enable for open-drain +#define bUDM 0x80 // ReadOnly: pin UDM input +#define bUDP 0x40 // ReadOnly: pin UDP input +#define bT1 0x20 // external count input for timer1 +#define bPWM2 0x10 // PWM output for PWM2 +#define bRXD1_ 0x10 // alternate pin for RXD1 +#define bT0 0x10 // external count input for timer0 +#define bINT1 0x08 // external interrupt 1 input +#define bTXD1_ 0x04 // alternate pin for TXD1 +#define bINT0 0x04 // external interrupt 0 input +#define bVBUS1 0x04 // VBUS1 for USB type-C +#define bAIN3 0x04 // AIN3 for ADC +#define bPWM2_ 0x02 // alternate pin for PWM2 +#define bTXD 0x02 // TXD output for UART0 +#define bPWM1_ 0x01 // alternate pin for PWM1 +#define bRXD 0x01 // RXD input for UART0 +SFR(PIN_FUNC, 0xC6); // pin function selection +#define bUSB_IO_EN 0x80 // USB UDP/UDM I/O pin enable: 0=P3.6/P3.7 as GPIO, 1=P3.6/P3.7 as USB +#define bIO_INT_ACT 0x40 // ReadOnly: GPIO interrupt request action status +#define bUART1_PIN_X 0x20 // UART1 alternate pin enable: 0=RXD1/TXD1 on P1.6/P1.7, 1=RXD1/TXD1 on P3.4/P3.2 +#define bUART0_PIN_X 0x10 // UART0 alternate pin enable: 0=RXD0/TXD0 on P3.0/P3.1, 1=RXD0/TXD0 on P1.2/P1.3 +#define bPWM2_PIN_X 0x08 // PWM2 alternate pin enable: 0=PWM2 on P3.4, 1=PWM2 on P3.1 +#define bPWM1_PIN_X 0x04 // PWM1 alternate pin enable: 0=PWM1 on P1.5, 1=PWM1 on P3.0 +#define bT2EX_PIN_X 0x02 // T2EX/CAP2 alternate pin enable: 0=T2EX/CAP2 on P1.1, 1=T2EX/CAP2 on RST +#define bT2_PIN_X 0x01 // T2/CAP1 alternate pin enable: 0=T2/CAP1 on P1.1, 1=T2/CAP1 on P1.4 +SFR(XBUS_AUX, 0xA2); // xBUS auxiliary setting +#define bUART0_TX 0x80 // ReadOnly: indicate UART0 transmittal status +#define bUART0_RX 0x40 // ReadOnly: indicate UART0 receiving status +#define bSAFE_MOD_ACT 0x20 // ReadOnly: safe mode action status +#define GF2 0x08 // general purpose flag bit 2 +#define bDPTR_AUTO_INC 0x04 // enable DPTR auto increase if finished MOVX_@DPTR instruction +#define DPS 0x01 // dual DPTR selection: 0=DPTR0 selected, 1=DPTR1 selected + +/* Timer0/1 Registers */ +SFR(TCON, 0x88); // timer 0/1 control and external interrupt control + SBIT(TF1, 0x88, 7); // timer1 overflow & interrupt flag, auto cleared when MCU enter interrupt routine + SBIT(TR1, 0x88, 6); // timer1 run enable + SBIT(TF0, 0x88, 5); // timer0 overflow & interrupt flag, auto cleared when MCU enter interrupt routine + SBIT(TR0, 0x88, 4); // timer0 run enable + SBIT(IE1, 0x88, 3); // INT1 interrupt flag, auto cleared when MCU enter interrupt routine + SBIT(IT1, 0x88, 2); // INT1 interrupt type: 0=low level action, 1=falling edge action + SBIT(IE0, 0x88, 1); // INT0 interrupt flag, auto cleared when MCU enter interrupt routine + SBIT(IT0, 0x88, 0); // INT0 interrupt type: 0=low level action, 1=falling edge action +SFR(TMOD, 0x89); // timer 0/1 mode +#define bT1_GATE 0x80 // gate control of timer1: 0=timer1 run enable while TR1=1, 1=timer1 run enable while P3.3 (INT1) pin is high and TR1=1 +#define bT1_CT 0x40 // counter or timer mode selection for timer1: 0=timer, use internal clock, 1=counter, use P3.5 (T1) pin falling edge as clock +#define bT1_M1 0x20 // timer1 mode high bit +#define bT1_M0 0x10 // timer1 mode low bit +#define MASK_T1_MOD 0x30 // bit mask of timer1 mode +// bT1_M1 & bT1_M0: timer1 mode +// 00: mode 0, 13-bit timer or counter by cascaded TH1 and lower 5 bits of TL1, the upper 3 bits of TL1 are ignored +// 01: mode 1, 16-bit timer or counter by cascaded TH1 and TL1 +// 10: mode 2, TL1 operates as 8-bit timer or counter, and TH1 provide initial value for TL1 auto-reload +// 11: mode 3, stop timer1 +#define bT0_GATE 0x08 // gate control of timer0: 0=timer0 run enable while TR0=1, 1=timer0 run enable while P3.2 (INT0) pin is high and TR0=1 +#define bT0_CT 0x04 // counter or timer mode selection for timer0: 0=timer, use internal clock, 1=counter, use P3.4 (T0) pin falling edge as clock +#define bT0_M1 0x02 // timer0 mode high bit +#define bT0_M0 0x01 // timer0 mode low bit +#define MASK_T0_MOD 0x03 // bit mask of timer0 mode +// bT0_M1 & bT0_M0: timer0 mode +// 00: mode 0, 13-bit timer or counter by cascaded TH0 and lower 5 bits of TL0, the upper 3 bits of TL0 are ignored +// 01: mode 1, 16-bit timer or counter by cascaded TH0 and TL0 +// 10: mode 2, TL0 operates as 8-bit timer or counter, and TH0 provide initial value for TL0 auto-reload +// 11: mode 3, TL0 is 8-bit timer or counter controlled by standard timer0 bits, TH0 is 8-bit timer using TF1 and controlled by TR1, timer1 run enable if it is not mode 3 +SFR(TL0, 0x8A); // low byte of timer 0 count +SFR(TL1, 0x8B); // low byte of timer 1 count +SFR(TH0, 0x8C); // high byte of timer 0 count +SFR(TH1, 0x8D); // high byte of timer 1 count + +/* UART0 Registers */ +SFR(SCON, 0x98); // UART0 control (serial port control) + SBIT(SM0, 0x98, 7); // UART0 mode bit0, selection data bit: 0=8 bits data, 1=9 bits data + SBIT(SM1, 0x98, 6); // UART0 mode bit1, selection baud rate: 0=fixed, 1=variable +// SM0 & SM1: UART0 mode +// 00 - mode 0, shift Register, baud rate fixed at: Fsys/12 +// 01 - mode 1, 8-bit UART, baud rate = variable by timer1 or timer2 overflow rate +// 10 - mode 2, 9-bit UART, baud rate fixed at: Fsys/128@SMOD=0, Fsys/32@SMOD=1 +// 11 - mode 3, 9-bit UART, baud rate = variable by timer1 or timer2 overflow rate + SBIT(SM2, 0x98, 5); // enable multi-device communication in mode 2/3 +#define MASK_UART0_MOD 0xE0 // bit mask of UART0 mode + SBIT(REN, 0x98, 4); // enable UART0 receiving + SBIT(TB8, 0x98, 3); // the 9th transmitted data bit in mode 2/3 + SBIT(RB8, 0x98, 2); // 9th data bit received in mode 2/3, or stop bit received for mode 1 + SBIT(TI, 0x98, 1); // transmit interrupt flag, set by hardware after completion of a serial transmittal, need software clear + SBIT(RI, 0x98, 0); // receive interrupt flag, set by hardware after completion of a serial receiving, need software clear +SFR(SBUF, 0x99); // UART0 data buffer: reading for receiving, writing for transmittal + +/* Timer2/Capture2 Registers */ +SFR(T2CON, 0xC8); // timer 2 control + SBIT(TF2, 0xC8, 7); // timer2 overflow & interrupt flag, need software clear, the flag will not be set when either RCLK=1 or TCLK=1 + SBIT(CAP1F, 0xC8, 7); // timer2 capture 1 interrupt flag, set by T2 edge trigger if bT2_CAP1_EN=1, need software clear + SBIT(EXF2, 0xC8, 6); // timer2 external flag, set by T2EX edge trigger if EXEN2=1, need software clear + SBIT(RCLK, 0xC8, 5); // selection UART0 receiving clock: 0=timer1 overflow pulse, 1=timer2 overflow pulse + SBIT(TCLK, 0xC8, 4); // selection UART0 transmittal clock: 0=timer1 overflow pulse, 1=timer2 overflow pulse + SBIT(EXEN2, 0xC8, 3); // enable T2EX trigger function: 0=ignore T2EX, 1=trigger reload or capture by T2EX edge + SBIT(TR2, 0xC8, 2); // timer2 run enable + SBIT(C_T2, 0xC8, 1); // timer2 clock source selection: 0=timer base internal clock, 1=external edge counter base T2 falling edge + SBIT(CP_RL2, 0xC8, 0); // timer2 function selection (force 0 if RCLK=1 or TCLK=1): 0=timer and auto reload if count overflow or T2EX edge, 1=capture by T2EX edge +SFR(T2MOD, 0xC9); // timer 2 mode and timer 0/1/2 clock mode +#define bTMR_CLK 0x80 // fastest internal clock mode for timer 0/1/2 under faster clock mode: 0=use divided clock, 1=use original Fsys as clock without dividing +#define bT2_CLK 0x40 // timer2 internal clock frequency selection: 0=standard clock, Fsys/12 for timer mode, Fsys/4 for UART0 clock mode, + // 1=faster clock, Fsys/4 @bTMR_CLK=0 or Fsys @bTMR_CLK=1 for timer mode, Fsys/2 @bTMR_CLK=0 or Fsys @bTMR_CLK=1 for UART0 clock mode +#define bT1_CLK 0x20 // timer1 internal clock frequency selection: 0=standard clock, Fsys/12, 1=faster clock, Fsys/4 if bTMR_CLK=0 or Fsys if bTMR_CLK=1 +#define bT0_CLK 0x10 // timer0 internal clock frequency selection: 0=standard clock, Fsys/12, 1=faster clock, Fsys/4 if bTMR_CLK=0 or Fsys if bTMR_CLK=1 +#define bT2_CAP_M1 0x08 // timer2 capture mode high bit +#define bT2_CAP_M0 0x04 // timer2 capture mode low bit +// bT2_CAP_M1 & bT2_CAP_M0: timer2 capture point selection +// x0: from falling edge to falling edge +// 01: from any edge to any edge (level changing) +// 11: from rising edge to rising edge +#define T2OE 0x02 // enable timer2 generated clock output: 0=disable output, 1=enable clock output at T2 pin, frequency = TF2/2 +#define bT2_CAP1_EN 0x01 // enable T2 trigger function for capture 1 of timer2 if RCLK=0 & TCLK=0 & CP_RL2=1 & C_T2=0 & T2OE=0 +SFR16(RCAP2, 0xCA); // reload & capture value, little-endian +SFR(RCAP2L, 0xCA); // low byte of reload & capture value +SFR(RCAP2H, 0xCB); // high byte of reload & capture value +SFR16(T2COUNT, 0xCC); // counter, little-endian +SFR(TL2, 0xCC); // low byte of timer 2 count +SFR(TH2, 0xCD); // high byte of timer 2 count +SFR16(T2CAP1, 0xCE); // ReadOnly: capture 1 value for timer2 +SFR(T2CAP1L, 0xCE); // ReadOnly: capture 1 value low byte for timer2 +SFR(T2CAP1H, 0xCF); // ReadOnly: capture 1 value high byte for timer2 + +/* PWM1/2 Registers */ +SFR(PWM_DATA2, 0x9B); // PWM data for PWM2 +SFR(PWM_DATA1, 0x9C); // PWM data for PWM1 +SFR(PWM_CTRL, 0x9D); // PWM 1/2 control +#define bPWM_IE_END 0x80 // enable interrupt for PWM mode cycle end +#define bPWM2_POLAR 0x40 // PWM2 output polarity: 0=default low and high action, 1=default high and low action +#define bPWM1_POLAR 0x20 // PWM1 output polarity: 0=default low and high action, 1=default high and low action +#define bPWM_IF_END 0x10 // interrupt flag for cycle end, write 1 to clear or write PWM_CYCLE or load new data to clear +#define bPWM2_OUT_EN 0x08 // PWM2 output enable +#define bPWM1_OUT_EN 0x04 // PWM1 output enable +#define bPWM_CLR_ALL 0x02 // force clear FIFO and count of PWM1/2 +SFR(PWM_CK_SE, 0x9E); // clock divisor setting + +/* SPI0/Master0/Slave Registers */ +SFR(SPI0_STAT, 0xF8); // SPI 0 status + SBIT(S0_FST_ACT, 0xF8, 7); // ReadOnly: indicate first byte received status for SPI0 + SBIT(S0_IF_OV, 0xF8, 6); // interrupt flag for slave mode FIFO overflow, direct bit address clear or write 1 to clear + SBIT(S0_IF_FIRST, 0xF8, 5); // interrupt flag for first byte received, direct bit address clear or write 1 to clear + SBIT(S0_IF_BYTE, 0xF8, 4); // interrupt flag for a byte data exchanged, direct bit address clear or write 1 to clear or accessing FIFO to clear if bS0_AUTO_IF=1 + SBIT(S0_FREE, 0xF8, 3); // ReadOnly: SPI0 free status + SBIT(S0_T_FIFO, 0xF8, 2); // ReadOnly: tx FIFO count for SPI0 + SBIT(S0_R_FIFO, 0xF8, 0); // ReadOnly: rx FIFO count for SPI0 +SFR(SPI0_DATA, 0xF9); // FIFO data port: reading for receiving, writing for transmittal +SFR(SPI0_CTRL, 0xFA); // SPI 0 control +#define bS0_MISO_OE 0x80 // SPI0 MISO output enable +#define bS0_MOSI_OE 0x40 // SPI0 MOSI output enable +#define bS0_SCK_OE 0x20 // SPI0 SCK output enable +#define bS0_DATA_DIR 0x10 // SPI0 data direction: 0=out(master_write), 1=in(master_read) +#define bS0_MST_CLK 0x08 // SPI0 master clock mode: 0=mode 0 with default low, 1=mode 3 with default high +#define bS0_2_WIRE 0x04 // enable SPI0 two wire mode: 0=3 wire (SCK+MOSI+MISO), 1=2 wire (SCK+MISO) +#define bS0_CLR_ALL 0x02 // force clear FIFO and count of SPI0 +#define bS0_AUTO_IF 0x01 // enable FIFO accessing to auto clear S0_IF_BYTE interrupt flag +SFR(SPI0_CK_SE, 0xFB); // clock divisor setting +//sfr SPI0_S_PRE = 0xFB; // preset value for SPI slave +#define SPI0_S_PRE SPI0_CK_SE +SFR(SPI0_SETUP, 0xFC); // SPI 0 setup +#define bS0_MODE_SLV 0x80 // SPI0 slave mode: 0=master, 1=slave +#define bS0_IE_FIFO_OV 0x40 // enable interrupt for slave mode FIFO overflow +#define bS0_IE_FIRST 0x20 // enable interrupt for first byte received for SPI0 slave mode +#define bS0_IE_BYTE 0x10 // enable interrupt for a byte received +#define bS0_BIT_ORDER 0x08 // SPI0 bit data order: 0=MSB first, 1=LSB first +#define bS0_SLV_SELT 0x02 // ReadOnly: SPI0 slave mode chip selected status: 0=unselected, 1=selected +#define bS0_SLV_PRELOAD 0x01 // ReadOnly: SPI0 slave mode data pre-loading status just after chip-selection + +/* UART1 Registers */ +SFR(SCON1, 0xC0); // UART1 control (serial port control) + SBIT(U1SM0, 0xC0, 7); // UART1 mode, selection data bit: 0=8 bits data, 1=9 bits data + SBIT(U1SMOD, 0xC0, 5); // UART1 2X baud rate selection: 0=slow(Fsys/32/(256-SBAUD1)), 1=fast(Fsys/16/(256-SBAUD1)) + SBIT(U1REN, 0xC0, 4); // enable UART1 receiving + SBIT(U1TB8, 0xC0, 3); // the 9th transmitted data bit in 9 bits data mode + SBIT(U1RB8, 0xC0, 2); // 9th data bit received in 9 bits data mode, or stop bit received for 8 bits data mode + SBIT(U1TI, 0xC0, 1); // transmit interrupt flag, set by hardware after completion of a serial transmittal, need software clear + SBIT(U1RI, 0xC0, 0); // receive interrupt flag, set by hardware after completion of a serial receiving, need software clear +SFR(SBUF1, 0xC1); // UART1 data buffer: reading for receiving, writing for transmittal +SFR(SBAUD1, 0xC2); // UART1 baud rate setting + +/* ADC and comparator Registers */ +SFR(ADC_CTRL, 0x80); // ADC control + SBIT(CMPO, 0x80, 7); // ReadOnly: comparator result input + SBIT(CMP_IF, 0x80, 6); // flag for comparator result changed, direct bit address clear + SBIT(ADC_IF, 0x80, 5); // interrupt flag for ADC finished, direct bit address clear + SBIT(ADC_START, 0x80, 4); // set 1 to start ADC, auto cleared when ADC finished + SBIT(CMP_CHAN, 0x80, 3); // comparator IN- input channel selection: 0=AIN1, 1=AIN3 + SBIT(ADC_CHAN1, 0x80, 1); // ADC/comparator IN+ channel selection high bit + SBIT(ADC_CHAN0, 0x80, 0); // ADC/comparator IN+ channel selection low bit +// ADC_CHAN1 & ADC_CHAN0: ADC/comparator IN+ channel selection +// 00: AIN0(P1.1) +// 01: AIN1(P1.4) +// 10: AIN2(P1.5) +// 11: AIN3(P3.2) +SFR(ADC_CFG, 0x9A); // ADC config +#define bADC_EN 0x08 // control ADC power: 0=shut down ADC, 1=enable power for ADC +#define bCMP_EN 0x04 // control comparator power: 0=shut down comparator, 1=enable power for comparator +#define bADC_CLK 0x01 // ADC clock frequency selection: 0=slow clock, 384 Fosc cycles for each ADC, 1=fast clock, 96 Fosc cycles for each ADC +SFR(ADC_DATA, 0x9F); // ReadOnly: ADC data + +/* Touch-key timer Registers */ +SFR(TKEY_CTRL, 0xC3); // touch-key control +#define bTKC_IF 0x80 // ReadOnly: interrupt flag for touch-key timer, cleared by writing touch-key control or auto cleared when start touch-key checking +#define bTKC_2MS 0x10 // touch-key timer cycle selection: 0=1mS, 1=2mS +#define bTKC_CHAN2 0x04 // touch-key channel selection high bit +#define bTKC_CHAN1 0x02 // touch-key channel selection middle bit +#define bTKC_CHAN0 0x01 // touch-key channel selection low bit +// bTKC_CHAN2 & bTKC_CHAN1 & bTKC_CHAN0: touch-key channel selection +// 000: disable touch-key +// 001: TIN0(P1.0) +// 010: TIN1(P1.1) +// 011: TIN2(P1.4) +// 100: TIN3(P1.5) +// 101: TIN4(P1.6) +// 110: TIN5(P1.7) +// 111: enable touch-key but disable all channel +SFR16(TKEY_DAT, 0xC4); // ReadOnly: touch-key data, little-endian +SFR(TKEY_DATL, 0xC4); // ReadOnly: low byte of touch-key data +SFR(TKEY_DATH, 0xC5); // ReadOnly: high byte of touch-key data +#define bTKD_CHG 0x80 // ReadOnly: indicate control changed, current data maybe invalid + +/* USB/Host/Device Registers */ +SFR(USB_C_CTRL, 0x91); // USB type-C control +#define bVBUS2_PD_EN 0x80 // USB VBUS2 10K pulldown resistance: 0=disable, 1=enable pullup +#define bUCC2_PD_EN 0x40 // USB CC2 5.1K pulldown resistance: 0=disable, 1=enable pulldown +#define bUCC2_PU1_EN 0x20 // USB CC2 pullup resistance control high bit +#define bUCC2_PU0_EN 0x10 // USB CC2 pullup resistance control low bit +#define bVBUS1_PD_EN 0x08 // USB VBUS1 10K pulldown resistance: 0=disable, 1=enable pullup +#define bUCC1_PD_EN 0x04 // USB CC1 5.1K pulldown resistance: 0=disable, 1=enable pulldown +#define bUCC1_PU1_EN 0x02 // USB CC1 pullup resistance control high bit +#define bUCC1_PU0_EN 0x01 // USB CC1 pullup resistance control low bit +// bUCC?_PU1_EN & bUCC?_PU0_EN: USB CC pullup resistance selection +// 00: disable pullup resistance +// 01: enable 56K pullup resistance for default USB power +// 10: enable 22K pullup resistance for 1.5A USB power +// 11: enable 10K pullup resistance for 3A USB power +SFR(UDEV_CTRL, 0xD1); // USB device physical port control +#define bUD_PD_DIS 0x80 // disable USB UDP/UDM pulldown resistance: 0=enable pulldown, 1=disable +#define bUD_DP_PIN 0x20 // ReadOnly: indicate current UDP pin level +#define bUD_DM_PIN 0x10 // ReadOnly: indicate current UDM pin level +#define bUD_LOW_SPEED 0x04 // enable USB physical port low speed: 0=full speed, 1=low speed +#define bUD_GP_BIT 0x02 // general purpose bit +#define bUD_PORT_EN 0x01 // enable USB physical port I/O: 0=disable, 1=enable +//sfr UHOST_CTRL = 0xD1; // USB host physical port control +#define UHOST_CTRL UDEV_CTRL +#define bUH_PD_DIS 0x80 // disable USB UDP/UDM pulldown resistance: 0=enable pulldown, 1=disable +#define bUH_DP_PIN 0x20 // ReadOnly: indicate current UDP pin level +#define bUH_DM_PIN 0x10 // ReadOnly: indicate current UDM pin level +#define bUH_LOW_SPEED 0x04 // enable USB port low speed: 0=full speed, 1=low speed +#define bUH_BUS_RESET 0x02 // control USB bus reset: 0=normal, 1=force bus reset +#define bUH_PORT_EN 0x01 // enable USB port: 0=disable, 1=enable port, automatic disabled if USB device detached +SFR(UEP1_CTRL, 0xD2); // endpoint 1 control +#define bUEP_R_TOG 0x80 // expected data toggle flag of USB endpoint X receiving (OUT): 0=DATA0, 1=DATA1 +#define bUEP_T_TOG 0x40 // prepared data toggle flag of USB endpoint X transmittal (IN): 0=DATA0, 1=DATA1 +#define bUEP_AUTO_TOG 0x10 // enable automatic toggle after successful transfer completion on endpoint 1/2/3: 0=manual toggle, 1=automatic toggle +#define bUEP_R_RES1 0x08 // handshake response type high bit for USB endpoint X receiving (OUT) +#define bUEP_R_RES0 0x04 // handshake response type low bit for USB endpoint X receiving (OUT) +#define MASK_UEP_R_RES 0x0C // bit mask of handshake response type for USB endpoint X receiving (OUT) +#define UEP_R_RES_ACK 0x00 +#define UEP_R_RES_TOUT 0x04 +#define UEP_R_RES_NAK 0x08 +#define UEP_R_RES_STALL 0x0C +// bUEP_R_RES1 & bUEP_R_RES0: handshake response type for USB endpoint X receiving (OUT) +// 00: ACK (ready) +// 01: no response, time out to host, for non-zero endpoint isochronous transactions +// 10: NAK (busy) +// 11: STALL (error) +#define bUEP_T_RES1 0x02 // handshake response type high bit for USB endpoint X transmittal (IN) +#define bUEP_T_RES0 0x01 // handshake response type low bit for USB endpoint X transmittal (IN) +#define MASK_UEP_T_RES 0x03 // bit mask of handshake response type for USB endpoint X transmittal (IN) +#define UEP_T_RES_ACK 0x00 +#define UEP_T_RES_TOUT 0x01 +#define UEP_T_RES_NAK 0x02 +#define UEP_T_RES_STALL 0x03 +// bUEP_T_RES1 & bUEP_T_RES0: handshake response type for USB endpoint X transmittal (IN) +// 00: DATA0 or DATA1 then expecting ACK (ready) +// 01: DATA0 or DATA1 then expecting no response, time out from host, for non-zero endpoint isochronous transactions +// 10: NAK (busy) +// 11: STALL (error) +SFR(UEP1_T_LEN, 0xD3); // endpoint 1 transmittal length +SFR(UEP2_CTRL, 0xD4); // endpoint 2 control +SFR(UEP2_T_LEN, 0xD5); // endpoint 2 transmittal length +SFR(UEP3_CTRL, 0xD6); // endpoint 3 control +SFR(UEP3_T_LEN, 0xD7); // endpoint 3 transmittal length +SFR(USB_INT_FG, 0xD8); // USB interrupt flag + SBIT(U_IS_NAK, 0xD8, 7); // ReadOnly: indicate current USB transfer is NAK received + SBIT(U_TOG_OK, 0xD8, 6); // ReadOnly: indicate current USB transfer toggle is OK + SBIT(U_SIE_FREE, 0xD8, 5); // ReadOnly: indicate USB SIE free status + SBIT(UIF_FIFO_OV, 0xD8, 4); // FIFO overflow interrupt flag for USB, direct bit address clear or write 1 to clear + SBIT(UIF_HST_SOF, 0xD8, 3); // host SOF timer interrupt flag for USB host, direct bit address clear or write 1 to clear + SBIT(UIF_SUSPEND, 0xD8, 2); // USB suspend or resume event interrupt flag, direct bit address clear or write 1 to clear + SBIT(UIF_TRANSFER, 0xD8, 1); // USB transfer completion interrupt flag, direct bit address clear or write 1 to clear + SBIT(UIF_DETECT, 0xD8, 0); // device detected event interrupt flag for USB host mode, direct bit address clear or write 1 to clear + SBIT(UIF_BUS_RST, 0xD8, 0); // bus reset event interrupt flag for USB device mode, direct bit address clear or write 1 to clear +SFR(USB_INT_ST, 0xD9); // ReadOnly: USB interrupt status +#define bUIS_IS_NAK 0x80 // ReadOnly: indicate current USB transfer is NAK received for USB device mode +#define bUIS_TOG_OK 0x40 // ReadOnly: indicate current USB transfer toggle is OK +#define bUIS_TOKEN1 0x20 // ReadOnly: current token PID code bit 1 received for USB device mode +#define bUIS_TOKEN0 0x10 // ReadOnly: current token PID code bit 0 received for USB device mode +#define MASK_UIS_TOKEN 0x30 // ReadOnly: bit mask of current token PID code received for USB device mode +#define UIS_TOKEN_OUT 0x00 +#define UIS_TOKEN_SOF 0x10 +#define UIS_TOKEN_IN 0x20 +#define UIS_TOKEN_SETUP 0x30 +// bUIS_TOKEN1 & bUIS_TOKEN0: current token PID code received for USB device mode +// 00: OUT token PID received +// 01: SOF token PID received +// 10: IN token PID received +// 11: SETUP token PID received +#define MASK_UIS_ENDP 0x0F // ReadOnly: bit mask of current transfer endpoint number for USB device mode +#define MASK_UIS_H_RES 0x0F // ReadOnly: bit mask of current transfer handshake response for USB host mode: 0000=no response, time out from device, others=handshake response PID received +SFR(USB_MIS_ST, 0xDA); // ReadOnly: USB miscellaneous status +#define bUMS_SOF_PRES 0x80 // ReadOnly: indicate host SOF timer presage status +#define bUMS_SOF_ACT 0x40 // ReadOnly: indicate host SOF timer action status for USB host +#define bUMS_SIE_FREE 0x20 // ReadOnly: indicate USB SIE free status +#define bUMS_R_FIFO_RDY 0x10 // ReadOnly: indicate USB receiving FIFO ready status (not empty) +#define bUMS_BUS_RESET 0x08 // ReadOnly: indicate USB bus reset status +#define bUMS_SUSPEND 0x04 // ReadOnly: indicate USB suspend status +#define bUMS_DM_LEVEL 0x02 // ReadOnly: indicate UDM level saved at device attached to USB host +#define bUMS_DEV_ATTACH 0x01 // ReadOnly: indicate device attached status on USB host +SFR(USB_RX_LEN, 0xDB); // ReadOnly: USB receiving length +SFR(UEP0_CTRL, 0xDC); // endpoint 0 control +SFR(UEP0_T_LEN, 0xDD); // endpoint 0 transmittal length +SFR(UEP4_CTRL, 0xDE); // endpoint 4 control +SFR(UEP4_T_LEN, 0xDF); // endpoint 4 transmittal length +SFR(USB_INT_EN, 0xE1); // USB interrupt enable +#define bUIE_DEV_SOF 0x80 // enable interrupt for SOF received for USB device mode +#define bUIE_DEV_NAK 0x40 // enable interrupt for NAK responded for USB device mode +#define bUIE_FIFO_OV 0x10 // enable interrupt for FIFO overflow +#define bUIE_HST_SOF 0x08 // enable interrupt for host SOF timer action for USB host mode +#define bUIE_SUSPEND 0x04 // enable interrupt for USB suspend or resume event +#define bUIE_TRANSFER 0x02 // enable interrupt for USB transfer completion +#define bUIE_DETECT 0x01 // enable interrupt for USB device detected event for USB host mode +#define bUIE_BUS_RST 0x01 // enable interrupt for USB bus reset event for USB device mode +SFR(USB_CTRL, 0xE2); // USB base control +#define bUC_HOST_MODE 0x80 // enable USB host mode: 0=device mode, 1=host mode +#define bUC_LOW_SPEED 0x40 // enable USB low speed: 0=full speed, 1=low speed +#define bUC_DEV_PU_EN 0x20 // USB device enable and internal pullup resistance enable +#define bUC_SYS_CTRL1 0x20 // USB system control high bit +#define bUC_SYS_CTRL0 0x10 // USB system control low bit +#define MASK_UC_SYS_CTRL 0x30 // bit mask of USB system control +// bUC_HOST_MODE & bUC_SYS_CTRL1 & bUC_SYS_CTRL0: USB system control +// 0 00: disable USB device and disable internal pullup resistance +// 0 01: enable USB device and disable internal pullup resistance, need external pullup resistance +// 0 1x: enable USB device and enable internal pullup resistance +// 1 00: enable USB host and normal status +// 1 01: enable USB host and force UDP/UDM output SE0 state +// 1 10: enable USB host and force UDP/UDM output J state +// 1 11: enable USB host and force UDP/UDM output resume or K state +#define bUC_INT_BUSY 0x08 // enable automatic responding busy for device mode or automatic pause for host mode during interrupt flag UIF_TRANSFER valid +#define bUC_RESET_SIE 0x04 // force reset USB SIE, need software clear +#define bUC_CLR_ALL 0x02 // force clear FIFO and count of USB +#define bUC_DMA_EN 0x01 // DMA enable and DMA interrupt enable for USB +SFR(USB_DEV_AD, 0xE3); // USB device address, lower 7 bits for USB device address +#define bUDA_GP_BIT 0x80 // general purpose bit +#define MASK_USB_ADDR 0x7F // bit mask for USB device address +SFR16(UEP2_DMA, 0xE4); // endpoint 2 buffer start address, little-endian +SFR(UEP2_DMA_L, 0xE4); // endpoint 2 buffer start address low byte +SFR(UEP2_DMA_H, 0xE5); // endpoint 2 buffer start address high byte +SFR16(UEP3_DMA, 0xE6); // endpoint 3 buffer start address, little-endian +SFR(UEP3_DMA_L, 0xE6); // endpoint 3 buffer start address low byte +SFR(UEP3_DMA_H, 0xE7); // endpoint 3 buffer start address high byte +SFR(UEP4_1_MOD, 0xEA); // endpoint 4/1 mode +#define bUEP1_RX_EN 0x80 // enable USB endpoint 1 receiving (OUT) +#define bUEP1_TX_EN 0x40 // enable USB endpoint 1 transmittal (IN) +#define bUEP1_BUF_MOD 0x10 // buffer mode of USB endpoint 1 +// bUEPn_RX_EN & bUEPn_TX_EN & bUEPn_BUF_MOD: USB endpoint 1/2/3 buffer mode, buffer start address is UEPn_DMA +// 0 0 x: disable endpoint and disable buffer +// 1 0 0: 64 bytes buffer for receiving (OUT endpoint) +// 1 0 1: dual 64 bytes buffer by toggle bit bUEP_R_TOG selection for receiving (OUT endpoint), total=128bytes +// 0 1 0: 64 bytes buffer for transmittal (IN endpoint) +// 0 1 1: dual 64 bytes buffer by toggle bit bUEP_T_TOG selection for transmittal (IN endpoint), total=128bytes +// 1 1 0: 64 bytes buffer for receiving (OUT endpoint) + 64 bytes buffer for transmittal (IN endpoint), total=128bytes +// 1 1 1: dual 64 bytes buffer by bUEP_R_TOG selection for receiving (OUT endpoint) + dual 64 bytes buffer by bUEP_T_TOG selection for transmittal (IN endpoint), total=256bytes +#define bUEP4_RX_EN 0x08 // enable USB endpoint 4 receiving (OUT) +#define bUEP4_TX_EN 0x04 // enable USB endpoint 4 transmittal (IN) +// bUEP4_RX_EN & bUEP4_TX_EN: USB endpoint 4 buffer mode, buffer start address is UEP0_DMA +// 0 0: single 64 bytes buffer for endpoint 0 receiving & transmittal (OUT & IN endpoint) +// 1 0: single 64 bytes buffer for endpoint 0 receiving & transmittal (OUT & IN endpoint) + 64 bytes buffer for endpoint 4 receiving (OUT endpoint), total=128bytes +// 0 1: single 64 bytes buffer for endpoint 0 receiving & transmittal (OUT & IN endpoint) + 64 bytes buffer for endpoint 4 transmittal (IN endpoint), total=128bytes +// 1 1: single 64 bytes buffer for endpoint 0 receiving & transmittal (OUT & IN endpoint) +// + 64 bytes buffer for endpoint 4 receiving (OUT endpoint) + 64 bytes buffer for endpoint 4 transmittal (IN endpoint), total=192bytes +SFR(UEP2_3_MOD, 0xEB); // endpoint 2/3 mode +#define bUEP3_RX_EN 0x80 // enable USB endpoint 3 receiving (OUT) +#define bUEP3_TX_EN 0x40 // enable USB endpoint 3 transmittal (IN) +#define bUEP3_BUF_MOD 0x10 // buffer mode of USB endpoint 3 +#define bUEP2_RX_EN 0x08 // enable USB endpoint 2 receiving (OUT) +#define bUEP2_TX_EN 0x04 // enable USB endpoint 2 transmittal (IN) +#define bUEP2_BUF_MOD 0x01 // buffer mode of USB endpoint 2 +SFR16(UEP0_DMA, 0xEC); // endpoint 0 buffer start address, little-endian +SFR(UEP0_DMA_L, 0xEC); // endpoint 0 buffer start address low byte +SFR(UEP0_DMA_H, 0xED); // endpoint 0 buffer start address high byte +SFR16(UEP1_DMA, 0xEE); // endpoint 1 buffer start address, little-endian +SFR(UEP1_DMA_L, 0xEE); // endpoint 1 buffer start address low byte +SFR(UEP1_DMA_H, 0xEF); // endpoint 1 buffer start address high byte +//sfr UH_SETUP = 0xD2; // host aux setup +#define UH_SETUP UEP1_CTRL +#define bUH_PRE_PID_EN 0x80 // USB host PRE PID enable for low speed device via hub +#define bUH_SOF_EN 0x40 // USB host automatic SOF enable +//sfr UH_RX_CTRL = 0xD4; // host receiver endpoint control +#define UH_RX_CTRL UEP2_CTRL +#define bUH_R_TOG 0x80 // expected data toggle flag of host receiving (IN): 0=DATA0, 1=DATA1 +#define bUH_R_AUTO_TOG 0x10 // enable automatic toggle after successful transfer completion: 0=manual toggle, 1=automatic toggle +#define bUH_R_RES 0x04 // prepared handshake response type for host receiving (IN): 0=ACK (ready), 1=no response, time out to device, for isochronous transactions +//sfr UH_EP_PID = 0xD5; // host endpoint and token PID, lower 4 bits for endpoint number, upper 4 bits for token PID +#define UH_EP_PID UEP2_T_LEN +#define MASK_UH_TOKEN 0xF0 // bit mask of token PID for USB host transfer +#define MASK_UH_ENDP 0x0F // bit mask of endpoint number for USB host transfer +//sfr UH_TX_CTRL = 0xD6; // host transmittal endpoint control +#define UH_TX_CTRL UEP3_CTRL +#define bUH_T_TOG 0x40 // prepared data toggle flag of host transmittal (SETUP/OUT): 0=DATA0, 1=DATA1 +#define bUH_T_AUTO_TOG 0x10 // enable automatic toggle after successful transfer completion: 0=manual toggle, 1=automatic toggle +#define bUH_T_RES 0x01 // expected handshake response type for host transmittal (SETUP/OUT): 0=ACK (ready), 1=no response, time out from device, for isochronous transactions +//sfr UH_TX_LEN = 0xD7; // host transmittal endpoint transmittal length +#define UH_TX_LEN UEP3_T_LEN +//sfr UH_EP_MOD = 0xEB; // host endpoint mode +#define UH_EP_MOD UEP2_3_MOD +#define bUH_EP_TX_EN 0x40 // enable USB host OUT endpoint transmittal +#define bUH_EP_TBUF_MOD 0x10 // buffer mode of USB host OUT endpoint +// bUH_EP_TX_EN & bUH_EP_TBUF_MOD: USB host OUT endpoint buffer mode, buffer start address is UH_TX_DMA +// 0 x: disable endpoint and disable buffer +// 1 0: 64 bytes buffer for transmittal (OUT endpoint) +// 1 1: dual 64 bytes buffer by toggle bit bUH_T_TOG selection for transmittal (OUT endpoint), total=128bytes +#define bUH_EP_RX_EN 0x08 // enable USB host IN endpoint receiving +#define bUH_EP_RBUF_MOD 0x01 // buffer mode of USB host IN endpoint +// bUH_EP_RX_EN & bUH_EP_RBUF_MOD: USB host IN endpoint buffer mode, buffer start address is UH_RX_DMA +// 0 x: disable endpoint and disable buffer +// 1 0: 64 bytes buffer for receiving (IN endpoint) +// 1 1: dual 64 bytes buffer by toggle bit bUH_R_TOG selection for receiving (IN endpoint), total=128bytes +//sfr16 UH_RX_DMA = 0xE4; // host rx endpoint buffer start address, little-endian +#define UH_RX_DMA UEP2_DMA +//sfr UH_RX_DMA_L = 0xE4; // host rx endpoint buffer start address low byte +#define UH_RX_DMA_L UEP2_DMA_L +//sfr UH_RX_DMA_H = 0xE5; // host rx endpoint buffer start address high byte +#define UH_RX_DMA_H UEP2_DMA_H +//sfr16 UH_TX_DMA = 0xE6; // host tx endpoint buffer start address, little-endian +#define UH_TX_DMA UEP3_DMA +//sfr UH_TX_DMA_L = 0xE6; // host tx endpoint buffer start address low byte +#define UH_TX_DMA_L UEP3_DMA_L +//sfr UH_TX_DMA_H = 0xE7; // host tx endpoint buffer start address high byte +#define UH_TX_DMA_H UEP3_DMA_H + +/*----- XDATA: xRAM ------------------------------------------*/ + +#define XDATA_RAM_SIZE 0x0400 // size of expanded xRAM, xdata SRAM embedded chip + +/*----- Reference Information --------------------------------------------*/ +#define ID_CH554 0x54 // chip ID + +/* Interrupt routine address and interrupt number */ +#define INT_ADDR_INT0 0x0003 // interrupt vector address for INT0 +#define INT_ADDR_TMR0 0x000B // interrupt vector address for timer0 +#define INT_ADDR_INT1 0x0013 // interrupt vector address for INT1 +#define INT_ADDR_TMR1 0x001B // interrupt vector address for timer1 +#define INT_ADDR_UART0 0x0023 // interrupt vector address for UART0 +#define INT_ADDR_TMR2 0x002B // interrupt vector address for timer2 +#define INT_ADDR_SPI0 0x0033 // interrupt vector address for SPI0 +#define INT_ADDR_TKEY 0x003B // interrupt vector address for touch-key timer +#define INT_ADDR_USB 0x0043 // interrupt vector address for USB +#define INT_ADDR_ADC 0x004B // interrupt vector address for ADC +#define INT_ADDR_UART1 0x0053 // interrupt vector address for UART1 +#define INT_ADDR_PWMX 0x005B // interrupt vector address for PWM1/2 +#define INT_ADDR_GPIO 0x0063 // interrupt vector address for GPIO +#define INT_ADDR_WDOG 0x006B // interrupt vector address for watch-dog timer +#define INT_NO_INT0 0 // interrupt number for INT0 +#define INT_NO_TMR0 1 // interrupt number for timer0 +#define INT_NO_INT1 2 // interrupt number for INT1 +#define INT_NO_TMR1 3 // interrupt number for timer1 +#define INT_NO_UART0 4 // interrupt number for UART0 +#define INT_NO_TMR2 5 // interrupt number for timer2 +#define INT_NO_SPI0 6 // interrupt number for SPI0 +#define INT_NO_TKEY 7 // interrupt number for touch-key timer +#define INT_NO_USB 8 // interrupt number for USB +#define INT_NO_ADC 9 // interrupt number for ADC +#define INT_NO_UART1 10 // interrupt number for UART1 +#define INT_NO_PWMX 11 // interrupt number for PWM1/2 +#define INT_NO_GPIO 12 // interrupt number for GPIO +#define INT_NO_WDOG 13 // interrupt number for watch-dog timer + +/* Special Program Space */ +#define DATA_FLASH_ADDR 0xC000 // start address of Data-Flash +#define BOOT_LOAD_ADDR 0x3800 // start address of boot loader program +#define ROM_CFG_ADDR 0x3FF8 // chip configuration information address +#define ROM_CHIP_ID_HX 0x3FFA // chip ID number highest byte (only low byte valid) +#define ROM_CHIP_ID_LO 0x3FFC // chip ID number low word +#define ROM_CHIP_ID_HI 0x3FFE // chip ID number high word + +/* +New Instruction: MOVX @DPTR1,A +Instruction Code: 0xA5 +Instruction Cycle: 1 +Instruction Operation: + step-1. write ACC @DPTR1 into xdata SRAM embedded chip + step-2. increase DPTR1 +ASM example: + INC XBUS_AUX + MOV DPTR,#TARGET_ADDR ;DPTR1 + DEC XBUS_AUX + MOV DPTR,#SOURCE_ADDR ;DPTR0 + MOV R7,#xxH + LOOP: MOVX A,@DPTR ;DPTR0 + INC DPTR ;DPTR0, if need + .DB 0xA5 ;MOVX @DPTR1,A & INC DPTR1 + DJNZ R7,LOOP +*/ + +#endif // __CH554_H__ diff --git a/src/include/ch554_datatypes.h b/src/include/ch554_datatypes.h new file mode 100644 index 0000000..97e1feb --- /dev/null +++ b/src/include/ch554_datatypes.h @@ -0,0 +1,125 @@ +/*-------------------------------------------------------------------------- +CH554.H +Header file for CH554 microcontrollers. +**************************************** +** Copyright (C) W.ch 1999-2014 ** +** Web: http://wch.cn ** +**************************************** +--------------------------------------------------------------------------*/ + +#ifndef __BASE_TYPE__ +#define __BASE_TYPE__ + +/*----- constant and type define -----------------------------------------*/ + +#ifndef TRUE +#define TRUE 1 +#define FALSE 0 +#endif +#ifndef NULL +#define NULL 0 +#endif +/* +#ifndef BOOL +typedef bit BOOL; +#endif +*/ +#ifndef UINT8 +typedef unsigned char UINT8; +#endif +#ifndef UINT16 +typedef unsigned short UINT16; +#endif +#ifndef UINT32 +typedef unsigned long UINT32; +#endif +#ifndef UINT8D +typedef unsigned char data UINT8D; +#endif +#ifndef UINT16D +typedef unsigned short data UINT16D; +#endif +#ifndef UINT32D +typedef unsigned long data UINT32D; +#endif +#ifndef UINT8I +typedef unsigned char idata UINT8I; +#endif +#ifndef UINT16I +typedef unsigned short idata UINT16I; +#endif +#ifndef UINT32I +typedef unsigned long idata UINT32I; +#endif +#ifndef UINT8X +typedef unsigned char xdata UINT8X; +#endif +#ifndef UINT16X +typedef unsigned short xdata UINT16X; +#endif +#ifndef UINT32X +typedef unsigned long xdata UINT32X; +#endif +#ifndef UINT8V +typedef unsigned char volatile UINT8V; +#endif +#ifndef UINT8DV +typedef unsigned char volatile data UINT8DV; +#endif +#ifndef UINT8XV +typedef unsigned char volatile xdata UINT8XV; +#endif +#ifndef UINT8PV +typedef unsigned char volatile pdata UINT8PV; +#endif +#ifndef UINT8C +typedef const unsigned char code UINT8C; +#endif +#ifndef PUINT8 +typedef unsigned char *PUINT8; +#endif +#ifndef PUINT16 +typedef unsigned short *PUINT16; +#endif +#ifndef PUINT32 +typedef unsigned long *PUINT32; +#endif +#ifndef PUINT8I +typedef unsigned char idata *PUINT8I; +#endif +#ifndef PUINT16I +typedef unsigned short idata *PUINT16I; +#endif +#ifndef PUINT32I +typedef unsigned long idata *PUINT32I; +#endif +#ifndef PUINT8X +typedef unsigned char xdata *PUINT8X; +#endif +#ifndef PUINT16X +typedef unsigned short xdata *PUINT16X; +#endif +#ifndef PUINT32X +typedef unsigned long xdata *PUINT32X; +#endif +#ifndef PUINT8V +typedef unsigned char volatile *PUINT8V; +#endif +#ifndef PUINT8DV +typedef unsigned char volatile data *PUINT8DV; +#endif +#ifndef PUINT8XV +typedef unsigned char volatile xdata *PUINT8XV; +#endif +#ifndef PUINT8PV +typedef unsigned char volatile pdata *PUINT8PV; +#endif +#ifndef PUINT8C +typedef const unsigned char code *PUINT8C; +#endif + +#ifndef STRUCT_OFFSET +#define STRUCT_OFFSET( s, m ) ( (UINT8)( & (((s) *)0) -> (m) ) ) /* get the offset address for a member of a structure */ +#endif + +#endif // __BASE_TYPE__ diff --git a/src/include/ch554_usb.h b/src/include/ch554_usb.h new file mode 100644 index 0000000..34d0d25 --- /dev/null +++ b/src/include/ch554_usb.h @@ -0,0 +1,337 @@ +/*-------------------------------------------------------------------------- +CH554.H +Header file for CH554 microcontrollers. +**************************************** +** Copyright (C) W.ch 1999-2014 ** +** Web: http://wch.cn ** +**************************************** +--------------------------------------------------------------------------*/ + + +#ifndef __USB_DEF__ +#define __USB_DEF__ + +/*----- USB constant and structure define --------------------------------*/ + +/* USB PID */ +#ifndef USB_PID_SETUP +#define USB_PID_NULL 0x00 /* reserved PID */ +#define USB_PID_SOF 0x05 +#define USB_PID_SETUP 0x0D +#define USB_PID_IN 0x09 +#define USB_PID_OUT 0x01 +#define USB_PID_ACK 0x02 +#define USB_PID_NAK 0x0A +#define USB_PID_STALL 0x0E +#define USB_PID_DATA0 0x03 +#define USB_PID_DATA1 0x0B +#define USB_PID_PRE 0x0C +#endif + +/* USB standard device request code */ +#ifndef USB_GET_DESCRIPTOR +#define USB_GET_STATUS 0x00 +#define USB_CLEAR_FEATURE 0x01 +#define USB_SET_FEATURE 0x03 +#define USB_SET_ADDRESS 0x05 +#define USB_GET_DESCRIPTOR 0x06 +#define USB_SET_DESCRIPTOR 0x07 +#define USB_GET_CONFIGURATION 0x08 +#define USB_SET_CONFIGURATION 0x09 +#define USB_GET_INTERFACE 0x0A +#define USB_SET_INTERFACE 0x0B +#define USB_SYNCH_FRAME 0x0C +#endif + +/* USB hub class request code */ +#ifndef HUB_GET_DESCRIPTOR +#define HUB_GET_STATUS 0x00 +#define HUB_CLEAR_FEATURE 0x01 +#define HUB_GET_STATE 0x02 +#define HUB_SET_FEATURE 0x03 +#define HUB_GET_DESCRIPTOR 0x06 +#define HUB_SET_DESCRIPTOR 0x07 +#endif + +/* USB HID class request code */ +#ifndef HID_GET_REPORT +#define HID_GET_REPORT 0x01 +#define HID_GET_IDLE 0x02 +#define HID_GET_PROTOCOL 0x03 +#define HID_SET_REPORT 0x09 +#define HID_SET_IDLE 0x0A +#define HID_SET_PROTOCOL 0x0B +#endif + +/* Bit define for USB request type */ +#ifndef USB_REQ_TYP_MASK +#define USB_REQ_TYP_IN 0x80 /* control IN, device to host */ +#define USB_REQ_TYP_OUT 0x00 /* control OUT, host to device */ +#define USB_REQ_TYP_READ 0x80 /* control read, device to host */ +#define USB_REQ_TYP_WRITE 0x00 /* control write, host to device */ +#define USB_REQ_TYP_MASK 0x60 /* bit mask of request type */ +#define USB_REQ_TYP_STANDARD 0x00 +#define USB_REQ_TYP_CLASS 0x20 +#define USB_REQ_TYP_VENDOR 0x40 +#define USB_REQ_TYP_RESERVED 0x60 +#define USB_REQ_RECIP_MASK 0x1F /* bit mask of request recipient */ +#define USB_REQ_RECIP_DEVICE 0x00 +#define USB_REQ_RECIP_INTERF 0x01 +#define USB_REQ_RECIP_ENDP 0x02 +#define USB_REQ_RECIP_OTHER 0x03 +#endif + +/* USB request type for hub class request */ +#ifndef HUB_GET_HUB_DESCRIPTOR +#define HUB_CLEAR_HUB_FEATURE 0x20 +#define HUB_CLEAR_PORT_FEATURE 0x23 +#define HUB_GET_BUS_STATE 0xA3 +#define HUB_GET_HUB_DESCRIPTOR 0xA0 +#define HUB_GET_HUB_STATUS 0xA0 +#define HUB_GET_PORT_STATUS 0xA3 +#define HUB_SET_HUB_DESCRIPTOR 0x20 +#define HUB_SET_HUB_FEATURE 0x20 +#define HUB_SET_PORT_FEATURE 0x23 +#endif + +/* Hub class feature selectors */ +#ifndef HUB_PORT_RESET +#define HUB_C_HUB_LOCAL_POWER 0 +#define HUB_C_HUB_OVER_CURRENT 1 +#define HUB_PORT_CONNECTION 0 +#define HUB_PORT_ENABLE 1 +#define HUB_PORT_SUSPEND 2 +#define HUB_PORT_OVER_CURRENT 3 +#define HUB_PORT_RESET 4 +#define HUB_PORT_POWER 8 +#define HUB_PORT_LOW_SPEED 9 +#define HUB_C_PORT_CONNECTION 16 +#define HUB_C_PORT_ENABLE 17 +#define HUB_C_PORT_SUSPEND 18 +#define HUB_C_PORT_OVER_CURRENT 19 +#define HUB_C_PORT_RESET 20 +#endif + +/* USB descriptor type */ +#ifndef USB_DESCR_TYP_DEVICE +#define USB_DESCR_TYP_DEVICE 0x01 +#define USB_DESCR_TYP_CONFIG 0x02 +#define USB_DESCR_TYP_STRING 0x03 +#define USB_DESCR_TYP_INTERF 0x04 +#define USB_DESCR_TYP_ENDP 0x05 +#define USB_DESCR_TYP_QUALIF 0x06 +#define USB_DESCR_TYP_SPEED 0x07 +#define USB_DESCR_TYP_OTG 0x09 +#define USB_DESCR_TYP_HID 0x21 +#define USB_DESCR_TYP_REPORT 0x22 +#define USB_DESCR_TYP_PHYSIC 0x23 +#define USB_DESCR_TYP_CS_INTF 0x24 +#define USB_DESCR_TYP_CS_ENDP 0x25 +#define USB_DESCR_TYP_HUB 0x29 +#endif + +/* USB device class */ +#ifndef USB_DEV_CLASS_HUB +#define USB_DEV_CLASS_RESERVED 0x00 +#define USB_DEV_CLASS_AUDIO 0x01 +#define USB_DEV_CLASS_COMMUNIC 0x02 +#define USB_DEV_CLASS_HID 0x03 +#define USB_DEV_CLASS_MONITOR 0x04 +#define USB_DEV_CLASS_PHYSIC_IF 0x05 +#define USB_DEV_CLASS_POWER 0x06 +#define USB_DEV_CLASS_PRINTER 0x07 +#define USB_DEV_CLASS_STORAGE 0x08 +#define USB_DEV_CLASS_HUB 0x09 +#define USB_DEV_CLASS_VEN_SPEC 0xFF +#endif + +/* USB endpoint type and attributes */ +#ifndef USB_ENDP_TYPE_MASK +#define USB_ENDP_DIR_MASK 0x80 +#define USB_ENDP_ADDR_MASK 0x0F +#define USB_ENDP_TYPE_MASK 0x03 +#define USB_ENDP_TYPE_CTRL 0x00 +#define USB_ENDP_TYPE_ISOCH 0x01 +#define USB_ENDP_TYPE_BULK 0x02 +#define USB_ENDP_TYPE_INTER 0x03 +#endif + +#ifndef USB_DEVICE_ADDR +#define USB_DEVICE_ADDR 0x02 /* ĬϵUSB豸ַ */ +#endif +#ifndef DEFAULT_ENDP0_SIZE +#define DEFAULT_ENDP0_SIZE 8 /* default maximum packet size for endpoint 0 */ +#endif +#ifndef DEFAULT_ENDP1_SIZE +#define DEFAULT_ENDP1_SIZE 8 /* default maximum packet size for endpoint 1 */ +#endif +#ifndef MAX_PACKET_SIZE +#define MAX_PACKET_SIZE 64 /* maximum packet size */ +#endif +#ifndef USB_BO_CBW_SIZE +#define USB_BO_CBW_SIZE 0x1F /* CBWܳ */ +#define USB_BO_CSW_SIZE 0x0D /* ״̬CSWܳ */ +#endif +#ifndef USB_BO_CBW_SIG0 +#define USB_BO_CBW_SIG0 0x55 /* CBWʶ־'USBC' */ +#define USB_BO_CBW_SIG1 0x53 +#define USB_BO_CBW_SIG2 0x42 +#define USB_BO_CBW_SIG3 0x43 +#define USB_BO_CSW_SIG0 0x55 /* ״̬CSWʶ־'USBS' */ +#define USB_BO_CSW_SIG1 0x53 +#define USB_BO_CSW_SIG2 0x42 +#define USB_BO_CSW_SIG3 0x53 +#endif + +typedef struct _USB_SETUP_REQ { + uint8_t bRequestType; + uint8_t bRequest; + uint8_t wValueL; + uint8_t wValueH; + uint8_t wIndexL; + uint8_t wIndexH; + uint8_t wLengthL; + uint8_t wLengthH; +} USB_SETUP_REQ, *PUSB_SETUP_REQ; + +typedef USB_SETUP_REQ __xdata *PXUSB_SETUP_REQ; + +typedef struct _USB_DEVICE_DESCR { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bcdUSBL; + uint8_t bcdUSBH; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint8_t idVendorL; + uint8_t idVendorH; + uint8_t idProductL; + uint8_t idProductH; + uint8_t bcdDeviceL; + uint8_t bcdDeviceH; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; +} USB_DEV_DESCR, *PUSB_DEV_DESCR; + +typedef USB_DEV_DESCR __xdata *PXUSB_DEV_DESCR; + +typedef struct _USB_CONFIG_DESCR { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t wTotalLengthL; + uint8_t wTotalLengthH; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t MaxPower; +} USB_CFG_DESCR, *PUSB_CFG_DESCR; + +typedef USB_CFG_DESCR __xdata *PXUSB_CFG_DESCR; + +typedef struct _USB_INTERF_DESCR { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t bInterfaceProtocol; + uint8_t iInterface; +} USB_ITF_DESCR, *PUSB_ITF_DESCR; + +typedef USB_ITF_DESCR __xdata *PXUSB_ITF_DESCR; + +typedef struct _USB_ENDPOINT_DESCR { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + uint8_t wMaxPacketSizeL; + uint8_t wMaxPacketSizeH; + uint8_t bInterval; +} USB_ENDP_DESCR, *PUSB_ENDP_DESCR; + +typedef USB_ENDP_DESCR __xdata *PXUSB_ENDP_DESCR; + +typedef struct _USB_CONFIG_DESCR_LONG { + USB_CFG_DESCR cfg_descr; + USB_ITF_DESCR itf_descr; + USB_ENDP_DESCR endp_descr[1]; +} USB_CFG_DESCR_LONG, *PUSB_CFG_DESCR_LONG; + +typedef USB_CFG_DESCR_LONG __xdata *PXUSB_CFG_DESCR_LONG; + +typedef struct _USB_HUB_DESCR { + uint8_t bDescLength; + uint8_t bDescriptorType; + uint8_t bNbrPorts; + uint8_t wHubCharacteristicsL; + uint8_t wHubCharacteristicsH; + uint8_t bPwrOn2PwrGood; + uint8_t bHubContrCurrent; + uint8_t DeviceRemovable; + uint8_t PortPwrCtrlMask; +} USB_HUB_DESCR, *PUSB_HUB_DESCR; + +typedef USB_HUB_DESCR __xdata *PXUSB_HUB_DESCR; + +typedef struct _USB_HID_DESCR { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bcdHIDL; + uint8_t bcdHIDH; + uint8_t bCountryCode; + uint8_t bNumDescriptors; + uint8_t bDescriptorTypeX; + uint8_t wDescriptorLengthL; + uint8_t wDescriptorLengthH; +} USB_HID_DESCR, *PUSB_HID_DESCR; + +typedef USB_HID_DESCR __xdata *PXUSB_HID_DESCR; + +typedef struct _UDISK_BOC_CBW { /* command of BulkOnly USB-FlashDisk */ + uint8_t mCBW_Sig0; + uint8_t mCBW_Sig1; + uint8_t mCBW_Sig2; + uint8_t mCBW_Sig3; + uint8_t mCBW_Tag0; + uint8_t mCBW_Tag1; + uint8_t mCBW_Tag2; + uint8_t mCBW_Tag3; + uint8_t mCBW_DataLen0; + uint8_t mCBW_DataLen1; + uint8_t mCBW_DataLen2; + uint8_t mCBW_DataLen3; /* uppest byte of data length, always is 0 */ + uint8_t mCBW_Flag; /* transfer direction and etc. */ + uint8_t mCBW_LUN; + uint8_t mCBW_CB_Len; /* length of command block */ + uint8_t mCBW_CB_Buf[16]; /* command block buffer */ +} UDISK_BOC_CBW, *PUDISK_BOC_CBW; + +typedef UDISK_BOC_CBW __xdata *PXUDISK_BOC_CBW; + +typedef struct _UDISK_BOC_CSW { /* status of BulkOnly USB-FlashDisk */ + uint8_t mCSW_Sig0; + uint8_t mCSW_Sig1; + uint8_t mCSW_Sig2; + uint8_t mCSW_Sig3; + uint8_t mCSW_Tag0; + uint8_t mCSW_Tag1; + uint8_t mCSW_Tag2; + uint8_t mCSW_Tag3; + uint8_t mCSW_Residue0; /* return: remainder bytes */ + uint8_t mCSW_Residue1; + uint8_t mCSW_Residue2; + uint8_t mCSW_Residue3; /* uppest byte of remainder length, always is 0 */ + uint8_t mCSW_Status; /* return: result status */ +} UDISK_BOC_CSW, *PUDISK_BOC_CSW; + +typedef UDISK_BOC_CSW __xdata *PXUDISK_BOC_CSW; + +#endif // __USB_DEF__ diff --git a/src/include/debug.c b/src/include/debug.c new file mode 100644 index 0000000..00f1571 --- /dev/null +++ b/src/include/debug.c @@ -0,0 +1,125 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : Debug.C +* Author : WCH +* Version : V1.0 +* Date : 2017/01/20 +* Description : CH554 DEBUG Interface + CH554 main frequency modification, delay function definition + Serial port 0 and serial port 1 initialization + Serial port 0 and serial port 1 transceiver subfunctions + Watchdog initialization +*******************************************************************************/ + +#include + +#include "ch554.h" +#include "debug.h" + + +/******************************************************************************* +* Function Name : mDelayus(UNIT16 n) +* Description : us delay function +* Input : UNIT16 n +* Output : None +* Return : None +*******************************************************************************/ +void mDelayuS( uint16_t n ) // Delay in uS +{ +#ifdef FREQ_SYS +#if FREQ_SYS <= 6000000 + n >>= 2; +#endif +#if FREQ_SYS <= 3000000 + n >>= 2; +#endif +#if FREQ_SYS <= 750000 + n >>= 4; +#endif +#endif + while ( n ) { // total = 12~13 Fsys cycles, 1uS @Fsys=12MHz + ++ SAFE_MOD; // 2 Fsys cycles, for higher Fsys, add operation here +#ifdef FREQ_SYS +#if FREQ_SYS >= 14000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 16000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 18000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 20000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 22000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 24000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 26000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 28000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 30000000 + ++ SAFE_MOD; +#endif +#if FREQ_SYS >= 32000000 + ++ SAFE_MOD; +#endif +#endif + -- n; + } +} + +/******************************************************************************* +* Function Name : mDelayms(UNIT16 n) +* Description : ms delay function +* Input : UNIT16 n +* Output : None +* Return : None +*******************************************************************************/ +void mDelaymS( uint16_t n ) // Delay in mS +{ + while ( n ) { +#ifdef DELAY_MS_HW + while ( ( TKEY_CTRL & bTKC_IF ) == 0 ); + while ( TKEY_CTRL & bTKC_IF ); +#else + mDelayuS( 1000 ); +#endif + -- n; + } +} + +#if SDCC < 370 +void putchar(char c) +{ + while (!TI); /* assumes UART is initialized */ + TI = 0; + SBUF = c; +} + +char getchar() { + while(!RI); /* assumes UART is initialized */ + RI = 0; + return SBUF; +} +#else +int putchar(int c) +{ + while (!TI); /* assumes UART is initialized */ + TI = 0; + SBUF = c & 0xFF; + + return c; +} + +int getchar() { + while(!RI); /* assumes UART is initialized */ + RI = 0; + return SBUF; +} +#endif diff --git a/src/include/debug.h b/src/include/debug.h new file mode 100644 index 0000000..dfddfd4 --- /dev/null +++ b/src/include/debug.h @@ -0,0 +1,211 @@ + +/* Debug */ +/* Provide printf subroutine and delay function */ + +#pragma once + +#include +#include + +#ifndef UART0_BAUD +#define UART0_BAUD 9600 +#endif + +#ifndef UART1_BAUD +#define UART1_BAUD 9600 +#endif + +void mDelayuS (uint16_t n); // Delay in units of uS +void mDelaymS (uint16_t n); // Delay in mS + +/******************************************************************************* +* Function Name : CfgFsys( ) +* Description : CH554 clock selection and configuration function, Fsys 6MHz is used by default, FREQ_SYS can be passed + CLOCK_CFG configuration, the formula is as follows: + Fsys = (Fosc * 4 / (CLOCK_CFG & MASK_SYS_CK_SEL); the specific clock needs to be configured by yourself +*******************************************************************************/ +inline void CfgFsys() +{ + SAFE_MOD = 0x55; + SAFE_MOD = 0xAA; +// CLOCK_CFG |= bOSC_EN_XT; // Enable external crystal +// CLOCK_CFG & = ~ bOSC_EN_INT; // Turn off the internal crystal + +#if FREQ_SYS == 32000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x07; // 32MHz +#elif FREQ_SYS == 24000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x06; // 24MHz +#elif FREQ_SYS == 16000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x05; // 16MHz +#elif FREQ_SYS == 12000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x04; // 12MHz +#elif FREQ_SYS == 6000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x03; // 6MHz +#elif FREQ_SYS == 3000000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x02; // 3MHz +#elif FREQ_SYS == 750000 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x01; // 750KHz +#elif FREQ_SYS == 187500 + CLOCK_CFG = CLOCK_CFG & ~ MASK_SYS_CK_SEL | 0x00; // 187.5MHz +#else + #warning FREQ_SYS invalid or not set +#endif + + SAFE_MOD = 0x00; +} + +/******************************************************************************* +* Function Name : CH554UART0Alter() +* Description : CH554 serial port 0 pin mapping, serial port mapping to P0.2 and P0.3 + +*******************************************************************************/ +inline void CH554UART0Alter() +{ + PIN_FUNC |= bUART0_PIN_X; // P1.2 & P1.3 +} + +/******************************************************************************* +* Function Name : mInitSTDIO() +* Description : CH554 serial port 0 is initialized, T1 is used as the baud rate generator of UART0 by default, T2 can also be used + As a baud rate generator +*******************************************************************************/ +inline void mInitSTDIO( ) +{ + uint32_t x; + uint8_t x2; + + SM0 = 0; + SM1 = 1; + SM2 = 0; //Serial port 0 usage mode 1 + //Use Timer1 as a baud rate generator + RCLK = 0; //UART0 receive clock + TCLK = 0; //UART0 transmit clock + PCON |= SMOD; + x = 10 * FREQ_SYS / UART0_BAUD / 16; //If you change the main frequency, be careful not to overflow the value of x + x2 = x % 10; + x /= 10; + if ( x2 >= 5 ) x ++; //rounding + + TMOD = TMOD & ~ bT1_GATE & ~ bT1_CT & ~ MASK_T1_MOD | bT1_M1; //0X20, Timer1 as 8-bit auto-reload timer + T2MOD = T2MOD | bTMR_CLK | bT1_CLK; //Timer1 clock selection + TH1 = 0-x; //12MHz crystal oscillator, buad / 12 is the actual need to set the baud rate + TR1 = 1; //Start timer 1 + TI = 1; + REN = 1; //Serial 0 receive enable +} + +/******************************************************************************* +* Function Name : CH554UART0RcvByte() +* Description : CH554UART0 receives a byte +* Return : SBUF +*******************************************************************************/ +inline uint8_t CH554UART0RcvByte( ) +{ + while(RI == 0); // wait for uart rx interrupt flag + RI = 0; + return SBUF; +} + +/******************************************************************************* +* Function Name : CH554UART0SendByte(uint8_t SendDat) +* Description : CH554UART0 sends a byte +* Input : uint8_t SendDat; the data to be sent +*******************************************************************************/ +inline void CH554UART0SendByte(uint8_t SendDat) +{ + SBUF = SendDat; + while(TI ==0); // wait for transmit to finish (TI == 1) + TI = 0; +} + +/******************************************************************************* +* Function Name : CH554UART1Alter() +* Description : Set the alternate pin mappings for UART1 (TX on P3.2, RX on P3.4) +*******************************************************************************/ +inline void CH554UART1Alter() +{ + PIN_FUNC |= bUART1_PIN_X; +} + +/******************************************************************************* +* Function Name : UART1Setup() +* Description : CH554 +*******************************************************************************/ +inline void UART1Setup() +{ + U1SM0 = 0; + U1SMOD = 1; + U1REN = 1; + // should correct for rounding in SBAUD1 calculation + SBAUD1 = 256 - FREQ_SYS/16/UART1_BAUD; +} + +/******************************************************************************* +* Function Name : CH554UART1RcvByte() +* Description : CH554UART1 +* Return : SBUF +*******************************************************************************/ +inline uint8_t CH554UART1RcvByte( ) +{ + while(U1RI == 0); + U1RI = 0; + return SBUF1; +} + +/******************************************************************************* +* Function Name : CH554UART1SendByte(uint8_t SendDat) +* Description : CH554UART1 +* Input : uint8_t SendDat +*******************************************************************************/ +inline void CH554UART1SendByte(uint8_t SendDat) +{ + SBUF1 = SendDat; + while(U1TI ==0); + U1TI = 0; +} + +#if SDCC < 370 +void putchar(char c); +char getchar(); +#else +int putchar(int c); +int getchar(void); +#endif + +/******************************************************************************* +* Function Name : CH554WDTModeSelect(uint8_t mode) +* Description : CH554 watchdog mode selection +* Input : uint8_t mode + 0 timer + 1 watchDog +* Output : None +* Return : None +*******************************************************************************/ +inline void CH554WDTModeSelect(uint8_t mode) +{ + SAFE_MOD = 0x55; + SAFE_MOD = 0xaa; //Enter Safe Mode + if(mode){ + GLOBAL_CFG |= bWDOG_EN; //Start watchdog reset + } + + else GLOBAL_CFG &= ~bWDOG_EN; //Start watchdog only as a timer + SAFE_MOD = 0x00; //exit safe Mode + WDOG_COUNT = 0; //Watchdog assignment initial value + +} + +/******************************************************************************* +* Function Name : CH554WDTFeed(uint8_t tim) +* Description : CH554 watchdog timer time setting +* Input : uint8_t tim watchdog reset time setting + + 00H(6MHz)=2.8s + 80H(6MHz)=1.4s +* Output : None +* Return : None +*******************************************************************************/ +inline void CH554WDTFeed(uint8_t tim) +{ + WDOG_COUNT = tim; // Watchdog counter assignment +} diff --git a/src/include/i2c.c b/src/include/i2c.c new file mode 100644 index 0000000..fc5f614 --- /dev/null +++ b/src/include/i2c.c @@ -0,0 +1,120 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : I2C.C +* Author : Zhiyuan Wan +* License : MIT +* Version : V1.0 +* Date : 2018/03/17 +* Description : 8051 Software I2C +*******************************************************************************/ +#include <8051.h> +#include +#include "i2c.h" + +#ifdef I2C_DEFAULT +#define I2C_SDAT P3_4 +#define I2C_SCLK P3_3 +#endif + +#ifndef I2C_SDAT +#define I2C_SDAT P3_4 +#endif + +#ifndef I2C_SCLK +#define I2C_SCLK P3_3 +#endif + +void i2c_init() +{ /* GPIO port initial */ + I2C_SDAT = 1; + I2C_SCLK = 1; +} + +void i2c_delay() +{ + volatile char i = 1; + while(i--); +} + +void i2c_start() +{ + I2C_SDAT = 1; + I2C_SCLK = 1; + i2c_delay(); + + I2C_SDAT = 0; + i2c_delay(); + + I2C_SCLK = 0; + i2c_delay(); +} + +void i2c_stop() +{ + I2C_SDAT = 0; + I2C_SCLK = 1; + i2c_delay(); + + I2C_SDAT = 1; + i2c_delay(); +} + +void i2c_write(unsigned char data) +{ + int i; + + for(i = 0; i < 8; i++) + { + data <<= 1; + I2C_SDAT = CY; + + I2C_SCLK = 1; + i2c_delay(); + + I2C_SCLK = 0; + i2c_delay(); + } +} + +unsigned char i2c_read() +{ + int i; + uint8_t ret = 0; + + I2C_SDAT = 1; + for(i = 0; i < 8; i++) + { + ret <<= 1; + I2C_SCLK = 1; + i2c_delay(); + + if(I2C_SDAT) + ret |= 0x01; + + I2C_SCLK = 0; + i2c_delay(); + + } + return ret; +} + +bool i2c_read_ack() +{ + bool status; + + I2C_SDAT = 1; + + I2C_SCLK = 1; + i2c_delay(); + + status = I2C_SDAT; + + I2C_SCLK = 0; + i2c_delay(); + + return !status; +} + +bool i2c_read_nak() +{ + return !i2c_read_ack(); +} diff --git a/src/include/i2c.h b/src/include/i2c.h new file mode 100644 index 0000000..f9da6d9 --- /dev/null +++ b/src/include/i2c.h @@ -0,0 +1,32 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : I2C.H +* Author : Zhiyuan Wan +* License : MIT +* Version : V1.0 +* Date : 2018/03/17 +* Description : 8051 软件 I2C +*******************************************************************************/ +#ifndef _I2C_H_ + +#define _I2C_H_ + + +typedef __bit bool; + +extern void i2c_init(); + +extern void i2c_start(); + +extern void i2c_stop(); + +extern void i2c_write(unsigned char data); + +extern bool i2c_read_ack(); + +extern bool i2c_read_nak(); + +extern unsigned char i2c_read(); + +#define TW_READ 0x01 + +#endif diff --git a/src/include/pwm.h b/src/include/pwm.h new file mode 100644 index 0000000..373939b --- /dev/null +++ b/src/include/pwm.h @@ -0,0 +1,25 @@ +#pragma once + +#define SetPWMClk(CK_SE) (PWM_CK_SE = CK_SE) //Frequency division, default clock Fsys + +#define SetPWM1Dat(dat) (PWM_DATA1 = dat) //Set PWM output duty cycle +#define SetPWM2Dat(dat) (PWM_DATA2 = dat) + +#define PWM1PinAlter( ) {PIN_FUNC |= bPWM1_PIN_X;} // PWM mapping pin P30 +#define PWM2PinAlter( ) {PIN_FUNC |= bPWM2_PIN_X;} // PWM mapping pin P31 + +#define ForceClearPWMFIFO( ) {PWM_CTRL |= bPWM_CLR_ALL;} //强制清除PWM FIFO和COUNT +#define CancelClearPWMFIFO( ) {PWM_CTRL &= ~bPWM_CLR_ALL;} //取消清除PWM FIFO和COUNT + +#define PWM1OutEnable() (PWM_CTRL |= bPWM1_OUT_EN) //允许PWM1输出 +#define PWM2OutEnable() (PWM_CTRL |= bPWM2_OUT_EN) //允许PWM2输出 +#define DsiablePWM1Out() (PWM_CTRL &= ~bPWM1_OUT_EN) //关闭PWM1输出 +#define DisablePWM2Out() (PWM_CTRL &= ~bPWM2_OUT_EN) //关闭PWM2输出 + +#define PWM1OutPolarHighAct()(PWM_CTRL &= ~bPWM1_POLAR) //PWM1输出默认低,高有效 +#define PWM2OutPolarHighAct()(PWM_CTRL &= ~bPWM2_POLAR) //PWM2输出默认低,高有效 +#define PWM1OutPolarLowAct() (PWM_CTRL |= bPWM1_POLAR) //PWM1输出默认高,低有效 +#define PWM2OutPolarLowAct() (PWM_CTRL |= bPWM2_POLAR) //PWM2输出默认高,低有效 + +#define PWMInterruptEnable() {PWM_CTRL |= bPWM_IF_END | bPWM_IE_END; IE_PWMX = 1;} +#define PWMInterruptDisable() {IE_PWMX = 0;} diff --git a/src/include/spi.c b/src/include/spi.c new file mode 100644 index 0000000..b39764a --- /dev/null +++ b/src/include/spi.c @@ -0,0 +1,131 @@ + + +/********************************** (C) COPYRIGHT ******************************* +* File Name : SPI.C +* Author : WCH +* Version : V1.0 +* Date : 2017/07/05 +* Description : CH554 SPIÖ÷¡¢´Óģʽ½Ó¿Úº¯Êý +×¢£ºÆ¬Ñ¡ÓÐЧʱ£¬´Ó»ú»á×Ô¶¯¼ÓÔØSPI0_S_PREµÄÔ¤ÖÃÖµµ½·¢ËÍÒÆÎ»»º³åÇø£¬ËùÒÔ×îºÃ¿ÉÒÔÔÚÆ¬Ñ¡ +ÓÐЧǰÏòSPI0_S_PRE¼Ä´æÆ÷дÈëÔ¤·¢Öµ£¬»òÕßÔÚÖ÷»ú¶Ë¶ªÆúÊ׸ö½ÓÊÕ×Ö½Ú£¬·¢ËÍʱעÒâÖ÷»ú»áÏÈ +È¡×ßSPI0_S_PREÀïÃæµÄÖµ²úÉúÒ»¸öS0_IF_BYTEÖжϡ£ +Èç¹ûƬѡ´ÓÎÞЧµ½ÓÐЧ£¬´Ó»úÊ×ÏȽøÐз¢Ë͵ϰ£¬×îºÃ°ÑÊä³öµÄÊ××ֽڷŵ½SPI0_S_PRE¼Ä´æÆ÷ÖУ» +Èç¹ûÒѾ­´¦ÓÚÆ¬Ñ¡ÓÐЧµÄ»°£¬Êý¾ÝÊý¾ÝʹÓÃSPI0_DATA¾Í¿ÉÒÔ +*******************************************************************************/ + +#include +#include "spi.h" + +/******************************************************************************* +* Function Name : SPIMasterModeSet( uint8_t mode ) +* Description : SPIÖ÷»úģʽ³õʼ»¯ +* Input : uint8_t mode +* Output : None +* Return : None +*******************************************************************************/ +void SPIMasterModeSet(uint8_t mode) +{ + SPI0_SETUP = 0; //Masterģʽ,¸ßλÔÚǰ + if(mode == 0){ + SPI0_CTRL = 0x60; //ģʽ0 + } + else if(mode == 3){ + SPI0_CTRL = 0x68; //ģʽ3 + } + P1_MOD_OC &= 0x0F; + P1_DIR_PU |= 0xB0; //SCS,MOSI,SCKÉèÍÆÍìÊä³ö + P1_DIR_PU &= 0xBF; //MISOÉ踡¿ÕÊäÈë + + // Set clock speed + SPI0_CK_SE = 0x02; +} + +/******************************************************************************* +* Function Name : CH554SPIInterruptInit() +* Description : CH554SPIÖжϳõʼ»¯ +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPIInterruptInit() +{ + //IP_EX |= bIP_SPI0; //SPI0ÖжÏÓÅÏȼ¶ÉèÖà + SPI0_SETUP |= bS0_IE_FIFO_OV | bS0_IE_BYTE; //ʹÄܽÓÊÕ1×Ö½ÚÖжϣ¬Ê¹ÄÜFIFOÒç³öÖÐ¶Ï + SPI0_CTRL |= bS0_AUTO_IF; //×Ô¶¯ÇåS0_IF_BYTEÖжϱêÖ¾ + SPI0_STAT |= 0xff; //Çå¿ÕSPI0ÖжϱêÖ¾ +#ifdef SPI_Interrupt + IE_SPI0 = 1; //ʹÄÜSPI0ÖÐ¶Ï +#endif +} + +/******************************************************************************* +* Function Name : CH554SPIMasterWrite(uint8_t dat) +* Description : CH554Ó²¼þSPIдÊý¾Ý,Ö÷»úģʽ +* Input : uint8_t dat Êý¾Ý +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPIMasterWrite(uint8_t dat) +{ + SPI0_DATA = dat; + while(S0_FREE == 0); //µÈ´ý´«ÊäÍê³É +//Èç¹ûbS0_DATA_DIRΪ1£¬´Ë´¦¿ÉÒÔÖ±½Ó¶Áȡһ¸ö×Ö½ÚµÄÊý¾ÝÓÃÓÚ¿ìËÙ¶Áд +} + +/******************************************************************************* +* Function Name : CH554SPIMasterRead( ) +* Description : CH554Ó²¼þSPI0¶ÁÊý¾Ý£¬Ö÷»úģʽ +* Input : None +* Output : None +* Return : uint8_t ret +*******************************************************************************/ +uint8_t CH554SPIMasterRead() +{ + SPI0_DATA = 0xff; + while(S0_FREE == 0); + return SPI0_DATA; +} + +/******************************************************************************* +* Function Name : SPISlvModeSet( ) +* Description : SPI´Ó»úģʽ³õʼ»¯ +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SPISlvModeSet( ) +{ + SPI0_SETUP = 0x80; //Slvģʽ,¸ßλÔÚǰ + SPI0_CTRL = 0x81; //¶ÁдFIFO,×Ô¶¯ÇåS0_IF_BYTE±êÖ¾ + P1_MOD_OC &= 0x0F; + P1_DIR_PU &= 0x0F; //SCS,MOSI,SCK,MISOÈ«ÉèÖø¡¿ÕÊäÈë +} + +/******************************************************************************* +* Function Name : CH554SPISlvWrite(uint8_t dat) +* Description : CH554Ó²¼þSPIдÊý¾Ý£¬´Ó»úģʽ +* Input : uint8_t dat Êý¾Ý +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPISlvWrite(uint8_t dat) +{ + SPI0_DATA = dat; + while(S0_IF_BYTE==0); + S0_IF_BYTE = 0; +} + +/******************************************************************************* +* Function Name : CH554SPISlvRead( ) +* Description : CH554Ó²¼þSPI0¶ÁÊý¾Ý£¬´Ó»úģʽ +* Input : None +* Output : None +* Return : uint8_t ret +*******************************************************************************/ +uint8_t CH554SPISlvRead() +{ + while(S0_IF_BYTE==0); + S0_IF_BYTE = 0; + return SPI0_DATA; +} + diff --git a/src/include/spi.h b/src/include/spi.h new file mode 100644 index 0000000..cc4906e --- /dev/null +++ b/src/include/spi.h @@ -0,0 +1,72 @@ +#pragma once + +#include + + +#define SPI_CK_SET( n ) (SPI0_CK_SE = n) //SPIʱÖÓÉèÖú¯Êý + +#define SPIMasterAssertCS() (SCS = 0) +#define SPIMasterDeassertCS() (SCS = 1) + +/******************************************************************************* +* Function Name : SPIMasterModeSet( uint8_t mode ) +* Description : SPIÖ÷»úģʽ³õʼ»¯ +* Input : uint8_t mode +* Output : None +* Return : None +*******************************************************************************/ +void SPIMasterModeSet(uint8_t mode); + +/******************************************************************************* +* Function Name : CH554SPIInterruptInit() +* Description : CH554SPIÖжϳõʼ»¯ +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPIInterruptInit(); + +/******************************************************************************* +* Function Name : CH554SPIMasterWrite(uint8_t dat) +* Description : CH554Ó²¼þSPIдÊý¾Ý£¬Ö÷»úģʽ +* Input : uint8_t dat Êý¾Ý +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPIMasterWrite(uint8_t dat); + +/******************************************************************************* +* Function Name : CH554SPIMasterRead( ) +* Description : CH554Ó²¼þSPI0¶ÁÊý¾Ý£¬Ö÷»úģʽ +* Input : None +* Output : None +* Return : uint8_t ret +*******************************************************************************/ +uint8_t CH554SPIMasterRead(); + +/******************************************************************************* +* Function Name : SPISlvModeSet( ) +* Description : SPI´Ó»úģʽ³õʼ»¯ +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SPISlvModeSet( ); + +/******************************************************************************* +* Function Name : CH554SPISlvWrite(uint8_t dat) +* Description : CH554Ó²¼þSPIдÊý¾Ý£¬´Ó»úģʽ +* Input : uint8_t dat Êý¾Ý +* Output : None +* Return : None +*******************************************************************************/ +void CH554SPISlvWrite(uint8_t dat); + +/******************************************************************************* +* Function Name : CH554SPISlvRead( ) +* Description : CH554Ó²¼þSPI0¶ÁÊý¾Ý£¬´Ó»úģʽ +* Input : None +* Output : None +* Return : uint8_t ret +*******************************************************************************/ +uint8_t CH554SPISlvRead(); diff --git a/src/include/touchkey.c b/src/include/touchkey.c new file mode 100644 index 0000000..b82d8d6 --- /dev/null +++ b/src/include/touchkey.c @@ -0,0 +1,119 @@ + +/********************************** (C) COPYRIGHT ******************************* +* File Name : TouchKey.C +* Author : WCH +* Version : V1.1 +* Date : 2017/07/05 +* Description : CH554Touch button sampling interval setting, channel selection and switching, and interrupt processing function +*******************************************************************************/ +#include +#include + +#include "ch554.h" +#include "debug.h" +#include "touchkey.h" + +uint16_t KeyFree[KEY_LAST-KEY_FIRST+1]; //Touch idle value storage, used to compare the state of the key +volatile uint8_t KeyBuf = 0; //Touch button status, 0 means no button, non-zero means currently detected button is pressed +volatile uint16_t KeyData; + +/******************************************************************************* +* Function Name : GetTouchKeyFree() +* Description : Get the value of the touch button idle state +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void GetTouchKeyFree() +{ + uint8_t i, j; + for(i = KEY_FIRST; i<= KEY_LAST; ++i) + KeyFree[i-KEY_FIRST] = 0; + for(j = 0; j < 4; ++j){ + for(i = KEY_FIRST; i<= KEY_LAST; ++i){ + TKEY_CTRL = ((TKEY_CTRL & 0xF8) | i) + 1; + while((TKEY_CTRL & bTKC_IF) == 0); + uint16_t val = TKEY_DAT & 0x3FFF; + KeyFree[i-KEY_FIRST] += val; + } + } + for(i = KEY_FIRST; i<= KEY_LAST; ++i) + KeyFree[i-KEY_FIRST] /= 4; +#if INTERRUPT_TouchKey + IE_TKEY = 1; //Enable Touch_Key interrupt +#endif +} + +/******************************************************************************* +* Function Name : TouchKeyChannelSelect(uint8_t ch) +* Description : Touch key channel selection +* Input : uint8_t ch Use channel + 0~5 Representing sampling channels +* Output : None +* Return : success 1 + failure 0 Unsupported channel +*******************************************************************************/ +uint8_t TouchKeyChannelSelect(uint8_t ch) +{ + KeyBuf = 0; + if(ch < 6) + { + TKEY_CTRL = ((TKEY_CTRL & 0xF8) | ch)+1; + return 1; + } + return 0; +} + +#if INTERRUPT_TouchKey +/******************************************************************************* +* Function Name : TouchKeyInterrupt(void) +* Description : Touch_Key Interrupt service routine +*******************************************************************************/ +void TouchKeyInterrupt( void ) interrupt INT_NO_TKEY using 1 //Touch_Key interrupt service routine, use register set 1 +{ + uint8_t ch; + uint16_t KeyData; + + KeyData = TKEY_DAT & 0x3fff; //Keep 87us, take it away as soon as possible + ch = TKEY_CTRL&7; //Get current sampling channel + if ( ch > KEY_LAST ){ + TKEY_CTRL = ((TKEY_CTRL & 0xF8) | KEY_FIRST) + 1; + } + else + { + TKEY_CTRL ++; //Switch to the next sampling channel + } + if ( KeyData < (KeyFree[ch-KEY_FIRST] - KEY_ACT) ) //If the condition is met, it means that the key is pressed + { + KeyBuf=ch; //You can perform key action processing here or set a flag to notify main for processing + } +} +#else +/******************************************************************************* +* Function Name : TouchKeyChannelQuery() +* Description : Touch button channel status query +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TouchKeyChannelQuery() +{ + uint8_t ch; + + while((TKEY_CTRL&bTKC_IF) == 0); //When bTKC_IF becomes 1, the sampling of this cycle is completed + KeyData = TKEY_DAT & 0x3FFF; //Keep 87us, take it away as soon as possible + ch = (TKEY_CTRL&7) - 1; //Get current sampling channel + if ( ch == KEY_LAST ){ + TKEY_CTRL = (TKEY_CTRL & 0xF8 | KEY_FIRST) + 1; //Start sampling from the first channel + } + else + { + ++TKEY_CTRL; //Switch to the next sampling channel + } + if ( KeyData < (KeyFree[ch-KEY_FIRST] - KEY_ACT) ) //If the condition is met, it means that the key is pressed + { + KeyBuf=ch; //You can perform key action processing here or set a flag to notify main for processing + } +} +#endif + diff --git a/src/include/touchkey.h b/src/include/touchkey.h new file mode 100644 index 0000000..fe9dd1a --- /dev/null +++ b/src/include/touchkey.h @@ -0,0 +1,49 @@ +#pragma once + +//#define INTERRUPT_TouchKey 0 //Open TouchKey interrupt mode +#define KEY_FIRST 4 //Sampling start channel +#define KEY_LAST 5 //End of sampling channel +#define KEY_ACT 500 // Button is pressed, the channel sampling value decreases, the value decreases, the sensitivity is high, the value increases, the sensitivity is low + +extern uint16_t KeyFree[KEY_LAST-KEY_FIRST+1]; //Touch idle value storage, used to compare the state of the key +extern volatile uint8_t KeyBuf; //Touch button status, 0 means no button, 1 means currently detected button is pressed +extern volatile uint16_t KeyData; + +#define TouchKeyOFF() {TKEY_CTRL &= 0xF8;} //Turn off the capacitance detection, only for 1ms or 2ms timer interrupt +#define TouchKeyON_NoChannel() {TKEY_CTRL = TKEY_CTRL & 0xF8 | 7;} //Turn on capacitance detection, but do not connect the channel +#define TouchKeyQueryCyl1ms() {TKEY_CTRL &= ~bTKC_2MS;} //Touch button sampling period setting 1ms +#define TouchKeyQueryCyl2ms() {TKEY_CTRL |= bTKC_2MS;} //Touch button sampling period setting 2ms + +/******************************************************************************* +* Function Name : TouchKeyChannelSelect(UINT8 ch) +* Description : Touch key channel selection +* Input : UINT8 ch Use channel + 0: Turn off the capacitance detection, only for 1ms or 2ms timer interrupt + 1~6 Representing sampling channels + 7: Turn on capacitance detection, but do not connect the channel +* Output : None +* Return : success1 + failure 0 +*******************************************************************************/ +uint8_t TouchKeyChannelSelect(uint8_t ch); + +/******************************************************************************* +* Function Name : GetTouchKeyFree() +* Description : Get the value of the touch button idle state +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void GetTouchKeyFree(); + +#if !INTERRUPT_TouchKey +/******************************************************************************* +* Function Name : TouchKeyChannelQuery() +* Description : Touch button channel status query +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TouchKeyChannelQuery(); +#endif + diff --git a/src/pwm/Makefile b/src/pwm/Makefile new file mode 100644 index 0000000..3ef1910 --- /dev/null +++ b/src/pwm/Makefile @@ -0,0 +1,7 @@ +TARGET = pwm + +C_FILES = \ + main.c \ + ../include/debug.c + +include ../Makefile.include diff --git a/src/pwm/main.c b/src/pwm/main.c new file mode 100644 index 0000000..45b4e20 --- /dev/null +++ b/src/pwm/main.c @@ -0,0 +1,40 @@ +// Enable both PWM peripherals, and connect them to their GPIO outputs + +#include +#include +#include + +void main(){ + CfgFsys(); + SetPWMClk(4); + ForceClearPWMFIFO(); + CancelClearPWMFIFO(); + + // Uncomment these lines to use the alternate pin mapping + //PWM1PinAlter(); + //PWM2PinAlter(); + + PWM1OutEnable(); + //PWM2OutEnable(); + + PWM1OutPolarHighAct(); + //PWM2OutPolarLowAct(); + + SetPWM1Dat(0x10); + //SetPWM2Dat(0x40); + + while(1){ + int i = 0; + for (i = 0 ; i < 255; i++){ + SetPWM1Dat(i); + //SetPWM2Dat(i); + mDelaymS(1); + } + for (i = 255 ; i > 0; i--){ + SetPWM1Dat(i); + //SetPWM2Dat(i); + mDelaymS(1); + } + mDelaymS(1); + } +} diff --git a/src/pwm/pwm.bin b/src/pwm/pwm.bin new file mode 100644 index 0000000000000000000000000000000000000000..d3cfb77210f7fef812f5c2a261849e0e64e724e2 GIT binary patch literal 310 zcmZQ#U}IuPDs5yJVl;Z%l)%iyz+B1j(uE;Gx{6@}qge$*=>mo)lRquy*ulWWy5Q!Q zTc1i7{C`sM|J#kf6$~$c>bNSwNgTq~*AwUBf)~;(>-~7%$ zL6mhNG6ZXAc&-GKoxuD8V&x5xmB_LJGnpEG_s#5U>TgyOm;q$3n+dcZ#4BxLPyzsa C>xM`G literal 0 HcmV?d00001 diff --git a/src/touchkey/Makefile b/src/touchkey/Makefile new file mode 100644 index 0000000..44ba187 --- /dev/null +++ b/src/touchkey/Makefile @@ -0,0 +1,8 @@ +TARGET = touchkey + +C_FILES = \ + main.c \ + ../include/debug.c \ + ../include/touchkey.c + +include ../Makefile.include diff --git a/src/touchkey/main.c b/src/touchkey/main.c new file mode 100644 index 0000000..ecdef59 --- /dev/null +++ b/src/touchkey/main.c @@ -0,0 +1,60 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : Main.C +* Author : WCH +* Version : V1.1 +* Date : 2017/07/05 +* Description : CH554Touch button interrupt and query mode to collect and report the current sampling channel button status, including demo functions such as initialization and button sampling +*******************************************************************************/ +#include +#include + +#include +#include +#include + +void main() +{ + uint8_t i; + CfgFsys( ); //CH554 clock selection configuration + mDelaymS(5); //It is recommended to modify the main frequency with a slight delay to wait for the chip power supply to stabilize + mInitSTDIO( ); //Serial port 0 initialization + + printf("\n\n\n\nstart ...\n"); + + P1_DIR_PU &= 0x0C; //All touch channels are set as floating input, and channels that are not used can be left unset + TouchKeyQueryCyl2ms(); //TouchKey query cycle 2ms + GetTouchKeyFree(); //Get sampling reference value + for(i=KEY_FIRST;i<(KEY_LAST+1);i++) //Print sampling reference value + { + printf("Channel %d base sample %d\n",(uint16_t)i, KeyFree[i-KEY_FIRST]); + } + TouchKeyChannelSelect(KEY_FIRST); + +#if INTERRUPT_TouchKey + EA = 1; + while(1) + { + if(KeyBuf) //key_buf is non-zero, indicating that a key press was detected + { + printf("INT TouchKey Channel %02x \n",(uint16_t)KeyBuf); //Print current key status channel + KeyBuf = 0; //Clear key press sign + mDelaymS(100); //Delay is meaningless, simulate single-chip to do button processing + } + mDelaymS(100); //Delay is meaningless, imitating microcontroller to do other things + } +#else + while(1) + { + TouchKeyChannelQuery(); //Query the status of touch keys + if(KeyBuf) //key_buf is non-zero, indicating that a key press was detected + { + printf("Query TouchKey Channel %d (val: %d)\t", KeyBuf, KeyData); //Print current key status channel + printf("keyfree=%d\n", KeyFree[KeyBuf-KEY_FIRST]); + KeyBuf = 0; + + mDelaymS(1000); //Delay is meaningless, simulate single-chip to do button processing + } + mDelaymS(100); //Delay is meaningless, imitating microcontroller to do other things + } +#endif +} diff --git a/src/touchkey/touchkey.bin b/src/touchkey/touchkey.bin new file mode 100644 index 0000000000000000000000000000000000000000..bb4124880f834c9c114cfffa4429bee2f9bd2f57 GIT binary patch literal 3137 zcma)8d2AEe8GoMf_(+@s6FYIj;rJle65EN#S1!{W>bC60Es3O@iES24o1+gm2l~kyacGXf`43%1e>hjOB?H`RQPuWdEh_-!8Acy;A91>@j ztvVyW?;XGI{@ynxfPw&h>|mER|6_pOv5A@# z>WI=HA#1;koJWJ$<6-hs?A^TkXEY!ShA?*4g%FdQ1ry|Jn-2ua8!Ohxr3UE z%BNqGqok0uKbpUGhiU7*yBH-a@H15>dP1lpq+z;t;c?UACAs<%Whk7%?01W9$$|go zs`Qoc&Lr30Uw>a3mM&51OA3Re?_<*#kKM*$4HS+hcPQqbypEN!yv)S%z$7Ujm6T_q z1+l`hB%^$@By)?>j3$}6A9TnumLsU-my`L}qFJ1AE-hUxxK@~)IyXHMAYvL*q6H4N z90k#^RyLAqF+tu4!ltvrTCbStAnTLsA6XZyuMHoaamibJ~ynH0!)!cET>UgE< zxCw)_q$psFPpnUrBy?J`fKw*cCA2Z#l&v$WB0XL~P#Z9WvD-41KL+v{r7a^A2g!D& zF~$=l5ctfUo+892lv>i9QZhwvBD`&eeCt*HwbJWlqlPQxtlxN2`NW3WX3RaZ&bH@M zb@S7W3y&KYXBwB1lkrx+YBCvbecn#W1b;~;<`4b#lzyo6bXnAJvK+g&4u-XG<9fKM z1a8))Q3cv?-8fn~W;)GB!?9Uy{%;o;*;Zssx1!3JX*v@kiTq=?tOSSY&yIq(LDUkp z4uHcTy5$InR;7^*+1ct0Ta$rC2dr#>rbg)CVM7=;io%fdBIF$~+yEU$*iZ=@O^kKi zse(>kO9BouDXY^@67mVbiNhgIn9O)}?|993p{*6#+lE0Nz86$Nj&C2K%^!h04a2S! zks?#_6qQmyr&dxz;sL7>zIH@mA%Xkar+?CvyAGMj`hqN60Kmqm)$2+mZM@YSc^1T#qqE--6D=t z!92lS^6Z2;;^qnjvtP`yoI8J2T9_SEk$+#QQf<5j*E=W6| zt3gL&2Aa^h1V?8>a0AO5bEM~*$NdG;Ht4d$Y8uwKpq_`NVOS>BrUN=&33eybahlFz4Vm(k+3Cb{XdN6{1~*9^^83(Y9h)d;^H$CnpDBtvNWFXzR zAm}?wJIgu^p$|{gLvJng)rs9TM6os*vOf;B&xHKY=7o0O)!O`1VpA4xfEQn1U!Zce zvWaYwNh)<-d;`3M&d1$@UK{k;CxaVVervWcL|hhS!zde}vvXZSZD(E3FIYra-Pgi4 z3)W!8ipHRYiPDb&6r)V&+n_Bf~*upb7Te86}ZoLmmqiWKh87>K)4 z9qvj+;;pX5UkQ7>4tcnOG;(92fL=HBc`nz(S}&~gUGZLDRWkWnuzoq5p*-~?{H0$! zUCt>Z6jStlR1V8UZE`U&W}Fy#O2Pd>Y$oK5>+Vs{X)-F`crzp0G__sYTlP@241Wi? ziI`Z-VpUi0a6{O1g})lcpWh&Pk()~j{5yyj!tbK6N#J4Y?E825#4K!^eLpp8oxK|t zcdTK2Xna~?|DxpQ;SYEtQvU0MFdGJ@e{xULXG{~)AFn+89AI|tXN>jr^?9Iu@6Na0 z>f2|u?lJD#d7#gDVCPRl`}*)Q4}6F1+uv{O`6;`5@3;H)pn#?cLjYTETw-8}pou literal 0 HcmV?d00001