Further rewrite safety handling
This commit is contained in:
parent
5eb51f08b6
commit
9136dc196c
@ -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__ */
|
||||
|
@ -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__ */
|
||||
|
@ -29,26 +29,7 @@
|
||||
#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();
|
||||
|
||||
@ -63,14 +44,9 @@ 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__ */
|
||||
|
||||
|
@ -68,4 +68,9 @@ enum analog_value_monitor {
|
||||
|
||||
#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)
|
||||
|
||||
#endif /* __SAFETY_CONFIG_H__ */
|
||||
|
@ -30,6 +30,12 @@
|
||||
#include <reflow-controller/safety/safety-config.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
enum analog_monitor_status {ANALOG_MONITOR_OK = 0,
|
||||
ANALOG_MONITOR_ERROR,
|
||||
ANALOG_MONITOR_INACTIVE,
|
||||
ANALOG_MONITOR_OVER,
|
||||
ANALOG_MONITOR_UNDER};
|
||||
|
||||
/**
|
||||
* @brief Initialize the safety controller
|
||||
*
|
||||
@ -50,8 +56,14 @@ int safety_controller_report_error(enum safety_flag flag);
|
||||
|
||||
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);
|
||||
|
||||
bool safety_controller_get_flag(enum safety_flag);
|
||||
|
||||
#endif /* __SAFETY_CONTROLLER_H__ */
|
||||
|
||||
/** @} */
|
||||
|
@ -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;
|
||||
|
||||
@ -154,12 +154,14 @@ static inline void setup_system(void)
|
||||
led_setup();
|
||||
loudspeaker_setup();
|
||||
reflow_menu_init();
|
||||
safety_adc_init();
|
||||
|
||||
|
||||
uart_gpio_config();
|
||||
setup_shell_uart(&shell_uart);
|
||||
|
||||
setup_unused_pins();
|
||||
|
||||
|
||||
}
|
||||
|
||||
static void handle_shell_uart_input(shellmatta_handle_t shell_handle)
|
||||
@ -188,39 +190,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 +207,20 @@ 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)
|
||||
if (0)
|
||||
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);
|
||||
|
||||
oven_driver_apply_power_level();
|
||||
|
||||
if (menu_wait_request)
|
||||
__WFI();
|
||||
else
|
||||
|
@ -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(¤t_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(¤t_temp);
|
||||
(void)temp_converter_convert_resistance_to_temp(current_temp, ¤t_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;
|
||||
}
|
||||
|
@ -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);
|
||||
}
|
||||
|
@ -28,24 +28,10 @@
|
||||
#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;
|
||||
|
||||
@ -65,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)channel / 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)
|
||||
@ -136,60 +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;
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
@ -26,6 +26,8 @@
|
||||
#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 <helper-macros/helper-macros.h>
|
||||
#include <reflow-controller/systick.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
@ -42,6 +44,7 @@ struct error_flag {
|
||||
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;
|
||||
@ -51,6 +54,7 @@ struct timing_mon {
|
||||
struct analog_mon {
|
||||
const char *name;
|
||||
enum analog_value_monitor monitor;
|
||||
enum safety_flag associated_flag;
|
||||
float min;
|
||||
float max;
|
||||
float value;
|
||||
@ -64,8 +68,8 @@ struct analog_mon {
|
||||
#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)}
|
||||
#define TIM_MON_ENTRY(mon, min, max) {.name=#mon, .monitor = (mon), .min_delta = (min), .max_delta = (max), .last = 0ULL, .enabled= false}
|
||||
#define ANA_MON_ENTRY(mon, min_value, max_value) {.name=#mon, .monitor = (mon), .min = (min_value), .max = (max_value), .value = 0.0f, .valid = false}
|
||||
#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 struct error_flag flags[] = {
|
||||
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_OFF, false),
|
||||
@ -80,16 +84,59 @@ static struct error_flag flags[] = {
|
||||
};
|
||||
|
||||
static struct timing_mon timings[] = {
|
||||
TIM_MON_ENTRY(ERR_TIMING_PID, 1, 800),
|
||||
TIM_MON_ENTRY(ERR_TIMING_MEAS_ADC, 1, 50),
|
||||
TIM_MON_ENTRY(ERR_TIMING_SAFETY_ADC, 220, 500),
|
||||
TIM_MON_ENTRY(ERR_TIMING_PID, 1, 800, ERR_FLAG_TIMING_PID),
|
||||
TIM_MON_ENTRY(ERR_TIMING_MEAS_ADC, 1, 50, ERR_FLAG_TIMING_MEAS_ADC),
|
||||
};
|
||||
|
||||
static struct analog_mon analog_mons[] = {
|
||||
ANA_MON_ENTRY(ERR_AMON_VREF, 2480.0f, 2520.0f),
|
||||
ANA_MON_ENTRY(ERR_AMON_UC_TEMP, 0.0f, 55.0f),
|
||||
ANA_MON_ENTRY(ERR_AMON_VREF, 2480.0f, 2520.0f, ERR_FLAG_AMON_VREF),
|
||||
ANA_MON_ENTRY(ERR_AMON_UC_TEMP, 0.0f, 55.0f, ERR_FLAG_AMON_UC_TEMP),
|
||||
};
|
||||
|
||||
static struct analog_mon *find_analog_mon(enum analog_value_monitor mon)
|
||||
{
|
||||
uint32_t i;
|
||||
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 struct timing_mon *find_timing_mon(enum timing_monitor mon)
|
||||
{
|
||||
uint32_t i;
|
||||
struct timing_mon *ret = NULL;
|
||||
|
||||
for (i = 0; i < COUNT_OF(timings); i++) {
|
||||
if (timings[i].monitor == mon)
|
||||
ret = &timings[i];
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static struct error_flag *find_error_flag(enum safety_flag flag)
|
||||
{
|
||||
uint32_t i;
|
||||
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_checks()
|
||||
{
|
||||
// TODO: Implement
|
||||
}
|
||||
|
||||
int safety_controller_report_error(enum safety_flag flag)
|
||||
{
|
||||
uint32_t i;
|
||||
@ -102,11 +149,11 @@ int safety_controller_report_error(enum safety_flag flag)
|
||||
}
|
||||
}
|
||||
|
||||
safety_controller_process_checks();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
||||
void safety_controller_report_timing(enum timing_monitor monitor)
|
||||
{
|
||||
uint32_t i;
|
||||
@ -115,22 +162,41 @@ void safety_controller_report_timing(enum timing_monitor monitor)
|
||||
|
||||
timestamp = systick_get_global_tick();
|
||||
|
||||
for (i = 0; i < COUNT_OF(timings); i++) {
|
||||
tim = &timings[i];
|
||||
if (tim->monitor & monitor) {
|
||||
tim->enabled = true;
|
||||
tim->last = timestamp;
|
||||
}
|
||||
tim = find_timing_mon(monitor);
|
||||
if (tim) {
|
||||
tim->last = timestamp;
|
||||
tim->enabled = true;
|
||||
}
|
||||
|
||||
safety_controller_process_checks();
|
||||
}
|
||||
|
||||
void safety_controller_report_analog_value(enum analog_value_monitor monitor, float value)
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
safety_controller_process_checks();
|
||||
}
|
||||
|
||||
void safety_controller_init()
|
||||
{
|
||||
safety_adc_init();
|
||||
watchdog_setup(WATCHDOG_PRESCALER);
|
||||
}
|
||||
|
||||
int safety_controller_handle()
|
||||
{
|
||||
static
|
||||
|
||||
int ret = 0;
|
||||
|
||||
/* TODO: Handle safety ADC */
|
||||
@ -144,19 +210,49 @@ int safety_controller_handle()
|
||||
|
||||
int safety_controller_enable_timing_mon(enum timing_monitor monitor, bool enable)
|
||||
{
|
||||
uint32_t i;
|
||||
struct timing_mon *tim;
|
||||
|
||||
if (enable) {
|
||||
safety_controller_report_timing(monitor);
|
||||
} else {
|
||||
for (i = 0; i < COUNT_OF(timings); i++) {
|
||||
tim = &timings[i];
|
||||
if (tim->monitor & monitor) {
|
||||
tim->enabled = false;
|
||||
}
|
||||
}
|
||||
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)
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
/** @} */
|
||||
|
@ -358,22 +358,10 @@ static shellmatta_retCode_t shell_cmd_safety_adc(const shellmatta_handle_t handl
|
||||
(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, "VREF:\t%8.2f\tmV\r\n", 2500.0f);
|
||||
shellmatta_printf(handle, "TEMP:\t%8.2f\tdeg. Celsius\r\n", 25.0f);
|
||||
|
||||
shellmatta_printf(handle, "Errors:\t%X", safety_adc_get_errors());
|
||||
|
||||
return SHELLMATTA_OK;
|
||||
}
|
||||
|
||||
static shellmatta_retCode_t shell_cmd_safety_adc_clear_error(const shellmatta_handle_t handle, const char *arguments,
|
||||
uint32_t length)
|
||||
{
|
||||
(void)length;
|
||||
(void)arguments;
|
||||
(void)handle;
|
||||
|
||||
safety_adc_clear_errors();
|
||||
shellmatta_printf(handle, "Errors:\t%X", 0);
|
||||
|
||||
return SHELLMATTA_OK;
|
||||
}
|
||||
@ -388,7 +376,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[14] = {
|
||||
{
|
||||
.cmd = "version",
|
||||
.cmdAlias = "ver",
|
||||
@ -499,17 +487,8 @@ static shellmatta_cmd_t cmd[15] = {
|
||||
.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,
|
||||
.next = NULL,
|
||||
},
|
||||
|
||||
};
|
||||
|
||||
shellmatta_handle_t shell_init(shellmatta_write_t write_func)
|
||||
|
Loading…
Reference in New Issue
Block a user