diff --git a/measurement-data/Analog_Measurement_Analysis.ipynb b/measurement-data/Analog_Measurement_Analysis.ipynb index f452809..b7cdd91 100644 --- a/measurement-data/Analog_Measurement_Analysis.ipynb +++ b/measurement-data/Analog_Measurement_Analysis.ipynb @@ -391,7 +391,12 @@ "outputs": [], "source": [ "print(calc_temp(1000.6)-calc_temp(1000.4))\n", - "print(1/4096*2500)" + "\n", + "adc_min_res = 1/4095*2500\n", + "print('Min res: ', adc_min_res)\n", + "\n", + "print(calc_temp(2000))\n", + "print(calc_temp(2000+adc_min_res))" ] } ], diff --git a/stm-firmware/Makefile b/stm-firmware/Makefile index 9464635..91944e7 100644 --- a/stm-firmware/Makefile +++ b/stm-firmware/Makefile @@ -46,6 +46,7 @@ CFILES += ui/lcd.c ui/menu.c CFILES += fatfs/diskio.c fatfs/ff.c fatfs/ffsystem.c fatfs/ffunicode.c fatfs/shimatta_sdio_driver/shimatta_sdio.c CFILES += pid-controller.c oven-driver.c CFILES += settings/settings.c settings/settings-sd-card.c +CFILES += safety-adc.c DEFINES += -DDEBUGBUILD diff --git a/stm-firmware/adc-meas.c b/stm-firmware/adc-meas.c index 2ea8762..254e689 100644 --- a/stm-firmware/adc-meas.c +++ b/stm-firmware/adc-meas.c @@ -70,12 +70,12 @@ static inline void adc_pt1000_setup_sample_frequency_timer() static inline void adc_pt1000_disable_adc() { - ADC1->CR2 &= ~ADC_CR2_ADON; + ADC_PT1000_PERIPH->CR2 &= ~ADC_CR2_ADON; DMA2_Stream0->CR = 0; pt1000_error |= ADC_PT1000_INACTIVE; - rcc_manager_disable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC1EN)); + rcc_manager_disable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC3EN)); rcc_manager_disable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(ADC_PT1000_PORT_RCC_MASK)); } @@ -99,7 +99,7 @@ static inline void adc_pt1000_enable_dma_stream() DMA2_Stream0->M0AR = (uint32_t)dma_sample_buffer; /* Source is the ADC data register */ - DMA2_Stream0->PAR = (uint32_t)&ADC1->DR; + DMA2_Stream0->PAR = (uint32_t)&ADC_PT1000_PERIPH->DR; /* Transfer size is ADC_PT1000_DMA_AVG_SAMPLES */ DMA2_Stream0->NDTR = ADC_PT1000_DMA_AVG_SAMPLES; @@ -112,7 +112,7 @@ static inline void adc_pt1000_enable_dma_stream() * Todo: Maybe use twice as big of a buffer and also use half-fill interrupt in order to prevent overruns */ DMA2_Stream0->CR = DMA_SxCR_PL_1 | DMA_SxCR_MSIZE_0 | DMA_SxCR_PSIZE_0 | DMA_SxCR_MINC | - DMA_SxCR_CIRC | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_EN; + DMA_SxCR_CIRC | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_EN | ((ADC_PT1000_CHANNEL & 0x7)<<25); } static inline void adc_pt1000_disable_dma_stream() @@ -129,32 +129,32 @@ static inline void adc_pt1000_disable_dma_stream() void adc_pt1000_setup_meas() { - rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC1EN)); + rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC3EN)); rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(ADC_PT1000_PORT_RCC_MASK)); ADC_PT1000_PORT->MODER |= ANALOG(ADC_PT1000_PIN); /* Set S&H time for PT1000 ADC channel */ #if ADC_PT1000_CHANNEL < 10 - ADC1->SMPR2 |= (7U << (3*ADC_PT1000_CHANNEL)); + ADC_PT1000_PERIPH->SMPR2 |= (7U << (3*ADC_PT1000_CHANNEL)); #else - ADC1->SMPR1 |= (7U << (3*(ADC_PT1000_CHANNEL-10))); + ADC_PT1000_PERIPH->SMPR1 |= (7U << (3*(ADC_PT1000_CHANNEL-10))); #endif - ADC->CCR |= (0x2<<16); + ADC->CCR |= (0x3<<16); /* Set watchdog limits */ - ADC1->HTR = ADC_PT1000_UPPER_WATCHDOG; - ADC1->LTR = ADC_PT1000_LOWER_WATCHDOG; + ADC_PT1000_PERIPH->HTR = ADC_PT1000_UPPER_WATCHDOG; + ADC_PT1000_PERIPH->LTR = ADC_PT1000_LOWER_WATCHDOG; /* Set length of sequence to 1 */ - ADC1->SQR1 = (0UL<<20); + ADC_PT1000_PERIPH->SQR1 = (0UL<<20); /* Set channel as 1st element in sequence */ - ADC1->SQR3 = (ADC_PT1000_CHANNEL<<0); + ADC_PT1000_PERIPH->SQR3 = (ADC_PT1000_CHANNEL<<0); - ADC1->CR1 = ADC_CR1_OVRIE | ADC_CR1_AWDEN | ADC_CR1_AWDIE; - ADC1->CR2 = ADC_CR2_EXTEN_0 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_ADON | ADC_CR2_DMA | ADC_CR2_DDS; + ADC_PT1000_PERIPH->CR1 = ADC_CR1_OVRIE | ADC_CR1_AWDEN | ADC_CR1_AWDIE; + ADC_PT1000_PERIPH->CR2 = ADC_CR2_EXTEN_0 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_ADON | ADC_CR2_DMA | ADC_CR2_DDS; adc_pt1000_set_moving_average_filter_param(ADC_PT1000_FILTER_WEIGHT); adc_pt1000_set_resistance_calibration(0, 0, false); @@ -324,17 +324,17 @@ void ADC_IRQHandler(void) { uint32_t adc1_sr; - adc1_sr = ADC1->SR; + adc1_sr = ADC_PT1000_PERIPH->SR; if (adc1_sr & ADC_SR_OVR) { - ADC1->SR &= ~ADC_SR_OVR; + ADC_PT1000_PERIPH->SR &= ~ADC_SR_OVR; pt1000_error |= ADC_PT1000_OVERFLOW; /* Disable ADC in case of overrrun*/ adc_pt1000_disable(); } if (adc1_sr & ADC_SR_AWD) { - ADC1->SR &= ~ADC_SR_AWD; + ADC_PT1000_PERIPH->SR &= ~ADC_SR_AWD; adc_watchdog_counter++; if (adc_watchdog_counter >= ADC_PT1000_WATCHDOG_SAMPLE_COUNT) pt1000_error |= ADC_PT1000_WATCHDOG_ERROR; diff --git a/stm-firmware/include/reflow-controller/adc-meas.h b/stm-firmware/include/reflow-controller/adc-meas.h index b265bae..d2847d2 100644 --- a/stm-firmware/include/reflow-controller/adc-meas.h +++ b/stm-firmware/include/reflow-controller/adc-meas.h @@ -24,6 +24,11 @@ #include #include #include + +/*If this is changed, change DMA code to fit the channel assignment! */ +#define ADC_PT1000_PERIPH ADC3 +#define ADC_PT1000_DMA2_STREAM0_CHANNEL 2 + /** * @brief Moving average filter coefficient for PT1000 measurement */ diff --git a/stm-firmware/include/reflow-controller/periph-config/safety-adc-hwcfg.h b/stm-firmware/include/reflow-controller/periph-config/safety-adc-hwcfg.h new file mode 100644 index 0000000..bd9e6c7 --- /dev/null +++ b/stm-firmware/include/reflow-controller/periph-config/safety-adc-hwcfg.h @@ -0,0 +1,31 @@ +/* Reflow Oven Controller +* +* Copyright (C) 2020 Mario Hüttel +* +* This file is part of the Reflow Oven Controller Project. +* +* The reflow oven controller is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License version 2 as +* published by the Free Software Foundation. +* +* The Reflow Oven Control Firmware is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with the reflow oven controller project. +* If not, see . +*/ + +#ifndef __SAFETY_ADC_HWCFG_H__ +#define __SAFETY_ADC_HWCFG_H__ + +#include + +#define SAFETY_ADC_ADC_PERIPHERAL ADC1 +#define SAFETY_ADC_ADC_RCC_MASK RCC_APB2ENR_ADC1EN +#define TEMP_CHANNEL_NUM (16) +#define INT_REF_CHANNEL_NUM (17) + +#endif /* __SAFETY_ADC_HWCFG_H__ */ diff --git a/stm-firmware/include/reflow-controller/safety-adc.h b/stm-firmware/include/reflow-controller/safety-adc.h new file mode 100644 index 0000000..75400ce --- /dev/null +++ b/stm-firmware/include/reflow-controller/safety-adc.h @@ -0,0 +1,64 @@ +/* Reflow Oven Controller +* +* Copyright (C) 2020 Mario Hüttel +* +* This file is part of the Reflow Oven Controller Project. +* +* The reflow oven controller is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License version 2 as +* published by the Free Software Foundation. +* +* The Reflow Oven Control Firmware is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with the reflow oven controller project. +* If not, see . +*/ + +#ifndef __SAFETY_ADC_H__ +#define __SAFETY_ADC_H__ + +#include +#include + +#define SAFETY_ADC_FRAC_BITS (8) +#define SAFETY_ADC_VREF_VOLT (2.5) +#define SAFETY_ADC_VREF_TOL (0.25) +#define SAFETY_ADC_VREF_INT () + + +enum safety_adc_meas_channel {SAFETY_ADC_MEAS_VREF, SAFETY_ADC_MEAS_TEMP}; +enum safety_adc_check_result { + SAFETY_ADC_CHECK_OK = 0UL, + SAFETY_ADC_CHECK_VREF_LOW = (1U<<0), + SAFETY_ADC_CHECK_VREF_HIGH = (1U<<1), + SAFETY_ADC_CHECK_TEMP_LOW = (1U<<2), + SAFETY_ADC_CHECK_TEMP_HIGH = (1U<<3), + }; + +void safety_adc_init(); + +void safety_adc_deinit(); + +void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement); + +/** + * @brief Poll ADC result. + * @param results adc results + * @return 1 if measurement successful, 0 if not ready, -1 if ADC aborted or not started + */ +int safety_adc_poll_result(uint16_t *adc_result); + +enum safety_adc_check_result safety_adc_check_results(uint16_t vref_result, uint16_t temp_result, + float *vref_calculated, float *temp_calculated); + +enum safety_adc_check_result handle_safety_adc(); + +float safety_adc_get_temp(); + +float safety_adc_get_vref(); + +#endif /* __SAFETY_ADC_H__ */ diff --git a/stm-firmware/main.c b/stm-firmware/main.c index fd1b479..9965338 100644 --- a/stm-firmware/main.c +++ b/stm-firmware/main.c @@ -47,6 +47,7 @@ #include #include #include +#include #include static void setup_nvic_priorities() @@ -142,12 +143,10 @@ static bool mount_sd_card_if_avail(bool mounted) } static inline int32_t handle_pid_controller(struct pid_controller *pid, float target_temperature, - float current_pt1000_resistance) + float current_temperature) { - float current_temperature; int32_t pid_out; - (void)temp_converter_convert_resistance_to_temp(current_pt1000_resistance, (float *)¤t_temperature); pid_out = (int32_t)pid_sample(pid, target_temperature - current_temperature); /* Blink green LED */ @@ -179,6 +178,7 @@ static inline void setup_system() rotary_encoder_setup(); button_init(); lcd_init(); + safety_adc_init(); uart_gpio_config(); setup_sell_uart(&shell_uart); @@ -198,6 +198,8 @@ static void handle_shell_uart_input(shellmatta_handle_t shell_handle) shell_handle_input(shell_handle, uart_input, uart_input_len); } + + int main() { bool sd_card_mounted = false; @@ -209,6 +211,8 @@ int main() uint64_t display_timestamp = 0ULL; char disp[4][21] = {0}; enum lcd_fsm_ret lcd_ret = LCD_FSM_NOP; + int temp_status; + float current_temp; target_temperature = 25.0f; @@ -228,15 +232,25 @@ int main() pt1000_value_status = adc_pt1000_get_current_resistance(&pt1000_value); if (systick_ticks_have_passed(pid_timestamp, 250)) { + + (void)handle_safety_adc(); + pid_timestamp = systick_get_global_tick(); + + temp_status = temp_converter_convert_resistance_to_temp(pt1000_value, + ¤t_temp); + if (pt1000_value_status >= 0 && pid_controller_active) - pid_controller_output = handle_pid_controller(&pid, target_temperature, pt1000_value); + pid_controller_output = handle_pid_controller(&pid, target_temperature, current_temp); /* Blink red led in case of temp error */ if (pt1000_value_status < 0) led_set(0, !led_get(0)); else led_set(0, 0); + + snprintf(&disp[3][0], 17, "Temp: %s%.1f C", (temp_status == 0 ? "" : temp_status < 0 ? "<" : ">") + , current_temp); } /* Handle error in case PID controller should be active, but temperature measurement failed */ diff --git a/stm-firmware/safety-adc.c b/stm-firmware/safety-adc.c new file mode 100644 index 0000000..fb91b5f --- /dev/null +++ b/stm-firmware/safety-adc.c @@ -0,0 +1,153 @@ +/* Reflow Oven Controller +* +* Copyright (C) 2020 Mario Hüttel +* +* This file is part of the Reflow Oven Controller Project. +* +* The reflow oven controller is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License version 2 as +* published by the Free Software Foundation. +* +* The Reflow Oven Control Firmware is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with the reflow oven controller project. +* If not, see . +*/ + +#include +#include + +#include + +void safety_adc_init() +{ + rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(SAFETY_ADC_ADC_RCC_MASK)); + + /* Enable temperature and VREFINT measurement */ + ADC->CCR |= ADC_CCR_TSVREFE; + + /* Set sample time for channels 16 and 17 */ + SAFETY_ADC_ADC_PERIPHERAL->SMPR1 |= ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16; + + /* Standard sequence. One measurement */ + SAFETY_ADC_ADC_PERIPHERAL->SQR1 = 0UL; +} + + +void safety_adc_deinit() +{ + SAFETY_ADC_ADC_PERIPHERAL->CR1 = 0UL; + SAFETY_ADC_ADC_PERIPHERAL->CR2 = 0UL; + SAFETY_ADC_ADC_PERIPHERAL->SMPR1 = 0UL; + rcc_manager_enable_clock(&RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC2EN)); +} + +enum safety_adc_check_result safety_adc_check_results(uint16_t vref_result, uint16_t temp_result, + float *vref_calculated, float *temp_calculated) +{ + enum safety_adc_check_result res = SAFETY_ADC_CHECK_OK; + + + if (vref_calculated) { + *vref_calculated = (1210.0 * 4095) / (float)vref_result; + } + + if (temp_calculated) { + *temp_calculated = (((float)temp_result / 4095.0f * 2500.0f - 760.0f) / 2.5f) + 25.0f; + } + + return res; +} + +int safety_adc_poll_result(uint16_t *adc_result) +{ + int ret = 0; + + if (!adc_result) + return -1000; + + if (!(SAFETY_ADC_ADC_PERIPHERAL->CR2 & ADC_CR2_ADON)) { + return -1; + } + + if (SAFETY_ADC_ADC_PERIPHERAL->SR & ADC_SR_EOC) { + *adc_result = (uint16_t)SAFETY_ADC_ADC_PERIPHERAL->DR; + SAFETY_ADC_ADC_PERIPHERAL->CR2 &= ~ADC_CR2_ADON; + ret = 1; + } + + return ret; +} + +void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement) +{ + switch (measurement) { + case SAFETY_ADC_MEAS_TEMP: + SAFETY_ADC_ADC_PERIPHERAL->SQR3 = TEMP_CHANNEL_NUM; + break; + case SAFETY_ADC_MEAS_VREF: + SAFETY_ADC_ADC_PERIPHERAL->SQR3 = INT_REF_CHANNEL_NUM; + break; + default: + return; + } + + SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_ADON; + SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_SWSTART; +} + +static volatile uint16_t safety_vref_meas_raw; +static volatile bool safety_vref_valid = false; +static volatile uint16_t safety_temp_meas_raw; +static volatile bool safety_temp_valid = false; +static float safety_vref; +static float safety_temp; + +enum safety_adc_check_result handle_safety_adc() +{ + static enum safety_adc_meas_channel safety_meas_channel = SAFETY_ADC_MEAS_VREF; + uint16_t result; + int poll_status; + + poll_status = safety_adc_poll_result(&result); + + if (poll_status < 0) { + safety_adc_trigger_meas(safety_meas_channel); + } else if (poll_status > 0) { + switch (safety_meas_channel) { + case SAFETY_ADC_MEAS_TEMP: + safety_temp_meas_raw = result; + safety_temp_valid = true; + safety_meas_channel = SAFETY_ADC_MEAS_VREF; + break; + case SAFETY_ADC_MEAS_VREF: + safety_vref_meas_raw = result; + safety_vref_valid = true; + safety_meas_channel = SAFETY_ADC_MEAS_TEMP; + break; + default: + safety_meas_channel = SAFETY_ADC_MEAS_VREF; + return -2000; + } + } + + if (safety_temp_valid && safety_vref_valid) { + return safety_adc_check_results(safety_vref_meas_raw, safety_temp_meas_raw, &safety_vref, &safety_temp); + } else { + return SAFETY_ADC_CHECK_OK; + } +} + +float safety_adc_get_temp() +{ + return safety_temp; +} + +float safety_adc_get_vref() +{ + return safety_vref; +} diff --git a/stm-firmware/shell.c b/stm-firmware/shell.c index 80cccb7..6e3808c 100644 --- a/stm-firmware/shell.c +++ b/stm-firmware/shell.c @@ -35,6 +35,7 @@ #include #include #include +#include #ifndef GIT_VER #define GIT_VER "VERSION NOT SET" @@ -342,6 +343,18 @@ static shellmatta_retCode_t shell_cmd_cat(const shellmatta_handle_t handle, cons return SHELLMATTA_OK; } +static shellmatta_retCode_t shell_cmd_safety_adc(const shellmatta_handle_t handle, const char *arguments, + uint32_t length) +{ + (void)length; + (void)arguments; + + shellmatta_printf(handle, "VREF:\t%8.2f\tmV\r\n", safety_adc_get_vref()); + shellmatta_printf(handle, "TEMP:\t%8.2f\tdeg. Celsius\r\n", safety_adc_get_temp()); + + return SHELLMATTA_OK; +} + //typedef struct shellmatta_cmd //{ // char *cmd; /**< command name */ @@ -352,7 +365,7 @@ static shellmatta_retCode_t shell_cmd_cat(const shellmatta_handle_t handle, cons // struct shellmatta_cmd *next; /**< pointer to next command or NULL */ //} shellmatta_cmd_t; -static shellmatta_cmd_t cmd[13] = { +static shellmatta_cmd_t cmd[14] = { { .cmd = "version", .cmdAlias = "ver", @@ -455,8 +468,16 @@ static shellmatta_cmd_t cmd[13] = { .helpText = "Print file contents", .usageText = "cat ", .cmdFct = shell_cmd_cat, + .next = &cmd[13], + }, + { + .cmd = "safety-adc", + .cmdAlias = NULL, + .helpText = "", + .usageText = "", + .cmdFct = shell_cmd_safety_adc, .next = NULL, - } + }, };