Started implementing the hardware access modules

Nothing tested yet…
This commit is contained in:
Thomas Kolb 2023-09-23 17:34:32 +02:00
parent 5aaef38965
commit 82d370bf83
13 changed files with 581 additions and 5 deletions

View File

@ -136,7 +136,7 @@ program: program_jlink
reset: reset_jlink
/tmp/jlink_prog_script: Makefile
echo "Device STM32F030C8" > $@
echo "Device STM32L010K8" > $@
echo "connect" >> $@
echo "S" >> $@
echo "4000" >> $@
@ -146,7 +146,7 @@ reset: reset_jlink
echo "exit" >> $@
/tmp/jlink_rst_script: Makefile
echo "Device STM32F030C8" > $@
echo "Device STM32L010K8" > $@
echo "connect" >> $@
echo "S" >> $@
echo "4000" >> $@
@ -177,4 +177,4 @@ program_debug: $(TARGET_BASE).hex
-c "shutdown"
debug: $(TARGET_BASE).hex
JLinkGDBServerCLExe -device STM32F030K6 -if SWD
JLinkGDBServerCLExe -device STM32L010K8 -if SWD

30
compile_flags.txt Normal file
View File

@ -0,0 +1,30 @@
-Wall
-std=c99
-pedantic
-Wextra
-Wimplicit-function-declaration
-Wredundant-decls
-Wmissing-prototypes
-Wstrict-prototypes
-Wundef
-Wshadow
-fno-common
-ffunction-sections
-fdata-sections
-mcpu=cortex-m0
-mthumb
-mfloat-abi=soft
-MD
-DSTM32L0
-I./libopencm3/include
-Ifxplib/include
-DPOINTPOS=16
-DVERSION="5aaef38"
-O0
-ggdb
-DDEBUG
-Wall
-std=c99
-pedantic
-Iinclude
-DVERSION="0.0.0-896464e"

2
fxplib

@ -1 +1 @@
Subproject commit 896464ee67bbbae82930c9c972e5267b97c7de6d
Subproject commit 77a69a9ddad11a9f0e780aaad39eff2361b6eca2

73
src/fan_ctrl_dc.c Normal file
View File

@ -0,0 +1,73 @@
#include <libopencm3/stm32/gpio.h>
#include "fan_ctrl_dc.h"
#include "pinout.h"
void fan_ctrl_dc_init(void)
{
// configure the GPIOs: DC/DC disabled by default
gpio_clear(DCDC_PORT, DCDC_EN_PIN);
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_EN_PIN);
// configure the feedback resistor GPIOs. These are used as open-drain
// outputs, so either they are configured as input or as output, but the
// only valid output value is 0.
gpio_clear(DCDC_PORT, DCDC_CTRL_FB0_PIN | DCDC_CTRL_FB1_PIN | DCDC_CTRL_FB2_PIN | DCDC_CTRL_FB3_PIN);
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE,
DCDC_CTRL_FB0_PIN | DCDC_CTRL_FB1_PIN | DCDC_CTRL_FB2_PIN | DCDC_CTRL_FB3_PIN);
}
void fan_ctrl_dc_enable(void)
{
// enable the DC/DC converter
gpio_set(DCDC_PORT, DCDC_EN_PIN);
}
void fan_ctrl_dc_disable(void)
{
// shut down the DC/DC converter and disable all feedback resistors.
gpio_clear(DCDC_PORT, DCDC_EN_PIN);
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE,
DCDC_CTRL_FB0_PIN | DCDC_CTRL_FB1_PIN | DCDC_CTRL_FB2_PIN | DCDC_CTRL_FB3_PIN);
}
void fan_ctrl_dc_set_duty(uint8_t percent)
{
// note: as we only have 4 switchable feedback resistors, there are only 16
// voltage steps available.
uint8_t step = 15 * (uint16_t)percent / 100;
// if a resistor is active, the output voltage increases. The smallest
// resistor (FB0) has the strongest influence on the output voltage.
// Therefore, FB0 corresponds to the MSB of the calculated step.
if(step & (1 << 3)) {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB0_PIN);
} else {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB0_PIN);
}
if(step & (1 << 2)) {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB1_PIN);
} else {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB1_PIN);
}
if(step & (1 << 1)) {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB2_PIN);
} else {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB2_PIN);
}
if(step & (1 << 0)) {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB3_PIN);
} else {
gpio_mode_setup(DCDC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, DCDC_CTRL_FB3_PIN);
}
}

13
src/fan_ctrl_dc.h Normal file
View File

@ -0,0 +1,13 @@
#ifndef FAN_CTRL_DC_H
#define FAN_CTRL_DC_H
#include <stdint.h>
void fan_ctrl_dc_init(void);
void fan_ctrl_dc_enable(void);
void fan_ctrl_dc_disable(void);
void fan_ctrl_dc_set_duty(uint8_t percent);
#endif // FAN_CTRL_DC_H

73
src/fan_ctrl_pwm.c Normal file
View File

@ -0,0 +1,73 @@
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/timer.h>
#include "fan_ctrl_pwm.h"
#include "pinout.h"
void fan_ctrl_pwm_init(void)
{
// disable the DC/DC bypass until PWM control mode is actually enabled
gpio_clear(DCDC_PORT, DCDC_BYPASS_SWITCH_PIN);
gpio_mode_setup(DCDC_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, DCDC_BYPASS_SWITCH_PIN);
// *** TIM21 ***
// Configure channel 1 for PWM
// Ch1 = charge pump output
timer_set_mode(TIM21, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
// set up PWM channel
timer_set_oc_mode(TIM21, TIM_OC1, TIM_OCM_PWM1);
timer_enable_oc_output(TIM21, TIM_OC1);
timer_enable_oc_preload(TIM21, TIM_OC1);
timer_set_oc_polarity_high(TIM21, TIM_OC1);
// prescaler
timer_set_prescaler(TIM21, 21 - 1); // Timer runs at 100 kHz
// auto-reload value
timer_set_period(TIM21, 100 - 1); // overflow every 100 cycles = 1 kHz
// output compare value
timer_set_oc_value(TIM21, TIM_OC1, 0); // No PWM output by default
// only generate interrupt on overflow
timer_update_on_overflow(TIM21);
// enable main output
timer_enable_break_main_output(TIM21);
}
void fan_ctrl_pwm_enable(void)
{
// enable the DC/DC bypass (power the fan directly from the supply voltage)
gpio_set(DCDC_PORT, DCDC_BYPASS_SWITCH_PIN);
// Enable PWM output on the PWM GPIO
gpio_set_af(FAN_PORT, GPIO_AF0, FAN_PWM_PIN);
// start the PWM timer
timer_enable_counter(TIM21);
}
void fan_ctrl_pwm_disable(void)
{
// disable the DC/DC bypass again
gpio_clear(DCDC_PORT, DCDC_BYPASS_SWITCH_PIN);
// set PWM value to 0 and stop the counter
timer_set_oc_value(TIM21, TIM_OC1, 0);
timer_disable_counter(TIM21);
// configure the PWM GPIO as input so the fan runs full speed if powered
}
void fan_ctrl_pwm_set_duty(uint8_t percent)
{
// as the timer has 100 steps per cycle, we can directly use the percentage value
timer_set_oc_value(TIM21, TIM_OC1, percent);
}

13
src/fan_ctrl_pwm.h Normal file
View File

@ -0,0 +1,13 @@
#ifndef FAN_CTRL_PWM_H
#define FAN_CTRL_PWM_H
#include <stdint.h>
void fan_ctrl_pwm_init(void);
void fan_ctrl_pwm_enable(void);
void fan_ctrl_pwm_disable(void);
void fan_ctrl_pwm_set_duty(uint8_t percent);
#endif // FAN_CTRL_PWM_H

View File

@ -2,6 +2,20 @@
#include <libopencm3/cm3/systick.h>
#include <libopencmsis/core_cm3.h>
#include "uart.h"
#include "fan_ctrl_pwm.h"
#include "fan_ctrl_dc.h"
static void clock_setup(void)
{
/* We are running on MSI (2.1 MHz) after boot. */
rcc_periph_clock_enable(RCC_GPIOA); // for basically everything
rcc_periph_clock_enable(RCC_GPIOC); // for UART only
/* Enable clocks for USART2. */
rcc_periph_clock_enable(RCC_USART2);
}
/* Set up systick to fire freq times per second */
static void init_systick(int freq)
{
@ -19,9 +33,20 @@ int main(void)
{
uint64_t timebase_ms = 0;
// delay startup a bit to allow debugger to connect before debug pins are
// reconfigured to UART.
for(uint32_t i = 0; i < 1000000; i++) {
__asm__("nop");
}
clock_setup();
init_systick(1000);
//rs485_enqueue("LNSC-2420 v" VERSION " initialized.\n");
uart_init();
fan_ctrl_pwm_init();
fan_ctrl_dc_init();
uart_enqueue("TinyFanControl v" VERSION " initialized.\n");
// triggered every 1 ms
while (1) {

36
src/pinout.h Normal file
View File

@ -0,0 +1,36 @@
#ifndef PINOUT_H
#define PINOUT_H
/* Fan-related pins */
#define FAN_PORT GPIOA
#define FAN_PWM_PIN GPIO2
#define FAN_TACHO_PIN GPIO3
/* DC/DC control pins */
#define DCDC_PORT GPIOA
#define DCDC_EN_PIN GPIO8
#define DCDC_CTRL_FB0_PIN GPIO7
#define DCDC_CTRL_FB1_PIN GPIO6
#define DCDC_CTRL_FB2_PIN GPIO5
#define DCDC_CTRL_FB3_PIN GPIO4
#define DCDC_BYPASS_SWITCH_PIN GPIO9
/* Analog channels */
#define ANALOG_INPUT_U_NTC 0
/* UART */
#define UART_PORT GPIOA
#define UART_TX_PIN GPIO14
#define UART_RX_PIN GPIO15
#endif // PINOUT_H

155
src/temp_sensor.c Normal file
View File

@ -0,0 +1,155 @@
#include <math.h>
#include "temp_sensor.h"
#include "fxp.h"
#include <libopencm3/cm3/common.h>
#include <libopencm3/stm32/adc.h>
#include <libopencm3/stm32/dma.h>
#define ADC_NUM_CHANNELS 2
static volatile int16_t adc_values[ADC_NUM_CHANNELS];
static fxp_t m_temperature_internal = 0;
static fxp_t m_temperature_ntc = 0;
/* Temperature sensor calibration value address */
#define TEMP110_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7C2))
#define TEMP30_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7B8))
#define VDD_CALIB ((int32_t) (330)) /* calibration voltage = 3,30V - DO NOT CHANGE */
#define VDD_APPLI ((int32_t) (330)) /* actual supply voltage */
/* function for temperature conversion */
static fxp_t calc_temperature(uint16_t adc_val)
{
int32_t temperature_raw = ((int32_t)adc_val * VDD_APPLI / VDD_CALIB)
- (int32_t)(*TEMP30_CAL_ADDR);
fxp_t temperature = FXP_FROM_INT(temperature_raw);
fxp_t scale_dividend = FXP_FROM_INT(110 - 30);
fxp_t scale_divisor = FXP_FROM_INT((int32_t)(*TEMP110_CAL_ADDR - *TEMP30_CAL_ADDR));
fxp_t scale = fxp_div(scale_dividend, scale_divisor);
return fxp_add(fxp_mult(temperature, scale), FXP_FROM_INT(30));
}
static fxp_t adc_val_to_pin_voltage(uint16_t adc_val)
{
return fxp_div(
fxp_mult(FXP_FROM_INT((int32_t)adc_val), fxp_div(FXP_FROM_INT(33), FXP_FROM_INT(10))),
FXP_FROM_INT(4096));
}
static fxp_t calc_temperature_ntc(uint16_t adc_val)
{
static const fxp_t ln_r_ntc_nom = 705030; // ln(47kΩ) converted to fxp_t with 16 fractional bits
static const fxp_t r1 = FXP_FROM_INT(10000);
static const fxp_t b_constant = FXP_FROM_INT(4125);
static const fxp_t ntc_temp_nom = 19539558; // (273.15+25) * 2**16
static const fxp_t celsius2kelvin = 17901158; // (273.15) * 2**16
fxp_t v_r1 = adc_val_to_pin_voltage(adc_val);
fxp_t v_ref = fxp_div(FXP_FROM_INT(33), FXP_FROM_INT(10));
fxp_t r_ntc = fxp_div(fxp_mult(fxp_sub(v_ref, v_r1), r1), v_r1);
fxp_t ln_r_ntc = fxp_from_float(logf(fxp_to_float(r_ntc)));
fxp_t temp_k = fxp_div(FXP_FROM_INT(1.0),
fxp_div(
fxp_add(
fxp_div(
fxp_sub(
ln_r_ntc,
ln_r_ntc_nom),
b_constant),
FXP_FROM_INT(1)),
ntc_temp_nom));
return fxp_sub(temp_k, celsius2kelvin);
}
void temp_sensor_init(void)
{
uint8_t channels[ADC_NUM_CHANNELS] = {
0, // The NTC is connected to ADC_IN0
ADC_CHANNEL_TEMP // Temperature sensor
};
// Prepare the ADC
adc_power_off(ADC1);
// enable the temperature sensor
adc_enable_temperature_sensor();
// configure ADC
//adc_enable_scan_mode(ADC1);
//adc_set_clk_source(ADC1, ADC_CLKSOURCE_PCLK_DIV2); // -> 1.05 MHz @ 2.1 MHz ABP
ADC_CFGR2(ADC1) = ADC_CFGR2_CKMODE_PCLK_DIV2;
adc_set_single_conversion_mode(ADC1);
adc_set_resolution(ADC1, ADC_CFGR1_RES_12_BIT);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_12DOT5CYC);
//adc_disable_external_trigger_regular(ADC1);
adc_set_right_aligned(ADC1);
adc_set_regular_sequence(ADC1, ADC_NUM_CHANNELS, channels);
adc_calibrate(ADC1);
// configure DMA for ADC
//nvic_enable_irq(NVIC_DMA1_CHANNEL1_IRQ);
//dma_channel_reset(DMA1, DMA_CHANNEL1);
dma_set_priority(DMA1, DMA_CHANNEL1, DMA_CCR_PL_LOW);
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_16BIT);
dma_set_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1);
dma_enable_circular_mode(DMA1, DMA_CHANNEL1);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &ADC_DR(ADC1));
/* The array adc_values[] is filled with the waveform data to be output */
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) adc_values);
dma_set_number_of_data(DMA1, DMA_CHANNEL1, ADC_NUM_CHANNELS);
//dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
dma_enable_channel(DMA1, DMA_CHANNEL1);
adc_enable_dma(ADC1);
adc_power_on(ADC1);
}
void temp_sensor_trigger_update(void)
{
// start the ADC conversion sequency. The result will be transferred to RAM
// by the DMA.
adc_start_conversion_regular(ADC1);
}
bool temp_sensor_has_new_values(void)
{
if(dma_get_interrupt_flag(DMA1, DMA_CHANNEL1, DMA_TCIF)) {
dma_clear_interrupt_flags(DMA1, DMA_CHANNEL1, DMA_TCIF);
// TODO: calculate temperature values and cache them here.
m_temperature_internal = calc_temperature(adc_values[1]);
return true;
} else {
return false;
}
}
fxp_t temp_sensor_get_ntc_temperature(void)
{
}
fxp_t temp_sensor_get_internal_temperature(void)
{
}

17
src/temp_sensor.h Normal file
View File

@ -0,0 +1,17 @@
#ifndef TEMP_SENSOR_H
#define TEMP_SENSOR_H
#include <stdbool.h>
#include <stdint.h>
#include <fxp.h>
void temp_sensor_init(void);
void temp_sensor_trigger_update(void);
bool temp_sensor_has_new_values(void);
fxp_t temp_sensor_get_ntc_temperature(void);
fxp_t temp_sensor_get_internal_temperature(void);
#endif // TEMP_SENSOR_H

130
src/uart.c Normal file
View File

@ -0,0 +1,130 @@
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include "pinout.h"
#include "uart.h"
#define UART_BUFFER_SIZE 128
static volatile char debugBuffer[UART_BUFFER_SIZE];
static volatile uint16_t readPos, writePos;
static volatile uint8_t bufferFull, bufferEmpty, usartActive;
void uart_init(void)
{
// initialize the ring buffer
readPos = 0;
writePos = 0;
bufferFull = 0;
bufferEmpty = 1;
usartActive = 0;
/* Initialize GPIOs */
// RX and TX pins
gpio_mode_setup(UART_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, UART_TX_PIN | UART_RX_PIN);
gpio_set_af(UART_PORT, GPIO_AF0, UART_TX_PIN | UART_RX_PIN);
// enable interrupt
nvic_enable_irq(NVIC_USART2_IRQ);
/* Setup USART2 parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_CR2_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Enable the USART. */
usart_enable(USART2);
/* Enable the USART2 TX Interrupt */
usart_enable_tx_interrupt(USART2);
usart_enable_tx_complete_interrupt(USART2);
}
static void uart_transfer(void)
{
if(bufferEmpty) {
usart_disable_tx_interrupt(USART2);
usartActive = 0;
return;
}
usart_send(USART2, debugBuffer[readPos]);
readPos++;
if(readPos == UART_BUFFER_SIZE) {
readPos = 0;
}
if(readPos == writePos) {
bufferEmpty = 1;
}
bufferFull = 0;
usart_enable_tx_interrupt(USART2);
}
void usart2_isr(void)
{
if(USART2_ISR & USART_ISR_TXE) {
uart_transfer();
}
if(USART2_ISR & USART_ISR_TC) {
USART2_ICR |= USART_ICR_TCCF;
}
}
void uart_enqueue(const char *str)
{
while(*str) {
if(bufferFull) {
break;
}
debugBuffer[writePos] = *str;
writePos++;
if(writePos == UART_BUFFER_SIZE) {
writePos = 0;
}
if(writePos == readPos) {
bufferFull = 1;
}
bufferEmpty = 0;
str++;
}
if(!usartActive) {
usartActive = 1;
//gpio_set(UART_PORT, UART_DE_PIN);
uart_transfer();
}
}
void uart_deepsleep_prepare(void)
{
// force the transceiver to RX mode
//gpio_clear(UART_PORT, UART_DE_PIN);
}
void uart_deepsleep_resume(void)
{
// if a transmission is still in progress, switch to TX mode again
if(usartActive) {
//gpio_set(UART_PORT, UART_DE_PIN);
}
}

11
src/uart.h Normal file
View File

@ -0,0 +1,11 @@
#ifndef UART_H
#define UART_H
void uart_init(void);
void uart_enqueue(const char *str);
void uart_deepsleep_prepare(void);
void uart_deepsleep_resume(void);
#endif // UART_H