From 096131b87b983b40b1a2c96cfedbc7e2c857d309 Mon Sep 17 00:00:00 2001 From: true Date: Mon, 16 Oct 2023 14:29:23 -0700 Subject: [PATCH] WIP code Builds, but is not yet usable in any way nor is anything tested. This includes ADC reading, basic RGBLED control, and init code. Still need to do probe, user IO including mode select and settings, RGBLED programs, and more. --- include/adc.h | 10 ++ include/led.h | 20 ++++ include/py32f0xx_conf.h | 34 +++++++ include/py32f0xx_it.h | 48 ++++++++++ include/testo.h | 80 ++++++++++++++++ src/adc.c | 142 ++++++++++++++++++++++++++++ src/led.c | 151 ++++++++++++++++++++++++++++++ src/main.c | 135 +++++++++++++++++++++++++++ src/probe.c | 8 ++ src/py32f0xx_it.c | 86 +++++++++++++++++ src/rgbprog.c | 25 +++++ src/system/system_py32f0xx.c | 173 +++++++++++++++++++++++++++++++++++ src/userio.c | 60 ++++++++++++ 13 files changed, 972 insertions(+) create mode 100644 include/adc.h create mode 100644 include/led.h create mode 100644 include/py32f0xx_conf.h create mode 100644 include/py32f0xx_it.h create mode 100644 include/testo.h create mode 100644 src/adc.c create mode 100644 src/led.c create mode 100644 src/main.c create mode 100644 src/probe.c create mode 100644 src/py32f0xx_it.c create mode 100644 src/rgbprog.c create mode 100644 src/system/system_py32f0xx.c create mode 100644 src/userio.c diff --git a/include/adc.h b/include/adc.h new file mode 100644 index 0000000..2253999 --- /dev/null +++ b/include/adc.h @@ -0,0 +1,10 @@ + +/* + * adc.c: probe, user config, and user IO (switch and button) reading + * + * file creation: 20231016 0102 + */ + + +void adc_init(); +void adc_next(); \ No newline at end of file diff --git a/include/led.h b/include/led.h new file mode 100644 index 0000000..e96c45f --- /dev/null +++ b/include/led.h @@ -0,0 +1,20 @@ + +/* + * led.h: rgbled (and piezo) routines + * + * file creation: 20231015 0059 + */ + + +#include + + + +void led_init(); +void led_next(); + +void led_mode_rgb(); +void led_mode_buzzer(); + +void led_setrgb(uint8_t i, uint16_t r, uint16_t g, uint16_t b); +void led_buzz(uint8_t buzz); diff --git a/include/py32f0xx_conf.h b/include/py32f0xx_conf.h new file mode 100644 index 0000000..cae5e7d --- /dev/null +++ b/include/py32f0xx_conf.h @@ -0,0 +1,34 @@ +#ifndef _INC_PY32F00X_CONF_H_ +#define _INC_PY32F00X_CONF_H_ + + + +#include + +// low level libs +#include "py32f0xx_ll_adc.h" +#include "py32f0xx_ll_bus.h" +//#include "py32f0xx_ll_comp.h" +#include "py32f0xx_ll_cortex.h" +//#include "py32f0xx_ll_crc.h" +#include "py32f0xx_ll_dma.h" +//#include "py32f0xx_ll_exti.h" +#include "py32f0xx_ll_flash.h" +#include "py32f0xx_ll_gpio.h" +//#include "py32f0xx_ll_iwdg.h" +#include "py32f0xx_ll_i2c.h" +//#include "py32f0xx_ll_led.h" +//#include "py32f0xx_ll_lptim.h" +//#include "py32f0xx_ll_pwr.h" +#include "py32f0xx_ll_rcc.h" +//#include "py32f0xx_ll_rtc.h" +//#include "py32f0xx_ll_spi.h" +#include "py32f0xx_ll_system.h" +#include "py32f0xx_ll_tim.h" +//#include "py32f0xx_ll_usart.h" +#include "py32f0xx_ll_utils.h" +//#include "py32f0xx_ll_wwdg.h" + + + +#endif /* _INC_PY32F00X_CONF_H */ diff --git a/include/py32f0xx_it.h b/include/py32f0xx_it.h new file mode 100644 index 0000000..447d294 --- /dev/null +++ b/include/py32f0xx_it.h @@ -0,0 +1,48 @@ +/** + ****************************************************************************** + * @file py32f0xx_it.h + * @author MCU Application Team + * @brief This file contains the headers of the interrupt handlers. + ****************************************************************************** + * @attention + * + *

© Copyright (c) Puya Semiconductor Co. + * All rights reserved.

+ * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __PY32F0XX_IT_H +#define __PY32F0XX_IT_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Private includes ----------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions prototypes ---------------------------------------------*/ +void NMI_Handler(void); +void HardFault_Handler(void); +void SVC_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __PY32F0XX_IT_H */ + +/************************ (C) COPYRIGHT Puya *****END OF FILE******************/ diff --git a/include/testo.h b/include/testo.h new file mode 100644 index 0000000..36c7f21 --- /dev/null +++ b/include/testo.h @@ -0,0 +1,80 @@ +/* + * testo.h: test-o hardware configuration + * + * file creation: 20231015 0021 + */ + + +#include "py32f0xx_conf.h" + + + +#define CONF_SET1_PORT GPIOA +#define CONF_SET1_PIN 0 // analog-input +#define CONF_SET1_AN ADC_CHSELR_CHSEL0 + +#define VREF_IN_PORT GPIOA +#define VREF_IN_PIN 0 // anlog-input +#define VREF_IN_AN ADC_CHSELR_CHSEL0 + +#define PROBE_PORT GPIOA +#define PROBE_PIN 1 // analog-input +#define PROBE_AN ADC_CHSELR_CHSEL1 + +#define I2C_PORT GPIOA +#define I2C_DEV I2C1 +#define I2C_AF LL_GPIO_AF12_I2C +#define I2C_IRQn I2C1_IRQn +#define I2C_SDA_PIN 2 // alt-func +#define I2C_SCL_PIN 3 // alt-func + +#define RGB_PORT GPIOA +#define RGB_B_PIN 4 // alt-func +#define RGB_G_PIN 5 // alt-func +#define RGB_R_PIN 6 // alt-func +#define TIM_RGB TIM3 +#define TIM_RGB_B_CH LL_TIM_CHANNEL_CH3 +#define TIM_RGB_G_CH LL_TIM_CHANNEL_CH2 +#define TIM_RGB_R_CH LL_TIM_CHANNEL_CH1 +#define PWM_RGB_B TIM_RGB->CCR3 +#define PWM_RGB_G TIM_RGB->CCR2 +#define PWM_RGB_R TIM_RGB->CCR1 + +#define CONF_MODE_PORT GPIOA +#define CONF_MODE_PIN 7 // analog-input +#define CONF_MODE_AN ADC_CHSELR_CHSEL7 + +#define RGBSEL0_PORT GPIOA +#define RGBSEL0_PIN 12 // output, default low + +#define UART_PORT GPIOA +#define UART_DEV USART1 +#define UART_IRQN USART1_IRQn +#define UART_RX_PIN 13 // alt-func (if used) +#define UART_RX_AF LL_GPIO_AF8_USART1 +#define UART_TX_PIN 14 // alt-func (if used) +#define UART_TX_AF LL_GPIO_AF1_USART1 + + +#define CONF_SET0_PORT GPIOB +#define CONF_SET0_PIN 0 // analog-input +#define CONF_SET0_AN ADC_CHSELR_CHSEL8 + +#define RGBSEL1_PORT GPIOB +#define RGBSEL1_PIN 1 // output, default low + + +#define PROBESEL_PORT GPIOF +#define PROBESEL_PIN 2 // output, default high + + +#define ADC_SET0 3 +#define ADC_SET1 0 +#define ADC_SET_MODE 2 + +#define ADC_PROBE 1 + +#define ADC_VREF_INT 5 +#define ADC_VREF_EXT 0 +#define ADC_THERM 4 + diff --git a/src/adc.c b/src/adc.c new file mode 100644 index 0000000..19b19cb --- /dev/null +++ b/src/adc.c @@ -0,0 +1,142 @@ +/* + * adc.c: probe, user config, and user IO (switch and button) reading + * + * performs a scanning read on all used ADC inputs and will DMA + * the results to working variables in one-shot mode. this ADC + * only uses main voltage as a reference, so scans also include + * VREFINT for compensation. There is no way to configure a + * different analog channel (including VREFINT) as the reference + * voltage - only the analog supply can be the reference. + * + * because most inputs are high impedance, which is not ideal, + * sampling time is increased to the maximum. this results in + * a final ADC sample rate of ~33KHz, still well beyond + * what is needed in this application. + * + * file creation: 20231015 0121 + */ + + +#include + +#include "testo.h" + + + +#define SAMPLE_TIME LL_ADC_SAMPLINGTIME_239CYCLES_5 + +#define ADC_CHANNELS 6 +#define ADC_HISTLEN 16 + + + +static uint16_t adc_read[ADC_CHANNELS]; +static uint16_t adc_hist[ADC_CHANNELS][ADC_HISTLEN]; +static uint16_t adc_avg[ADC_CHANNELS]; + +static uint8_t adc_idx = ADC_HISTLEN; + +static int16_t vref; +static uint8_t calibrate = 0; + + + +void adc_init() +{ + // ensure ADC is disabled + ADC1->CR = 0; + + // calibration configuration + ADC1->CCSR = LL_ADC_CAL_SAMPLINGTIME_8CYCLES | ADC_CCSR_CALSEL; + + // enable VREFINT and temperature sensor + ADC->CCR = ADC_CCR_TSEN | ADC_CCR_VREFEN; + + // configure scan channels, sampling time + ADC1->CHSELR = CONF_SET1_AN | PROBE_AN | + CONF_MODE_AN | CONF_SET0_AN | + ADC_CHSELR_CHSEL11 | ADC_CHSELR_CHSEL12; + ADC1->SMPR = SAMPLE_TIME; + + // by default, DMA selection for all channels is ADC + // so all we need to do is set the peripheral address + DMA1_Channel1->CPAR = (uint32_t)&ADC1->DR; +} + +void adc_next() +{ + uint8_t i, j; + int16_t w; + + // start ADC calibration + if (calibrate) { + calibrate = 0; + + // stop if conversion in progress (it shouldn't ever be) + if (ADC1->CR & ADC_CR_ADSTART) { + ADC1->CR |= ADC_CR_ADSTP; + while (ADC1->CR & ADC_CR_ADSTP); + } + + // disable ADC and start calibration + ADC1->CR &= ~(ADC_CR_ADEN); + ADC1->CR |= ADC_CR_ADCAL; + } + + // copy data to history from last read + adc_idx++; + if (adc_idx > ADC_HISTLEN) { + // nothing to copy when first starting + adc_idx = 0; + calibrate = 1; + } else { + // copy data to history + for (i = 0; i < ADC_CHANNELS; i++) { + adc_hist[i][adc_idx] = adc_read[i]; + } + + // next one + // if we're looping, then average our last reads + adc_idx++; + if (adc_idx >= ADC_HISTLEN) { + adc_idx = 0; + + // average old analog data + for (i = 0; i < ADC_CHANNELS; i++) { + adc_avg[i] = 0; + for (j = 0; j < ADC_HISTLEN; j++) { + adc_avg[i] += adc_hist[i][j]; + } + adc_avg[i] >>= 4; + } + + // check vref to determine if we need to recalibrate + // the way this is written now, + // this will always do a double-calibrate at the start + w = adc_avg[ADC_VREF_INT]; + if ((abs(vref - w) > 3) || (abs(w - vref) > 3)) { + calibrate = 1; + vref = adc_avg[ADC_VREF_INT]; + } + } + } + + // wait for calibration to complete, if started + while (ADC1->CR & ADC_CR_ADCAL); + + // configure and enable DMA + DMA1_Channel1->CNDTR = ADC_CHANNELS; + DMA1_Channel1->CMAR = (uint32_t)adc_read; + DMA1_Channel1->CCR = LL_DMA_PRIORITY_MEDIUM | + LL_DMA_MDATAALIGN_HALFWORD | + LL_DMA_PDATAALIGN_HALFWORD | + LL_DMA_MEMORY_INCREMENT | + LL_DMA_MODE_CIRCULAR | + LL_DMA_DIRECTION_PERIPH_TO_MEMORY | + DMA_CCR_EN; + + // enable and start ADC + ADC1->ISR = 0x8e; // clear all interrupt flags (per DS; mistranslated) + ADC1->CR = ADC_CR_ADEN; + ADC1->CR |= ADC_CR_ADSTART; +} \ No newline at end of file diff --git a/src/led.c b/src/led.c new file mode 100644 index 0000000..bcdcb45 --- /dev/null +++ b/src/led.c @@ -0,0 +1,151 @@ +/* + * led.c: rgbled (and piezo) routines + * + * file creation: 20231015 0037 + */ + + +#include "testo.h" + + + +#define RED 0 +#define GRN 1 +#define BLU 2 + +#define MODE_RGB 0 +#define MODE_BUZZ 1 + + + +static uint8_t led_mode; // RGBLED mode or piezo mode +static uint8_t led_sel; // which RGBLED active? + +static uint8_t snd_buzz; // piezo sounder active? + +static uint16_t rgb[2][3]; // RGBLED actual values to set + + + +/* + * deselects, configures, then outputs the next RGBLED. + * also sounds the buzzer if buzzer mode is enabled. + * run this at an interrupt frequency twice the buzzer frequency. + */ +void led_next() +{ + // next LED + led_sel++; + led_sel &= 1; + + // clear outputs + RGBSEL0_PORT->BRR = (1 << RGBSEL0_PIN); + RGBSEL1_PORT->BRR = (1 << RGBSEL1_PIN); + + if (!led_sel || (led_mode == MODE_RGB)) { + // set PWMs in RGB mode, or when right LED set + PWM_RGB_R = rgb[led_sel][RED]; + PWM_RGB_R = rgb[led_sel][GRN]; + PWM_RGB_R = rgb[led_sel][BLU]; + } else { + // clear PWMs in piezo mode when piezo should be active + PWM_RGB_R = PWM_RGB_G = PWM_RGB_B = 0; + } + + // reset timer counter for consistency + TIM_RGB->CNT = 0; + + // enable selected LED + if (led_sel) { + if ((led_mode == MODE_BUZZ) && !snd_buzz) return; + RGBSEL1_PORT->BSRR = (1 << RGBSEL1_PIN); + } else { + RGBSEL0_PORT->BSRR = (1 << RGBSEL0_PIN); + } +} + +/* + * sets RGBLED values directly. + */ +void led_setrgb(uint8_t i, uint16_t r, uint16_t g, uint16_t b) +{ + i &= 1; + rgb[i][RED] = r; + rgb[i][GRN] = g; + rgb[i][BLU] = b; +} + +/* + * configures system to use right RGBLED instead of piezo sounder. + */ +void led_mode_rgb() +{ + led_mode = MODE_RGB; +} + +/* + * configures system to use piezo sounder instead of right RGBLED. + */ +void led_mode_buzzer() +{ + led_mode = MODE_BUZZ; +} + +/* + * activates piezo buzzer output. + */ +void led_buzz(uint8_t buzz) +{ + snd_buzz = buzz & 1; +} + +/* + * initializes RGBLED PWMs and variables. + * assumes GPIO has already been configured. + */ +void led_init() +{ + LL_TIM_InitTypeDef tim = {0}; + LL_TIM_OC_InitTypeDef pwm = {0}; + + + // configure timer + tim.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + tim.CounterMode = LL_TIM_COUNTERMODE_UP; + tim.Prescaler = 0; + /* PWM period = 1000 */ + tim.Autoreload = 1000 - 1; // ~8KHz operation, roughly 10-bit + tim.RepetitionCounter = 0; + + LL_TIM_Init(TIM_RGB, &tim); + + + // configure timer outputs + pwm.OCMode = LL_TIM_OCMODE_PWM2; + pwm.OCState = LL_TIM_OCSTATE_ENABLE; + pwm.OCPolarity = LL_TIM_OCPOLARITY_HIGH; + pwm.OCIdleState = LL_TIM_OCIDLESTATE_LOW; + + pwm.CompareValue = 0; + LL_TIM_OC_Init(TIM_RGB, TIM_RGB_R_CH, &pwm); + LL_TIM_OC_Init(TIM_RGB, TIM_RGB_G_CH, &pwm); + LL_TIM_OC_Init(TIM_RGB, TIM_RGB_B_CH, &pwm); + + + // clear all outputs + for (uint8_t i = 0; i < 3; i++) { + rgb[0][i] = rgb[1][i] = 0; + } + + // enable timer + LL_TIM_EnableAllOutputs(TIM_RGB); + LL_TIM_EnableCounter(TIM_RGB); + + // other setup + led_mode = MODE_RGB; + led_sel = 1; + snd_buzz = 0; + + // start outputting data + led_next(); +} \ No newline at end of file diff --git a/src/main.c b/src/main.c new file mode 100644 index 0000000..e222442 --- /dev/null +++ b/src/main.c @@ -0,0 +1,135 @@ +/* + * main.c: test-o continuity and diode tester + * + * your robot addon badge buddy for testing all the things + * + * file creation: 20231015 0021 + */ + + +#include "testo.h" + +#include "adc.h" +#include "led.h" + + + +uint16_t ctr; +uint32_t uptime; + + + +static inline void gpio_init() +{ + // set registers manually instead of with + // LL functions to save space. + // though we probably don't _need_ this space... + + // set I2C outputs as open drain + GPIOA->OTYPER = 0x000c; + // enable pullups on I2C outputs + GPIOA->PUPDR = 0x24000050; + // datasheet doesn't say what the speeds are for GPIO... + // so set SWDIO to very high speed, all other outputs as high speed + GPIOA->OSPEEDR = 0x2E002AA0; + // alternate function select + // PA6=T3C1, PA5=T3C2, PA4=T3C3, PA3=I2C_SCL, PA2=I2C_SDA + GPIOA->AFR[0] = 0x01DDCC00; + + // PA14=ALT, PA13=ALT, PA12=OUT, PA11=OUT + // PA7=AN, PA6=AF, PA5=AF, PA4=AF + // PA3=AF, PA2=AF, PA1=AN, PA0=AN + // unused pins are digital inputs + GPIOA->MODER = 0x2900EAAF; + + + // PB1=OUT, PB0=AN + // unused pins are analog + GPIOB->OSPEEDR = 0x00000008; + GPIOB->MODER = 0xfffffff7; + + // PF2=OUT, low speed + // unused pins are analog + GPIOF->MODER = 0xFFFFFCDF; +} + +static inline void clk_init() +{ + LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1); + LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1); + + // enable GPIO clocks + RCC->IOPENR = LL_IOP_GRP1_PERIPH_GPIOA | + LL_IOP_GRP1_PERIPH_GPIOB | + LL_IOP_GRP1_PERIPH_GPIOF; + + // enable peripheral clocks + RCC->AHBENR = LL_AHB1_GRP1_PERIPH_DMA1; + RCC->APBENR1 = LL_APB1_GRP1_PERIPH_TIM3; + RCC->APBENR2 = LL_APB1_GRP2_PERIPH_ADC1 | LL_APB1_GRP2_PERIPH_SYSCFG; +} + +static inline void systick_init() +{ + // configure nvic + NVIC_EnableIRQ(SysTick_IRQn); + NVIC_SetPriority(SysTick_IRQn, 0); + + // configure timebase with interrupt at 4096Hz + // this assumes we'll always be running at 8MHz + SysTick_Config((8000000 / 4096) - 1); +} + +/* + * get things started, then + * low priority application execution + */ +int main() +{ + // base hardware initialization + clk_init(); + gpio_init(); + + // peripheral initialization + led_init(); + adc_init(); + + // mainline loop interrupt + systick_init(); + + // let's go + __enable_irq(); + + while (1) { + // run LED programs out of interrupt context at 256Hz + if ((ctr & 0xf) == 0) { + + } + + // nap time + __WFI(); + } +} + +/* + * main application interrupt + */ +void SysTick_Handler(void) +{ + ctr++; + + // run LED programs quickly + led_next(); + + // limit counter to 4096 + ctr &= 0xfff; + if (!ctr) { + uptime++; + } + + // run main logic at 1024Hz + if ((ctr & 0x3) == 0) { + // adc + adc_next(); + } +} \ No newline at end of file diff --git a/src/probe.c b/src/probe.c new file mode 100644 index 0000000..87249eb --- /dev/null +++ b/src/probe.c @@ -0,0 +1,8 @@ +/* + * probe.c: helping you probe things + * + * this file is responsible for figuring out the + * continuity and diode tests from the raw analog data. + * + * file creation: 20231016 0255 + */ \ No newline at end of file diff --git a/src/py32f0xx_it.c b/src/py32f0xx_it.c new file mode 100644 index 0000000..4e5664b --- /dev/null +++ b/src/py32f0xx_it.c @@ -0,0 +1,86 @@ +/** + ****************************************************************************** + * @file py32f0xx_it.c + * @author MCU Application Team + * @brief Interrupt Service Routines. + ****************************************************************************** + * @attention + * + *

© Copyright (c) Puya Semiconductor Co. + * All rights reserved.

+ * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "py32f0xx_it.h" + +/* Private includes ----------------------------------------------------------*/ +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private user code ---------------------------------------------------------*/ +/* External variables --------------------------------------------------------*/ + +/******************************************************************************/ +/* Cortex-M0+ Processor Interruption and Exception Handlers */ +/******************************************************************************/ +/** + * @brief This function handles Non maskable interrupt. + */ +void NMI_Handler(void) +{ +} + +/** + * @brief This function handles Hard fault interrupt. + */ +void HardFault_Handler(void) +{ + while (1) + { + } +} + +/** + * @brief This function handles System service call via SWI instruction. + */ +void SVC_Handler(void) +{ +} + +/** + * @brief This function handles Pendable request for system service. + */ +void PendSV_Handler(void) +{ +} + +/** + * @brief This function handles System tick timer. + */ +/* +void SysTick_Handler(void) +{ + +} +*/ + +/******************************************************************************/ +/* PY32F0xx Peripheral Interrupt Handlers */ +/* Add here the Interrupt Handlers for the used peripherals. */ +/* For the available peripheral interrupt handler names, */ +/* please refer to the startup file. */ +/******************************************************************************/ + +/************************ (C) COPYRIGHT Puya *****END OF FILE******************/ diff --git a/src/rgbprog.c b/src/rgbprog.c new file mode 100644 index 0000000..d6532fb --- /dev/null +++ b/src/rgbprog.c @@ -0,0 +1,25 @@ +/* + * rgbprog.c: making your eyes light up + * + * file creation: 20231015 0119 + */ + + +#include "led.h" + + + +void rgbprog_continuity() +{ + +} + +void rgbprog_diode() +{ + +} + +void rgbprog_rainbow() +{ + +} \ No newline at end of file diff --git a/src/system/system_py32f0xx.c b/src/system/system_py32f0xx.c new file mode 100644 index 0000000..866b7b6 --- /dev/null +++ b/src/system/system_py32f0xx.c @@ -0,0 +1,173 @@ +/** + ****************************************************************************** + * @file system_py32f0xx.c + * @author MCU Application Team + * @Version V1.0.0 + * @Date 2020-10-19 + * @brief CMSIS Cortex-M0+ Device Peripheral Access Layer System Source File. + ****************************************************************************** + */ + +#include "py32f0xx.h" + +#if !defined (HSE_VALUE) +#define HSE_VALUE 24000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) +#define HSI_VALUE 8000000U /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +#if !defined (LSI_VALUE) +#define LSI_VALUE 32768U /*!< Value of LSI in Hz*/ +#endif /* LSI_VALUE */ + +#if !defined (LSE_VALUE) +#define LSE_VALUE 32768U /*!< Value of LSE in Hz*/ +#endif /* LSE_VALUE */ + + +/************************* Miscellaneous Configuration ************************/ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +//#define FORBID_VECT_TAB_MIGRATION +//#define VECT_TAB_SRAM +#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. + This value must be a multiple of 0x100. */ +/******************************************************************************/ +/*---------------------------------------------------------------------------- + Clock Variable definitions + *----------------------------------------------------------------------------*/ +/* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. +*/ +uint32_t SystemCoreClock = HSI_VALUE; + +const uint32_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +const uint32_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; +const uint32_t HSIFreqTable[8] = {4000000U, 8000000U, 16000000U, 22120000U, 24000000U, 4000000U, 4000000U, 4000000U}; + +/*---------------------------------------------------------------------------- + Clock functions + *----------------------------------------------------------------------------*/ +void SystemCoreClockUpdate(void) /* Get Core Clock Frequency */ +{ + uint32_t tmp; + uint32_t hsidiv; + uint32_t hsifs; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case RCC_CFGR_SWS_0: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + + case (RCC_CFGR_SWS_1 | RCC_CFGR_SWS_0): /* LSI used as system clock */ + SystemCoreClock = LSI_VALUE; + break; +#if defined(RCC_LSE_SUPPORT) + case RCC_CFGR_SWS_2: /* LSE used as system clock */ + SystemCoreClock = LSE_VALUE; + break; +#endif +#if defined(RCC_PLL_SUPPORT) + case RCC_CFGR_SWS_1: /* PLL used as system clock */ + if ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI) /* HSI used as PLL clock source */ + { + hsifs = ((READ_BIT(RCC->ICSCR, RCC_ICSCR_HSI_FS)) >> RCC_ICSCR_HSI_FS_Pos); + SystemCoreClock = 2 * (HSIFreqTable[hsifs]); + } + else /* HSE used as PLL clock source */ + { + SystemCoreClock = 2 * HSE_VALUE; + } + break; +#endif + case 0x00000000U: /* HSI used as system clock */ + default: /* HSI used as system clock */ + hsifs = ((READ_BIT(RCC->ICSCR, RCC_ICSCR_HSI_FS)) >> RCC_ICSCR_HSI_FS_Pos); + hsidiv = (1UL << ((READ_BIT(RCC->CR, RCC_CR_HSIDIV)) >> RCC_CR_HSIDIV_Pos)); + SystemCoreClock = (HSIFreqTable[hsifs] / hsidiv); + break; + } + /* Compute HCLK clock frequency --------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * Initialize the system + * + * @param none + * @return none + * + * @brief Setup the microcontroller system. + * Initialize the System. + */ +void SystemInit(void) +{ + /* Set the HSI clock to 8MHz by default */ + RCC->ICSCR = (RCC->ICSCR & 0xFFFF0000) | (0x1 << 13) | *(uint32_t *)(0x1fff0f04); + + /* Configure the Vector Table location add offset address ------------------*/ +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ +#endif +} + +#ifndef FORBID_VECT_TAB_MIGRATION +#ifndef VECT_TAB_SRAM +#if (defined (__CC_ARM)) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) +extern int32_t $Super$$main(void); +uint32_t VECT_SRAM_TAB[48]__attribute__((section(".ARM.__at_0x20000000"))); + +/* re-define main function */ +int $Sub$$main(void) +{ + uint8_t i; + uint32_t *pFmcVect = (uint32_t *)(FLASH_BASE | VECT_TAB_OFFSET); + for (i = 0; i < 48; i++) + { + VECT_SRAM_TAB[i] = pFmcVect[i]; + } + + SCB->VTOR = SRAM_BASE; + + $Super$$main(); + return 0; +} +#elif defined(__ICCARM__) +extern int32_t main(void); +/* __low_level_init will auto called by IAR cstartup */ +extern void __iar_data_init3(void); +uint32_t VECT_SRAM_TAB[48] @SRAM_BASE; +int __low_level_init(void) +{ + uint8_t i; + uint32_t *pFmcVect = (uint32_t *)(FLASH_BASE | VECT_TAB_OFFSET); + /* call IAR table copy function. */ + __iar_data_init3(); + + for (i = 0; i < 48; i++) + { + VECT_SRAM_TAB[i] = pFmcVect[i]; + } + + SCB->VTOR = SRAM_BASE; + + main(); + return 0; +} +#endif +#endif +#endif diff --git a/src/userio.c b/src/userio.c new file mode 100644 index 0000000..99cf643 --- /dev/null +++ b/src/userio.c @@ -0,0 +1,60 @@ +/* + * adc.c: reacting when you fiddle with buttons, switches, and knobs + * + * mode switch: modes are changed only when the button is not being + * pushed, as button being pushed negates the mode switch response. + * for the mode to change, the mode switch must be in the new position + * without wavering for at least 3 rounds. this will prevent the + * mode from changing by someone fucking around with the button or + * when the button is used normally. + * + * button: is connected to mode switch ADC. if below threshold, then + * we can be certain button is pushed. we still wait a debounce + * round to ensure button is pushed. our code can fire events on + * either button being held or button being released. the actual + * push event does not do anything with this code. + * + * settings knobs: these are used by the settings module which works + * with the other modules and the button for setting user settings. + * the values are scaled from the ADC value, with bounds being set + * on the low and high ends and further scaled for usability. + * please read the manual if you want to know what settings do. + * + * file creation: 20231015 0122 + */ + + +#include + + + +#define MODE_CONT 0 +#define MODE_CONT_TARGET 0x46d + +#define MODE_FUN 1 +#define MODE_FUN_TARGET 0xa2b + +#define MODE_DIODE 2 +#define MODE_DIODE_TARGET 0xf80 + +#define MODE_HYSTERESIS 20 + +#define MODE_ANALOG_MIN 0x80 + + + +uint8_t modesw; +uint8_t modesw_next; +uint8_t modesw_count; + +uint8_t knob[2]; + +uint8_t btn = 0; +uint16_t btn_held = 0; + + + +void userio_parse() +{ + +} \ No newline at end of file