8 Commits

18 changed files with 529 additions and 34 deletions

View File

@@ -18,6 +18,11 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup digio
* @{
*/
#include <reflow-controller/digio.h>
#include <stm32/stm32f4xx.h>
#include <stm-periph/rcc-manager.h>
@@ -119,7 +124,12 @@ int led_get(uint8_t num)
return ((LED_PORT->ODR & (1<<led_pins[num])) ? 1 : 0);
}
/**
* @brief Initialize the timer for the beeper to generate the output frequency
*
* TIM7 is used as the frequency generating timer. If @ref LOUDSPEAKER_MULTIFREQ
* is 0, the timer is unused and this function does nothing.
*/
static void loudspeaker_freq_timer_init(void)
{
#if LOUDSPEAKER_MULTIFREQ
@@ -143,6 +153,13 @@ void loudspeaker_setup(void)
loudspeaker_set(0U);
}
/**
* @brief Start the beeper
* @param val frequency value of the speaker in 'Timer relaod values'
* @note If @ref LOUDSPEAKER_MULTIFREQ isn't set,
* the speaker output will be set to high and no frequency is generated.
* The value of @p val is ignored in this case
*/
static void loudspeaker_start_beep(uint16_t val)
{
#if LOUDSPEAKER_MULTIFREQ
@@ -155,6 +172,9 @@ static void loudspeaker_start_beep(uint16_t val)
#endif
}
/**
* @brief Stop the beeping of the loudspeaker
*/
static void loudspeaker_stop_beep(void)
{
#if LOUDSPEAKER_MULTIFREQ
@@ -184,6 +204,12 @@ uint16_t loudspeaker_get(void)
}
#if LOUDSPEAKER_MULTIFREQ
/**
* @brief Timer7 IRQ Handler
*
* This IRQ Handler is used by the loudspeaker to synthesize the output frequency.
* If @ref LOUDSPEAKER_MULTIFREQ is 0, TIM7 and this interrupt will not be used.
*/
void TIM7_IRQHandler(void)
{
TIM7->SR = 0UL;
@@ -191,3 +217,5 @@ void TIM7_IRQHandler(void)
LOUDSPEAKER_PORT->ODR ^= (1<<LOUDSPEAKER_PIN);
}
#endif
/** @} */

View File

@@ -463,7 +463,7 @@ LOOKUP_CACHE_SIZE = 0
# DOT_NUM_THREADS setting.
# Minimum value: 0, maximum value: 32, default value: 1.
NUM_PROC_THREADS = 1
NUM_PROC_THREADS = 0
#---------------------------------------------------------------------------
# Build related configuration options
@@ -968,7 +968,8 @@ EXCLUDE = ../include/stm32 \
../linklist-lib/test \
../base64-lib/test \
../shellmatta/doc/main.dox \
../updater/ram-code
../updater/ram-code \
./
# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or
# directories that are symbolic links (a Unix file system feature) are excluded

View File

@@ -146,7 +146,7 @@ int led_get(uint8_t num);
#define LOUDSPEAKER_PIN 1
/**
* @brief The loudpseaker requires a frequncy signal instead of a simple on/off signal.
* @brief The loudpseaker requires a frequency signal instead of a simple on/off signal.
*/
#define LOUDSPEAKER_MULTIFREQ 1
@@ -162,7 +162,14 @@ void loudspeaker_setup(void);
/**
* @brief Set the loudspeaker value
* @param val Value
*
* Zero turns off the beeper. 1 is a special value
* and will set the @ref LOUDSPEAKER_MULTIFREQ_DEFAULT value.
*
* If @ref LOUDSPEAKER_MULTIFREQ is 0, then no actual frequency is produced.
* Instead any @p val unequal to zero turns the output pin high and 0 will turn it low.
*
* @param val Value.
*/
void loudspeaker_set(uint16_t val);

View File

@@ -18,15 +18,34 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @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 <stdint.h>
/**
* @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__ */
/** @} */

View File

@@ -21,32 +21,93 @@
#ifndef __OVEN_DRIVER_H__
#define __OVEN_DRIVER_H__
/**
* @defgroup oven-driver Oven SSR Driver and PID Controller
* @{
*/
#include <stdint.h>
#include <stdbool.h>
#include <reflow-controller/pid-controller.h>
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__ */

View File

@@ -122,12 +122,6 @@ enum analog_value_monitor {
*/
#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)

View File

@@ -0,0 +1,45 @@
/* 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.
*
* GDSII-Converter 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 _OPTION_BYTES_H_
#define _OPTION_BYTES_H_
#include <stdint.h>
struct option_bytes {
/* Word 1 */
uint32_t read_protection;// : 8;
uint32_t nrst_standby;// : 1;
uint32_t nrst_stop;// : 1;
uint32_t wdg_sw;// : 1;
uint32_t brown_out_level;// : 2;
/* Word 2 */
uint32_t nwrpi;// : 12;
};
/**
* @brief Read out the option bytes to structs
* @param opts
*/
void stm_option_bytes_read(struct option_bytes *opts);
int stm_option_bytes_program(const struct option_bytes *opts);
#endif /* _OPTION_BYTES_H_ */

View File

@@ -29,6 +29,8 @@
* @param mid mid word of ID
* @param low low word of ID
*/
void unique_id_get(uint32_t *high, uint32_t *mid, uint32_t *low);
void stm_unique_id_get(uint32_t *high, uint32_t *mid, uint32_t *low);
void stm_dev_rev_id_get(uint32_t *device_id, uint32_t *revision_id);
#endif /* __UNIQUE_ID_H__ */

View File

@@ -18,9 +18,19 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup main-cycle-counter
* @{
*/
#include <reflow-controller/main-cycle-counter.h>
#include <helper-macros/helper-macros.h>
/**
* @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;
}
/** @} */

View File

@@ -49,6 +49,7 @@
#include <reflow-controller/temp-profile/temp-profile-executer.h>
#include <reflow-controller/settings/spi-eeprom.h>
#include <reflow-controller/main-cycle-counter.h>
#include <stm-periph/option-bytes.h>
static void setup_nvic_priorities(void)
{
@@ -67,13 +68,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 +87,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 +108,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 +136,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 +170,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 +212,101 @@ static inline void handle_boot_status(void)
}
}
/**
* @brief Read out the option bytes of the STM32 and program them to the desired values.
*
* - This function currently forces the brown out level to Level 3.
*/
static void check_and_program_opt_bytes(void)
{
struct option_bytes opts;
int err;
/** - Read option bytes */
stm_option_bytes_read(&opts);
if (opts.brown_out_level != 0) {
/* Set the brown out level to level 3 => highest brown out limit. */
opts.brown_out_level = 0;
/** - Program the option bytes if brown out level was not set correctly */
err = stm_option_bytes_program(&opts);
/** - If programming failes, enter panic mode */
if (err)
panic_mode();
/** - If programming is successful, reset the system to apply new settings */
NVIC_SystemReset();
}
}
/**
* @brief Setup the system.
*
* This function does all basic initializations of the MCU and its peripherals
*/
static inline void setup_system(void)
{
float tmp;
/** - Read the option bytes and if necessary program them to the desired values */
check_and_program_opt_bytes();
/** - 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 +319,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 +335,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 +376,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);

View File

@@ -18,6 +18,11 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @addtogroup oven-driver
* @{
*/
#include <reflow-controller/oven-driver.h>
#include <reflow-controller/periph-config/oven-driver-hwcfg.h>
#include <stm-periph/rcc-manager.h>
@@ -28,13 +33,42 @@
#include <reflow-controller/safety/safety-controller.h>
#include <reflow-controller/hw-version-detect.h>
/**
* @brief PID controller 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;
}
/** @} */

View File

@@ -24,6 +24,12 @@
#include <reflow-controller/safety/safety-memory.h>
#include <helper-macros/helper-macros.h>
/**
* @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 */

View File

@@ -38,7 +38,7 @@ static void get_controller_folder_path(char *path, size_t size)
if (!path)
return;
unique_id_get(&high, &mid, &low);
stm_unique_id_get(&high, &mid, &low);
snprintf(path, size, "/%08X-%08X-%08X",
(unsigned int)high, (unsigned int)mid, (unsigned int)low);

View File

@@ -45,6 +45,8 @@
#include <reflow-controller/temp-profile/temp-profile-executer.h>
#include <reflow-controller/updater/updater.h>
#include <reflow-controller/main-cycle-counter.h>
#include <stm-periph/option-bytes.h>
#include <stdio.h>
#ifndef GIT_VER
@@ -64,10 +66,13 @@ static shellmatta_retCode_t shell_cmd_ver(const shellmatta_handle_t handle,
uint32_t low_id;
uint32_t mid_id;
uint32_t high_id;
uint32_t stm_rev_id;
uint32_t stm_dev_id;
const char *hw_rev_str;
enum hw_revision pcb_rev;
unique_id_get(&high_id, &mid_id, &low_id);
stm_unique_id_get(&high_id, &mid_id, &low_id);
stm_dev_rev_id_get(&stm_dev_id, &stm_rev_id);
shellmatta_printf(handle, "Reflow Oven Controller Firmware " xstr(GIT_VER) "\r\n"
"Compiled: " __DATE__ " at " __TIME__ "\r\n");
@@ -85,7 +90,10 @@ static shellmatta_retCode_t shell_cmd_ver(const shellmatta_handle_t handle,
hw_rev_str = "Hardware: Unknown Revision. You might have to update the firmware!";
break;
}
shellmatta_printf(handle, "%s", hw_rev_str);
shellmatta_printf(handle, "%s\r\n", hw_rev_str);
shellmatta_printf(handle, "STM Device ID: 0x%04X\r\n", stm_dev_id);
shellmatta_printf(handle, "STM Revision ID: 0x%04X\r\n", stm_rev_id);
return SHELLMATTA_OK;
}
@@ -877,6 +885,25 @@ shellmatta_retCode_t shell_cmd_filter_alpha(const shellmatta_handle_t handle, co
return SHELLMATTA_OK;
}
shellmatta_retCode_t shell_cmd_print_opt_bytes(const shellmatta_handle_t handle,
const char *args, uint32_t len)
{
(void)args;
(void)len;
struct option_bytes opts;
stm_option_bytes_read(&opts);
shellmatta_printf(handle, "Brown-out Level: 0x%x\r\n", opts.brown_out_level);
shellmatta_printf(handle, "nRST Standby: 0x%x\r\n", opts.nrst_standby);
shellmatta_printf(handle, "nRST Stop: 0x%x\r\n", opts.nrst_stop);
shellmatta_printf(handle, "Write Protection: 0x%x\r\n", opts.nwrpi);
shellmatta_printf(handle, "Read Protection: 0x%x\r\n", opts.read_protection);
shellmatta_printf(handle, "SW Watchdog: 0x%x\r\n", opts.wdg_sw);
return SHELLMATTA_OK;
}
//typedef struct shellmatta_cmd
//{
// char *cmd; /**< command name */
@@ -1070,6 +1097,14 @@ static shellmatta_cmd_t cmd[24] = {
.helpText = "Sets the filter constant",
.usageText = "filter-alpha <alpha>",
.cmdFct = shell_cmd_filter_alpha,
.next = &cmd[23],
},
{
.cmd = "print-option-bytes",
.cmdAlias = "opt-bytes",
.helpText = "Print the currently set option bytes of the STM32",
.usageText = "",
.cmdFct = shell_cmd_print_opt_bytes,
.next = NULL,
}
};

View File

@@ -0,0 +1,90 @@
/* Reflow Oven Controller
*
* Copyright (C) 2021 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/>.
*/
#include <stm-periph/option-bytes.h>
#include <stm32/stm32f4xx.h>
/**
* @brief First key for unlocking hte option byte write access
*/
#define FLASH_OPTION_KEY1 (0x08192A3BUL)
/**
* @brief Second key for unlocking hte option byte write access
*/
#define FLASH_OPTION_KEY2 (0x4C5D6E7FUL)
void stm_option_bytes_read(struct option_bytes *opts)
{
uint32_t opt_reg;
if (!opts)
return;
opt_reg = FLASH->OPTCR;
opts->brown_out_level = (opt_reg & FLASH_OPTCR_BOR_LEV) >> 2;
opts->nrst_standby = (opt_reg & FLASH_OPTCR_nRST_STDBY) >> 7;
opts->nrst_stop = (opt_reg & FLASH_OPTCR_nRST_STOP) >> 6;
opts->nwrpi = (opt_reg & FLASH_OPTCR_nWRP) >> 16;
opts->read_protection = (opt_reg & FLASH_OPTCR_RDP) >> 8;
opts->wdg_sw = (opt_reg & FLASH_OPTCR_WDG_SW) >> 5;
}
int stm_option_bytes_program(const struct option_bytes *opts)
{
uint32_t reg;
FLASH->OPTKEYR = FLASH_OPTION_KEY1;
FLASH->OPTKEYR = FLASH_OPTION_KEY2;
__DSB();
if (FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) {
/* Unlocking failed */
return -1;
}
reg = FLASH->OPTCR;
reg &= ~FLASH_OPTCR_BOR_LEV;
reg &= ~FLASH_OPTCR_nRST_STDBY;
reg &= ~FLASH_OPTCR_nRST_STOP;
reg &= ~FLASH_OPTCR_nWRP;
reg &= ~FLASH_OPTCR_RDP;
reg &= ~FLASH_OPTCR_WDG_SW;
reg |= (opts->brown_out_level << 2) & FLASH_OPTCR_BOR_LEV;
reg |= (opts->nrst_standby << 7) & FLASH_OPTCR_nRST_STDBY;
reg |= (opts->nrst_stop << 6) & FLASH_OPTCR_nRST_STOP;
reg |= (opts->nwrpi << 16) & FLASH_OPTCR_nWRP;
reg |= (opts->read_protection << 8) & FLASH_OPTCR_RDP;
reg |= (opts->wdg_sw << 5) & FLASH_OPTCR_WDG_SW;
while (FLASH->SR & FLASH_SR_BSY);
FLASH->OPTCR = reg;
FLASH->OPTCR |= FLASH_OPTCR_OPTSTRT;
__DSB();
while (FLASH->SR & FLASH_SR_BSY);
FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
__DSB();
return 0;
}

View File

@@ -19,12 +19,13 @@
*/
#include <stm-periph/unique-id.h>
#include <stm32/stm32f4xx.h>
#define LOW_WORD_ADDR (0x1FFF7A10UL)
#define MID_WORD_ADDR (LOW_WORD_ADDR+4U)
#define HIGH_WORD_ADDR (LOW_WORD_ADDR+8U)
void unique_id_get(uint32_t *high, uint32_t *mid, uint32_t *low)
void stm_unique_id_get(uint32_t *high, uint32_t *mid, uint32_t *low)
{
if (!high || !mid || !low)
return;
@@ -33,3 +34,12 @@ void unique_id_get(uint32_t *high, uint32_t *mid, uint32_t *low)
*mid = *((uint32_t *)MID_WORD_ADDR);
*high = *((uint32_t *)HIGH_WORD_ADDR);
}
void stm_dev_rev_id_get(uint32_t *device_id, uint32_t *revision_id)
{
if (device_id)
*device_id = DBGMCU->IDCODE & DBGMCU_IDCODE_DEV_ID;
if (revision_id)
*revision_id = (DBGMCU->IDCODE & DBGMCU_IDCODE_REV_ID) >> 16;
}

View File

@@ -53,6 +53,7 @@ void button_init()
enum button_state button_read_event()
{
uint64_t time_delta;
uint64_t activation_stmp;
enum button_state temp_state;
if (override_state != BUTTON_IDLE) {
@@ -66,7 +67,13 @@ enum button_state button_read_event()
int_state = BUTTON_IDLE;
return temp_state;
} else {
time_delta = systick_get_global_tick() - to_active_timestamp;
/* Unfortunately I don't jave a better idea for now to ensure,
* that to_active_timestamp is read atomically
*/
__disable_irq();
activation_stmp = to_active_timestamp;
__enable_irq();
time_delta = systick_get_global_tick() - activation_stmp;
if (time_delta >= BUTTON_LONG_ON_TIME_MS)
return BUTTON_LONG;
else if (time_delta >= BUTTON_SHORT_ON_TIME_MS)

View File

@@ -189,7 +189,7 @@ static void gui_menu_about(struct lcd_menu *menu, enum menu_entry_func_entry ent
if (last_page == 3)
break;
last_page = 3;
unique_id_get(&ser1, &ser2, &ser3);
stm_unique_id_get(&ser1, &ser2, &ser3);
menu_lcd_outputf(menu, 0, "Serial: %08X", ser1);
menu_lcd_outputf(menu, 1, " %08X", ser2);
@@ -791,7 +791,7 @@ static void gui_menu_root_entry(struct lcd_menu *menu, enum menu_entry_func_entr
}
}
int gui_handle()
int gui_handle(void)
{
int32_t rot_delta;
enum button_state button;
@@ -813,7 +813,7 @@ int gui_handle()
return 1;
}
void gui_init()
void gui_init(void)
{
rotary_encoder_setup();
button_init();