diff --git a/stm-firmware/digio.c b/stm-firmware/digio.c
index 10f7a85..a8c67e9 100644
--- a/stm-firmware/digio.c
+++ b/stm-firmware/digio.c
@@ -18,6 +18,11 @@
* If not, see .
*/
+/**
+ * @addtogroup digio
+ * @{
+ */
+
#include
#include
#include
@@ -119,7 +124,12 @@ int led_get(uint8_t num)
return ((LED_PORT->ODR & (1<SR = 0UL;
@@ -191,3 +217,5 @@ void TIM7_IRQHandler(void)
LOUDSPEAKER_PORT->ODR ^= (1<.
*/
+/**
+ * @defgroup main-cycle-counter Main Cycle Counter
+ * The main cycle counter is incremented after every loop run of the main loop in main.c
+ * @{
+ */
+
#ifndef __MAIN_CYCLE_COUNTER_H__
#define __MAIN_CYCLE_COUNTER_H__
#include
+/**
+ * @brief Initialize/Reset the main cycle counter to 0.
+ * This function can be called multiple times.
+ */
void main_cycle_counter_init(void);
+/**
+ * @brief Increment the main cycle counter by 1
+ */
void main_cycle_counter_inc(void);
+/**
+ * @brief Get the current main cycle counter value
+ * @return Value
+ */
uint64_t main_cycle_counter_get(void);
#endif /* __MAIN_CYCLE_COUNTER_H__ */
+
+/** @} */
diff --git a/stm-firmware/include/reflow-controller/oven-driver.h b/stm-firmware/include/reflow-controller/oven-driver.h
index b3d5367..fbbf345 100644
--- a/stm-firmware/include/reflow-controller/oven-driver.h
+++ b/stm-firmware/include/reflow-controller/oven-driver.h
@@ -21,32 +21,93 @@
#ifndef __OVEN_DRIVER_H__
#define __OVEN_DRIVER_H__
+/**
+ * @defgroup oven-driver Oven SSR Driver and PID Controller
+ * @{
+ */
+
#include
#include
#include
-enum oven_pid_status {OVEN_PID_DEACTIVATED,
- OVEN_PID_RUNNING,
- OVEN_PID_ABORTED};
+/**
+ * @brief Status of the PID controlling the oven
+ */
+enum oven_pid_status {
+ OVEN_PID_DEACTIVATED, /**< @brief The PID of the oven is deactivated. */
+ OVEN_PID_RUNNING, /**< @brief The PID of the oven is currently active and running. */
+ OVEN_PID_ABORTED, /**< @brief The PID of the oven has been aborted due to an error and is not running. */
+};
+/**
+ * @brief Initialize the oven driver.
+ *
+ * This will initialize the Timer for the PWM output to the SSR.
+ * If the hardware revision is >= v1.3 the SSR safety enable line will also be initialized.
+ */
void oven_driver_init(void);
+/**
+ * @brief Set a power level on the oven control output
+ * @param power Power level between 0 to 100
+ * @note This will not actually set the output. For this, @ref oven_driver_apply_power_level() has to be called.
+ * It will be called in the main loop.
+ */
void oven_driver_set_power(uint8_t power);
+/**
+ * @brief Disable the oven driver.
+ *
+ * This shuts down the oven driver timer and the corresponding clocks.
+ */
void oven_driver_disable(void);
+/**
+ * @brief Initialize the PID controller for the oven output
+ * @param PID controller holding the settings
+ */
void oven_pid_init(struct pid_controller *controller_to_copy);
+/**
+ * @brief Handle the PID controller.
+ * This must be called cyclically. When the sampling period has passed, the function will process the PT1000
+ * resistance and do a PID cycluilation for this sample.
+ * @note This function must be called with a frequency greater or equal to the PID's sampling frequency
+ */
void oven_pid_handle(void);
+/**
+ * @brief Stop the oven PID controller
+ */
void oven_pid_stop(void);
+/**
+ * @brief Abort the oven PID controller. This is the same as oven_pid_stop() but will set the abort flag.
+ * @note this function is called by the safety controller to disable the PID controller in case of an error.
+ */
void oven_pid_abort(void);
+/**
+ * @brief Set the target temperature of the PID controller.
+ * @param temp
+ */
void oven_pid_set_target_temperature(float temp);
+/**
+ * @brief Output the power level currently configured to the SSR.
+ *
+ * This function is separated from oven_driver_set_power() because it is called in the main loop after the
+ * safety controller has run. This ensures, that if the safety controller decides to stop the PID no glitch makes it
+ * out to the SSR.
+ */
void oven_driver_apply_power_level(void);
+/**
+ * @brief Get the current status of the oven's PID controller
+ * @return
+ */
enum oven_pid_status oven_pid_get_status(void);
+/** @} */
+
#endif /* __OVEN_DRIVER_H__ */
diff --git a/stm-firmware/main-cycle-counter.c b/stm-firmware/main-cycle-counter.c
index 07b4cac..bb0d4e8 100644
--- a/stm-firmware/main-cycle-counter.c
+++ b/stm-firmware/main-cycle-counter.c
@@ -18,9 +18,19 @@
* If not, see .
*/
+/**
+ * @addtogroup main-cycle-counter
+ * @{
+ */
+
#include
#include
+/**
+ * @brief Variable storing the main cycle counter.
+ * @note This variable should not be accessed directly.
+ * Use the main_cycle_counter_get() or main_cycle_counter_inc() functions.
+ */
static uint64_t IN_SECTION(.ccm.bss) main_cycle_counter;
void main_cycle_counter_init(void)
@@ -37,3 +47,5 @@ uint64_t main_cycle_counter_get(void)
{
return main_cycle_counter;
}
+
+/** @} */
diff --git a/stm-firmware/main.c b/stm-firmware/main.c
index efb8ad1..373c0b0 100644
--- a/stm-firmware/main.c
+++ b/stm-firmware/main.c
@@ -67,13 +67,13 @@ static void setup_nvic_priorities(void)
FATFS fs;
#define fs_ptr (&fs)
+/**
+ * @brief Configure UART GPIOs
+ * In case the application is build in debug mode, use the TX/RX Pins on the debug header
+ * else the Pins on the DIGIO header are configured in the digio module and this function does nothing.
+ */
static inline void uart_gpio_config(void)
{
- /*
- * In case the application is build in debug mode, use the TX/RX Pins on the debug header
- * else the Pins on the DIGIO header are configured in the digio module
- */
-
#if defined(DEBUGBUILD) || defined(UART_ON_DEBUG_HEADER)
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(SHELL_UART_PORT_RCC_MASK));
SHELL_UART_PORT->MODER &= MODER_DELETE(SHELL_UART_TX_PIN) & MODER_DELETE(SHELL_UART_RX_PIN);
@@ -86,9 +86,19 @@ static inline void uart_gpio_config(void)
#endif
}
-
+/**
+ * @brief TX buffer for the shell's uart
+ */
static char shell_uart_tx_buff[256];
+
+/**
+ * @brief RX buffer for the shell's uart
+ */
static char shell_uart_rx_buff[48];
+
+/**
+ * @brief The uart instance handling the shellmatta shell.
+ */
struct stm_uart shell_uart;
static shellmatta_retCode_t write_shell_callback(const char *data, uint32_t len)
@@ -97,6 +107,12 @@ static shellmatta_retCode_t write_shell_callback(const char *data, uint32_t len)
return SHELLMATTA_OK;
}
+/**
+ * @brief Configure the UART for the shellmatta shell.
+ *
+ * This will configure the UART for use with a DMA ring buffer.
+ * @param uart
+ */
static inline void setup_shell_uart(struct stm_uart *uart)
{
uart->rx = 1;
@@ -119,6 +135,11 @@ static inline void setup_shell_uart(struct stm_uart *uart)
NVIC_EnableIRQ(DMA2_Stream7_IRQn);
}
+/**
+ * @brief Mount the SD card if available and not already mounted
+ * @param mounted The current mounting state of the SD card
+ * @return true if mounted, false if an error occured or the SD is not inserted and cannot be mounted
+ */
static bool mount_sd_card_if_avail(bool mounted)
{
FRESULT res;
@@ -148,6 +169,13 @@ static bool mount_sd_card_if_avail(bool mounted)
return mounted;
}
+/**
+ * @brief Process the boot status structure in the safety (backup) RAM
+ * Depending on the flags set there, this function will:
+ * - Reboot into the ram code for reflashing
+ * - Display the PANIC message
+ * - Display if the flash has been successfully updated
+ */
static inline void handle_boot_status(void)
{
struct safety_memory_boot_status status;
@@ -183,34 +211,69 @@ static inline void handle_boot_status(void)
}
}
+/**
+ * @brief Setup the system.
+ *
+ * This function does all basic initializations of the MCU and its peripherals
+ */
static inline void setup_system(void)
{
float tmp;
+ /** - Setup the NVIC priorities of the core peripherals using interrupts */
setup_nvic_priorities();
- /* Init safety controller and safety memory */
+ /** - Init safety controller and safety memory */
safety_controller_init();
+ /** - Setup the systick module generating the 100us tick fort the GUI and
+ * the 1ms tick for the global systick timestamp
+ */
systick_setup();
+
+ /** - Initialize the oven output driver outputting the wavepacket control signal for the SSR and */
oven_driver_init();
+
+ /** - Initialize all DIGIO Pins to theri default state and pin functions */
digio_setup_default_all();
+
+ /** - Set-up the LED outputs */
led_setup();
+
+ /** - Set-up the loudspeaker / beeper output */
loudspeaker_setup();
+
+ /** - Initialize the GUI */
gui_init();
+
+ /** - Initialize the pins for the uart interface. */
uart_gpio_config();
+
+ /** - Set-up the settings module */
settings_setup();
- /* Load the overtemperature limit from eeprom if available. Otherwise the default value will be used */
+ /** - Load the overtemperature limit from eeprom if available. Otherwise the default value will be used */
if (settings_load_overtemp_limit(&tmp) == SETT_LOAD_SUCCESS)
safety_controller_set_overtemp_limit(tmp);
+ /** - Handle the boot status struct in the safety memory */
handle_boot_status();
+ /** - Initialize the shell UART */
setup_shell_uart(&shell_uart);
+
+ /** - Enable the ADC for PT1000 measurement */
adc_pt1000_setup_meas();
}
+/**
+ * @brief Handle the input for the shell instance.
+ *
+ * This function will check if the RX ring buffer of the UART contains data.
+ * If so, it will prowvide it to the shellmatta shell.
+ *
+ * @param shell_handle Handle to the shellmatta instance
+ */
static void handle_shell_uart_input(shellmatta_handle_t shell_handle)
{
int uart_receive_status;
@@ -223,6 +286,10 @@ static void handle_shell_uart_input(shellmatta_handle_t shell_handle)
shell_handle_input(shell_handle, uart_input, uart_input_len);
}
+/**
+ * @brief This is the main function containing the initilizations and the cyclic main loop
+ * @return Don't care. This function will never return. We're on an embedded device...
+ */
int main(void)
{
bool cal_active;
@@ -235,21 +302,30 @@ int main(void)
int menu_wait_request;
uint64_t quarter_sec_timestamp = 0ULL;
- /* Setup all the peripherals and external componets like LCD, EEPROM etc. and the safety controller */
+ /** - Setup all the peripherals and external componets like LCD, EEPROM etc. and the safety controller */
setup_system();
- /* Try load the calibration. This will only succeed if there's an EEPROM */
+ /** - Try load the calibration. This will only succeed if there's an EEPROM */
status = settings_load_calibration(&sens, &offset);
if (!status)
adc_pt1000_set_resistance_calibration(offset, sens, true);
+ /** - Initialize the shellmatta shell */
shell_handle = shell_init(write_shell_callback);
+
+ /** - Print motd to shell */
shell_print_motd(shell_handle);
+ /** - Set the main cycle counter to 0 */
main_cycle_counter_init();
+ /** - Do a loop over the following */
while (1) {
+ /** - If 250 ms have passed since the last time this step was reached, we try to initialize the
+ * SD card. If the card has been mounted and there is no current resistance calibration,
+ * it is tried to load it from SD card.
+ */
if (systick_ticks_have_passed(quarter_sec_timestamp, 250)) {
led_set(1, 0);
sd_old = sd_card_mounted;
@@ -267,29 +343,47 @@ int main(void)
quarter_sec_timestamp = systick_get_global_tick();
}
+ /** - Handle the GUI */
menu_wait_request = gui_handle();
+
+ /** - Handle the uart input for the shell */
handle_shell_uart_input(shell_handle);
- /* Execute current profile step, if a profile is active */
+ /** - Execute current profile step, if a profile is active */
temp_profile_executer_handle();
+ /** - Handle the safety controller. This must be called! Otherwise a watchdog reset will occur */
safety_controller_handle();
+
+ /** - If the Oven PID controller is running, we handle its sample function */
if (oven_pid_get_status() == OVEN_PID_RUNNING)
oven_pid_handle();
+ /** - Apply the power level of the oven driver */
oven_driver_apply_power_level();
+
+ /** - Report the main loop timing to the timing monitor to detect a slowed down main loop */
safety_controller_report_timing(ERR_TIMING_MAIN_LOOP);
+ /** - If the menu requests a directly following loop run, the main loop will continue.
+ * Otherwise it will wait for the next interrupt
+ */
if (menu_wait_request)
__WFI();
else
__NOP();
+ /** - Increment the main cycle counter */
main_cycle_counter_inc();
}
return 0;
}
+/**
+ * @brief Callback function for the SDIO driver to wait \p ms milliseconds
+ * @param ms
+ * @warning This function relies on the systick and must not be used in interrupt context.
+ */
void sdio_wait_ms(uint32_t ms)
{
systick_wait_ms(ms);
diff --git a/stm-firmware/oven-driver.c b/stm-firmware/oven-driver.c
index ec88817..79be403 100644
--- a/stm-firmware/oven-driver.c
+++ b/stm-firmware/oven-driver.c
@@ -18,6 +18,11 @@
* If not, see .
*/
+/**
+ * @addtogroup oven-driver
+ * @{
+ */
+
#include
#include
#include
@@ -28,13 +33,42 @@
#include
#include
+/**
+ * @brief PID ontroller instance of the oven driver
+ */
static struct pid_controller IN_SECTION(.ccm.bss) oven_pid;
+
+/**
+ * @brief Oven PID is currently running
+ */
static bool oven_pid_running;
+
+/**
+ * @brief Oven PID has been aborted / abnormally stopped.
+ */
static bool oven_pid_aborted;
+
+/**
+ * @brief Power level [0..100] of the oven to be applied
+ */
static uint8_t IN_SECTION(.ccm.bss) oven_driver_power_level;
+
+/**
+ * @brief Current target temperature of the oven PID controller in degC
+ */
static float IN_SECTION(.ccm.bss) target_temp;
+
+/**
+ * @brief The millisecond timestamp of the last run of the PID controller
+ */
static uint64_t IN_SECTION(.ccm.bss) timestamp_last_run;
+/**
+ * @brief Enable or disable the safety enable line of the oven control relay.
+ * @param enable
+ * @note This function is only working for hardware revisions >= v1.3. Below,
+ * the safety enable is unavailable.
+ */
static void ssr_safety_en(bool enable)
{
if (get_pcb_hardware_version() >= HW_REV_V1_3) {
@@ -165,3 +199,5 @@ enum oven_pid_status oven_pid_get_status(void)
return ret;
}
+
+/** @} */
diff --git a/stm-firmware/safety/fault.c b/stm-firmware/safety/fault.c
index 44af36a..17237f3 100644
--- a/stm-firmware/safety/fault.c
+++ b/stm-firmware/safety/fault.c
@@ -24,6 +24,12 @@
#include
#include
+/**
+ * @brief Handler for hard faults.
+ *
+ * This hard fault handler will turn of the oven output and go to panic mode.
+ * @note Depending on the fault condition some of the things done here could fail.
+ */
void HardFault_Handler(void)
{
/* This is a non recoverable fault. Stop the oven */
@@ -38,11 +44,26 @@ void HardFault_Handler(void)
}
/* Overwrite default handler. Go to panic mode */
+/**
+ * @brief Default interrupt handler. This will trigger a panic.
+ * @note This function should never be called during normal operation.
+ */
void __int_default_handler(void)
{
panic_mode();
}
+/**
+ * @brief Put the device into panic mode.
+ *
+ * This function can be used when a irrecoverable error is encountered.
+ * The function will:
+ * - Disable the oven output
+ * - Set the panic flag in the safety memory
+ * - Hang and wait for the watchdog to trigger a system reset.
+ *
+ * The panic state will be entered after the reset due to the set panic flag in the safety memory
+ */
void panic_mode(void)
{
/* This variable is static, because I don't want it to be on the stack */