Merge branch 'safety-controller' into dev

This commit is contained in:
Mario Hüttel 2020-08-02 19:00:35 +02:00
commit 6cde956c31
22 changed files with 1151 additions and 394 deletions

View File

@ -47,7 +47,7 @@ CFILES += fatfs/diskio.c fatfs/ff.c fatfs/ffsystem.c fatfs/ffunicode.c fatfs/shi
CFILES += pid-controller.c oven-driver.c
CFILES += settings/settings.c settings/settings-sd-card.c
CFILES += safety/safety-adc.c
CFILES += safety/safety-adc.c safety/safety-controller.c safety/watchdog.c
DEBUG_DEFINES = -DDEBUGBUILD
RELEASE_DEFINES =

View File

@ -1,4 +1,4 @@
/* Reflow Oven Controller
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
@ -24,14 +24,13 @@
#include <stm-periph/stm32-gpio-macros.h>
#include <stdlib.h>
#include <stm-periph/clock-enable-manager.h>
#include <reflow-controller/safety/safety-controller.h>
static float pt1000_offset;
static float pt1000_sens_dev;
static bool calibration_active;
static float filter_alpha;
static volatile float pt1000_res_raw_lf;
static volatile bool filter_ready;
static volatile enum adc_pt1000_error pt1000_error = ADC_PT1000_INACTIVE;
static volatile int * volatile streaming_flag_ptr = NULL;
static uint32_t filter_startup_cnt;
static volatile float adc_pt1000_raw_reading_hf;
@ -54,8 +53,8 @@ static inline void adc_pt1000_setup_sample_frequency_timer()
{
rcc_manager_enable_clock(&RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB1ENR_TIM2EN));
/* Divide 42 MHz peripheral clock by 42 */
TIM2->PSC = (42UL-1UL);
/* Divide 2*42 MHz peripheral clock by 42 */
TIM2->PSC = (84UL-1UL);
/* Reload value */
TIM2->ARR = ADC_PT1000_SAMPLE_CNT_DELAY;
@ -73,8 +72,8 @@ static inline void adc_pt1000_disable_adc()
ADC_PT1000_PERIPH->CR2 &= ~ADC_CR2_ADON;
DMA2_Stream0->CR = 0;
pt1000_error |= ADC_PT1000_INACTIVE;
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_OFF, MEAS_ADC_SAFETY_FLAG_KEY);
safety_controller_enable_timing_mon(ERR_TIMING_MEAS_ADC, false);
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));
}
@ -166,13 +165,13 @@ void adc_pt1000_setup_meas()
adc_pt1000_setup_sample_frequency_timer();
pt1000_error &= ~ADC_PT1000_INACTIVE;
safety_controller_ack_flag_with_key(ERR_FLAG_MEAS_ADC_OFF, MEAS_ADC_SAFETY_FLAG_KEY);
}
void adc_pt1000_set_moving_average_filter_param(float alpha)
{
filter_alpha = alpha;
filter_ready = false;
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
filter_startup_cnt = ADC_FILTER_STARTUP_CYCLES;
}
@ -181,6 +180,12 @@ void adc_pt1000_set_resistance_calibration(float offset, float sensitivity_devia
pt1000_offset = offset;
pt1000_sens_dev = sensitivity_deviation;
calibration_active = active;
if (!calibration_active) {
safety_controller_report_error_with_key(ERR_FLAG_UNCAL, MEAS_ADC_SAFETY_FLAG_KEY);
} else {
safety_controller_ack_flag_with_key(ERR_FLAG_UNCAL, MEAS_ADC_SAFETY_FLAG_KEY);
}
}
void adc_pt1000_get_resistance_calibration(float *offset, float *sensitivity_deviation, bool *active)
@ -205,18 +210,23 @@ static inline float adc_pt1000_apply_calibration(float raw_resistance)
int adc_pt1000_get_current_resistance(float *resistance)
{
int ret_val = 0;
bool flag = true;
if (!resistance)
return -1001;
*resistance = adc_pt1000_apply_calibration(pt1000_res_raw_lf);
if (adc_pt1000_check_error()) {
if (safety_controller_get_flags_by_mask(ERR_FLAG_MEAS_ADC_OFF | ERR_FLAG_MEAS_ADC_OVERFLOW |
ERR_FLAG_MEAS_ADC_WATCHDOG)) {
ret_val = -100;
goto return_value;
}
if (!filter_ready) {
(void)safety_controller_get_flag(ERR_FLAG_MEAS_ADC_UNSTABLE, &flag, false);
if (flag) {
ret_val = 2;
goto return_value;
}
@ -260,25 +270,15 @@ void adc_pt1000_convert_raw_value_array_to_resistance(float *resistance_dest, fl
resistance_dest[i] = ADC_TO_RES(raw_source[i]);
}
enum adc_pt1000_error adc_pt1000_check_error()
{
return pt1000_error;
}
void adc_pt1000_clear_error()
{
pt1000_error &= ~ADC_PT1000_OVERFLOW & ~ADC_PT1000_WATCHDOG_ERROR;
}
void adc_pt1000_disable()
{
adc_pt1000_disable_adc();
adc_pt1000_stop_sample_frequency_timer();
adc_pt1000_disable_dma_stream();
filter_ready = false;
pt1000_res_raw_lf = 0.0f;
pt1000_error |= ADC_PT1000_INACTIVE;
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_OFF, MEAS_ADC_SAFETY_FLAG_KEY);
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
if (streaming_flag_ptr) {
*streaming_flag_ptr = -3;
@ -288,10 +288,15 @@ void adc_pt1000_disable()
static inline __attribute__((optimize("O3"))) void adc_pt1000_filter(float adc_prefiltered_value)
{
if (!filter_ready && --filter_startup_cnt <= 0)
filter_ready = true;
if (filter_startup_cnt > 0) {
filter_startup_cnt--;
if (filter_startup_cnt == 0) {
safety_controller_ack_flag_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
}
}
pt1000_res_raw_lf = (1.0f-filter_alpha) * pt1000_res_raw_lf + filter_alpha * ADC_TO_RES(adc_prefiltered_value);
safety_controller_report_timing(ERR_TIMING_MEAS_ADC);
}
static inline __attribute__((optimize("O3"))) float adc_pt1000_dma_avg_pre_filter()
@ -328,7 +333,7 @@ void ADC_IRQHandler(void)
if (adc1_sr & ADC_SR_OVR) {
ADC_PT1000_PERIPH->SR &= ~ADC_SR_OVR;
pt1000_error |= ADC_PT1000_OVERFLOW;
safety_controller_report_error(ERR_FLAG_MEAS_ADC_OVERFLOW);
/* Disable ADC in case of overrrun*/
adc_pt1000_disable();
}
@ -337,7 +342,7 @@ void ADC_IRQHandler(void)
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;
safety_controller_report_error(ERR_FLAG_MEAS_ADC_WATCHDOG);
}
}

View File

@ -26,6 +26,7 @@
#include <arm_math.h>
#include <stdlib.h>
#include <float.h>
#include <reflow-controller/safety/safety-controller.h>
enum calibration_shell_state {CAL_START = 0, CAL_WAIT_RES1, CAL_MEAS_RES1, CAL_WAIT_RES2, CAL_MEAS_RES2};
@ -121,6 +122,8 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
{
(void)arg;
(void)len;
bool error_occured;
const enum safety_flag meas_adc_err_mask = ERR_FLAG_MEAS_ADC_OFF | ERR_FLAG_MEAS_ADC_WATCHDOG;
/* This stores the current state of the calibration process */
static enum calibration_shell_state cal_state = CAL_START;
@ -139,7 +142,7 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
switch (cal_state) {
case CAL_START:
/* Clear errors of PT1000 reading */
adc_pt1000_clear_error();
safety_controller_ack_flag(ERR_FLAG_MEAS_ADC_WATCHDOG);
shellmatta_printf(shell, "Starting calibration: Insert 1000 Ohm calibration resistor and press ENTER\r\n");
cal_state = CAL_WAIT_RES1;
ret_val = SHELLMATTA_CONTINUE;
@ -154,7 +157,7 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
cal_state = CAL_MEAS_RES1;
ret_val = SHELLMATTA_BUSY;
shellmatta_printf(shell, "Measurement...\r\n");
adc_pt1000_clear_error();
safety_controller_ack_flag(ERR_FLAG_MEAS_ADC_WATCHDOG);
data_buffer = calibration_acquire_data_start(512UL, &flag);
break;
} else if (stdin_data[i] == '\x03') {
@ -179,8 +182,9 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
cal_state = CAL_MEAS_RES1;
} else if (res == 0) {
shellmatta_printf(shell, "R=%.2f, Noise peak-peak: %.2f\r\n", mu, dev);
if (adc_pt1000_check_error() != ADC_PT1000_NO_ERR) {
shellmatta_printf(shell, "Error in resistance measurement: %d", adc_pt1000_check_error());
error_occured = safety_controller_get_flags_by_mask(meas_adc_err_mask);
if (error_occured) {
shellmatta_printf(shell, "Error in resistance measurement");
ret_val = SHELLMATTA_OK;
cal_state = CAL_START;
} else {
@ -189,7 +193,7 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
cal_state = CAL_WAIT_RES2;
}
} else {
shellmatta_printf(shell, "Error in resistance measurement: %d", adc_pt1000_check_error());
shellmatta_printf(shell, "Error in resistance measurement");
ret_val = SHELLMATTA_OK;
cal_state = CAL_START;
}
@ -204,7 +208,7 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
cal_state = CAL_MEAS_RES2;
ret_val = SHELLMATTA_BUSY;
shellmatta_printf(shell, "Measurement...\r\n");
adc_pt1000_clear_error();
safety_controller_ack_flag(ERR_FLAG_MEAS_ADC_WATCHDOG);
data_buffer = calibration_acquire_data_start(512UL, &flag);
break;
} else if (stdin_data[i] == '\x03') {
@ -229,8 +233,9 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
cal_state = CAL_MEAS_RES2;
} else if (res == 0) {
shellmatta_printf(shell, "R=%.2f, Noise peak-peak: %.2f\r\n", mu2, dev2);
if (adc_pt1000_check_error() != ADC_PT1000_NO_ERR) {
shellmatta_printf(shell, "Error in resistance measurement: %d", adc_pt1000_check_error());
error_occured = safety_controller_get_flags_by_mask(meas_adc_err_mask);
if (error_occured) {
shellmatta_printf(shell, "Error in resistance measurement");
ret_val = SHELLMATTA_OK;
cal_state = CAL_START;
} else {
@ -250,7 +255,7 @@ shellmatta_retCode_t calibration_sequence_shell_cmd(shellmatta_handle_t shell, c
adc_pt1000_set_resistance_calibration(offset, sens_dev, true);
}
} else {
shellmatta_printf(shell, "Error in resistance measurement: %d", adc_pt1000_check_error());
shellmatta_printf(shell, "Error in resistance measurement");
ret_val = SHELLMATTA_OK;
cal_state = CAL_START;
}

View File

@ -36,4 +36,6 @@
#define ABS(a) ((a) < 0 ? (-1*(a)) : (a))
#define is_power_of_two(num) ((num) && !((num) & ((num) - 1)))
#endif /* __HELPER_MACROS_H__ */

View File

@ -90,8 +90,6 @@
*/
#define ADC_PT1000_WATCHDOG_SAMPLE_COUNT 25U
enum adc_pt1000_error {ADC_PT1000_NO_ERR= 0, ADC_PT1000_WATCHDOG_ERROR=(1UL<<0), ADC_PT1000_OVERFLOW=(1UL<<1), ADC_PT1000_INACTIVE = (1UL<<2)};
/**
* @brief This function sets up the ADC measurement fo the external PT1000 temperature sensor
*
@ -162,18 +160,6 @@ int adc_pt1000_stream_raw_value_to_memory(volatile float *adc_array, uint32_t le
void adc_pt1000_convert_raw_value_array_to_resistance(float *resistance_dest, float *raw_source, uint32_t count);
/**
* @brief Check if the ADC measurement experienced any kind of error (DMA, Analog Watchdog, etc...)
*
* In case of an error, it may be necessary to call adc_pt1000_setup_meas() again in order to recover from the error
*/
enum adc_pt1000_error adc_pt1000_check_error();
/**
* @brief Clear the error status of the PT1000 measurement
*/
void adc_pt1000_clear_error();
/**
* @brief Disable the PT1000 measurement
*/

View File

@ -25,32 +25,9 @@
#include <stdbool.h>
#include <reflow-controller/pid-controller.h>
enum oven_pid_error_report {
OVEN_PID_NO_ERROR = 0,
OVEN_PID_ERR_PT1000_ADC_WATCHDOG = (1<<0),
OVEN_PID_ERR_PT1000_ADC_OFF = (1<<1),
OVEN_PID_ERR_PT1000_OTHER = (1<<2),
OVEN_PID_ERR_VREF_TOL = (1<<3),
OVEN_PID_ERR_OVERTEMP = (1<<4),
};
struct oven_pid_errors {
bool generic_error;
bool pt1000_adc_watchdog;
bool pt1000_adc_off;
bool pt1000_other;
bool vref_tol;
bool controller_overtemp;
};
struct oven_pid_status {
bool active;
bool error_set;
struct oven_pid_errors error_flags;
float target_temp;
float current_temp;
uint64_t timestamp_last_run;
};
enum oven_pid_status {OVEN_PID_DEACTIVATED,
OVEN_PID_RUNNING,
OVEN_PID_ABORTED};
void oven_driver_init(void);
@ -66,8 +43,8 @@ void oven_pid_handle(float target_temp);
void oven_pid_stop();
void oven_pid_report_error(enum oven_pid_error_report report);
void oven_driver_apply_power_level(void);
const struct oven_pid_status *oven_pid_get_status(void);
enum oven_pid_status oven_pid_get_status(void);
#endif /* __OVEN_DRIVER_H__ */

View File

@ -18,32 +18,18 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup safety-adc
* @{
*/
#ifndef __SAFETY_ADC_H__
#define __SAFETY_ADC_H__
#include <stdint.h>
#include <stdbool.h>
#define SAFETY_ADC_VREF_MVOLT (2500.0f)
#define SAFETY_ADC_VREF_TOL_MVOLT (100.0f)
#define SAFETY_ADC_TEMP_LOW_LIM (0.0f)
#define SAFETY_ADC_TEMP_HIGH_LIM (65.0f)
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),
SAFETY_ADC_INTERNAL_ERROR = (1U<<4),
};
extern enum safety_adc_check_result global_safety_adc_status;
enum safety_adc_check_result safety_adc_get_errors();
void safety_adc_clear_errors(void);
void safety_adc_init();
@ -58,13 +44,10 @@ void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement);
*/
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();
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value);
#endif /* __SAFETY_ADC_H__ */
/** @} */

View File

@ -0,0 +1,93 @@
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
* 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 <http://www.gnu.org/licenses/>.
*/
#ifndef __SAFETY_CONFIG_H__
#define __SAFETY_CONFIG_H__
enum safety_flag {
ERR_FLAG_MEAS_ADC_OFF = (1<<0),
ERR_FLAG_MEAS_ADC_OVERFLOW = (1<<1),
ERR_FLAG_MEAS_ADC_WATCHDOG = (1<<2),
ERR_FLAG_MEAS_ADC_UNSTABLE = (1<<3),
ERR_FLAG_TIMING_PID = (1<<4),
ERR_FLAG_TIMING_MEAS_ADC = (1<<5),
ERR_FLAG_AMON_VREF = (1<<6),
ERR_FLAG_AMON_UC_TEMP = (1<<7),
ERR_FLAG_STACK = (1<<8),
ERR_FLAG_SAFETY_ADC = (1<<9),
ERR_FLAG_SYSTICK = (1<<10),
ERR_FLAG_WTCHDG_FIRED = (1<<11),
ERR_FLAG_UNCAL = (1<<12),
ERR_FLAG_DEBUG = (1<<13),
};
enum timing_monitor {
ERR_TIMING_PID = (1<<0),
ERR_TIMING_MEAS_ADC = (1<<1),
ERR_TIMING_SAFETY_ADC = (1<<2),
};
enum analog_value_monitor {
ERR_AMON_VREF = (1<<0),
ERR_AMON_UC_TEMP = (1<<1),
};
/**
* @brief Magic key used to reset the watchdog using the @ref watchdog_ack function
*/
#define WATCHDOG_MAGIC_KEY 0x1a2c56F4
#ifdef DEBUGBUILD
/**
* @brief If one, the watchdog is halted whenever the core is halted by the debugger.
*
* This is only applicable in a debug build. In release mode, the watchdog stays always enabled
*/
#define WATCHDOG_HALT_DEBUG (1)
#else
#define WATCHDOG_HALT_DEBUG (0)
#endif
#define WATCHDOG_PRESCALER 4
#define SAFETY_MIN_STACK_FREE 0x100
#define PID_CONTROLLER_ERR_CAREMASK (ERR_FLAG_STACK | ERR_FLAG_AMON_UC_TEMP | ERR_FLAG_AMON_VREF | \
ERR_FLAG_TIMING_PID | ERR_FLAG_TIMING_MEAS_ADC | ERR_FLAG_MEAS_ADC_OFF | \
ERR_FLAG_MEAS_ADC_OVERFLOW)
#define HALTING_CAREMASK (ERR_FLAG_STACK | ERR_FLAG_AMON_UC_TEMP)
#define SAFETY_ADC_VREF_MVOLT (2500.0f)
#define SAFETY_ADC_VREF_TOL_MVOLT (100.0f)
#define SAFETY_ADC_TEMP_LOW_LIM (0.0f)
#define SAFETY_ADC_TEMP_HIGH_LIM (65.0f)
/**
* @brief Key used to lock the safefety flags from external ack'ing
*/
#define MEAS_ADC_SAFETY_FLAG_KEY 0xe554dac3UL
#define SAFETY_CONTROLLER_ADC_DELAY_MS 120
#endif /* __SAFETY_CONFIG_H__ */

View File

@ -0,0 +1,99 @@
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup safety-controller
* @{
*/
#ifndef __SAFETY_CONTROLLER_H__
#define __SAFETY_CONTROLLER_H__
#include <reflow-controller/safety/safety-config.h>
#include <stdbool.h>
#include <stdint.h>
#include <stddef.h>
enum analog_monitor_status {ANALOG_MONITOR_OK = 0,
ANALOG_MONITOR_ERROR,
ANALOG_MONITOR_INACTIVE,
ANALOG_MONITOR_OVER,
ANALOG_MONITOR_UNDER};
struct analog_monitor_info {
float value;
float min;
float max;
enum analog_monitor_status status;
uint64_t timestamp;
};
/**
* @brief Initialize the safety controller
*
* After a call to this function the controller is iniotlaized and the watchdog is set up.
* You have to call safety_controller_handle
* If this function fails, it will hang, because errors in the safety controller are not recoverable
*/
void safety_controller_init();
/**
* @brief Handle the safety controller.
* @note This function must be executed periodically in order to prevent the watchdog from resetting the firmware
* @return 0 if successful
*/
int safety_controller_handle();
int safety_controller_report_error(enum safety_flag flag);
int safety_controller_report_error_with_key(enum safety_flag flag, uint32_t key);
void safety_controller_report_timing(enum timing_monitor monitor);
void safety_controller_report_analog_value(enum analog_value_monitor monitor, float value);
int safety_controller_enable_timing_mon(enum timing_monitor monitor, bool enable);
enum analog_monitor_status safety_controller_get_analog_mon_value(enum analog_value_monitor monitor, float *value);
int safety_controller_get_flag(enum safety_flag flag, bool *status, bool try_ack);
int safety_controller_ack_flag(enum safety_flag flag);
int safety_controller_ack_flag_with_key(enum safety_flag flag, uint32_t key);
bool safety_controller_get_flags_by_mask(enum safety_flag mask);
uint32_t safety_controller_get_flag_count();
uint32_t safety_controller_get_analog_monitor_count();
int safety_controller_get_flag_name_by_index(uint32_t index, char *buffer, size_t buffsize);
int safety_controller_get_flag_by_index(uint32_t index, bool *status, enum safety_flag *flag_enum);
int safety_controller_get_analog_mon_by_index(uint32_t index, struct analog_monitor_info *info);
int safety_controller_get_analog_mon_name_by_index(uint32_t index, char *buffer, size_t buffsize);
#endif /* __SAFETY_CONTROLLER_H__ */
/** @} */

View File

@ -0,0 +1,50 @@
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
* 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 <http://www.gnu.org/licenses/>.
*/
#ifndef __WATCHDOG_H__
#define __WATCHDOG_H__
#include <reflow-controller/safety/safety-config.h>
#include <stdint.h>
#include <stdbool.h>
/**
* @brief Setup the watchdog for the safety controller
* @param Prescaler to use for the 32 KHz LSI clock
* @return 0 if successful
* @note Once the watchdog is enabled, it cannot be turned off!
*/
int watchdog_setup(uint8_t prescaler);
/**
* @brief Reset watchdog counter
* @param magic Magic value to prevent this fuinction from being called randomly
* @return 0 if successful
*/
int watchdog_ack(uint32_t magic);
/**
* @brief Check if reset was generated by the watchdog.
* @note This also clears the relevant flag, so the function will reutrn false when called a second time
* @return
*/
bool watchdog_check_reset_source(void);
#endif /* __WATCHDOG_H__ */

View File

@ -64,5 +64,4 @@ int rcc_manager_enable_clock(volatile uint32_t *rcc_enable_register, uint8_t bit
*/
int rcc_manager_disable_clock(volatile uint32_t *rcc_enable_register, uint8_t bit_no);
#endif /* __CLOCK_ENABLE_MANAGER_H__ */

View File

@ -41,9 +41,9 @@
#include <stm-periph/uart.h>
#include <reflow-controller/shell-uart-config.h>
#include <reflow-controller/oven-driver.h>
#include <reflow-controller/safety/safety-adc.h>
#include <fatfs/ff.h>
#include <reflow-controller/reflow-menu.h>
#include <reflow-controller/safety/safety-controller.h>
bool global_error_state;
@ -148,18 +148,21 @@ static inline void setup_system(void)
setup_nvic_priorities();
systick_setup();
adc_pt1000_setup_meas();
oven_driver_init();
digio_setup_default_all();
led_setup();
loudspeaker_setup();
reflow_menu_init();
safety_adc_init();
uart_gpio_config();
setup_shell_uart(&shell_uart);
setup_unused_pins();
safety_controller_init();
adc_pt1000_setup_meas();
}
static void handle_shell_uart_input(shellmatta_handle_t shell_handle)
@ -188,39 +191,12 @@ static void zero_ccm_ram(void)
ptr[i] = 0UL;
}
/**
* @brief This function sets the appropriate error flags in the oven PID controller
* depending on the Safety ADC measurements.
* The PID controller's error flags have to be cleared via the GUI by either starting a new RUN or explicitly
* ack'ing these errors.
*/
static void propagate_safety_adc_error_to_oven_pid(void)
{
enum safety_adc_check_result safety_adc_result;
safety_adc_result = safety_adc_get_errors();
if (safety_adc_result & SAFETY_ADC_CHECK_TEMP_LOW ||
safety_adc_result & SAFETY_ADC_CHECK_TEMP_HIGH)
oven_pid_report_error(OVEN_PID_ERR_OVERTEMP);
if (safety_adc_result & SAFETY_ADC_CHECK_VREF_LOW ||
safety_adc_result & SAFETY_ADC_CHECK_VREF_HIGH)
oven_pid_report_error(OVEN_PID_ERR_VREF_TOL);
if (safety_adc_result & SAFETY_ADC_INTERNAL_ERROR)
oven_pid_report_error(0);
}
int main(void)
{
bool sd_card_mounted = false;
shellmatta_handle_t shell_handle;
int menu_wait_request;
uint64_t quarter_sec_timestamp = 0ULL;
const struct oven_pid_status *pid_status;
enum adc_pt1000_error pt1000_status;
zero_ccm_ram();
setup_system();
@ -232,31 +208,18 @@ int main(void)
while (1) {
sd_card_mounted = mount_sd_card_if_avail(sd_card_mounted);
pid_status = oven_pid_get_status();
if (systick_ticks_have_passed(quarter_sec_timestamp, 250)) {
quarter_sec_timestamp = systick_get_global_tick();
(void)handle_safety_adc();
propagate_safety_adc_error_to_oven_pid();
if (global_error_state)
led_set(0, !led_get(0));
else
led_set(0, 0);
}
pt1000_status = adc_pt1000_check_error();
global_error_state = pid_status->error_set || !!safety_adc_get_errors() || !!pt1000_status;
menu_wait_request = reflow_menu_handle();
/* Deactivate oven output in case of error! */
if (!pid_status->active || global_error_state)
oven_driver_set_power(0U);
handle_shell_uart_input(shell_handle);
safety_controller_handle();
oven_driver_set_power(0);
oven_driver_apply_power_level();
if (menu_wait_request)
__WFI();
else

View File

@ -24,16 +24,12 @@
#include <reflow-controller/systick.h>
#include <reflow-controller/adc-meas.h>
#include <reflow-controller/temp-converter.h>
#include <reflow-controller/safety/safety-controller.h>
static struct pid_controller oven_pid;
static struct oven_pid_status oven_pid_current_status = {
.active = false,
.error_set = false,
.target_temp = 0.0f,
.current_temp = 0.0f,
.timestamp_last_run = 0ULL
};
static bool oven_pid_running = false;
static bool oven_pid_aborted = false;
static uint8_t oven_driver_power_level = 0U;
void oven_driver_init()
{
@ -60,7 +56,12 @@ void oven_driver_set_power(uint8_t power)
if (power > 100U)
power = 100U;
OVEN_CONTROLLER_PWM_TIMER->CCR3 = power * 10;
oven_driver_power_level = power;
}
void oven_driver_apply_power_level(void)
{
OVEN_CONTROLLER_PWM_TIMER->CCR3 = oven_driver_power_level * 10;
}
void oven_driver_disable()
@ -71,93 +72,52 @@ void oven_driver_disable()
rcc_manager_disable_clock(&RCC->APB1ENR, BITMASK_TO_BITNO(OVEN_CONTROLLER_TIM_RCC_MASK));
}
void oven_pid_ack_errors(void)
{
oven_pid_current_status.error_set = false;
oven_pid_current_status.error_flags.vref_tol = false;
oven_pid_current_status.error_flags.pt1000_other = false;
oven_pid_current_status.error_flags.generic_error = false;
oven_pid_current_status.error_flags.pt1000_adc_off = false;
oven_pid_current_status.error_flags.controller_overtemp = false;
oven_pid_current_status.error_flags.pt1000_adc_watchdog = false;
}
void oven_pid_init(struct pid_controller *controller_to_copy)
{
pid_copy(&oven_pid, controller_to_copy);
oven_pid.output_sat_min = 0.0f;
oven_pid.output_sat_max = 100.0f;
oven_pid_current_status.timestamp_last_run = 0ULL;
oven_pid_current_status.active = true;
oven_pid_ack_errors();
oven_pid_running = true;
oven_pid_aborted = false;
safety_controller_report_timing(ERR_TIMING_PID);
}
void oven_pid_handle(float target_temp)
{
float pid_out;
float current_temp;
int resistance_status;
enum adc_pt1000_error pt1000_error;
if (oven_pid_current_status.active && !oven_pid_current_status.error_set) {
if (systick_ticks_have_passed(oven_pid_current_status.timestamp_last_run,
(uint64_t)(oven_pid.sample_period * 1000))) {
resistance_status = adc_pt1000_get_current_resistance(&current_temp);
if (resistance_status < 0) {
oven_driver_set_power(0);
pt1000_error = adc_pt1000_check_error();
if (pt1000_error & ADC_PT1000_WATCHDOG_ERROR)
oven_pid_report_error(OVEN_PID_ERR_PT1000_ADC_WATCHDOG);
if (pt1000_error & ADC_PT1000_INACTIVE)
oven_pid_report_error(OVEN_PID_ERR_PT1000_ADC_OFF);
if (pt1000_error & ADC_PT1000_OVERFLOW)
oven_pid_report_error(OVEN_PID_ERR_PT1000_OTHER);
return;
}
static uint64_t timestamp_last_run;
if (oven_pid_running && !oven_pid_aborted) {
if (systick_ticks_have_passed(timestamp_last_run, (uint64_t)(oven_pid.sample_period * 1000))) {
/* No need to check. Safety controller will monitor this */
(void)adc_pt1000_get_current_resistance(&current_temp);
(void)temp_converter_convert_resistance_to_temp(current_temp, &current_temp);
pid_out = pid_sample(&oven_pid, target_temp - current_temp);
oven_driver_set_power((uint8_t)pid_out);
oven_pid_current_status.timestamp_last_run = systick_get_global_tick();
oven_pid_current_status.target_temp = target_temp;
oven_pid_current_status.current_temp = current_temp;
timestamp_last_run = systick_get_global_tick();
safety_controller_report_timing(ERR_TIMING_PID);
}
}
}
void oven_pid_report_error(enum oven_pid_error_report report)
{
struct oven_pid_errors *e = &oven_pid_current_status.error_flags;
oven_pid_current_status.active = false;
oven_pid_current_status.error_set = true;
if (report == 0) {
e->generic_error = true;
}
if (report & OVEN_PID_ERR_OVERTEMP)
e->controller_overtemp = true;
if (report & OVEN_PID_ERR_VREF_TOL)
e->controller_overtemp = true;
if (report & OVEN_PID_ERR_PT1000_OTHER)
e->pt1000_other = true;
if (report & OVEN_PID_ERR_PT1000_ADC_OFF)
e->pt1000_adc_off = true;
if (report & OVEN_PID_ERR_PT1000_ADC_WATCHDOG)
e->pt1000_adc_watchdog = true;
}
const struct oven_pid_status *oven_pid_get_status()
{
return &oven_pid_current_status;
}
void oven_pid_stop()
{
oven_pid_current_status.active = false;
oven_pid_current_status.target_temp = 0.0f;
oven_pid_current_status.current_temp = 0.0f;
oven_pid_running = false;
safety_controller_enable_timing_mon(ERR_TIMING_PID, false);
}
enum oven_pid_status oven_pid_get_status(void)
{
enum oven_pid_status ret = OVEN_PID_ABORTED;
if (oven_pid_running && !oven_pid_aborted)
ret = OVEN_PID_RUNNING;
else if (!oven_pid_running && !oven_pid_aborted)
ret = OVEN_PID_DEACTIVATED;
return ret;
}

View File

@ -24,7 +24,7 @@
#include <reflow-controller/rotary-encoder.h>
#include <reflow-controller/systick.h>
#include <reflow-controller/adc-meas.h>
#include <reflow-controller/safety/safety-adc.h>
#include <reflow-controller/safety/safety-controller.h>
#include <reflow-controller/temp-converter.h>
#include <helper-macros/helper-macros.h>
#include <stm-periph/unique-id.h>
@ -90,11 +90,11 @@ static void reflow_menu_monitor(struct lcd_menu *menu, enum menu_entry_func_entr
snprintf(line, sizeof(line), "Temp: %s%.1f " LCD_DEGREE_SYMBOL_STRING "C", prefix, tmp);
menu->update_display(1, line);
tmp = safety_adc_get_temp();
(void)safety_controller_get_analog_mon_value(ERR_AMON_UC_TEMP, &tmp);
snprintf(line, sizeof(line), "Tj: %.1f " LCD_DEGREE_SYMBOL_STRING "C", tmp);
menu->update_display(2, line);
tmp = safety_adc_get_vref();
(void)safety_controller_get_analog_mon_value(ERR_AMON_VREF, &tmp);
snprintf(line, sizeof(line), "Vref: %.1f mV", tmp);
menu->update_display(3, line);
}

View File

@ -18,29 +18,20 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup safety-adc
* @{
*/
#include <reflow-controller/safety/safety-adc.h>
#include <reflow-controller/periph-config/safety-adc-hwcfg.h>
#include <helper-macros/helper-macros.h>
#include <stm-periph/clock-enable-manager.h>
enum safety_adc_check_result global_safety_adc_status;
enum safety_adc_check_result safety_adc_get_errors()
{
return global_safety_adc_status;
}
void safety_adc_clear_errors(void)
{
global_safety_adc_status = SAFETY_ADC_CHECK_OK;
}
void safety_adc_init()
{
rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(SAFETY_ADC_ADC_RCC_MASK));
safety_adc_clear_errors();
/* Enable temperature and VREFINT measurement */
ADC->CCR |= ADC_CCR_TSVREFE;
@ -60,38 +51,27 @@ void safety_adc_deinit()
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)
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value)
{
enum safety_adc_check_result res = SAFETY_ADC_CHECK_OK;
float vref;
float temp;
float converted_val;
vref = (SAFETY_ADC_INT_REF_MV * 4095.0f) / (float)vref_result;
if (vref_calculated) {
*vref_calculated = vref;
switch (channel) {
case SAFETY_ADC_MEAS_TEMP:
converted_val = (((float)analog_value / 4095.0f * 2500.0f - SAFETY_ADC_TEMP_NOM_MV) /
SAFETY_ADC_TEMP_MV_SLOPE) + SAFETY_ADC_TEMP_NOM;
break;
case SAFETY_ADC_MEAS_VREF:
converted_val = (SAFETY_ADC_INT_REF_MV * 4095.0f) / (float)analog_value;
break;
default:
/* Generate NaN value as default return */
converted_val = 0.0f / 0.0f;
break;
}
temp = (((float)temp_result / 4095.0f * 2500.0f -
SAFETY_ADC_TEMP_NOM_MV) / SAFETY_ADC_TEMP_MV_SLOPE) + SAFETY_ADC_TEMP_NOM;
if (temp_calculated) {
*temp_calculated = temp;
}
if (ABS(vref - SAFETY_ADC_VREF_MVOLT) > SAFETY_ADC_VREF_TOL_MVOLT) {
if (vref > SAFETY_ADC_VREF_MVOLT)
res |= SAFETY_ADC_CHECK_VREF_HIGH;
else
res |= SAFETY_ADC_CHECK_VREF_LOW;
}
if (temp < SAFETY_ADC_TEMP_LOW_LIM)
res |= SAFETY_ADC_CHECK_TEMP_LOW;
else if (temp < SAFETY_ADC_CHECK_TEMP_HIGH)
res |= SAFETY_ADC_CHECK_TEMP_HIGH;
return res;
return converted_val;
}
int safety_adc_poll_result(uint16_t *adc_result)
@ -131,58 +111,5 @@ void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement)
SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_SWSTART;
}
static uint16_t safety_vref_meas_raw;
static bool safety_vref_valid = false;
static uint16_t safety_temp_meas_raw;
static 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;
enum safety_adc_check_result check_result;
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 SAFETY_ADC_INTERNAL_ERROR;
}
}
if (safety_temp_valid && safety_vref_valid) {
check_result = safety_adc_check_results(safety_vref_meas_raw, safety_temp_meas_raw, &safety_vref, &safety_temp);
global_safety_adc_status |= check_result;
} else {
check_result = SAFETY_ADC_CHECK_OK;
}
return check_result;
}
float safety_adc_get_temp()
{
return safety_temp;
}
float safety_adc_get_vref()
{
return safety_vref;
}
/** @} */

View File

@ -0,0 +1,8 @@
/**
@defgroup safety-adc Safety ADC
@ingroup safety
The safety ADC continuously monitors the microcontrollers internal core temperature (and therefore the whole device's temperature) and the external reference voltage compared to its
internal bandgap reference voltage.
*/

View File

@ -0,0 +1,546 @@
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup safety-controller
* @{
*/
#include <reflow-controller/safety/safety-controller.h>
#include <reflow-controller/safety/safety-config.h>
#include <reflow-controller/safety/watchdog.h>
#include <reflow-controller/safety/safety-adc.h>
#include <reflow-controller/stack-check.h>
#include <helper-macros/helper-macros.h>
#include <reflow-controller/systick.h>
#include <stddef.h>
#include <string.h>
struct error_flag {
const char *name;
enum safety_flag flag;
bool error_state;
bool persistent;
uint32_t key;
};
struct timing_mon {
const char *name;
enum timing_monitor monitor;
enum safety_flag associated_flag;
uint64_t min_delta;
uint64_t max_delta;
uint64_t last;
bool enabled;
};
struct analog_mon {
const char *name;
enum analog_value_monitor monitor;
enum safety_flag associated_flag;
float min;
float max;
float value;
bool valid;
uint64_t timestamp;
};
#ifdef COUNT_OF
#undef COUNT_OF
#endif
#define COUNT_OF(x) ((sizeof(x)/sizeof(0[x])) / ((size_t)(!(sizeof(x) % sizeof(0[x])))))
#define ERR_FLAG_ENTRY(errflag, persistency) {.name=#errflag, .flag = (errflag), .error_state = false, .persistent = (persistency), .key = 0UL}
#define TIM_MON_ENTRY(mon, min, max, flag) {.name=#mon, .monitor = (mon), .associated_flag=(flag), .min_delta = (min), .max_delta = (max), .last = 0ULL, .enabled= false}
#define ANA_MON_ENTRY(mon, min_value, max_value, flag) {.name=#mon, .monitor = (mon), .associated_flag=(flag), .min = (min_value), .max = (max_value), .value = 0.0f, .valid = false}
static volatile struct error_flag flags[] = {
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_OFF, false),
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG, false),
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_UNSTABLE, false),
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_OVERFLOW, true),
ERR_FLAG_ENTRY(ERR_FLAG_TIMING_MEAS_ADC, false),
ERR_FLAG_ENTRY(ERR_FLAG_TIMING_PID, false),
ERR_FLAG_ENTRY(ERR_FLAG_AMON_UC_TEMP, true),
ERR_FLAG_ENTRY(ERR_FLAG_AMON_VREF, false),
ERR_FLAG_ENTRY(ERR_FLAG_STACK, true),
ERR_FLAG_ENTRY(ERR_FLAG_SAFETY_ADC, true),
ERR_FLAG_ENTRY(ERR_FLAG_SYSTICK, true),
ERR_FLAG_ENTRY(ERR_FLAG_WTCHDG_FIRED, true),
ERR_FLAG_ENTRY(ERR_FLAG_UNCAL, false),
ERR_FLAG_ENTRY(ERR_FLAG_DEBUG, true),
};
static volatile struct timing_mon timings[] = {
TIM_MON_ENTRY(ERR_TIMING_PID, 2, 1000, ERR_FLAG_TIMING_PID),
TIM_MON_ENTRY(ERR_TIMING_MEAS_ADC, 0, 50, ERR_FLAG_TIMING_MEAS_ADC),
TIM_MON_ENTRY(ERR_TIMING_SAFETY_ADC, 10, SAFETY_CONTROLLER_ADC_DELAY_MS + 500, ERR_FLAG_SAFETY_ADC),
};
static volatile struct analog_mon analog_mons[] = {
ANA_MON_ENTRY(ERR_AMON_VREF, SAFETY_ADC_VREF_MVOLT - SAFETY_ADC_VREF_TOL_MVOLT,
SAFETY_ADC_VREF_MVOLT + SAFETY_ADC_VREF_TOL_MVOLT, ERR_FLAG_AMON_VREF),
ANA_MON_ENTRY(ERR_AMON_UC_TEMP, SAFETY_ADC_TEMP_LOW_LIM, SAFETY_ADC_TEMP_HIGH_LIM,
ERR_FLAG_AMON_UC_TEMP),
};
static volatile struct analog_mon *find_analog_mon(enum analog_value_monitor mon)
{
uint32_t i;
volatile struct analog_mon *ret = NULL;
for (i = 0; i < COUNT_OF(analog_mons); i++) {
if (analog_mons[i].monitor == mon)
ret = &analog_mons[i];
}
return ret;
}
static volatile struct timing_mon *find_timing_mon(enum timing_monitor mon)
{
uint32_t i;
volatile struct timing_mon *ret = NULL;
for (i = 0; i < COUNT_OF(timings); i++) {
if (timings[i].monitor == mon)
ret = &timings[i];
}
return ret;
}
static volatile struct error_flag *find_error_flag(enum safety_flag flag)
{
uint32_t i;
volatile struct error_flag *ret = NULL;
for (i = 0; i < COUNT_OF(flags); i++) {
if (flags[i].flag == flag)
ret = &flags[i];
}
return ret;
}
static void safety_controller_process_active_timing_mons()
{
uint32_t i;
volatile struct timing_mon *current_mon;
for (i = 0; i < COUNT_OF(timings); i++) {
current_mon = &timings[i];
if (current_mon->enabled) {
if (systick_ticks_have_passed(current_mon->last, current_mon->max_delta))
safety_controller_report_error(current_mon->associated_flag);
}
}
}
static void safety_controller_process_checks()
{
static bool startup_completed = false;
enum analog_monitor_status amon_state;
float amon_value;
if (!startup_completed && systick_get_global_tick() >= 1000)
startup_completed = true;
if (startup_completed) {
amon_state = safety_controller_get_analog_mon_value(ERR_AMON_VREF, &amon_value);
if (amon_state != ANALOG_MONITOR_OK)
safety_controller_report_error(ERR_FLAG_AMON_VREF);
amon_state = safety_controller_get_analog_mon_value(ERR_AMON_UC_TEMP, &amon_value);
if (amon_state != ANALOG_MONITOR_OK)
safety_controller_report_error(ERR_FLAG_AMON_UC_TEMP);
}
safety_controller_process_active_timing_mons();
}
int safety_controller_report_error(enum safety_flag flag)
{
return safety_controller_report_error_with_key(flag, 0x0UL);
}
int safety_controller_report_error_with_key(enum safety_flag flag, uint32_t key)
{
uint32_t i;
int ret = -1;
for (i = 0; i < COUNT_OF(flags); i++) {
if (flags[i].flag & flag) {
flags[i].error_state = true;
flags[i].key = key;
ret = 0;
}
}
return ret;
}
void safety_controller_report_timing(enum timing_monitor monitor)
{
volatile struct timing_mon *tim;
uint64_t timestamp;
timestamp = systick_get_global_tick();
tim = find_timing_mon(monitor);
if (tim) {
if (tim->enabled) {
if (!systick_ticks_have_passed(tim->last, tim->min_delta) && tim->min_delta > 0U) {
safety_controller_report_error(tim->associated_flag);
}
}
tim->last = timestamp;
tim->enabled = true;
}
}
void safety_controller_report_analog_value(enum analog_value_monitor monitor, float value)
{
volatile struct analog_mon *ana;
/* Return if not a power of two */
if (!is_power_of_two(monitor))
return;
ana = find_analog_mon(monitor);
if (ana) {
ana->valid = true;
ana->value = value;
ana->timestamp = systick_get_global_tick();
}
}
void safety_controller_init()
{
/* Init default flag states */
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_OFF | ERR_FLAG_MEAS_ADC_UNSTABLE,
MEAS_ADC_SAFETY_FLAG_KEY);
safety_adc_init();
watchdog_setup(WATCHDOG_PRESCALER);
if (watchdog_check_reset_source())
safety_controller_report_error(ERR_FLAG_WTCHDG_FIRED);
#ifdef DEBUGBUILD
safety_controller_report_error(ERR_FLAG_DEBUG);
#endif
}
static void safety_controller_check_stack()
{
int32_t free_stack;
free_stack = stack_check_get_free();
if (free_stack < SAFETY_MIN_STACK_FREE)
safety_controller_report_error(ERR_FLAG_STACK);
}
static void safety_controller_handle_safety_adc()
{
static enum safety_adc_meas_channel current_channel = SAFETY_ADC_MEAS_TEMP;
static uint64_t last_result_timestamp = 0;
int poll_result;
uint16_t result;
float analog_value;
poll_result = safety_adc_poll_result(&result);
if (!systick_ticks_have_passed(last_result_timestamp, SAFETY_CONTROLLER_ADC_DELAY_MS) && poll_result != 1)
return;
if (poll_result) {
if (poll_result == -1) {
switch (current_channel) {
case SAFETY_ADC_MEAS_TEMP:
current_channel = SAFETY_ADC_MEAS_VREF;
break;
case SAFETY_ADC_MEAS_VREF:
/* Expected fallthru */
default:
current_channel = SAFETY_ADC_MEAS_TEMP;
break;
}
safety_adc_trigger_meas(current_channel);
} else if (poll_result == 1) {
last_result_timestamp = systick_get_global_tick();
analog_value = safety_adc_convert_channel(current_channel, result);
safety_controller_report_timing(ERR_TIMING_SAFETY_ADC);
switch (current_channel) {
case SAFETY_ADC_MEAS_TEMP:
safety_controller_report_analog_value(ERR_AMON_UC_TEMP, analog_value);
break;
case SAFETY_ADC_MEAS_VREF:
safety_controller_report_analog_value(ERR_AMON_VREF, analog_value);
break;
default:
safety_controller_report_error(ERR_FLAG_SAFETY_ADC);
break;
}
}
}
}
int safety_controller_handle()
{
static uint64_t last_systick;
static uint32_t same_systick_cnt = 0UL;
uint64_t systick;
int ret = 0;
safety_controller_check_stack();
safety_controller_handle_safety_adc();
systick = systick_get_global_tick();
if (systick == last_systick) {
same_systick_cnt++;
if (same_systick_cnt > 1000)
safety_controller_report_error(ERR_FLAG_SYSTICK);
} else {
same_systick_cnt = 0UL;
}
last_systick = systick;
safety_controller_process_checks();
/* TODO: Check flags for PID and HALT */
ret |= watchdog_ack(WATCHDOG_MAGIC_KEY);
return (ret ? -1 : 0);
}
int safety_controller_enable_timing_mon(enum timing_monitor monitor, bool enable)
{
volatile struct timing_mon *tim;
if (enable) {
safety_controller_report_timing(monitor);
} else {
tim = find_timing_mon(monitor);
if (!tim)
return -1;
tim->enabled = false;
}
return 0;
}
enum analog_monitor_status safety_controller_get_analog_mon_value(enum analog_value_monitor monitor, float *value)
{
volatile struct analog_mon *mon;
int ret = ANALOG_MONITOR_ERROR;
if (!is_power_of_two(monitor))
goto go_out;
if (!value)
goto go_out;
mon = find_analog_mon(monitor);
if (mon) {
if (!mon->valid) {
ret = ANALOG_MONITOR_INACTIVE;
goto go_out;
}
*value = mon->value;
if (mon->value < mon->min)
ret = ANALOG_MONITOR_UNDER;
else if (mon->value > mon->max)
ret = ANALOG_MONITOR_OVER;
else
ret = ANALOG_MONITOR_OK;
}
go_out:
return ret;
}
int safety_controller_get_flag(enum safety_flag flag, bool *status, bool try_ack)
{
volatile struct error_flag *found_flag;
int ret = -1;
if (!status)
return -1002;
if (!is_power_of_two(flag))
return -1001;
found_flag = find_error_flag(flag);
if (found_flag) {
*status = found_flag->error_state;
if (try_ack && !found_flag->persistent) {
/* Flag is generally non persistent
* If key is set, this function cannot remove the flag
*/
if (found_flag->key == 0UL)
found_flag->error_state = false;
}
}
return ret;
}
int safety_controller_ack_flag(enum safety_flag flag)
{
return safety_controller_ack_flag_with_key(flag, 0UL);
}
int safety_controller_ack_flag_with_key(enum safety_flag flag, uint32_t key)
{
int ret = -1;
volatile struct error_flag *found_flag;
if (!is_power_of_two(flag)) {
return -1001;
}
found_flag = find_error_flag(flag);
if (found_flag) {
if (!found_flag->persistent && (found_flag->key == key || !key)) {
found_flag->error_state = false;
ret = 0;
} else {
ret = -2;
}
}
return ret;
}
bool safety_controller_get_flags_by_mask(enum safety_flag mask)
{
uint32_t i;
bool ret = false;
for (i = 0; i < COUNT_OF(flags); i++) {
if ((flags[i].flag & mask) && flags[i].error_state) {
ret = true;
break;
}
}
return ret;
}
uint32_t safety_controller_get_flag_count()
{
return COUNT_OF(flags);
}
uint32_t safety_controller_get_analog_monitor_count()
{
return COUNT_OF(analog_mons);
}
int safety_controller_get_analog_mon_name_by_index(uint32_t index, char *buffer, size_t buffsize)
{
if (index >= COUNT_OF(analog_mons))
return -1;
if (buffsize == 0 || !buffer)
return -1000;
strncpy(buffer, analog_mons[index].name, buffsize);
buffer[buffsize - 1] = 0;
return 0;
}
int safety_controller_get_flag_name_by_index(uint32_t index, char *buffer, size_t buffsize)
{
if (index >= COUNT_OF(flags))
return -1;
if (buffsize == 0 || !buffer)
return -1000;
strncpy(buffer, flags[index].name, buffsize);
buffer[buffsize - 1] = 0;
return 0;
}
int safety_controller_get_flag_by_index(uint32_t index, bool *status, enum safety_flag *flag_enum)
{
int ret = -1;
if (!status && !flag_enum)
return -1000;
if (index < COUNT_OF(flags)) {
if (status)
*status = flags[index].error_state;
if (flag_enum)
*flag_enum = flags[index].flag;
ret = 0;
}
return ret;
}
int safety_controller_get_analog_mon_by_index(uint32_t index, struct analog_monitor_info *info)
{
volatile struct analog_mon *mon;
if (!info)
return -1002;
if (index >= COUNT_OF(analog_mons)) {
info->status = ANALOG_MONITOR_ERROR;
return -1001;
}
mon = &analog_mons[index];
info->max = mon->max;
info->min = mon->min;
info->value = mon->value;
info->timestamp = mon->timestamp;
if (!mon->valid) {
info->status = ANALOG_MONITOR_INACTIVE;
} else {
if (mon->value > mon->max)
info->status = ANALOG_MONITOR_OVER;
else if (mon->value < mon->min)
info->status = ANALOG_MONITOR_UNDER;
else
info->status = ANALOG_MONITOR_OK;
}
return 0;
}
/** @} */

View File

@ -0,0 +1,7 @@
/**
@defgroup safety-controller Safety Controller
@ingroup safety
This is the main module for the safety part of the firmware. It monitors
analog values, error states and timeouts of timing critical sections of the firmware.
*/

View File

@ -0,0 +1,6 @@
/**
@defgroup safety Safety Module
@brief Safety Supervisor Module
This is the safety module which ensures safe operation of the reflow controller
*/

View File

@ -0,0 +1,120 @@
/* Reflow Oven Controller
*
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup watchdog
* @{
*/
#include <reflow-controller/safety/watchdog.h>
#include <stm32/stm32f4xx.h>
/**
* @brief This key is expected by hardware to be written to the IWDG_KR register in order to reset the watchdog
*/
#define STM32_WATCHDOG_RESET_KEY 0xAAAA
/**
* @brief This key is expected by hardware to be written to the IWDG_KR register in order to enable the watchdog
*/
#define STM32_WATCHDOG_ENABLE_KEY 0xCCCC
/**
* @brief This key is expected by hardware to be written to the IWDG_KR register in order to enable access to config
* registers
*/
#define STM32_WATCHDOG_REGISTER_ACCESS_KEY 0x5555
int watchdog_setup(uint8_t prescaler)
{
uint32_t prescaler_reg_val;
/** - Activate the LSI oscillator */
RCC->CSR |= RCC_CSR_LSION;
__DSB();
/** - Wait for the oscillator to be ready */
while (!(RCC->CSR & RCC_CSR_LSIRDY));
if (prescaler == 4)
prescaler_reg_val = 0UL;
else if (prescaler == 8)
prescaler_reg_val = 1UL;
else if (prescaler == 16)
prescaler_reg_val = 2UL;
else if (prescaler == 32)
prescaler_reg_val = 3UL;
else if (prescaler == 64)
prescaler_reg_val = 4UL;
else if (prescaler == 128)
prescaler_reg_val = 5UL;
else
prescaler_reg_val = 6UL;
/** - Unlock registers */
IWDG->KR = STM32_WATCHDOG_REGISTER_ACCESS_KEY;
/** - Wait until prescaler can be written */
while (IWDG->SR & IWDG_SR_PVU);
/** - Write prescaler value */
IWDG->PR = prescaler_reg_val;
/* - Wait until reload value can be written */
while (IWDG->SR & IWDG_SR_RVU);
/** - Set reload value fixed to 0xFFF */
IWDG->RLR = 0xFFFU;
/** - Write enable key */
IWDG->KR = STM32_WATCHDOG_ENABLE_KEY;
/** - Do a first reset of the counter. This also locks the config regs */
watchdog_ack(WATCHDOG_MAGIC_KEY);
return 0;
}
int watchdog_ack(uint32_t magic)
{
int ret = -1;
/** - Check if magic key is correct */
if (magic == WATCHDOG_MAGIC_KEY) {
/** - Write reset key to watchdog */
IWDG->KR = STM32_WATCHDOG_RESET_KEY;
ret = 0;
}
return ret;
}
bool watchdog_check_reset_source(void)
{
bool ret;
ret = !!(RCC->CSR & RCC_CSR_WDGRSTF);
if (ret)
RCC->CSR |= RCC_CSR_RMVF;
return ret;
}
/** @} */

View File

@ -0,0 +1,9 @@
/**
@defgroup watchdog Independent Watchdog
@ingroup safety
The independet watchdog module enusres that the safety controller run continuously and the whole formware does not lock.
The watchdog is entirely controlled by the safety controller and must not be used by the rest of the firmware
*/

View File

@ -35,7 +35,7 @@
#include <fatfs/ff.h>
#include <reflow-controller/stack-check.h>
#include <reflow-controller/rotary-encoder.h>
#include <reflow-controller/safety/safety-adc.h>
#include <reflow-controller/safety/safety-controller.h>
#ifndef GIT_VER
#define GIT_VER "VERSION NOT SET"
@ -59,8 +59,8 @@ static shellmatta_retCode_t shell_cmd_ver(const shellmatta_handle_t handle,
unique_id_get(&high_id, &mid_id, &low_id);
shellmatta_printf(handle, "Reflow Oven Controller Firmware " xstr(GIT_VER) "\r\n"
"Compiled: " __DATE__ " at " __TIME__ "\r\n"
"Serial: %08X-%08X-%08X", high_id, mid_id, low_id);
"Compiled: " __DATE__ " at " __TIME__ "\r\n");
shellmatta_printf(handle, "Serial: %08X-%08X-%08X", high_id, mid_id, low_id);
return SHELLMATTA_OK;
}
@ -128,7 +128,6 @@ static shellmatta_retCode_t shell_cmd_pt1000_res(const shellmatta_handle_t han
(void)length;
float resistance;
int pt1000_status;
enum adc_pt1000_error pt1000_flags;
char display_status[100];
float temp;
int temp_conv_status;
@ -141,13 +140,7 @@ static shellmatta_retCode_t shell_cmd_pt1000_res(const shellmatta_handle_t han
if (pt1000_status == 2) {
strcat(display_status, " UNSTABLE ");
} else if (pt1000_status) {
pt1000_flags = adc_pt1000_check_error();
if (pt1000_flags & ADC_PT1000_INACTIVE)
strcat(display_status, " DEACTIVATED ");
else if (pt1000_flags & ADC_PT1000_WATCHDOG_ERROR)
strcat(display_status, " WATCHDOG ");
else if (pt1000_flags & ADC_PT1000_OVERFLOW)
strcat(display_status, " OVERFLOW ");
strcpy(display_status, "ERROR");
} else {
strcpy(display_status, "VALID");
}
@ -171,17 +164,6 @@ static shellmatta_retCode_t shell_cmd_pt1000_res(const shellmatta_handle_t han
return SHELLMATTA_OK;
}
static shellmatta_retCode_t shell_cmd_clear_error_status(const shellmatta_handle_t handle, const char *arguments,
uint32_t length)
{
(void)arguments;
(void)length;
(void)handle;
adc_pt1000_clear_error();
return SHELLMATTA_OK;
}
static shellmatta_retCode_t shell_cmd_uptime(const shellmatta_handle_t handle,
const char *arguments,
@ -313,6 +295,8 @@ static shellmatta_retCode_t shell_cmd_reset(const shellmatta_handle_t handle, co
static shellmatta_retCode_t shell_cmd_cat(const shellmatta_handle_t handle, const char *arguments,
uint32_t length)
{
#ifdef IMPLEMENT_SHELL_CAT
FIL file;
char path_buff[256];
const char *path;
@ -349,31 +333,76 @@ static shellmatta_retCode_t shell_cmd_cat(const shellmatta_handle_t handle, cons
f_close(&file);
return SHELLMATTA_OK;
}
static shellmatta_retCode_t shell_cmd_safety_adc(const shellmatta_handle_t handle, const char *arguments,
uint32_t length)
{
#else
(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());
shellmatta_printf(handle, "Errors:\t%X", safety_adc_get_errors());
shellmatta_printf(handle, "cat not implemented!\r\n");
#endif
return SHELLMATTA_OK;
}
static shellmatta_retCode_t shell_cmd_safety_adc_clear_error(const shellmatta_handle_t handle, const char *arguments,
static shellmatta_retCode_t shell_cmd_read_flags(const shellmatta_handle_t handle, const char *arguments,
uint32_t length)
{
(void)length;
(void)arguments;
(void)handle;
uint32_t count;
uint32_t i;
char name[64];
bool flag;
int status;
struct analog_monitor_info amon_info;
safety_adc_clear_errors();
shellmatta_printf(handle, "Error flags\r\n"
"-----------\r\n");
count = safety_controller_get_flag_count();
for (i = 0; i < count; i++) {
status = safety_controller_get_flag_name_by_index(i, name, sizeof(name));
if (status) {
shellmatta_printf(handle, "Error getting flag name %lu\r\n", i);
continue;
}
status = safety_controller_get_flag_by_index(i, &flag, NULL);
if (status) {
shellmatta_printf(handle, "Error getting flag value %lu\r\n", i);
continue;
}
shellmatta_printf(handle, "\t%2lu) %-20s\t[%s]\r\n", i+1, name, (flag ? "\e[1;31mERR\e[m" : "\e[32mOK\e[m"));
}
shellmatta_printf(handle, "\r\nAnalog Monitors\r\n"
"---------------\r\n");
count = safety_controller_get_analog_monitor_count();
for (i = 0; i < count; i++) {
status = safety_controller_get_analog_mon_name_by_index(i, name, sizeof(name));
if (status) {
shellmatta_printf(handle, "Error getting analog value monitor %lu name\r\n", i);
continue;
}
status = safety_controller_get_analog_mon_by_index(i, &amon_info);
if (status) {
shellmatta_printf(handle, "Error reading analog monitor status %lu\r\n", i);
continue;
}
shellmatta_printf(handle, "\t%2lu) %-20s\t[%s%8.2f%s]", i+1, name,
amon_info.status == ANALOG_MONITOR_OK ? "\e[32m" : "\e[1;31m",
amon_info.value,
"\e[m");
if (amon_info.status == ANALOG_MONITOR_INACTIVE) {
shellmatta_printf(handle, "Inactive\r\n");
} else {
shellmatta_printf(handle, " valid from %-8.2f to %-8.2f", amon_info.min, amon_info.max);
shellmatta_printf(handle, "\tchecked %llu ms ago\r\n", systick_get_global_tick() - amon_info.timestamp);
}
}
return SHELLMATTA_OK;
}
@ -388,7 +417,7 @@ static shellmatta_retCode_t shell_cmd_safety_adc_clear_error(const shellmatta_ha
// struct shellmatta_cmd *next; /**< pointer to next command or NULL */
//} shellmatta_cmd_t;
static shellmatta_cmd_t cmd[15] = {
static shellmatta_cmd_t cmd[13] = {
{
.cmd = "version",
.cmdAlias = "ver",
@ -413,21 +442,13 @@ static shellmatta_cmd_t cmd[15] = {
.cmdFct = shell_cmd_pt1000_res_loop,
.next = &cmd[3],
},
{
.cmd = "pt1000-clear-error",
.cmdAlias = "pt-clear",
.helpText = "Clear error status of PT1000 reading",
.usageText = NULL,
.cmdFct = shell_cmd_clear_error_status,
.next = &cmd[4],
},
{
.cmd = "digio-get",
.cmdAlias = "dg",
.helpText = "Read all digital input/output ports",
.usageText = NULL,
.cmdFct = shell_cmd_digio_get,
.next = &cmd[5],
.next = &cmd[4],
},
{
.cmd = "digio-set",
@ -435,7 +456,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Set DIGIO Port",
.usageText = "digio-set <num> <state>",
.cmdFct = shell_cmd_digio_set,
.next = &cmd[6],
.next = &cmd[5],
},
{
.cmd = "uptime",
@ -443,7 +464,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Get uptime in seconds",
.usageText = "",
.cmdFct = shell_cmd_uptime,
.next = &cmd[7],
.next = &cmd[6],
},
{
.cmd = "calibrate",
@ -451,7 +472,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Calibrate resistance measurement",
.usageText = "",
.cmdFct = shell_cmd_cal,
.next = &cmd[8],
.next = &cmd[7],
},
{
.cmd = "meminfo",
@ -459,7 +480,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Get information about memory usage",
.usageText = "",
.cmdFct = shell_meminfo,
.next = &cmd[9],
.next = &cmd[8],
},
{
.cmd = "rotary-encoder",
@ -467,7 +488,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Get current rotary encoder value",
.usageText = "",
.cmdFct = shell_cmd_rot,
.next = &cmd[10],
.next = &cmd[9],
},
{
.cmd = "ls",
@ -475,7 +496,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "List filesystem contents",
.usageText = "",
.cmdFct = shell_cmd_ls,
.next = &cmd[11],
.next = &cmd[10],
},
{
.cmd = "reset",
@ -483,7 +504,7 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Reset controller",
.usageText = "reset",
.cmdFct = shell_cmd_reset,
.next = &cmd[12],
.next = &cmd[11],
},
{
.cmd = "cat",
@ -491,25 +512,16 @@ static shellmatta_cmd_t cmd[15] = {
.helpText = "Print file contents",
.usageText = "cat <path>",
.cmdFct = shell_cmd_cat,
.next = &cmd[13],
.next = &cmd[12],
},
{
.cmd = "safety-adc",
.cmdAlias = NULL,
.cmd = "safety-flags",
.cmdAlias = "flags",
.helpText = "",
.usageText = "",
.cmdFct = shell_cmd_safety_adc,
.next = &cmd[14],
},
{
.cmd = "safety-adc-clear-error",
.cmdAlias = NULL,
.helpText = "",
.usageText = "",
.cmdFct = shell_cmd_safety_adc_clear_error,
.cmdFct = shell_cmd_read_flags,
.next = NULL,
},
}
};
shellmatta_handle_t shell_init(shellmatta_write_t write_func)
@ -529,7 +541,7 @@ void shell_print_motd(shellmatta_handle_t shell)
{
/* Clear display and set cursor to home position */
shellmatta_printf(shell, "\e[2J\e[H");
shellmatta_printf(shell, "Shimatta 仕舞った Reflow Controller ready\r\n\r\n");
shellmatta_printf(shell, "Shimatta Reflow Controller ready\r\n\r\n");
shell_cmd_ver(shell, NULL, 0UL);
shell_handle_input(shell, "\r\n", 2UL);
}