WIP code
ADC is sort of functioning, but not reliably. LEDs are sort of working. Buzzer isn't working right and is nearly always on as I can't set the PF2 mode.
This commit is contained in:
parent
096131b87b
commit
ecc478661f
|
@ -1,7 +1,7 @@
|
|||
{
|
||||
"build": {
|
||||
"cpu": "cortex-m0plus",
|
||||
"extra_flags": "-DPY32F003x6",
|
||||
"extra_flags": "-DPY32F030x6",
|
||||
"f_cpu": "8000000L",
|
||||
"mcu": "py32f030x6",
|
||||
"product_line": "PY32F030x6"
|
||||
|
@ -21,7 +21,7 @@
|
|||
"cmsis-dap"
|
||||
]
|
||||
},
|
||||
"name": "Generic PY32F002/003/030 (configured as 32K PY32F030x6)",
|
||||
"name": "Generic 16/32K PY32F002/003/030 (configured as 32K PY32F030x6)",
|
||||
"url": "https://github.com/trueserve",
|
||||
"vendor": "trueControl"
|
||||
}
|
|
@ -5,6 +5,18 @@
|
|||
* file creation: 20231016 0102
|
||||
*/
|
||||
|
||||
#ifndef _INC_ADC_H
|
||||
#define _INC_ADC_H
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
|
||||
void adc_init();
|
||||
void adc_next();
|
||||
|
||||
uint8_t adc_next();
|
||||
|
||||
|
||||
|
||||
#endif /* _INC_ADC_H */
|
|
@ -0,0 +1,20 @@
|
|||
/*
|
||||
* flash.h: flashing user config and system option bytes
|
||||
*
|
||||
* file creation: 20231019 0129
|
||||
*/
|
||||
|
||||
#ifndef _INC_FLASH_H
|
||||
#define _INC_FLASH_H
|
||||
|
||||
|
||||
|
||||
void flash_optr_checkfix();
|
||||
|
||||
void flash_optr_set();
|
||||
|
||||
void flash_init();
|
||||
|
||||
|
||||
|
||||
#endif /* _INC_FLASH_H */
|
|
@ -5,6 +5,9 @@
|
|||
* file creation: 20231015 0059
|
||||
*/
|
||||
|
||||
#ifndef _INC_LED_H
|
||||
#define _INC_LED_H
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
@ -18,3 +21,7 @@ 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);
|
||||
|
||||
|
||||
|
||||
#endif /* _INC_LED_H */
|
|
@ -4,6 +4,9 @@
|
|||
* file creation: 20231015 0021
|
||||
*/
|
||||
|
||||
#ifndef _INC_TESTO_H
|
||||
#define _INC_TESTO_H
|
||||
|
||||
|
||||
#include "py32f0xx_conf.h"
|
||||
|
||||
|
@ -78,3 +81,6 @@
|
|||
#define ADC_VREF_EXT 0
|
||||
#define ADC_THERM 4
|
||||
|
||||
|
||||
|
||||
#endif /* _INC_TESTO_H */
|
|
@ -0,0 +1,12 @@
|
|||
/*
|
||||
* userio.h: reacting when you fiddle with buttons, switches, and knobs
|
||||
*
|
||||
* file creation: 20231016 1505
|
||||
*/
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
|
||||
void userio_parse();
|
|
@ -871,7 +871,7 @@ ErrorStatus LL_FLASH_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit)
|
|||
FLASH->CR|=FLASH_CR_OPTSTRT;
|
||||
|
||||
/* set bit EOPIE */
|
||||
FLASH->CR|=FLASH_CR_EOPIE;
|
||||
// FLASH->CR|=FLASH_CR_EOPIE;
|
||||
|
||||
/* trigger program */
|
||||
*((__IO uint32_t *)(0x40022080))=0xff;
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
[env]
|
||||
platform = nxplpc ; not actually this and we are not using a framework
|
||||
build_type = debug ; setting platform = nxplpc makes everything happy
|
||||
; setting platform = nxplpc makes everything happy
|
||||
; as we'll get nano specs and any other needed shit
|
||||
board = generic_py32f030x6
|
||||
|
||||
|
@ -28,13 +28,17 @@ debug_extra_cmds =
|
|||
upload_protocol = custom
|
||||
upload_command = $PYTHONEXE ${platformio.packages_dir}/tool-pyocd/pyocd-flashtool.py --config $PROJECT_DIR/pyocd.yaml -t PY32F030x6 $SOURCE
|
||||
|
||||
build_flags =
|
||||
-DUSE_FULL_LL_DRIVER
|
||||
-L.
|
||||
-Os
|
||||
-std=gnu11
|
||||
platform_packages =
|
||||
toolchain-gccarmnoneeabi@1.100301.220327 ; build issues with GCC12, use GCC10 for now
|
||||
tool-pyocd ; user won't have to install it
|
||||
|
||||
|
||||
[env:sc7-testobot-py32f-dbg_pyocd]
|
||||
build_type = debug
|
||||
board_build.ldscript = py32f030x6.ld
|
||||
|
||||
debug_build_flags =
|
||||
-Wl,-Map=.pio/output_dbg.map
|
||||
-DUSE_FULL_LL_DRIVER
|
||||
-L.
|
||||
-Os
|
||||
|
@ -42,26 +46,15 @@ debug_build_flags =
|
|||
-Wl,-Map=.pio/output_dbg.map
|
||||
-g
|
||||
|
||||
platform_packages =
|
||||
toolchain-gccarmnoneeabi@1.100301.220327 ; build issues with GCC12, use GCC10 for now
|
||||
tool-pyocd ; user won't have to install it
|
||||
|
||||
|
||||
[env:sc7-testobot-py32f-dbg_pyocd]
|
||||
board_build.ldscript = py32f030x6.ld
|
||||
|
||||
debug_build_flags =
|
||||
-Wl,-Map=.pio/output_dbg.map
|
||||
|
||||
|
||||
[env:sc7-testobot-py32f-rel_bl]
|
||||
build_type = release
|
||||
board_build.ldscript = py32f030x6_bl.ld
|
||||
board_upload.maximum_size = 30720 ; 2K reserved for bootloader
|
||||
|
||||
build_flags =
|
||||
-Wl,-Map=.pio/output_rel.map
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
-DUSE_FULL_LL_DRIVER
|
||||
-L.
|
||||
-Os
|
||||
-std=gnu11
|
||||
|
|
|
@ -31,6 +31,8 @@ MEMORY
|
|||
{
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
PERIPHERAL (rw): ORIGIN = 0x40000000, LENGTH = 512M
|
||||
PPB (rw) : ORIGIN = 0xe0000000, LENGTH = 512M
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
|
|
|
@ -3,12 +3,13 @@
|
|||
def will_connect(board):
|
||||
print("notice: adding peripheral memory map...");
|
||||
|
||||
target.memory_map.add_region(DeviceRegion(
|
||||
name="Peripheral",
|
||||
start=0x40000000,
|
||||
length=0x20000000,
|
||||
access='rw'
|
||||
))
|
||||
# target.memory_map.add_region(DeviceRegion(
|
||||
# name="Peripheral",
|
||||
# start=0x40000000,
|
||||
# length=0x20000000,
|
||||
# access='rw'
|
||||
# ))
|
||||
|
||||
target.memory_map.add_region(DeviceRegion(
|
||||
name="PPB",
|
||||
start=0xE0000000,
|
||||
|
|
113
src/adc.c
113
src/adc.c
|
@ -9,9 +9,9 @@
|
|||
* 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.
|
||||
* sampling time is increased. this results in a final ADC sample rate
|
||||
* of about 33KHz, still well beyond what is needed in this application.
|
||||
* this value may change in the future.
|
||||
*
|
||||
* file creation: 20231015 0121
|
||||
*/
|
||||
|
@ -28,13 +28,16 @@
|
|||
#define ADC_CHANNELS 6
|
||||
#define ADC_HISTLEN 16
|
||||
|
||||
#define CONF_CALIBRATE (1 << 0)
|
||||
#define CONF_USEPROBE (1 << 1)
|
||||
|
||||
|
||||
|
||||
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 uint8_t adc_idx = ADC_HISTLEN + 1;
|
||||
|
||||
static int16_t vref;
|
||||
static uint8_t calibrate = 0;
|
||||
|
@ -52,31 +55,90 @@ void adc_init()
|
|||
// 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 |
|
||||
// configure scan channels, sampling time (11 = temp, 12 = vrefint)
|
||||
ADC1->CHSELR = CONF_SET1_AN | PROBE_AN | // note: SET1 and PROBE are
|
||||
CONF_MODE_AN | CONF_SET0_AN | // shared and reflect one chan
|
||||
ADC_CHSELR_CHSEL11 | ADC_CHSELR_CHSEL12;
|
||||
ADC1->SMPR = SAMPLE_TIME;
|
||||
|
||||
// run in non-circular DMA mode, with wait mode enabled
|
||||
ADC1->CFGR1 = ADC_CFGR1_OVRMOD | ADC_CFGR1_WAIT | LL_ADC_REG_DMA_TRANSFER_LIMITED;
|
||||
|
||||
// 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;
|
||||
DMA1_Channel1->CMAR = (uint32_t)adc_read;
|
||||
}
|
||||
|
||||
void adc_next()
|
||||
/*
|
||||
* internal function for stopping ADC conversion in progress.
|
||||
*/
|
||||
void adc_stop()
|
||||
{
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* internal function for setting up the ADC for a read.
|
||||
*/
|
||||
void adc_go()
|
||||
{
|
||||
// stop if conversion in progress (it shouldn't ever be)
|
||||
adc_stop();
|
||||
|
||||
// configure and enable DMA
|
||||
DMA1_Channel1->CCR = 0;
|
||||
DMA1_Channel1->CNDTR = ADC_CHANNELS;
|
||||
DMA1_Channel1->CCR = LL_DMA_PRIORITY_HIGH |
|
||||
LL_DMA_MDATAALIGN_HALFWORD |
|
||||
LL_DMA_PDATAALIGN_HALFWORD |
|
||||
LL_DMA_MEMORY_INCREMENT |
|
||||
LL_DMA_MODE_NORMAL |
|
||||
LL_DMA_DIRECTION_PERIPH_TO_MEMORY |
|
||||
DMA_CCR_EN;
|
||||
|
||||
// enable and start ADC
|
||||
ADC1->ISR = 0x1e; // clear all interrupt flags (per DS; mistranslated)
|
||||
ADC1->CR = ADC_CR_ADEN;
|
||||
ADC1->CR |= ADC_CR_ADSTART;
|
||||
}
|
||||
|
||||
/*
|
||||
* when switching AN0 to/from SET1 and VREFEXT, we need to clear
|
||||
* old history stored for the first analog input as well as reset the
|
||||
* history index to start over. finally we need to trigger the ADC
|
||||
* to get fresh data.
|
||||
*/
|
||||
void adc_switch0()
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
adc_read[0] = 0;
|
||||
adc_avg[0] = 0;
|
||||
for (i = 0; i < ADC_HISTLEN; i++) {
|
||||
adc_hist[0][i] = 0;
|
||||
}
|
||||
|
||||
adc_idx = 0;
|
||||
|
||||
// force ADC read to get fresh data
|
||||
adc_go();
|
||||
}
|
||||
|
||||
uint8_t adc_next()
|
||||
{
|
||||
uint8_t i, j;
|
||||
int16_t w;
|
||||
|
||||
// stop if conversion in progress (it shouldn't ever be)
|
||||
adc_stop();
|
||||
|
||||
// start ADC calibration
|
||||
if (calibrate) {
|
||||
calibrate = 0;
|
||||
|
||||
// disable ADC and start calibration
|
||||
ADC1->CR &= ~(ADC_CR_ADEN);
|
||||
|
@ -84,7 +146,6 @@ void adc_next()
|
|||
}
|
||||
|
||||
// copy data to history from last read
|
||||
adc_idx++;
|
||||
if (adc_idx > ADC_HISTLEN) {
|
||||
// nothing to copy when first starting
|
||||
adc_idx = 0;
|
||||
|
@ -122,21 +183,9 @@ void adc_next()
|
|||
}
|
||||
|
||||
// wait for calibration to complete, if started
|
||||
while (ADC1->CR & ADC_CR_ADCAL);
|
||||
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;
|
||||
adc_go();
|
||||
|
||||
// enable and start ADC
|
||||
ADC1->ISR = 0x8e; // clear all interrupt flags (per DS; mistranslated)
|
||||
ADC1->CR = ADC_CR_ADEN;
|
||||
ADC1->CR |= ADC_CR_ADSTART;
|
||||
return adc_idx;
|
||||
}
|
|
@ -0,0 +1,75 @@
|
|||
/*
|
||||
* flash.c: flashing user config and system option bytes
|
||||
*
|
||||
* by default, the pin used for PF2 is configured as a reset.
|
||||
* this code will check that the no-reset bit is set.
|
||||
* if it is not, this code will update the option bytes to
|
||||
* set the BOR voltage, enable BOR, and enable the no-reset bit.
|
||||
*
|
||||
* file creation: 20231019 0126
|
||||
*/
|
||||
|
||||
|
||||
#include "py32f0xx_conf.h"
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* checks the flash option byte to determine if the reset pin
|
||||
* is configured to be PF2. if not, sets this bit as well as
|
||||
* the BOR values. if the bits were updated, they will be reloaded.
|
||||
*
|
||||
* only call this function during startup, before interrupts
|
||||
* are enabled.
|
||||
*
|
||||
* note: this code caused me to lose MCU. consider it buggy.
|
||||
*/
|
||||
void flash_optr_checkfix()
|
||||
{
|
||||
FLASH_OBProgramInitTypeDef opt;
|
||||
|
||||
if ((FLASH->OPTR & FLASH_OPTR_NRST_MODE) == OB_RESET_MODE_RESET) {
|
||||
// let's update this
|
||||
opt.OptionType = OPTIONBYTE_RDP | OPTIONBYTE_USER;
|
||||
opt.USERType = 0xff00;
|
||||
opt.USERConfig = OB_BOR_ENABLE | OB_BOR_LEVEL_2p3_2p4 | OB_IWDG_SW | OB_WWDG_SW | OB_RESET_MODE_GPIO | OB_BOOT1_SYSTEM | OB_RDP_LEVEL_0;
|
||||
|
||||
if (LL_FLASH_Unlock() != SUCCESS) return;
|
||||
if (LL_FLASH_OB_Unlock() != SUCCESS) return;
|
||||
|
||||
LL_FLASH_OBProgram(&opt);
|
||||
|
||||
LL_FLASH_OB_Lock();
|
||||
LL_FLASH_Lock();
|
||||
|
||||
// reload newly programmed option bytes
|
||||
LL_FLASH_OB_Launch();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* manually load values into flash option byte, to configure
|
||||
* the BOR and configure the reset pin to be PF2.
|
||||
*/
|
||||
void flash_optr_set()
|
||||
{
|
||||
FLASH->OPTR &= (FLASH_OPTR_BOR_EN_Msk | FLASH_OPTR_BOR_LEV_Msk | FLASH_OPTR_NRST_MODE_Msk);
|
||||
FLASH->OPTR |= OB_BOR_ENABLE | OB_BOR_LEVEL_2p3_2p4 | OB_RESET_MODE_GPIO;
|
||||
}
|
||||
|
||||
void flash_init()
|
||||
{
|
||||
// load flash write timings for 8MHz operation
|
||||
// (these are listed in the datasheet)
|
||||
FLASH->TS0 = 0x3c;
|
||||
FLASH->TS2P = 0x3c;
|
||||
FLASH->TS3 = 0x3c;
|
||||
|
||||
FLASH->TS1 = 0x90;
|
||||
FLASH->TPS3 = 0x240;
|
||||
|
||||
FLASH->PERTPE = 0x5dc0;
|
||||
FLASH->SMERTPE = 0x5dc0;
|
||||
FLASH->PRGTPE = 0x1f40;
|
||||
FLASH->PRETPE = 0x640;
|
||||
}
|
15
src/led.c
15
src/led.c
|
@ -39,14 +39,14 @@ void led_next()
|
|||
led_sel &= 1;
|
||||
|
||||
// clear outputs
|
||||
RGBSEL0_PORT->BRR = (1 << RGBSEL0_PIN);
|
||||
RGBSEL1_PORT->BRR = (1 << RGBSEL1_PIN);
|
||||
RGBSEL0_PORT->BSRR = (1 << RGBSEL0_PIN);
|
||||
RGBSEL1_PORT->BSRR = (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];
|
||||
PWM_RGB_G = rgb[led_sel][GRN];
|
||||
PWM_RGB_B = 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;
|
||||
|
@ -58,9 +58,9 @@ void led_next()
|
|||
// enable selected LED
|
||||
if (led_sel) {
|
||||
if ((led_mode == MODE_BUZZ) && !snd_buzz) return;
|
||||
RGBSEL1_PORT->BSRR = (1 << RGBSEL1_PIN);
|
||||
RGBSEL1_PORT->BRR = (1 << RGBSEL1_PIN);
|
||||
} else {
|
||||
RGBSEL0_PORT->BSRR = (1 << RGBSEL0_PIN);
|
||||
RGBSEL0_PORT->BRR = (1 << RGBSEL0_PIN);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -146,6 +146,9 @@ void led_init()
|
|||
led_sel = 1;
|
||||
snd_buzz = 0;
|
||||
|
||||
rgb[0][0] = 100;
|
||||
rgb[1][1] = 100;
|
||||
|
||||
// start outputting data
|
||||
led_next();
|
||||
}
|
48
src/main.c
48
src/main.c
|
@ -10,7 +10,9 @@
|
|||
#include "testo.h"
|
||||
|
||||
#include "adc.h"
|
||||
#include "flash.h"
|
||||
#include "led.h"
|
||||
#include "userio.h"
|
||||
|
||||
|
||||
|
||||
|
@ -30,8 +32,8 @@ static inline void gpio_init()
|
|||
// 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;
|
||||
// so set SWDIO to very high speed, PA12 low speed, all other outputs as high speed
|
||||
GPIOA->OSPEEDR = 0x2C002AA0;
|
||||
// alternate function select
|
||||
// PA6=T3C1, PA5=T3C2, PA4=T3C3, PA3=I2C_SCL, PA2=I2C_SDA
|
||||
GPIOA->AFR[0] = 0x01DDCC00;
|
||||
|
@ -44,26 +46,27 @@ static inline void gpio_init()
|
|||
|
||||
|
||||
// PB1=OUT, PB0=AN
|
||||
// unused pins are analog
|
||||
GPIOB->OSPEEDR = 0x00000008;
|
||||
// unused pins are analog, all outputs are low speed
|
||||
GPIOB->OSPEEDR = 0x00000000;
|
||||
GPIOB->MODER = 0xfffffff7;
|
||||
|
||||
// PF2=OUT, low speed
|
||||
// PF2=OUT(low), low speed
|
||||
// unused pins are analog
|
||||
GPIOF->ODR = (1 << 2);
|
||||
GPIOF->MODER = 0xFFFFFCDF;
|
||||
}
|
||||
|
||||
static inline void clk_init()
|
||||
{
|
||||
// run all buses at core clock speed
|
||||
LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1);
|
||||
LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1);
|
||||
|
||||
// enable GPIO clocks
|
||||
// enable GPIO and peripheral 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;
|
||||
|
@ -78,6 +81,12 @@ static inline void systick_init()
|
|||
// configure timebase with interrupt at 4096Hz
|
||||
// this assumes we'll always be running at 8MHz
|
||||
SysTick_Config((8000000 / 4096) - 1);
|
||||
|
||||
// configure unused DMA channels to not be on ADC
|
||||
// (otherwise ADC can shows reads of 0... it's a hardware bug)
|
||||
SYSCFG->CFGR3 = LL_SYSCFG_DMA_MAP_ADC | // ch0
|
||||
LL_SYSCFG_DMA_MAP_TIM17_UP << 8 | // ch1
|
||||
LL_SYSCFG_DMA_MAP_TIM17_UP << 16; // ch2
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -88,6 +97,7 @@ int main()
|
|||
{
|
||||
// base hardware initialization
|
||||
clk_init();
|
||||
flash_init(); // also configures option bytes, if necessary
|
||||
gpio_init();
|
||||
|
||||
// peripheral initialization
|
||||
|
@ -116,20 +126,36 @@ int main()
|
|||
*/
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
uint16_t cs;
|
||||
|
||||
ctr++;
|
||||
|
||||
// run LED programs quickly
|
||||
led_next();
|
||||
|
||||
// limit counter to 4096
|
||||
// limit counter to 4096 counts
|
||||
ctr &= 0xfff;
|
||||
if (!ctr) {
|
||||
uptime++;
|
||||
}
|
||||
|
||||
// run main logic at 1024Hz
|
||||
if ((ctr & 0x3) == 0) {
|
||||
// adc
|
||||
adc_next();
|
||||
if (!(ctr & 0x3)) {
|
||||
// shifted counter for use in the program
|
||||
cs = ctr >> 2;
|
||||
|
||||
// adc (512Hz/16 avg = 32Hz update rate)
|
||||
if (cs & 1) {
|
||||
if (!adc_next()) {
|
||||
// adc has new computed results,
|
||||
// so we can do userio, probe, etc
|
||||
|
||||
// but the results are only valid
|
||||
// after our first cycle
|
||||
if (uptime || cs) {
|
||||
userio_parse();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
26
src/userio.c
26
src/userio.c
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* adc.c: reacting when you fiddle with buttons, switches, and knobs
|
||||
* userio.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.
|
||||
|
@ -29,23 +29,26 @@
|
|||
|
||||
|
||||
#define MODE_CONT 0
|
||||
#define MODE_CONT_TARGET 0x46d
|
||||
#define MODE_CONT_TARGET (4096 * (1 - (1 / 4)))
|
||||
|
||||
#define MODE_FUN 1
|
||||
#define MODE_FUN_TARGET 0xa2b
|
||||
#define MODE_FUN_TARGET (4096 * (1 - (1 / 3)))
|
||||
|
||||
#define MODE_DIODE 2
|
||||
#define MODE_DIODE_TARGET 0xf80
|
||||
#define MODE_DIODE_TARGET (4096 * (1 - (1 / 2)))
|
||||
|
||||
#define MODE_HYSTERESIS 20
|
||||
#define MODE_HYSTERESIS 60 // 3x worst case expected (1% tol)
|
||||
|
||||
#define MODE_ANALOG_MIN 0x80
|
||||
#define MODE_ANALOG_MIN 20
|
||||
|
||||
|
||||
|
||||
uint8_t modesw;
|
||||
uint8_t modesw_next;
|
||||
uint8_t modesw_count;
|
||||
uint8_t mode;
|
||||
uint8_t mode_next;
|
||||
uint8_t mode_count;
|
||||
static const uint16_t mode_targets[] = {
|
||||
MODE_CONT_TARGET, MODE_FUN_TARGET, MODE_DIODE_TARGET
|
||||
};
|
||||
|
||||
uint8_t knob[2];
|
||||
|
||||
|
@ -54,6 +57,11 @@ uint16_t btn_held = 0;
|
|||
|
||||
|
||||
|
||||
void userio_update()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void userio_parse()
|
||||
{
|
||||
|
||||
|
|
Loading…
Reference in New Issue