Merge branch 'dev' into error-mem-viewer
This commit is contained in:
commit
59ff842f56
2
doc/.gitignore
vendored
2
doc/.gitignore
vendored
@ -0,0 +1,2 @@
|
|||||||
|
build/*
|
||||||
|
venv
|
21
doc/make-with-virtualenv.sh
Executable file
21
doc/make-with-virtualenv.sh
Executable file
@ -0,0 +1,21 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
SOURCE="${BASH_SOURCE[0]}"
|
||||||
|
while [ -h "$SOURCE" ]; do # resolve $SOURCE until the file is no longer a symlink
|
||||||
|
DIR="$( cd -P "$( dirname "$SOURCE" )" >/dev/null 2>&1 && pwd )"
|
||||||
|
SOURCE="$(readlink "$SOURCE")"
|
||||||
|
[[ $SOURCE != /* ]] && SOURCE="$DIR/$SOURCE" # if $SOURCE was a relative symlink, we need to resolve it relative to the path where the symlink file was located
|
||||||
|
done
|
||||||
|
DIR="$( cd -P "$( dirname "$SOURCE" )" >/dev/null 2>&1 && pwd )"
|
||||||
|
|
||||||
|
cd "$DIR"
|
||||||
|
|
||||||
|
if [[ ! -d "venv" ]]; then
|
||||||
|
virtualenv venv
|
||||||
|
source ./venv/bin/activate
|
||||||
|
pip install -r requirements.txt
|
||||||
|
else
|
||||||
|
source ./venv/bin/activate
|
||||||
|
fi
|
||||||
|
|
||||||
|
make SPHINXBUILD='venv/bin/python venv/bin/sphinx-build' $@
|
32
doc/requirements.txt
Normal file
32
doc/requirements.txt
Normal file
@ -0,0 +1,32 @@
|
|||||||
|
alabaster==0.7.12
|
||||||
|
Babel==2.9.0
|
||||||
|
blockdiag==2.0.1
|
||||||
|
breathe==4.24.1
|
||||||
|
certifi==2020.11.8
|
||||||
|
chardet==3.0.4
|
||||||
|
docutils==0.16
|
||||||
|
funcparserlib==0.3.6
|
||||||
|
idna==2.10
|
||||||
|
imagesize==1.2.0
|
||||||
|
Jinja2==2.11.2
|
||||||
|
MarkupSafe==1.1.1
|
||||||
|
packaging==20.7
|
||||||
|
Pillow==8.0.1
|
||||||
|
Pygments==2.7.2
|
||||||
|
pyparsing==2.4.7
|
||||||
|
pytz==2020.4
|
||||||
|
requests==2.25.0
|
||||||
|
six==1.15.0
|
||||||
|
snowballstemmer==2.0.0
|
||||||
|
Sphinx==3.3.1
|
||||||
|
sphinx-rtd-theme==0.5.0
|
||||||
|
sphinxcontrib-applehelp==1.0.2
|
||||||
|
sphinxcontrib-blockdiag==2.0.0
|
||||||
|
sphinxcontrib-devhelp==1.0.2
|
||||||
|
sphinxcontrib-drawio==0.0.12
|
||||||
|
sphinxcontrib-htmlhelp==1.0.3
|
||||||
|
sphinxcontrib-jsmath==1.0.1
|
||||||
|
sphinxcontrib-qthelp==1.0.3
|
||||||
|
sphinxcontrib-serializinghtml==1.1.4
|
||||||
|
urllib3==1.26.2
|
||||||
|
webcolors==1.11.1
|
2
doc/source/.gitignore
vendored
Normal file
2
doc/source/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
|||||||
|
.drawio/*
|
||||||
|
.drawio
|
@ -13,6 +13,10 @@
|
|||||||
# TAG += value [value, ...]
|
# TAG += value [value, ...]
|
||||||
# Values that contain spaces should be placed between quotes (\" \").
|
# Values that contain spaces should be placed between quotes (\" \").
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#---------------------------------------------------------------------------
|
#---------------------------------------------------------------------------
|
||||||
# Project related configuration options
|
# Project related configuration options
|
||||||
#---------------------------------------------------------------------------
|
#---------------------------------------------------------------------------
|
||||||
@ -869,34 +873,7 @@ FILE_PATTERNS = *.c \
|
|||||||
*.hxx \
|
*.hxx \
|
||||||
*.hpp \
|
*.hpp \
|
||||||
*.h++ \
|
*.h++ \
|
||||||
*.cs \
|
*.dox
|
||||||
*.d \
|
|
||||||
*.php \
|
|
||||||
*.php4 \
|
|
||||||
*.php5 \
|
|
||||||
*.phtml \
|
|
||||||
*.inc \
|
|
||||||
*.m \
|
|
||||||
*.markdown \
|
|
||||||
*.md \
|
|
||||||
*.mm \
|
|
||||||
*.dox \
|
|
||||||
*.doc \
|
|
||||||
*.txt \
|
|
||||||
*.py \
|
|
||||||
*.pyw \
|
|
||||||
*.f90 \
|
|
||||||
*.f95 \
|
|
||||||
*.f03 \
|
|
||||||
*.f08 \
|
|
||||||
*.f18 \
|
|
||||||
*.f \
|
|
||||||
*.for \
|
|
||||||
*.vhd \
|
|
||||||
*.vhdl \
|
|
||||||
*.ucf \
|
|
||||||
*.qsf \
|
|
||||||
*.ice
|
|
||||||
|
|
||||||
# The RECURSIVE tag can be used to specify whether or not subdirectories should
|
# The RECURSIVE tag can be used to specify whether or not subdirectories should
|
||||||
# be searched for input files as well.
|
# be searched for input files as well.
|
||||||
@ -911,10 +888,7 @@ RECURSIVE = YES
|
|||||||
# Note that relative paths are relative to the directory from which doxygen is
|
# Note that relative paths are relative to the directory from which doxygen is
|
||||||
# run.
|
# run.
|
||||||
|
|
||||||
EXCLUDE = ../../stm-firmware/include/stm32 \
|
EXCLUDE =
|
||||||
../../stm-firmware/include/cmsis \
|
|
||||||
../../stm-firmware/shellmatta/test \
|
|
||||||
../../stm-firmware/shellmatta/example
|
|
||||||
|
|
||||||
# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or
|
# 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
|
# directories that are symbolic links (a Unix file system feature) are excluded
|
||||||
@ -930,7 +904,12 @@ EXCLUDE_SYMLINKS = NO
|
|||||||
# Note that the wildcards are matched against the file with absolute path, so to
|
# Note that the wildcards are matched against the file with absolute path, so to
|
||||||
# exclude all test directories for example use the pattern */test/*
|
# exclude all test directories for example use the pattern */test/*
|
||||||
|
|
||||||
EXCLUDE_PATTERNS =
|
EXCLUDE_PATTERNS = */include/stm32/* \
|
||||||
|
*/include/cmsis/* \
|
||||||
|
*/shellmatta/test/* \
|
||||||
|
*/shellmatta/example/* \
|
||||||
|
*/base64-lib/test/* \
|
||||||
|
*/updater/ram-code/*
|
||||||
|
|
||||||
# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names
|
# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names
|
||||||
# (namespaces, classes, functions, etc.) that should be excluded from the
|
# (namespaces, classes, functions, etc.) that should be excluded from the
|
||||||
|
@ -32,6 +32,7 @@ try:
|
|||||||
os.mkdir('../build/_doxygen')
|
os.mkdir('../build/_doxygen')
|
||||||
except FileExistsError:
|
except FileExistsError:
|
||||||
pass
|
pass
|
||||||
|
|
||||||
subprocess.call('doxygen Doxyfile.in', shell=True)
|
subprocess.call('doxygen Doxyfile.in', shell=True)
|
||||||
|
|
||||||
# -- General configuration ---------------------------------------------------
|
# -- General configuration ---------------------------------------------------
|
||||||
@ -44,6 +45,7 @@ extensions = [
|
|||||||
'sphinx.ext.autodoc',
|
'sphinx.ext.autodoc',
|
||||||
'sphinx.ext.todo',
|
'sphinx.ext.todo',
|
||||||
'sphinxcontrib.blockdiag',
|
'sphinxcontrib.blockdiag',
|
||||||
|
'sphinxcontrib.drawio',
|
||||||
'breathe'
|
'breathe'
|
||||||
]
|
]
|
||||||
|
|
||||||
|
@ -12,30 +12,7 @@ PT1000 Value Sampling
|
|||||||
|
|
||||||
The following block diagram shows the processing chain of the temperature signal.
|
The following block diagram shows the processing chain of the temperature signal.
|
||||||
|
|
||||||
.. blockdiag::
|
.. drawio-image:: pt1000.drawio
|
||||||
:desctable:
|
|
||||||
|
|
||||||
blockdiag {
|
|
||||||
orientation = portrait;
|
|
||||||
|
|
||||||
FRONTEND[description=":ref:`hw_analog_fe`", label="Frontend"];
|
|
||||||
ADC[description="`Analog to Digital Converter <ADC_>`_"];
|
|
||||||
WATCHDOG [label = "WDT", shape=endpoint, description="`Hardware Value Watchdog <Watchdog_>`_"];
|
|
||||||
PREFILTER [label=Prefilter, description="`Prefiltering and Downsampling <Prefilter_>`_"];
|
|
||||||
ADC2RES [label= "Val -> Ohm", description="`Conversion from ADC value to resistance in Ohms <ADC Value to Ohm_>`_"]
|
|
||||||
MAVG [label="MAVG Filter", description="`Exponential Moving Average Filter`_"];
|
|
||||||
RAW_HF [label="HF", shape = endpoint, description="High Frequency raw value reading"];
|
|
||||||
PT1000 [label = "LF", shape = endpoint, description="Low Frequency PT1000 resistance value (see: `MAVG Filter <Exponential Moving Average Filter_>`_)"]
|
|
||||||
RAW_STREAM [label = "Stream", shape = endpoint, description="Raw value streaming"];
|
|
||||||
|
|
||||||
FRONTEND -> ADC -> WATCHDOG;
|
|
||||||
ADC -> PREFILTER [label="1 kHz"];
|
|
||||||
PREFILTER -> ADC2RES [label="1/6 kHz"];
|
|
||||||
ADC2RES -> MAVG;
|
|
||||||
MAVG -> PT1000 [label="1/6 kHz"];
|
|
||||||
PREFILTER -> RAW_HF [label="1/6 kHz"];
|
|
||||||
PREFILTER -> RAW_STREAM [label="1/6 kHz"];
|
|
||||||
}
|
|
||||||
|
|
||||||
ADC
|
ADC
|
||||||
~~~
|
~~~
|
||||||
@ -110,9 +87,16 @@ and can be changed in code using
|
|||||||
|
|
||||||
.. doxygenfunction:: adc_pt1000_set_moving_average_filter_param
|
.. doxygenfunction:: adc_pt1000_set_moving_average_filter_param
|
||||||
|
|
||||||
After initial startup and after each change of the filter constant, the filter will set the :ref:`safety_flags_adc_unstable` flag for a defined sample count of:
|
The moving average filter is considered unstable, if the input to output difference is greater than
|
||||||
|
|
||||||
.. doxygendefine:: ADC_FILTER_STARTUP_CYCLES
|
.. doxygendefine:: ADC_PT1000_FILTER_UNSTABLE_DIFF
|
||||||
|
|
||||||
|
In this case, the :ref:`safety_flags_adc_unstable` flag will be set until the filter output converges within the range for at least
|
||||||
|
|
||||||
|
.. doxygendefine:: ADC_PT1000_FILTER_STABLE_SAMPLE_COUNT
|
||||||
|
|
||||||
|
samples.
|
||||||
|
If the input value keeps changing or oscillating, the error flag will be permanently set.
|
||||||
|
|
||||||
The moving average filter's output signal is the Low Frequency (LF) PT1000 resistance signal used for internal PT1000 measurements.
|
The moving average filter's output signal is the Low Frequency (LF) PT1000 resistance signal used for internal PT1000 measurements.
|
||||||
|
|
||||||
|
1
doc/source/firmware/pt1000.drawio
Normal file
1
doc/source/firmware/pt1000.drawio
Normal file
@ -0,0 +1 @@
|
|||||||
|
<mxfile host="Electron" modified="2021-01-26T21:12:06.071Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/14.1.8 Chrome/87.0.4280.88 Electron/11.1.1 Safari/537.36" etag="PrKjQ8DyGBUrBwv3aoCi" version="14.1.8" type="device"><diagram name="Page-1" id="099fd60b-425b-db50-ffb0-6b813814b670">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</diagram></mxfile>
|
5626
measurement-data/1000OhmSampling-v1.3.csv
Normal file
5626
measurement-data/1000OhmSampling-v1.3.csv
Normal file
File diff suppressed because it is too large
Load Diff
@ -384,6 +384,30 @@
|
|||||||
"plt.show()"
|
"plt.show()"
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"cell_type": "code",
|
||||||
|
"execution_count": null,
|
||||||
|
"metadata": {},
|
||||||
|
"outputs": [],
|
||||||
|
"source": [
|
||||||
|
"fig, axes = plt.subplots(nrows=1, ncols=2, sharex='col', figsize=(28, 8))\n",
|
||||||
|
"v12_df = pd.read_csv(r'hw-v12-1000Ohm.csv') \n",
|
||||||
|
"plot_histogram(axes[0], v12_df['pt1000_res_raw_lf'], 21, 'HW v1.2 1k Ohm Sampling', '1k Resistance')\n",
|
||||||
|
"plot_histogram(axes[1], v12_df['adc_pt1000_raw_reading_hf'], 21, 'HW v1.2 1k Ohm Sampling', '1k Resistance HF RAW')"
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"cell_type": "code",
|
||||||
|
"execution_count": null,
|
||||||
|
"metadata": {},
|
||||||
|
"outputs": [],
|
||||||
|
"source": [
|
||||||
|
"fig, axes = plt.subplots(nrows=1, ncols=2, sharex='col', figsize=(28, 8))\n",
|
||||||
|
"v13_df = pd.read_csv(r'1000OhmSampling-v1.3.csv') \n",
|
||||||
|
"plot_histogram(axes[0], v13_df['pt1000_res_raw_lf'], 21, 'HW v1.3 1k Ohm Sampling', '1k Resistance')\n",
|
||||||
|
"plot_histogram(axes[1], v13_df['adc_pt1000_raw_reading_hf'], 21, 'HW v1.3 1k Ohm Sampling', '1k Resistance')"
|
||||||
|
]
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"cell_type": "code",
|
"cell_type": "code",
|
||||||
"execution_count": null,
|
"execution_count": null,
|
||||||
@ -416,7 +440,7 @@
|
|||||||
"name": "python",
|
"name": "python",
|
||||||
"nbconvert_exporter": "python",
|
"nbconvert_exporter": "python",
|
||||||
"pygments_lexer": "ipython3",
|
"pygments_lexer": "ipython3",
|
||||||
"version": "3.8.2"
|
"version": "3.9.1"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"nbformat": 4,
|
"nbformat": 4,
|
||||||
|
5396
measurement-data/hw-v12-1000Ohm.csv
Normal file
5396
measurement-data/hw-v12-1000Ohm.csv
Normal file
File diff suppressed because it is too large
Load Diff
@ -34,22 +34,23 @@ INCLUDEPATH += -Ishellmatta/api
|
|||||||
DEFINES += -DSHELLMATTA_HELP_ALIAS=\"?\"
|
DEFINES += -DSHELLMATTA_HELP_ALIAS=\"?\"
|
||||||
|
|
||||||
# RCC Manager
|
# RCC Manager
|
||||||
CFILES += stm-periph/clock-enable-manager.c
|
CFILES += stm-periph/rcc-manager.c
|
||||||
CFILES += stm-periph/uart.c stm-periph/dma-ring-buffer.c stm-periph/backup-ram.c
|
CFILES += stm-periph/uart.c stm-periph/dma-ring-buffer.c stm-periph/backup-ram.c
|
||||||
CFILES += stm-periph/rng.c
|
CFILES += stm-periph/rng.c stm-periph/spi.c
|
||||||
CFILES += digio.c
|
CFILES += digio.c
|
||||||
CFILES += stm-periph/unique-id.c
|
CFILES += stm-periph/unique-id.c
|
||||||
CFILES += calibration.c
|
CFILES += calibration.c
|
||||||
CFILES += temp-converter.c
|
CFILES += temp-converter.c
|
||||||
CFILES += rotary-encoder.c button.c
|
CFILES += rotary-encoder.c button.c
|
||||||
CFILES += ui/lcd.c ui/menu.c reflow-menu.c
|
CFILES += ui/lcd.c ui/menu.c ui/gui.c
|
||||||
CFILES += fatfs/diskio.c fatfs/ff.c fatfs/ffsystem.c fatfs/ffunicode.c fatfs/shimatta_sdio_driver/shimatta_sdio.c
|
CFILES += fatfs/diskio.c fatfs/ff.c fatfs/ffsystem.c fatfs/ffunicode.c fatfs/shimatta_sdio_driver/shimatta_sdio.c
|
||||||
CFILES += pid-controller.c oven-driver.c
|
CFILES += pid-controller.c oven-driver.c
|
||||||
CFILES += settings/settings.c settings/settings-sd-card.c
|
CFILES += settings/settings.c settings/settings-sd-card.c settings/spi-eeprom.c settings/settings-eeprom.c
|
||||||
CFILES += stm-periph/crc-unit.c
|
CFILES += stm-periph/crc-unit.c
|
||||||
CFILES += safety/safety-adc.c safety/safety-controller.c safety/watchdog.c safety/fault.c safety/safety-memory.c safety/stack-check.c
|
CFILES += safety/safety-adc.c safety/safety-controller.c safety/watchdog.c safety/fault.c safety/safety-memory.c safety/stack-check.c
|
||||||
|
CFILES += hw-version-detect.c
|
||||||
CFILES += config-parser/config-parser.c
|
CFILES += config-parser/config-parser.c
|
||||||
|
CFILES += updater/updater.c
|
||||||
INCLUDEPATH += -Iconfig-parser/include
|
INCLUDEPATH += -Iconfig-parser/include
|
||||||
|
|
||||||
CFILES += base64-lib/src/base64-lib.c
|
CFILES += base64-lib/src/base64-lib.c
|
||||||
@ -123,6 +124,7 @@ debug:
|
|||||||
%.hex: %.elf
|
%.hex: %.elf
|
||||||
$(QUIET)$(OBJCOPY) -O ihex $^ $@
|
$(QUIET)$(OBJCOPY) -O ihex $^ $@
|
||||||
|
|
||||||
|
|
||||||
#Linking
|
#Linking
|
||||||
$(target).elf: $(OBJ) $(ASOBJ) $(LINKER_SCRIPT)
|
$(target).elf: $(OBJ) $(ASOBJ) $(LINKER_SCRIPT)
|
||||||
@echo [LD] $@
|
@echo [LD] $@
|
||||||
@ -130,6 +132,8 @@ $(target).elf: $(OBJ) $(ASOBJ) $(LINKER_SCRIPT)
|
|||||||
$(QUIET)$(SIZE) $@
|
$(QUIET)$(SIZE) $@
|
||||||
@echo "Built Version $(GIT_VER)"
|
@echo "Built Version $(GIT_VER)"
|
||||||
|
|
||||||
|
$(OBJDIR)/updater/updater.c.o: updater/ram-code/updater-ram-code.bin.h
|
||||||
|
|
||||||
#Compiling
|
#Compiling
|
||||||
$(OBJ):
|
$(OBJ):
|
||||||
@echo [CC] $@
|
@echo [CC] $@
|
||||||
@ -143,7 +147,10 @@ $(ASOBJ):
|
|||||||
$(QUIET)$(CC) $(CFLAGS) -MMD -MT $@ $(INCLUDEPATH) $(DEFINES) -o $@ $(@:$(OBJDIR)/%.S.o=%.S)
|
$(QUIET)$(CC) $(CFLAGS) -MMD -MT $@ $(INCLUDEPATH) $(DEFINES) -o $@ $(@:$(OBJDIR)/%.S.o=%.S)
|
||||||
|
|
||||||
|
|
||||||
.PHONY: qtproject-legacy qtproject qtproject-debug clean mrproper objcopy disassemble program program-debug
|
.PHONY: qtproject-legacy qtproject qtproject-debug clean mrproper objcopy disassemble program program-debug updater/ram-code/updater-ram-code.bin.h
|
||||||
|
|
||||||
|
updater/ram-code/updater-ram-code.bin.h:
|
||||||
|
$(QUIET)$(MAKE) -C updater/ram-code updater-ram-code.bin.h
|
||||||
|
|
||||||
program-debug:
|
program-debug:
|
||||||
$(QUIET)$(MAKE) DEBUGBUILD=true program
|
$(QUIET)$(MAKE) DEBUGBUILD=true program
|
||||||
@ -177,6 +184,7 @@ else
|
|||||||
endif
|
endif
|
||||||
$(QUIET)rm -f $(target).elf $(target).bin $(target).hex $(OBJ) $(ASOBJ) $(mapfile).map $(CFILES:%.c=$(OBJDIR)/%.c.d) $(ASFILES:%.S=$(OBJDIR)/%.S.d)
|
$(QUIET)rm -f $(target).elf $(target).bin $(target).hex $(OBJ) $(ASOBJ) $(mapfile).map $(CFILES:%.c=$(OBJDIR)/%.c.d) $(ASFILES:%.S=$(OBJDIR)/%.S.d)
|
||||||
$(QUIET)rm -rf $(OBJDIR)/*
|
$(QUIET)rm -rf $(OBJDIR)/*
|
||||||
|
$(MAKE) -C updater/ram-code clean
|
||||||
ifneq ($(DEBUGBUILD),true)
|
ifneq ($(DEBUGBUILD),true)
|
||||||
$(QUIET)$(MAKE) DEBUGBUILD=true clean
|
$(QUIET)$(MAKE) DEBUGBUILD=true clean
|
||||||
endif
|
endif
|
||||||
|
@ -29,7 +29,7 @@
|
|||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <reflow-controller/safety/safety-controller.h>
|
#include <reflow-controller/safety/safety-controller.h>
|
||||||
|
|
||||||
static float IN_SECTION(.ccm.bss) pt1000_offset;
|
static float IN_SECTION(.ccm.bss) pt1000_offset;
|
||||||
@ -45,7 +45,6 @@ static float IN_SECTION(.ccm.bss) filter_alpha;
|
|||||||
static volatile float IN_SECTION(.ccm.bss) pt1000_res_raw_lf;
|
static volatile float IN_SECTION(.ccm.bss) pt1000_res_raw_lf;
|
||||||
|
|
||||||
static volatile int * volatile streaming_flag_ptr;
|
static volatile int * volatile streaming_flag_ptr;
|
||||||
static uint32_t IN_SECTION(.ccm.bss) filter_startup_cnt;
|
|
||||||
static volatile float IN_SECTION(.ccm.bss) adc_pt1000_raw_reading_hf;
|
static volatile float IN_SECTION(.ccm.bss) adc_pt1000_raw_reading_hf;
|
||||||
static volatile uint16_t dma_sample_buffer[ADC_PT1000_DMA_AVG_SAMPLES];
|
static volatile uint16_t dma_sample_buffer[ADC_PT1000_DMA_AVG_SAMPLES];
|
||||||
static volatile uint32_t IN_SECTION(.ccm.bss) adc_watchdog_counter;
|
static volatile uint32_t IN_SECTION(.ccm.bss) adc_watchdog_counter;
|
||||||
@ -188,7 +187,6 @@ void adc_pt1000_set_moving_average_filter_param(float alpha)
|
|||||||
{
|
{
|
||||||
filter_alpha = alpha;
|
filter_alpha = alpha;
|
||||||
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
|
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
|
||||||
filter_startup_cnt = ADC_FILTER_STARTUP_CYCLES;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void adc_pt1000_set_resistance_calibration(float offset, float sensitivity_deviation, bool active)
|
void adc_pt1000_set_resistance_calibration(float offset, float sensitivity_deviation, bool active)
|
||||||
@ -303,14 +301,32 @@ void adc_pt1000_disable(void)
|
|||||||
|
|
||||||
static inline __attribute__((optimize("O3"))) void adc_pt1000_filter(float adc_prefiltered_value)
|
static inline __attribute__((optimize("O3"))) void adc_pt1000_filter(float adc_prefiltered_value)
|
||||||
{
|
{
|
||||||
if (filter_startup_cnt > 0) {
|
float alpha;
|
||||||
filter_startup_cnt--;
|
float res;
|
||||||
if (filter_startup_cnt == 0)
|
static uint8_t old_state = 0;
|
||||||
|
static uint32_t stable_sample_counter = 0;
|
||||||
|
|
||||||
|
res = ADC_TO_RES(adc_prefiltered_value);
|
||||||
|
if (ABS(res - pt1000_res_raw_lf) >= ADC_PT1000_FILTER_UNSTABLE_DIFF) {
|
||||||
|
stable_sample_counter = 0;
|
||||||
|
alpha = ADC_PT1000_FILTER_WEIGHT_FAST;
|
||||||
|
if (old_state != 1) {
|
||||||
|
safety_controller_report_error_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
|
||||||
|
old_state = 1;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
alpha = filter_alpha;
|
||||||
|
if (old_state != 2) {
|
||||||
|
stable_sample_counter++;
|
||||||
|
if (stable_sample_counter >= ADC_PT1000_FILTER_STABLE_SAMPLE_COUNT) {
|
||||||
safety_controller_ack_flag_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
|
safety_controller_ack_flag_with_key(ERR_FLAG_MEAS_ADC_UNSTABLE, MEAS_ADC_SAFETY_FLAG_KEY);
|
||||||
|
old_state = 2;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pt1000_res_raw_lf = (1.0f - filter_alpha) * pt1000_res_raw_lf +
|
pt1000_res_raw_lf = (1.0f - alpha) * pt1000_res_raw_lf +
|
||||||
filter_alpha * ADC_TO_RES(adc_prefiltered_value);
|
alpha * res;
|
||||||
|
|
||||||
safety_controller_report_timing(ERR_TIMING_MEAS_ADC);
|
safety_controller_report_timing(ERR_TIMING_MEAS_ADC);
|
||||||
}
|
}
|
||||||
@ -382,11 +398,11 @@ void DMA2_Stream0_IRQHandler(void)
|
|||||||
uint32_t lisr;
|
uint32_t lisr;
|
||||||
float adc_val;
|
float adc_val;
|
||||||
|
|
||||||
lisr = DMA2->LISR;
|
lisr = DMA2->LISR & (0x3F);
|
||||||
DMA2->LIFCR = lisr;
|
DMA2->LIFCR = lisr;
|
||||||
|
|
||||||
if (lisr & DMA_LISR_TCIF0) {
|
if (lisr & DMA_LISR_TCIF0) {
|
||||||
/* Samples Transfered */
|
/* Samples transferred */
|
||||||
adc_val = adc_pt1000_dma_avg_pre_filter();
|
adc_val = adc_pt1000_dma_avg_pre_filter();
|
||||||
adc_pt1000_raw_reading_hf = adc_val;
|
adc_pt1000_raw_reading_hf = adc_val;
|
||||||
|
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
#include <reflow-controller/button.h>
|
#include <reflow-controller/button.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <cmsis/core_cm4.h>
|
#include <cmsis/core_cm4.h>
|
||||||
|
@ -48,8 +48,6 @@ void calibration_calculate(float low_measured, float low_setpoint, float high_me
|
|||||||
*offset = (high_setpoint * low_measured - low_setpoint * high_measured) / (high_setpoint - low_setpoint);
|
*offset = (high_setpoint * low_measured - low_setpoint * high_measured) / (high_setpoint - low_setpoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
float *calibration_acquire_data_start(uint32_t count, volatile int *flag)
|
float *calibration_acquire_data_start(uint32_t count, volatile int *flag)
|
||||||
{
|
{
|
||||||
int status;
|
int status;
|
||||||
|
@ -188,4 +188,15 @@ enum config_parser_ret config_parser_close_file(config_parser_handle_t handle)
|
|||||||
return (res == FR_OK ? CONFIG_PARSER_OK : CONFIG_PARSER_IOERR);
|
return (res == FR_OK ? CONFIG_PARSER_OK : CONFIG_PARSER_IOERR);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool config_parser_ret_is_abort_condition(enum config_parser_ret return_val)
|
||||||
|
{
|
||||||
|
if (return_val == CONFIG_PARSER_END_REACHED ||
|
||||||
|
return_val == CONFIG_PARSER_GENERIC_ERR ||
|
||||||
|
return_val == CONFIG_PARSER_IOERR ||
|
||||||
|
return_val == CONFIG_PARSER_PARAM_ERR)
|
||||||
|
return true;
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
/** @} */
|
/** @} */
|
||||||
|
@ -90,6 +90,8 @@ enum config_parser_ret config_parser_write_entry(config_parser_handle_t handle,
|
|||||||
|
|
||||||
enum config_parser_ret config_parser_close_file(config_parser_handle_t handle);
|
enum config_parser_ret config_parser_close_file(config_parser_handle_t handle);
|
||||||
|
|
||||||
|
bool config_parser_ret_is_abort_condition(enum config_parser_ret return_val);
|
||||||
|
|
||||||
#endif /* _CONFIG_PARSER_H_ */
|
#endif /* _CONFIG_PARSER_H_ */
|
||||||
|
|
||||||
/** @} */
|
/** @} */
|
||||||
|
@ -20,7 +20,7 @@
|
|||||||
|
|
||||||
#include <reflow-controller/digio.h>
|
#include <reflow-controller/digio.h>
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
|
|
||||||
@ -146,7 +146,7 @@ void loudspeaker_setup(void)
|
|||||||
static void loudspeaker_start_beep(uint16_t val)
|
static void loudspeaker_start_beep(uint16_t val)
|
||||||
{
|
{
|
||||||
#if LOUDSPEAKER_MULTIFREQ
|
#if LOUDSPEAKER_MULTIFREQ
|
||||||
TIM7->ARR = val;
|
TIM7->ARR = (val == 1 ? LOUDSPEAKER_MULTIFREQ_DEFAULT : val);
|
||||||
TIM7->CNT = 0UL;
|
TIM7->CNT = 0UL;
|
||||||
TIM7->CR1 |= TIM_CR1_CEN;
|
TIM7->CR1 |= TIM_CR1_CEN;
|
||||||
#else
|
#else
|
||||||
|
@ -186,7 +186,7 @@ STRIP_FROM_INC_PATH =
|
|||||||
# support long names like on DOS, Mac, or CD-ROM.
|
# support long names like on DOS, Mac, or CD-ROM.
|
||||||
# The default value is: NO.
|
# The default value is: NO.
|
||||||
|
|
||||||
SHORT_NAMES = NO
|
SHORT_NAMES = YES
|
||||||
|
|
||||||
# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the
|
# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the
|
||||||
# first line (until the first dot) of a Javadoc-style comment as the brief
|
# first line (until the first dot) of a Javadoc-style comment as the brief
|
||||||
|
48
stm-firmware/hw-version-detect.c
Normal file
48
stm-firmware/hw-version-detect.c
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
|
#include <stm-periph/rcc-manager.h>
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
#define HW_REV_DETECT_GPIO GPIOE
|
||||||
|
#define HW_REV_DETECT_RCC_FIELD RCC_AHB1ENR_GPIOEEN
|
||||||
|
#define HW_REV_DETECT_PIN_LOW (8U)
|
||||||
|
#define HW_REV_DETECT_PIN_HIGH (15U)
|
||||||
|
|
||||||
|
enum hw_revision get_pcb_hardware_version(void)
|
||||||
|
{
|
||||||
|
uint8_t current_pin;
|
||||||
|
uint16_t port_bitmask = 0U;
|
||||||
|
static enum hw_revision revision = HW_REV_NOT_DETECTED;
|
||||||
|
|
||||||
|
if (revision != HW_REV_NOT_DETECTED)
|
||||||
|
return revision;
|
||||||
|
|
||||||
|
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(HW_REV_DETECT_RCC_FIELD));
|
||||||
|
|
||||||
|
/* Setup the pins as input with pull up */
|
||||||
|
for (current_pin = HW_REV_DETECT_PIN_LOW; current_pin <= HW_REV_DETECT_PIN_HIGH; current_pin++) {
|
||||||
|
HW_REV_DETECT_GPIO->MODER &= MODER_DELETE(current_pin);
|
||||||
|
HW_REV_DETECT_GPIO->PUPDR &= PUPDR_DELETE(current_pin);
|
||||||
|
HW_REV_DETECT_GPIO->PUPDR |= PULLUP(current_pin);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Loop again and read in the pin mask */
|
||||||
|
for (current_pin = HW_REV_DETECT_PIN_LOW; current_pin <= HW_REV_DETECT_PIN_HIGH; current_pin++) {
|
||||||
|
port_bitmask >>= 1;
|
||||||
|
port_bitmask |= (HW_REV_DETECT_GPIO->IDR & (1 << current_pin)) ? 0x0 : 0x80;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (port_bitmask) {
|
||||||
|
case 0U:
|
||||||
|
revision = HW_REV_V1_2;
|
||||||
|
break;
|
||||||
|
case 1U:
|
||||||
|
revision = HW_REV_V1_3;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
revision = HW_REV_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcc_manager_disable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(HW_REV_DETECT_RCC_FIELD));
|
||||||
|
|
||||||
|
return revision;
|
||||||
|
}
|
@ -38,6 +38,23 @@
|
|||||||
*/
|
*/
|
||||||
#define ADC_PT1000_FILTER_WEIGHT 0.005f
|
#define ADC_PT1000_FILTER_WEIGHT 0.005f
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Moving average filter weight used for fast regaulation. This is used when the measured resistance
|
||||||
|
* is more than 20 Ohms away from the current averaged value.
|
||||||
|
*/
|
||||||
|
#define ADC_PT1000_FILTER_WEIGHT_FAST 0.05
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Difference in Ohm between filter input and output that determines if the filter is stable or unstable.
|
||||||
|
*/
|
||||||
|
#define ADC_PT1000_FILTER_UNSTABLE_DIFF 10
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Sample count, the moving average filter has to be within @ref ADC_PT1000_FILTER_UNSTABLE_DIFF for the filter
|
||||||
|
* to be considered stable
|
||||||
|
*/
|
||||||
|
#define ADC_PT1000_FILTER_STABLE_SAMPLE_COUNT 200
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief ADC channel number of PT1000 sensor input
|
* @brief ADC channel number of PT1000 sensor input
|
||||||
*/
|
*/
|
||||||
@ -58,12 +75,6 @@
|
|||||||
*/
|
*/
|
||||||
#define ADC_PT1000_PIN 2U
|
#define ADC_PT1000_PIN 2U
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief The cycle count the moving average filter is labeled 'instable' after startup of the measurement or changing
|
|
||||||
* the alpha value @ref ADC_PT1000_FILTER_WEIGHT
|
|
||||||
*/
|
|
||||||
#define ADC_FILTER_STARTUP_CYCLES 800U
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief The delay value programmed into the sample timer
|
* @brief The delay value programmed into the sample timer
|
||||||
*/
|
*/
|
||||||
@ -99,6 +110,8 @@
|
|||||||
*/
|
*/
|
||||||
#define ADC_TO_RES(adc) ((float)(adc) / 4096.0f * 2500.0f)
|
#define ADC_TO_RES(adc) ((float)(adc) / 4096.0f * 2500.0f)
|
||||||
|
|
||||||
|
#define RES_TO_ADC(res) ((float)(res) / 2500.0f * 4096.0f)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function sets up the ADC measurement fo the external PT1000 temperature sensor
|
* @brief This function sets up the ADC measurement fo the external PT1000 temperature sensor
|
||||||
*
|
*
|
||||||
|
@ -59,6 +59,7 @@ int led_get(uint8_t num);
|
|||||||
#define LOUDSPEAKER_RCC_MASK RCC_AHB1ENR_GPIOBEN
|
#define LOUDSPEAKER_RCC_MASK RCC_AHB1ENR_GPIOBEN
|
||||||
#define LOUDSPEAKER_PIN 1
|
#define LOUDSPEAKER_PIN 1
|
||||||
#define LOUDSPEAKER_MULTIFREQ 1
|
#define LOUDSPEAKER_MULTIFREQ 1
|
||||||
|
#define LOUDSPEAKER_MULTIFREQ_DEFAULT 9
|
||||||
|
|
||||||
void loudspeaker_setup(void);
|
void loudspeaker_setup(void);
|
||||||
void loudspeaker_set(uint16_t val);
|
void loudspeaker_set(uint16_t val);
|
||||||
|
34
stm-firmware/include/reflow-controller/hw-version-detect.h
Normal file
34
stm-firmware/include/reflow-controller/hw-version-detect.h
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#ifndef _HW_VERSION_DETECT_H_
|
||||||
|
#define _HW_VERSION_DETECT_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief PCB/Hardware Revision Type
|
||||||
|
*/
|
||||||
|
enum hw_revision {
|
||||||
|
HW_REV_NOT_DETECTED = 0, /**< @brief The hardware has'nt been detected (yet) */
|
||||||
|
HW_REV_ERROR = 1, /**< @brief The hardware revision could not be detected due to an internal error */
|
||||||
|
HW_REV_V1_2 = 120, /**< @brief Hardware Revision v1.2 */
|
||||||
|
HW_REV_V1_3 = 130, /**< @brief Hardware Revision v1.3 */
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function returns the hardware version of the PCB.
|
||||||
|
*
|
||||||
|
* This is used to
|
||||||
|
* determine the feature set of the hardware. So this firmware can be used on all hardwares.
|
||||||
|
*
|
||||||
|
* The first hardware revision supported, is: v1.2
|
||||||
|
*
|
||||||
|
* The function returns the HW revision as an enum hw_revision.
|
||||||
|
* For v1.2 the return value is 120 (HW_REV_V1_2).
|
||||||
|
* For v1.3 the return value is 130 (HW_REV_V1_3).
|
||||||
|
*
|
||||||
|
* Other return values are not defined yet.
|
||||||
|
*
|
||||||
|
* @return Harware revision
|
||||||
|
*/
|
||||||
|
enum hw_revision get_pcb_hardware_version(void);
|
||||||
|
|
||||||
|
#endif /* _HW_VERSION_DETECT_H_ */
|
@ -39,12 +39,14 @@ void oven_pid_ack_errors(void);
|
|||||||
|
|
||||||
void oven_pid_init(struct pid_controller *controller_to_copy);
|
void oven_pid_init(struct pid_controller *controller_to_copy);
|
||||||
|
|
||||||
void oven_pid_handle(float target_temp);
|
void oven_pid_handle(void);
|
||||||
|
|
||||||
void oven_pid_stop(void);
|
void oven_pid_stop(void);
|
||||||
|
|
||||||
void oven_pid_abort(void);
|
void oven_pid_abort(void);
|
||||||
|
|
||||||
|
void oven_pid_set_target_temperature(float temp);
|
||||||
|
|
||||||
void oven_driver_apply_power_level(void);
|
void oven_driver_apply_power_level(void);
|
||||||
|
|
||||||
enum oven_pid_status oven_pid_get_status(void);
|
enum oven_pid_status oven_pid_get_status(void);
|
||||||
|
@ -18,16 +18,53 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file oven-driver-hwcfg.h
|
||||||
|
* @brief hardware configuration for oven PWM driver
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef __OVEN_DRIVER_HWCFG_H__
|
#ifndef __OVEN_DRIVER_HWCFG_H__
|
||||||
#define __OVEN_DRIVER_HWCFG_H__
|
#define __OVEN_DRIVER_HWCFG_H__
|
||||||
|
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Timer to use to generate PWM for oven
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_PWM_TIMER TIM3
|
#define OVEN_CONTROLLER_PWM_TIMER TIM3
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Port the oven control output is connected to
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_PORT GPIOB
|
#define OVEN_CONTROLLER_PORT GPIOB
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The Pin number the oven control output is located at
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_PIN (0)
|
#define OVEN_CONTROLLER_PIN (0)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The AHB1ENR Bitmask to enable the clock to the output port #OVEN_CONTROLLER_PORT
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_PORT_RCC_MASK RCC_AHB1ENR_GPIOBEN
|
#define OVEN_CONTROLLER_PORT_RCC_MASK RCC_AHB1ENR_GPIOBEN
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The APB1ENR bitmask to enable the #OVEN_CONTROLLER_PWM_TIMER
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_TIM_RCC_MASK RCC_APB1ENR_TIM3EN
|
#define OVEN_CONTROLLER_TIM_RCC_MASK RCC_APB1ENR_TIM3EN
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The alternate function #OVEN_CONTROLLER_PWM_TIMER's pwm output is located on #OVEN_CONTROLLER_PORT
|
||||||
|
*/
|
||||||
#define OVEN_CONTROLLER_PIN_ALTFUNC (2)
|
#define OVEN_CONTROLLER_PIN_ALTFUNC (2)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief GPIO Port for the safety enable line used by PCB versions > v1.3
|
||||||
|
*/
|
||||||
|
#define SSR_SAFETY_EN_PORT GPIOA
|
||||||
|
|
||||||
|
#define SSR_SAFETY_EN_PIN (3)
|
||||||
|
|
||||||
|
#define SSR_SAFETY_EN_PORT_RCC_MASK RCC_AHB1ENR_GPIOAEN
|
||||||
|
|
||||||
#endif /* __OVEN_DRIVER_HWCFG_H__ */
|
#endif /* __OVEN_DRIVER_HWCFG_H__ */
|
||||||
|
@ -21,18 +21,90 @@
|
|||||||
#ifndef __SAFETY_ADC_HWCFG_H__
|
#ifndef __SAFETY_ADC_HWCFG_H__
|
||||||
#define __SAFETY_ADC_HWCFG_H__
|
#define __SAFETY_ADC_HWCFG_H__
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file safety-adc-hwcfg.h
|
||||||
|
* @brief Safety ADC configuration settings
|
||||||
|
*/
|
||||||
|
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Peripheral to use as safety ADC.
|
||||||
|
* @note This must be ADC1, because it is the only ADC with access to the internal temperature sensor
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_ADC_PERIPHERAL ADC1
|
#define SAFETY_ADC_ADC_PERIPHERAL ADC1
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Clock enable mask in RCC->APB2ENR to enable the #SAFETY_ADC_ADC_PERIPHERAL
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_ADC_RCC_MASK RCC_APB2ENR_ADC1EN
|
#define SAFETY_ADC_ADC_RCC_MASK RCC_APB2ENR_ADC1EN
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief ADC channel number of the internal temperature sensor
|
||||||
|
*/
|
||||||
#define TEMP_CHANNEL_NUM (16)
|
#define TEMP_CHANNEL_NUM (16)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief ADC channel number of the internal reference voltage
|
||||||
|
*/
|
||||||
#define INT_REF_CHANNEL_NUM (17)
|
#define INT_REF_CHANNEL_NUM (17)
|
||||||
|
|
||||||
|
#define SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_CHANNEL_NUM (15)
|
||||||
|
#define SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PIN (5)
|
||||||
|
#define SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PORT GPIOC
|
||||||
|
#define SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PORT_RCC_MASK RCC_AHB1ENR_GPIOCEN
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Nominal value of the internal reference voltage.
|
||||||
|
*
|
||||||
|
* This is used to compare to the external reference voltage.
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_INT_REF_MV 1210.0f
|
#define SAFETY_ADC_INT_REF_MV 1210.0f
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Nominal temperature in degrees celsius of the internal temperature sensor at which it reads
|
||||||
|
* #SAFETY_ADC_TEMP_NOM_MV millivolts.
|
||||||
|
*
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_TEMP_NOM 25.0f
|
#define SAFETY_ADC_TEMP_NOM 25.0f
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Nominal internal temperature sensor voltage at temperature #SAFETY_ADC_TEMP_NOM
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_TEMP_NOM_MV 760.0f
|
#define SAFETY_ADC_TEMP_NOM_MV 760.0f
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Sensitivity of the internal temperature sensor in millivolts per Kelvin
|
||||||
|
*/
|
||||||
#define SAFETY_ADC_TEMP_MV_SLOPE 2.5f
|
#define SAFETY_ADC_TEMP_MV_SLOPE 2.5f
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Number of channels to handle for the SAFETY ADC.
|
||||||
|
* @note The maximum amount of channels is limited to 16
|
||||||
|
*/
|
||||||
|
#define SAFETY_ADC_NUM_OF_CHANNELS 12
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Channel numbers to sample with the SAFETY ADC
|
||||||
|
*
|
||||||
|
* - The first 4 values are the internal temperature sensor
|
||||||
|
* - The next 4 values are the internal reference voltage
|
||||||
|
*
|
||||||
|
* The values are samples 4 times each to allow averaging them to get
|
||||||
|
* more precise readings. Check the maximum value of #SAFETY_ADC_NUM_OF_CHANNELS
|
||||||
|
* when adding more channels.
|
||||||
|
* @warning Safety controller expects the current measurment list. If you change it, check @ref safety_controller_handle_safety_adc
|
||||||
|
*/
|
||||||
|
#define SAFETY_ADC_CHANNELS TEMP_CHANNEL_NUM, TEMP_CHANNEL_NUM, TEMP_CHANNEL_NUM, TEMP_CHANNEL_NUM, \
|
||||||
|
INT_REF_CHANNEL_NUM, INT_REF_CHANNEL_NUM, INT_REF_CHANNEL_NUM, INT_REF_CHANNEL_NUM, \
|
||||||
|
SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_CHANNEL_NUM, SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_CHANNEL_NUM, \
|
||||||
|
SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_CHANNEL_NUM, SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_CHANNEL_NUM
|
||||||
|
|
||||||
|
|
||||||
|
/* Check the channel count of the safety ADC */
|
||||||
|
#if SAFETY_ADC_NUM_OF_CHANNELS > 16 || SAFETY_ADC_NUM_OF_CHANNELS < 0
|
||||||
|
#error "Invlaid count of channels for safety ADC"
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif /* __SAFETY_ADC_HWCFG_H__ */
|
#endif /* __SAFETY_ADC_HWCFG_H__ */
|
||||||
|
@ -0,0 +1,36 @@
|
|||||||
|
/* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _SPI_EEPROM_HWCFG_H_
|
||||||
|
#define _SPI_EEPROM_HWCFG_H_
|
||||||
|
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
#define SPI_EEPROM_SPI_PORT GPIOA
|
||||||
|
#define SPI_EEPROM_SPI_PORT_RCC_REG RCC->AHB1ENR
|
||||||
|
#define SPI_EEPROM_SPI_PORT_RCC_MASK RCC_AHB1ENR_GPIOAEN
|
||||||
|
|
||||||
|
#define SPI_EEPROM_SPI_ALTFUNC_NO (5)
|
||||||
|
#define SPI_EEPROM_MISO_PIN (6)
|
||||||
|
#define SPI_EEPROM_MOSI_PIN (7)
|
||||||
|
#define SPI_EEPROM_SCK_PIN (5)
|
||||||
|
#define SPI_EEPROM_CS_PIN (4)
|
||||||
|
|
||||||
|
#endif /* _SPI_EEPROM_HWCFG_H_ */
|
@ -27,6 +27,7 @@ struct pid_controller {
|
|||||||
float k_p;
|
float k_p;
|
||||||
float k_int_t;
|
float k_int_t;
|
||||||
float k_deriv_t;
|
float k_deriv_t;
|
||||||
|
float k_inv_deriv_t;
|
||||||
float output_sat_max;
|
float output_sat_max;
|
||||||
float output_sat_min;
|
float output_sat_min;
|
||||||
float integral_max;
|
float integral_max;
|
||||||
@ -37,7 +38,8 @@ struct pid_controller {
|
|||||||
volatile float derivate;
|
volatile float derivate;
|
||||||
};
|
};
|
||||||
|
|
||||||
void pid_init(struct pid_controller *pid, float k_deriv, float k_int, float k_p, float output_sat_min, float output_sat_max, float integral_max, float sample_period);
|
void pid_init(struct pid_controller *pid, float k_deriv, float k_int, float k_p,
|
||||||
|
float output_sat_min, float output_sat_max, float integral_max, float kd_tau, float sample_period);
|
||||||
|
|
||||||
void pid_zero(struct pid_controller *pid);
|
void pid_zero(struct pid_controller *pid);
|
||||||
|
|
||||||
|
@ -29,23 +29,55 @@
|
|||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
enum safety_adc_meas_channel {SAFETY_ADC_MEAS_VREF, SAFETY_ADC_MEAS_TEMP};
|
/**
|
||||||
|
* @brief The safety ADC's measure channel
|
||||||
|
*/
|
||||||
|
enum safety_adc_meas_channel {
|
||||||
|
SAFETY_ADC_MEAS_VREF, /**< @brief Internal reference voltage @note This will not output the internal reference voltage but the recalculated external voltage! */
|
||||||
|
SAFETY_ADC_MEAS_TEMP, /**< @brief Internal temperature sensor */
|
||||||
|
SAFETY_ADC_MEAS_SUPPLY, /**< @brief Supply voltage */
|
||||||
|
};
|
||||||
|
|
||||||
void safety_adc_init();
|
/**
|
||||||
|
* @brief Initialize safety ADC. Only call this function once!
|
||||||
|
*/
|
||||||
|
void safety_adc_init(void);
|
||||||
|
|
||||||
void safety_adc_deinit();
|
/**
|
||||||
|
* @brief safety_adc_deinit Deactivate safety ADC
|
||||||
|
* @warning For completeness. Do not call! the safety ADC is a vital component. It's malfunction will trigger a critical safety flag.
|
||||||
|
*/
|
||||||
|
void safety_adc_deinit(void);
|
||||||
|
|
||||||
void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement);
|
/**
|
||||||
|
* @brief safety_adc_trigger_meas
|
||||||
|
*/
|
||||||
|
void safety_adc_trigger_meas(void);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Poll ADC result.
|
* @brief Poll ADC result.
|
||||||
* @param results adc results
|
|
||||||
* @return 1 if measurement successful, 0 if not ready, -1 if ADC aborted or not started
|
* @return 1 if measurement successful, 0 if not ready, -1 if ADC aborted or not started
|
||||||
*/
|
*/
|
||||||
int safety_adc_poll_result(uint16_t *adc_result);
|
int safety_adc_poll_result(void);
|
||||||
|
|
||||||
enum safety_adc_check_result handle_safety_adc();
|
/**
|
||||||
|
* @brief Get the sampled signal values of the safety ADC.
|
||||||
|
*
|
||||||
|
* Use #safety_adc_poll_result to poll for a finished conversion of the safety ADC.
|
||||||
|
* After that, it is safe to use the output values until a new conversion is triggered using #safety_adc_trigger_meas
|
||||||
|
*
|
||||||
|
* @warning This function return a constant buffer, that is directly written on by the DMA! Check #safety_adc_poll_result to prevent race conditions.
|
||||||
|
* @return Array of raw ADC readings with lenght of #SAFETY_ADC_NUM_OF_CHANNELS
|
||||||
|
*/
|
||||||
|
const uint16_t *safety_adc_get_values(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Convert a safety ADC raw value to an actual signal value
|
||||||
|
* @param channel Measurment channel to convert voltage for
|
||||||
|
* @param analog_value Raw value of the ADC to convert
|
||||||
|
* @warning Double check @ref safety_adc_meas_channel to make sure you understand the output of this function correctly.
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value);
|
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value);
|
||||||
|
|
||||||
#endif /* __SAFETY_ADC_H__ */
|
#endif /* __SAFETY_ADC_H__ */
|
||||||
|
@ -18,10 +18,23 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file safety-config.h
|
||||||
|
* @brief Safety Controller Configuration.
|
||||||
|
* @warning MAKE SURE XOU UNDERSTAND WHAT YOU ARE DOING IN HERE
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef __SAFETY_CONFIG_H__
|
#ifndef __SAFETY_CONFIG_H__
|
||||||
#define __SAFETY_CONFIG_H__
|
#define __SAFETY_CONFIG_H__
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Enum type representing safety flags.
|
||||||
|
*
|
||||||
|
* The enum type is binary or'able to allow combining
|
||||||
|
* multiple safety flags.
|
||||||
|
*
|
||||||
|
* @note For a more detailed explaination of the flags, check out the Sphinx documentation.
|
||||||
|
*/
|
||||||
enum safety_flag {
|
enum safety_flag {
|
||||||
ERR_FLAG_NO_FLAG = 0,
|
ERR_FLAG_NO_FLAG = 0,
|
||||||
ERR_FLAG_MEAS_ADC_OFF = (1<<0),
|
ERR_FLAG_MEAS_ADC_OFF = (1<<0),
|
||||||
@ -41,8 +54,15 @@ enum safety_flag {
|
|||||||
ERR_FLAG_TIMING_MAIN_LOOP = (1<<14),
|
ERR_FLAG_TIMING_MAIN_LOOP = (1<<14),
|
||||||
ERR_FLAG_SAFETY_MEM_CORRUPT = (1<<15),
|
ERR_FLAG_SAFETY_MEM_CORRUPT = (1<<15),
|
||||||
ERR_FLAG_SAFETY_TAB_CORRUPT = (1<<16),
|
ERR_FLAG_SAFETY_TAB_CORRUPT = (1<<16),
|
||||||
|
ERR_FLAG_AMON_SUPPLY_VOLT = (1<<17),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Enum Type representing timing monitors.
|
||||||
|
*
|
||||||
|
* The enum type is binary or'able to allow combining
|
||||||
|
* multiple safety flags.
|
||||||
|
*/
|
||||||
enum timing_monitor {
|
enum timing_monitor {
|
||||||
ERR_TIMING_PID = (1<<0),
|
ERR_TIMING_PID = (1<<0),
|
||||||
ERR_TIMING_MEAS_ADC = (1<<1),
|
ERR_TIMING_MEAS_ADC = (1<<1),
|
||||||
@ -50,16 +70,23 @@ enum timing_monitor {
|
|||||||
ERR_TIMING_MAIN_LOOP = (1<<3),
|
ERR_TIMING_MAIN_LOOP = (1<<3),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Enum Type representing analog value monitors.
|
||||||
|
*
|
||||||
|
* The enum type is binary or'able to allow combining
|
||||||
|
* multiple safety flags.
|
||||||
|
*/
|
||||||
enum analog_value_monitor {
|
enum analog_value_monitor {
|
||||||
ERR_AMON_VREF = (1<<0),
|
ERR_AMON_VREF = (1<<0),
|
||||||
ERR_AMON_UC_TEMP = (1<<1),
|
ERR_AMON_UC_TEMP = (1<<1),
|
||||||
|
ERR_AMON_SUPPLY_VOLT = (1<<2),
|
||||||
};
|
};
|
||||||
|
|
||||||
#define ERR_FLAG_ENTRY(errflag) {.name=#errflag, .flag = (errflag), .error_state = false, .error_state_inv = true, .key = 0UL, .weight = NULL, .persistency = NULL}
|
#define ERR_FLAG_ENTRY(errflag) {.name=#errflag, .flag = (errflag), .error_state = false, .error_state_inv = true, .key = 0UL, .weight = NULL, .persistence = NULL}
|
||||||
#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 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}
|
#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}
|
||||||
#define ERR_FLAG_WEIGHT_ENTRY(_flag, _weight) {.flag = (_flag), .flag_ptr = NULL, .weight = (_weight), .start_dummy = 0x11823344, .end_dummy = 0xAABBCCFD}
|
#define ERR_FLAG_WEIGHT_ENTRY(_flag, _weight) {.flag = (_flag), .flag_ptr = NULL, .weight = (_weight), .start_dummy = 0x11823344, .end_dummy = 0xAABBCCFD}
|
||||||
#define ERR_FLAG_PERSIST_ENTRY(_flag, _persist) {.flag = (_flag), .flag_ptr = NULL, .persistency = (_persist), .start_dummy = 0xFF1100BB, .end_dummy = 0xEBB439A2}
|
#define ERR_FLAG_PERSIST_ENTRY(_flag, _persist) {.flag = (_flag), .flag_ptr = NULL, .persistence = (_persist), .start_dummy = 0xFF1100BB, .end_dummy = 0xEBB439A2}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Magic key used to reset the watchdog using the @ref watchdog_ack function
|
* @brief Magic key used to reset the watchdog using the @ref watchdog_ack function
|
||||||
@ -94,14 +121,22 @@ enum analog_value_monitor {
|
|||||||
#define SAFETY_ADC_VREF_TOL_MVOLT (100.0f)
|
#define SAFETY_ADC_VREF_TOL_MVOLT (100.0f)
|
||||||
#define SAFETY_ADC_TEMP_LOW_LIM (0.0f)
|
#define SAFETY_ADC_TEMP_LOW_LIM (0.0f)
|
||||||
#define SAFETY_ADC_TEMP_HIGH_LIM (65.0f)
|
#define SAFETY_ADC_TEMP_HIGH_LIM (65.0f)
|
||||||
|
#define SAFETY_ADC_SUPPLY_MVOLT (3300.0f)
|
||||||
|
#define SAFETY_ADC_SUPPLY_TOL_MVOLT (150.0f)
|
||||||
|
|
||||||
|
#define SAFETY_EXT_WATCHDOG_PORT GPIOD
|
||||||
|
#define SAFETY_EXT_WATCHDOG_RCC_MASK RCC_AHB1ENR_GPIODEN
|
||||||
|
#define SAFETY_EXT_WATCHDOG_PIN (12)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Key used to lock the safety flags from external ack'ing
|
* @brief Key used to lock the safety flags coming from the measurment ADC from external ack'ing
|
||||||
*/
|
*/
|
||||||
#define MEAS_ADC_SAFETY_FLAG_KEY 0xe554dac3UL
|
#define MEAS_ADC_SAFETY_FLAG_KEY 0xe554dac3UL
|
||||||
|
|
||||||
#define SAFETY_CONTROLLER_ADC_DELAY_MS 120
|
/**
|
||||||
|
* @brief Safety ADC trigger interval
|
||||||
|
*/
|
||||||
|
#define SAFETY_CONTROLLER_ADC_DELAY_MS 250
|
||||||
|
|
||||||
#define SAFETY_CONFIG_DEFAULT_PERSIST ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_MEAS_ADC_OFF, false), \
|
#define SAFETY_CONFIG_DEFAULT_PERSIST ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_MEAS_ADC_OFF, false), \
|
||||||
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG, false), \
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG, false), \
|
||||||
@ -119,7 +154,8 @@ enum analog_value_monitor {
|
|||||||
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_DEBUG, true), \
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_DEBUG, true), \
|
||||||
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP, true), \
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP, true), \
|
||||||
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT, true), \
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT, true), \
|
||||||
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT, true),
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT, true), \
|
||||||
|
ERR_FLAG_PERSIST_ENTRY(ERR_FLAG_AMON_SUPPLY_VOLT, false), \
|
||||||
|
|
||||||
#define SAFETY_CONFIG_DEFAULT_WEIGHTS ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_MEAS_ADC_OFF, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
#define SAFETY_CONFIG_DEFAULT_WEIGHTS ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_MEAS_ADC_OFF, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
||||||
@ -132,13 +168,14 @@ enum analog_value_monitor {
|
|||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_STACK, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_STACK, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_ADC, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_ADC, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SYSTICK, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SYSTICK, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
||||||
/* Watchdog timeout is not handled perioodically, but only on startup.
|
/* Watchdog timeout is not handled periodically, but only on startup.
|
||||||
* Therefore, it is not listed here */\
|
* Therefore, it is not listed here */\
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_WTCHDG_FIRED, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_WTCHDG_FIRED, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_UNCAL, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_UNCAL, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_DEBUG, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_DEBUG, SAFETY_FLAG_CONFIG_WEIGHT_NONE), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
||||||
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT, SAFETY_FLAG_CONFIG_WEIGHT_PANIC),
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT, SAFETY_FLAG_CONFIG_WEIGHT_PANIC), \
|
||||||
|
ERR_FLAG_WEIGHT_ENTRY(ERR_FLAG_AMON_SUPPLY_VOLT, SAFETY_FLAG_CONFIG_WEIGHT_PID), \
|
||||||
|
|
||||||
#endif /* __SAFETY_CONFIG_H__ */
|
#endif /* __SAFETY_CONFIG_H__ */
|
||||||
|
@ -48,6 +48,7 @@ struct analog_monitor_info {
|
|||||||
float min; /**< @brief Minumum value allowed */
|
float min; /**< @brief Minumum value allowed */
|
||||||
float max; /**< @brief Maximum value allowed */
|
float max; /**< @brief Maximum value allowed */
|
||||||
enum analog_monitor_status status; /**< @brief Current monitor status */
|
enum analog_monitor_status status; /**< @brief Current monitor status */
|
||||||
|
enum safety_flag associated_flag; /**< @brief Associated safety flag, that will be set, if monitor out of range */
|
||||||
uint64_t timestamp; /**< @brief ms timestamp when @ref analog_monitor_info::value was taken. */
|
uint64_t timestamp; /**< @brief ms timestamp when @ref analog_monitor_info::value was taken. */
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -23,6 +23,7 @@
|
|||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
/** @addtogroup safety-memory
|
/** @addtogroup safety-memory
|
||||||
* @{
|
* @{
|
||||||
@ -119,7 +120,7 @@ struct error_memory_entry {
|
|||||||
*/
|
*/
|
||||||
enum config_override_entry_type {
|
enum config_override_entry_type {
|
||||||
SAFETY_MEMORY_CONFIG_OVERRIDE_WEIGHT = 1,
|
SAFETY_MEMORY_CONFIG_OVERRIDE_WEIGHT = 1,
|
||||||
SAFETY_MEMORY_CONFIG_OVERRIDE_PERSISTANCE = 2,
|
SAFETY_MEMORY_CONFIG_OVERRIDE_PERSISTENCE = 2,
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -143,7 +144,7 @@ struct config_override {
|
|||||||
} weight_override;
|
} weight_override;
|
||||||
struct {
|
struct {
|
||||||
uint8_t flag;
|
uint8_t flag;
|
||||||
uint8_t persistance;
|
bool persistance;
|
||||||
} persistance_override;
|
} persistance_override;
|
||||||
} entry;
|
} entry;
|
||||||
};
|
};
|
||||||
|
@ -40,11 +40,4 @@ int watchdog_setup(uint8_t prescaler);
|
|||||||
*/
|
*/
|
||||||
int watchdog_ack(uint32_t magic);
|
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 return false when called a second time
|
|
||||||
* @return true, if reset was generated by the watchdog
|
|
||||||
*/
|
|
||||||
bool watchdog_check_reset_source(void);
|
|
||||||
|
|
||||||
#endif /* __WATCHDOG_H__ */
|
#endif /* __WATCHDOG_H__ */
|
||||||
|
@ -0,0 +1,32 @@
|
|||||||
|
/* 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 __SETTINGS_SETTINGS_EEPROM_H__
|
||||||
|
#define __SETTINGS_SETTINGS_EEPROM_H__
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
bool settings_eeprom_detect_and_prepare(void);
|
||||||
|
|
||||||
|
int settings_eeprom_save_calibration(float sens, float offset, bool active);
|
||||||
|
|
||||||
|
int settings_eeprom_load_calibration(float *sens, float *offset, bool *active);
|
||||||
|
|
||||||
|
#endif /* __SETTINGS_SETTINGS_EEPROM_H__ */
|
@ -28,6 +28,7 @@ struct oven_pid_settings {
|
|||||||
float kd;
|
float kd;
|
||||||
float kp;
|
float kp;
|
||||||
float ki;
|
float ki;
|
||||||
|
float kd_tau;
|
||||||
float t_sample;
|
float t_sample;
|
||||||
float max_integral;
|
float max_integral;
|
||||||
};
|
};
|
||||||
@ -53,4 +54,6 @@ int settings_load_calibration(float *sens_dev, float *offset);
|
|||||||
|
|
||||||
enum settings_load_result settings_load_pid_oven_parameters(struct oven_pid_settings *settings);
|
enum settings_load_result settings_load_pid_oven_parameters(struct oven_pid_settings *settings);
|
||||||
|
|
||||||
|
void settings_setup(void);
|
||||||
|
|
||||||
#endif /* __SETTINGS_SETTINGS_H__ */
|
#endif /* __SETTINGS_SETTINGS_H__ */
|
||||||
|
42
stm-firmware/include/reflow-controller/settings/spi-eeprom.h
Normal file
42
stm-firmware/include/reflow-controller/settings/spi-eeprom.h
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
/* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __SETTINGS_SPI_EEPROM_H__
|
||||||
|
#define __SETTINGS_SPI_EEPROM_H__
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
|
||||||
|
int spi_eeprom_init();
|
||||||
|
|
||||||
|
void spi_eeprom_deinit();
|
||||||
|
|
||||||
|
int spi_eeprom_read(uint32_t addr, uint8_t *rx_buff, uint32_t count);
|
||||||
|
|
||||||
|
bool spi_eeprom_write_in_progress(void);
|
||||||
|
|
||||||
|
int spi_eeprom_write(uint32_t addr, const uint8_t *data, uint32_t count);
|
||||||
|
|
||||||
|
uint8_t spi_eeprom_read_status_reg(void);
|
||||||
|
|
||||||
|
bool spi_eeprom_check_connected(void);
|
||||||
|
|
||||||
|
#endif /* __SETTINGS_SPI_EEPROM_H__ */
|
7
stm-firmware/include/reflow-controller/ui/gui-config.h
Normal file
7
stm-firmware/include/reflow-controller/ui/gui-config.h
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
#ifndef _GUI_CONFIG_H_
|
||||||
|
#define _GUI_CONFIG_H_
|
||||||
|
|
||||||
|
#define GUI_MONITORING_INTERVAL_MS 500U
|
||||||
|
#define GUI_TEMP_DRIVER_REFRESH_MS 750U
|
||||||
|
|
||||||
|
#endif /* _GUI_CONFIG_H_ */
|
@ -18,15 +18,15 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef __REFLOW_MENU_H__
|
#ifndef _GUI_H_
|
||||||
#define __REFLOW_MENU_H__
|
#define _GUI_H_
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Handle the reflow controller's LCD Menu
|
* @brief Handle the reflow controller's LCD Menu
|
||||||
* @return 0 if no delay is requested, 1 if delay is requested
|
* @return 0 if no delay is requested, 1 if delay is requested
|
||||||
*/
|
*/
|
||||||
int reflow_menu_handle(void);
|
int gui_handle(void);
|
||||||
|
|
||||||
void reflow_menu_init(void);
|
void gui_init(void);
|
||||||
|
|
||||||
#endif /* __REFLOW_MENU_H__ */
|
#endif /* _GUI_H_ */
|
31
stm-firmware/include/reflow-controller/updater/updater.h
Normal file
31
stm-firmware/include/reflow-controller/updater/updater.h
Normal file
@ -0,0 +1,31 @@
|
|||||||
|
/* 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 __UPDATER_UPDATER_H__
|
||||||
|
#define __UPDATER_UPDATER_H__
|
||||||
|
|
||||||
|
#define UPDATER_RAM_CODE_BASE_ADDRESS (0x20000000UL)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Start the RAM Code of the updater. This function will never return!
|
||||||
|
*/
|
||||||
|
void __attribute__((noreturn)) start_updater(void);
|
||||||
|
|
||||||
|
#endif /* __UPDATER_UPDATER_H__ */
|
@ -18,11 +18,12 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef __CLOCK_ENABLE_MANAGER_H__
|
#ifndef __RCC_MANAGER_H__
|
||||||
#define __CLOCK_ENABLE_MANAGER_H__
|
#define __RCC_MANAGER_H__
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief The RCC Enable Manager uses static memory with a fixed maximum
|
* @brief The RCC Enable Manager uses static memory with a fixed maximum
|
||||||
@ -35,6 +36,19 @@
|
|||||||
#error "RCC Enable Manager not yet implemented with dynamic memory"
|
#error "RCC Enable Manager not yet implemented with dynamic memory"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The source/cause of a system reset. The values can be or'ed together as multiple flags may be possible at the same time.
|
||||||
|
*/
|
||||||
|
enum rcc_reset_source {
|
||||||
|
RCC_RESET_SOURCE_LOW_POWER = (1<<0), /**< @brief System reset caused by low power reset */
|
||||||
|
RCC_RESET_SOURCE_SOFTWARE = (1<<1), /**< @brief System reset caused by software */
|
||||||
|
RCC_RESET_SOURCE_WWD = (1<<2), /**< @brief System reset caused by window watchdog */
|
||||||
|
RCC_RESET_SOURCE_IWDG = (1<<3), /**< @brief System reset caused by independent watchdog */
|
||||||
|
RCC_RESET_SOURCE_POWER_ON = (1<<4), /**< @brief System reset caused by power on reset (POR) */
|
||||||
|
RCC_RESET_SOURCE_PIN = (1<<5), /**< @brief System reset caused by NRST pin */
|
||||||
|
RCC_RESET_BOR_POR = (1<<6), /**< @brief System reset caused by eitehr brown out or POR */
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Enable Clock for peripheral by setting the corresponding bit (@p bit_no) to one
|
* @brief Enable Clock for peripheral by setting the corresponding bit (@p bit_no) to one
|
||||||
*
|
*
|
||||||
@ -64,4 +78,11 @@ 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);
|
int rcc_manager_disable_clock(volatile uint32_t *rcc_enable_register, uint8_t bit_no);
|
||||||
|
|
||||||
#endif /* __CLOCK_ENABLE_MANAGER_H__ */
|
/**
|
||||||
|
* @brief Get the causes of the last system reset.
|
||||||
|
* @param clear_flags Clear the reset cause
|
||||||
|
* @return Reset cause
|
||||||
|
*/
|
||||||
|
enum rcc_reset_source rcc_manager_get_reset_cause(bool clear_flags);
|
||||||
|
|
||||||
|
#endif /* __RCC_MANAGER_H__ */
|
62
stm-firmware/include/stm-periph/spi.h
Normal file
62
stm-firmware/include/stm-periph/spi.h
Normal file
@ -0,0 +1,62 @@
|
|||||||
|
/* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __SPI_H__
|
||||||
|
#define __SPI_H__
|
||||||
|
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
enum stm_spi_prescaler {
|
||||||
|
SPI_PRSC_DIV2 = 0,
|
||||||
|
SPI_PRSC_DIV4 = 1,
|
||||||
|
SPI_PRSC_DIV8 = 2,
|
||||||
|
SPI_PRSC_DIV16 = 3,
|
||||||
|
SPI_PRSC_DIV32 = 4,
|
||||||
|
SPI_PRSC_DIV64 = 5,
|
||||||
|
SPI_PRSC_DIV128 = 6,
|
||||||
|
SPI_PRSC_DIV256 = 7,
|
||||||
|
};
|
||||||
|
|
||||||
|
struct stm_spi_settings {
|
||||||
|
void (*cs_activate)(void);
|
||||||
|
void (*cs_deactivate)(void);
|
||||||
|
bool cpol;
|
||||||
|
bool cpha;
|
||||||
|
bool master;
|
||||||
|
bool msb_first;
|
||||||
|
enum stm_spi_prescaler prescaler;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct stm_spi_dev {
|
||||||
|
uint32_t magic;
|
||||||
|
SPI_TypeDef *spi_regs;
|
||||||
|
struct stm_spi_settings settings;
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef void * stm_spi_handle;
|
||||||
|
|
||||||
|
stm_spi_handle spi_init(struct stm_spi_dev *spi_dev_struct, SPI_TypeDef *spi_regs, const struct stm_spi_settings *settings);
|
||||||
|
|
||||||
|
void spi_deinit(stm_spi_handle handle);
|
||||||
|
|
||||||
|
int spi_transfer(stm_spi_handle handle, const uint8_t *tx, uint8_t *rx, uint32_t count, bool handle_cs);
|
||||||
|
|
||||||
|
#endif /* __SPI_H__ */
|
@ -35,14 +35,19 @@
|
|||||||
#include <reflow-controller/digio.h>
|
#include <reflow-controller/digio.h>
|
||||||
#include "fatfs/shimatta_sdio_driver/shimatta_sdio.h"
|
#include "fatfs/shimatta_sdio_driver/shimatta_sdio.h"
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm-periph/uart.h>
|
#include <stm-periph/uart.h>
|
||||||
#include <reflow-controller/shell-uart-config.h>
|
#include <reflow-controller/shell-uart-config.h>
|
||||||
#include <reflow-controller/oven-driver.h>
|
#include <reflow-controller/oven-driver.h>
|
||||||
#include <fatfs/ff.h>
|
#include <fatfs/ff.h>
|
||||||
#include <reflow-controller/reflow-menu.h>
|
#include <reflow-controller/ui/gui.h>
|
||||||
#include <reflow-controller/safety/safety-controller.h>
|
#include <reflow-controller/safety/safety-controller.h>
|
||||||
#include <reflow-controller/settings/settings.h>
|
#include <reflow-controller/settings/settings.h>
|
||||||
|
#include <reflow-controller/safety/safety-memory.h>
|
||||||
|
#include <reflow-controller/safety/fault.h>
|
||||||
|
#include <reflow-controller/updater/updater.h>
|
||||||
|
|
||||||
|
#include <reflow-controller/settings/spi-eeprom.h>
|
||||||
|
|
||||||
static void setup_nvic_priorities(void)
|
static void setup_nvic_priorities(void)
|
||||||
{
|
{
|
||||||
@ -55,6 +60,7 @@ static void setup_nvic_priorities(void)
|
|||||||
NVIC_SetPriority(DMA2_Stream0_IRQn, 1);
|
NVIC_SetPriority(DMA2_Stream0_IRQn, 1);
|
||||||
/* Shelmatta UART TX */
|
/* Shelmatta UART TX */
|
||||||
NVIC_SetPriority(DMA2_Stream7_IRQn, 3);
|
NVIC_SetPriority(DMA2_Stream7_IRQn, 3);
|
||||||
|
NVIC_SetPriority(DMA2_Stream4_IRQn, 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
FATFS fs;
|
FATFS fs;
|
||||||
@ -80,7 +86,7 @@ static inline void uart_gpio_config(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
static char shell_uart_tx_buff[128];
|
static char shell_uart_tx_buff[256];
|
||||||
static char shell_uart_rx_buff[48];
|
static char shell_uart_rx_buff[48];
|
||||||
struct stm_uart shell_uart;
|
struct stm_uart shell_uart;
|
||||||
|
|
||||||
@ -141,34 +147,44 @@ static bool mount_sd_card_if_avail(bool mounted)
|
|||||||
return mounted;
|
return mounted;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void setup_unused_pins(void)
|
static inline void handle_boot_status(void)
|
||||||
{
|
{
|
||||||
int i;
|
struct safety_memory_boot_status status;
|
||||||
|
int res;
|
||||||
|
|
||||||
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(RCC_AHB1ENR_GPIOEEN));
|
res = safety_memory_get_boot_status(&status);
|
||||||
GPIOE->MODER = 0UL;
|
if (res != 0)
|
||||||
for (i = 0; i < 16; i++)
|
panic_mode();
|
||||||
GPIOE->PUPDR |= PULLDOWN(i);
|
if (status.reboot_to_bootloader) {
|
||||||
rcc_manager_disable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(RCC_AHB1ENR_GPIOEEN));
|
status.reboot_to_bootloader = 0UL;
|
||||||
|
safety_memory_set_boot_status(&status);
|
||||||
|
|
||||||
|
led_set(0, 1);
|
||||||
|
led_set(1, 1);
|
||||||
|
|
||||||
|
start_updater();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static inline void setup_system(void)
|
static inline void setup_system(void)
|
||||||
{
|
{
|
||||||
setup_nvic_priorities();
|
setup_nvic_priorities();
|
||||||
systick_setup();
|
|
||||||
|
|
||||||
|
/* Init safety controller and safety memory */
|
||||||
|
safety_controller_init();
|
||||||
|
|
||||||
|
systick_setup();
|
||||||
oven_driver_init();
|
oven_driver_init();
|
||||||
digio_setup_default_all();
|
digio_setup_default_all();
|
||||||
led_setup();
|
led_setup();
|
||||||
loudspeaker_setup();
|
loudspeaker_setup();
|
||||||
reflow_menu_init();
|
gui_init();
|
||||||
|
|
||||||
uart_gpio_config();
|
uart_gpio_config();
|
||||||
|
settings_setup();
|
||||||
|
|
||||||
|
handle_boot_status();
|
||||||
|
|
||||||
setup_shell_uart(&shell_uart);
|
setup_shell_uart(&shell_uart);
|
||||||
|
|
||||||
setup_unused_pins();
|
|
||||||
|
|
||||||
safety_controller_init();
|
|
||||||
adc_pt1000_setup_meas();
|
adc_pt1000_setup_meas();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -195,8 +211,15 @@ int main(void)
|
|||||||
shellmatta_handle_t shell_handle;
|
shellmatta_handle_t shell_handle;
|
||||||
int menu_wait_request;
|
int menu_wait_request;
|
||||||
uint64_t quarter_sec_timestamp = 0ULL;
|
uint64_t quarter_sec_timestamp = 0ULL;
|
||||||
|
|
||||||
setup_system();
|
setup_system();
|
||||||
|
|
||||||
|
/* 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);
|
||||||
|
}
|
||||||
|
|
||||||
shell_handle = shell_init(write_shell_callback);
|
shell_handle = shell_init(write_shell_callback);
|
||||||
shell_print_motd(shell_handle);
|
shell_print_motd(shell_handle);
|
||||||
|
|
||||||
@ -220,20 +243,20 @@ int main(void)
|
|||||||
quarter_sec_timestamp = systick_get_global_tick();
|
quarter_sec_timestamp = systick_get_global_tick();
|
||||||
}
|
}
|
||||||
|
|
||||||
menu_wait_request = reflow_menu_handle();
|
menu_wait_request = gui_handle();
|
||||||
handle_shell_uart_input(shell_handle);
|
handle_shell_uart_input(shell_handle);
|
||||||
|
|
||||||
safety_controller_handle();
|
safety_controller_handle();
|
||||||
/* Todo: Remove this */
|
if (oven_pid_get_status() == OVEN_PID_RUNNING) {
|
||||||
oven_driver_set_power(0);
|
oven_pid_handle();
|
||||||
|
}
|
||||||
oven_driver_apply_power_level();
|
oven_driver_apply_power_level();
|
||||||
|
|
||||||
safety_controller_report_timing(ERR_TIMING_MAIN_LOOP);
|
safety_controller_report_timing(ERR_TIMING_MAIN_LOOP);
|
||||||
|
|
||||||
if (menu_wait_request)
|
if (menu_wait_request)
|
||||||
__WFI();
|
__WFI();
|
||||||
else
|
else
|
||||||
__NOP();
|
__NOP();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
@ -249,7 +272,7 @@ void sdio_wait_ms(uint32_t ms)
|
|||||||
*/
|
*/
|
||||||
void DMA2_Stream7_IRQHandler(void)
|
void DMA2_Stream7_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uint32_t hisr = DMA2->HISR;
|
uint32_t hisr = DMA2->HISR & (0x3F << 22);
|
||||||
|
|
||||||
DMA2->HIFCR = hisr;
|
DMA2->HIFCR = hisr;
|
||||||
|
|
||||||
|
@ -20,17 +20,31 @@
|
|||||||
|
|
||||||
#include <reflow-controller/oven-driver.h>
|
#include <reflow-controller/oven-driver.h>
|
||||||
#include <reflow-controller/periph-config/oven-driver-hwcfg.h>
|
#include <reflow-controller/periph-config/oven-driver-hwcfg.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <reflow-controller/systick.h>
|
#include <reflow-controller/systick.h>
|
||||||
#include <reflow-controller/adc-meas.h>
|
#include <reflow-controller/adc-meas.h>
|
||||||
#include <reflow-controller/temp-converter.h>
|
#include <reflow-controller/temp-converter.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <reflow-controller/safety/safety-controller.h>
|
#include <reflow-controller/safety/safety-controller.h>
|
||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
|
|
||||||
static struct pid_controller IN_SECTION(.ccm.bss) oven_pid;
|
static struct pid_controller IN_SECTION(.ccm.bss) oven_pid;
|
||||||
static bool oven_pid_running;
|
static bool oven_pid_running;
|
||||||
static bool oven_pid_aborted;
|
static bool oven_pid_aborted;
|
||||||
static uint8_t IN_SECTION(.ccm.bss) oven_driver_power_level;
|
static uint8_t IN_SECTION(.ccm.bss) oven_driver_power_level;
|
||||||
|
static float IN_SECTION(.ccm.bss) target_temp;
|
||||||
|
static uint64_t IN_SECTION(.ccm.bss) timestamp_last_run;
|
||||||
|
|
||||||
|
static void ssr_safety_en(bool enable)
|
||||||
|
{
|
||||||
|
if (get_pcb_hardware_version() >= HW_REV_V1_3) {
|
||||||
|
if (enable)
|
||||||
|
SSR_SAFETY_EN_PORT->ODR |= (1<<SSR_SAFETY_EN_PIN);
|
||||||
|
else
|
||||||
|
SSR_SAFETY_EN_PORT->ODR &= ~(1<<SSR_SAFETY_EN_PIN);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void oven_driver_init(void)
|
void oven_driver_init(void)
|
||||||
{
|
{
|
||||||
@ -55,7 +69,16 @@ void oven_driver_init(void)
|
|||||||
oven_pid_aborted = false;
|
oven_pid_aborted = false;
|
||||||
oven_pid_running = false;
|
oven_pid_running = false;
|
||||||
|
|
||||||
|
if (get_pcb_hardware_version() >= HW_REV_V1_3) {
|
||||||
|
/* Init the safety SSR enable signal */
|
||||||
|
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(SSR_SAFETY_EN_PORT_RCC_MASK));
|
||||||
|
SSR_SAFETY_EN_PORT->MODER &= MODER_DELETE(SSR_SAFETY_EN_PIN);
|
||||||
|
SSR_SAFETY_EN_PORT->MODER |= OUTPUT(SSR_SAFETY_EN_PIN);
|
||||||
|
ssr_safety_en(false);
|
||||||
|
}
|
||||||
|
|
||||||
oven_driver_set_power(0U);
|
oven_driver_set_power(0U);
|
||||||
|
oven_driver_apply_power_level();
|
||||||
}
|
}
|
||||||
|
|
||||||
void oven_driver_set_power(uint8_t power)
|
void oven_driver_set_power(uint8_t power)
|
||||||
@ -88,13 +111,19 @@ void oven_pid_init(struct pid_controller *controller_to_copy)
|
|||||||
oven_pid_running = true;
|
oven_pid_running = true;
|
||||||
oven_pid_aborted = false;
|
oven_pid_aborted = false;
|
||||||
safety_controller_report_timing(ERR_TIMING_PID);
|
safety_controller_report_timing(ERR_TIMING_PID);
|
||||||
|
timestamp_last_run = systick_get_global_tick();
|
||||||
|
ssr_safety_en(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
void oven_pid_handle(float target_temp)
|
void oven_pid_set_target_temperature(float temp)
|
||||||
|
{
|
||||||
|
target_temp = temp;
|
||||||
|
}
|
||||||
|
|
||||||
|
void oven_pid_handle(void)
|
||||||
{
|
{
|
||||||
float pid_out;
|
float pid_out;
|
||||||
float current_temp;
|
float current_temp;
|
||||||
static uint64_t timestamp_last_run;
|
|
||||||
|
|
||||||
if (oven_pid_running && !oven_pid_aborted) {
|
if (oven_pid_running && !oven_pid_aborted) {
|
||||||
if (systick_ticks_have_passed(timestamp_last_run, (uint64_t)(oven_pid.sample_period * 1000))) {
|
if (systick_ticks_have_passed(timestamp_last_run, (uint64_t)(oven_pid.sample_period * 1000))) {
|
||||||
@ -116,6 +145,7 @@ void oven_pid_stop(void)
|
|||||||
oven_pid_running = false;
|
oven_pid_running = false;
|
||||||
oven_driver_set_power(0U);
|
oven_driver_set_power(0U);
|
||||||
safety_controller_enable_timing_mon(ERR_TIMING_PID, false);
|
safety_controller_enable_timing_mon(ERR_TIMING_PID, false);
|
||||||
|
ssr_safety_en(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
void oven_pid_abort(void)
|
void oven_pid_abort(void)
|
||||||
|
@ -22,7 +22,7 @@
|
|||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
void pid_init(struct pid_controller *pid, float k_deriv, float k_int, float k_p, float output_sat_min,
|
void pid_init(struct pid_controller *pid, float k_deriv, float k_int, float k_p, float output_sat_min,
|
||||||
float output_sat_max, float integral_max, float sample_period)
|
float output_sat_max, float integral_max, float kd_tau, float sample_period)
|
||||||
{
|
{
|
||||||
if (!pid)
|
if (!pid)
|
||||||
return;
|
return;
|
||||||
@ -32,7 +32,8 @@ void pid_init(struct pid_controller *pid, float k_deriv, float k_int, float k_p,
|
|||||||
pid->k_int = k_int;
|
pid->k_int = k_int;
|
||||||
pid->k_deriv = k_deriv;
|
pid->k_deriv = k_deriv;
|
||||||
pid->k_int_t = pid->k_int * pid->sample_period * 0.5f;
|
pid->k_int_t = pid->k_int * pid->sample_period * 0.5f;
|
||||||
pid->k_deriv_t = pid->k_deriv * 2.0f / pid->sample_period;
|
pid->k_deriv_t = pid->k_deriv * 2.0f / (pid->sample_period + 2.0f * kd_tau);
|
||||||
|
pid->k_inv_deriv_t = (2.0f * kd_tau - sample_period) / (2.0f * kd_tau + sample_period);
|
||||||
pid->output_sat_max = output_sat_max;
|
pid->output_sat_max = output_sat_max;
|
||||||
pid->output_sat_min = output_sat_min;
|
pid->output_sat_min = output_sat_min;
|
||||||
pid->integral_max = integral_max;
|
pid->integral_max = integral_max;
|
||||||
@ -61,7 +62,7 @@ static void calculate_integral(struct pid_controller *pid, float deviation)
|
|||||||
{
|
{
|
||||||
pid->integral = pid->integral + pid->k_int_t * (deviation + pid->last_in);
|
pid->integral = pid->integral + pid->k_int_t * (deviation + pid->last_in);
|
||||||
|
|
||||||
/* Saturate integral term to spoecified maximum */
|
/* Saturate integral term to specified maximum */
|
||||||
if (pid->integral > pid->integral_max)
|
if (pid->integral > pid->integral_max)
|
||||||
pid->integral = pid->integral_max;
|
pid->integral = pid->integral_max;
|
||||||
else if (pid->integral < -pid->integral_max)
|
else if (pid->integral < -pid->integral_max)
|
||||||
@ -78,13 +79,13 @@ float pid_sample(struct pid_controller *pid, float deviation)
|
|||||||
output = deviation * pid->k_p;
|
output = deviation * pid->k_p;
|
||||||
|
|
||||||
/* PID runaway compensation */
|
/* PID runaway compensation */
|
||||||
if (!(deviation > 0.0f && pid->control_output > pid->output_sat_max - 0.5f) &&
|
if (!(deviation > 0.0f && pid->control_output > pid->output_sat_max - 0.5f && pid->integral > 0) &&
|
||||||
!(deviation < 0.0f && pid->control_output < pid->output_sat_min + 0.5f)) {
|
!(deviation < 0.0f && pid->control_output < pid->output_sat_min + 0.5f && pid->integral < 0)) {
|
||||||
calculate_integral(pid, deviation);
|
calculate_integral(pid, deviation);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Calculate derivative part */
|
/* Calculate derivative part */
|
||||||
pid->derivate = pid->k_deriv_t * (deviation - pid->last_in) - pid->derivate;
|
pid->derivate = pid->k_deriv_t * (deviation - pid->last_in) - pid->k_inv_deriv_t * pid->derivate;
|
||||||
|
|
||||||
output += pid->derivate;
|
output += pid->derivate;
|
||||||
output += pid->integral;
|
output += pid->integral;
|
||||||
|
@ -19,7 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <reflow-controller/rotary-encoder.h>
|
#include <reflow-controller/rotary-encoder.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
|
|
||||||
|
@ -26,42 +26,99 @@
|
|||||||
#include <reflow-controller/safety/safety-adc.h>
|
#include <reflow-controller/safety/safety-adc.h>
|
||||||
#include <reflow-controller/periph-config/safety-adc-hwcfg.h>
|
#include <reflow-controller/periph-config/safety-adc-hwcfg.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
|
|
||||||
void safety_adc_init()
|
static const uint8_t safety_adc_channels[SAFETY_ADC_NUM_OF_CHANNELS] = {SAFETY_ADC_CHANNELS};
|
||||||
|
static volatile uint8_t safety_adc_conversion_complete;
|
||||||
|
static volatile uint8_t safety_adc_triggered;
|
||||||
|
static volatile uint16_t safety_adc_conversions[SAFETY_ADC_NUM_OF_CHANNELS];
|
||||||
|
|
||||||
|
void safety_adc_init(void)
|
||||||
{
|
{
|
||||||
|
enum hw_revision hw_rev;
|
||||||
|
int i;
|
||||||
|
|
||||||
|
hw_rev = get_pcb_hardware_version();
|
||||||
|
|
||||||
rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(SAFETY_ADC_ADC_RCC_MASK));
|
rcc_manager_enable_clock(&RCC->APB2ENR, BITMASK_TO_BITNO(SAFETY_ADC_ADC_RCC_MASK));
|
||||||
|
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(RCC_AHB1ENR_DMA2EN));
|
||||||
|
|
||||||
|
if (hw_rev != HW_REV_V1_2) {
|
||||||
|
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PORT_RCC_MASK));
|
||||||
|
SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PORT->MODER &= MODER_DELETE(SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PIN);
|
||||||
|
SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PORT->MODER |= ANALOG(SAFETY_ADC_SUPPLY_VOLTAGE_MONITOR_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
/* Enable temperature and VREFINT measurement */
|
/* Enable temperature and VREFINT measurement */
|
||||||
ADC->CCR |= ADC_CCR_TSVREFE;
|
ADC->CCR |= ADC_CCR_TSVREFE;
|
||||||
|
|
||||||
/* Set sample time for channels 16 and 17 */
|
/* Set sample time for channels 16 and 17 and 15 */
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->SMPR1 |= ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16;
|
SAFETY_ADC_ADC_PERIPHERAL->SMPR1 |= ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16 | ADC_SMPR1_SMP15;
|
||||||
|
|
||||||
/* Standard sequence. One measurement */
|
/* Standard sequence. Measure all channels in one sequence */
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->SQR1 = 0UL;
|
SAFETY_ADC_ADC_PERIPHERAL->SQR1 = (SAFETY_ADC_NUM_OF_CHANNELS - 1) << 20 ;
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->SQR2 = 0UL;
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->SQR3 = 0UL;
|
||||||
|
|
||||||
|
for (i = 0; i < SAFETY_ADC_NUM_OF_CHANNELS; i++) {
|
||||||
|
switch (i) {
|
||||||
|
case 0 ... 5:
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->SQR3 |= safety_adc_channels[i] << (i * 5);
|
||||||
|
break;
|
||||||
|
case 6 ... 11:
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->SQR2 |= safety_adc_channels[i] << ((i-6) * 5);
|
||||||
|
break;
|
||||||
|
case 12 ... 15:
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->SQR1 |= safety_adc_channels[i] << ((i-12) * 5);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
safety_adc_conversion_complete = 0;
|
||||||
|
safety_adc_triggered = 0;
|
||||||
|
|
||||||
|
/* Setup the DMA to move the data */
|
||||||
|
DMA2_Stream4->PAR = (uint32_t)&SAFETY_ADC_ADC_PERIPHERAL->DR;
|
||||||
|
DMA2_Stream4->M0AR = (uint32_t)safety_adc_conversions;
|
||||||
|
DMA2_Stream4->NDTR = SAFETY_ADC_NUM_OF_CHANNELS;
|
||||||
|
DMA2_Stream4->CR = DMA_SxCR_PL_0 | DMA_SxCR_MSIZE_0 | DMA_SxCR_PSIZE_0 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_TCIE | DMA_SxCR_EN;
|
||||||
|
NVIC_EnableIRQ(DMA2_Stream4_IRQn);
|
||||||
|
|
||||||
|
/* Enable ADC */
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->CR2 = ADC_CR2_ADON | ADC_CR2_DMA | ADC_CR2_DDS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void safety_adc_deinit()
|
void safety_adc_deinit(void)
|
||||||
{
|
{
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->CR1 = 0UL;
|
SAFETY_ADC_ADC_PERIPHERAL->CR1 = 0UL;
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->CR2 = 0UL;
|
SAFETY_ADC_ADC_PERIPHERAL->CR2 = 0UL;
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->SMPR1 = 0UL;
|
SAFETY_ADC_ADC_PERIPHERAL->SMPR1 = 0UL;
|
||||||
rcc_manager_enable_clock(&RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC2EN));
|
rcc_manager_disable_clock(&RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB2ENR_ADC2EN));
|
||||||
|
DMA2_Stream4->CR = 0;
|
||||||
|
rcc_manager_disable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(RCC_AHB1ENR_DMA2EN));
|
||||||
}
|
}
|
||||||
|
|
||||||
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value)
|
float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t analog_value)
|
||||||
{
|
{
|
||||||
float converted_val;
|
float converted_val;
|
||||||
|
enum hw_revision hw_rev;
|
||||||
|
|
||||||
switch (channel) {
|
switch (channel) {
|
||||||
case SAFETY_ADC_MEAS_TEMP:
|
case SAFETY_ADC_MEAS_TEMP:
|
||||||
converted_val = (((float)analog_value / 4095.0f * 2500.0f - SAFETY_ADC_TEMP_NOM_MV) /
|
converted_val = (((float)analog_value / 4096.0f * 2500.0f - SAFETY_ADC_TEMP_NOM_MV) /
|
||||||
SAFETY_ADC_TEMP_MV_SLOPE) + SAFETY_ADC_TEMP_NOM;
|
SAFETY_ADC_TEMP_MV_SLOPE) + SAFETY_ADC_TEMP_NOM;
|
||||||
break;
|
break;
|
||||||
case SAFETY_ADC_MEAS_VREF:
|
case SAFETY_ADC_MEAS_VREF:
|
||||||
converted_val = (SAFETY_ADC_INT_REF_MV * 4095.0f) / (float)analog_value;
|
converted_val = (SAFETY_ADC_INT_REF_MV * 4096.0f) / (float)analog_value;
|
||||||
|
break;
|
||||||
|
case SAFETY_ADC_MEAS_SUPPLY:
|
||||||
|
hw_rev = get_pcb_hardware_version();
|
||||||
|
if (hw_rev >= HW_REV_V1_3)
|
||||||
|
converted_val = ((float)analog_value) / 4096.0f * 2500.0f * 2.0f;
|
||||||
|
else
|
||||||
|
converted_val = 3300.0f;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
/* Generate NaN value as default return */
|
/* Generate NaN value as default return */
|
||||||
@ -72,42 +129,44 @@ float safety_adc_convert_channel(enum safety_adc_meas_channel channel, uint16_t
|
|||||||
return converted_val;
|
return converted_val;
|
||||||
}
|
}
|
||||||
|
|
||||||
int safety_adc_poll_result(uint16_t *adc_result)
|
int safety_adc_poll_result(void)
|
||||||
{
|
{
|
||||||
int ret = 0;
|
if (safety_adc_triggered)
|
||||||
|
return 0;
|
||||||
|
|
||||||
if (!adc_result)
|
if (safety_adc_conversion_complete)
|
||||||
return -1000;
|
return 1;
|
||||||
|
else
|
||||||
if (!(SAFETY_ADC_ADC_PERIPHERAL->CR2 & ADC_CR2_ADON)) {
|
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (SAFETY_ADC_ADC_PERIPHERAL->SR & ADC_SR_EOC) {
|
const uint16_t *safety_adc_get_values(void)
|
||||||
*adc_result = (uint16_t)SAFETY_ADC_ADC_PERIPHERAL->DR;
|
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->CR2 &= ~ADC_CR2_ADON;
|
|
||||||
ret = 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
void safety_adc_trigger_meas(enum safety_adc_meas_channel measurement)
|
|
||||||
{
|
{
|
||||||
switch (measurement) {
|
safety_adc_conversion_complete = 0;
|
||||||
case SAFETY_ADC_MEAS_TEMP:
|
return (const uint16_t *)safety_adc_conversions;
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->SQR3 = TEMP_CHANNEL_NUM;
|
|
||||||
break;
|
|
||||||
case SAFETY_ADC_MEAS_VREF:
|
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->SQR3 = INT_REF_CHANNEL_NUM;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void safety_adc_trigger_meas(void)
|
||||||
|
{
|
||||||
|
safety_adc_conversion_complete = 0;
|
||||||
|
|
||||||
|
SAFETY_ADC_ADC_PERIPHERAL->CR1 |= ADC_CR1_SCAN;
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_ADON;
|
SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_ADON;
|
||||||
SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_SWSTART;
|
SAFETY_ADC_ADC_PERIPHERAL->CR2 |= ADC_CR2_SWSTART;
|
||||||
|
safety_adc_triggered = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void DMA2_Stream4_IRQHandler()
|
||||||
|
{
|
||||||
|
uint32_t hisr;
|
||||||
|
|
||||||
|
hisr = DMA2->HISR & 0x3F;
|
||||||
|
DMA2->HIFCR = hisr;
|
||||||
|
|
||||||
|
if (hisr & DMA_HISR_TCIF4) {
|
||||||
|
safety_adc_triggered = 0;
|
||||||
|
safety_adc_conversion_complete = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/** @} */
|
/** @} */
|
||||||
|
@ -28,6 +28,7 @@
|
|||||||
#include <reflow-controller/safety/watchdog.h>
|
#include <reflow-controller/safety/watchdog.h>
|
||||||
#include <reflow-controller/safety/safety-adc.h>
|
#include <reflow-controller/safety/safety-adc.h>
|
||||||
#include <reflow-controller/safety/stack-check.h>
|
#include <reflow-controller/safety/stack-check.h>
|
||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stm-periph/crc-unit.h>
|
#include <stm-periph/crc-unit.h>
|
||||||
#include <reflow-controller/systick.h>
|
#include <reflow-controller/systick.h>
|
||||||
@ -39,33 +40,85 @@
|
|||||||
#include <reflow-controller/safety/safety-memory.h>
|
#include <reflow-controller/safety/safety-memory.h>
|
||||||
#include <reflow-controller/oven-driver.h>
|
#include <reflow-controller/oven-driver.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
|
#include <stm-periph/rcc-manager.h>
|
||||||
|
|
||||||
#define check_flag_persistent(flag) ((flag)->persistency && (flag)->persistency->persistency)
|
/**
|
||||||
#define get_flag_weight(flag) ((flag)->weight ? (flag->weight->weight) : SAFETY_FLAG_CONFIG_WEIGHT_NONE)
|
* @brief Macro that checks if a given @ref error_flag is persistent
|
||||||
|
*/
|
||||||
|
#define check_flag_persistent(flag) ((flag)->persistence && (flag)->persistence->persistence)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Macro that retrieves the flag weight of a given @ref error_flag
|
||||||
|
*
|
||||||
|
* If no flag weight table is present, the flag is evaluated as SAFETY_FLAG_CONFIG_WEIGHT_PANIC
|
||||||
|
*/
|
||||||
|
#define get_flag_weight(flag) ((flag)->weight ? ((flag)->weight->weight) : SAFETY_FLAG_CONFIG_WEIGHT_PANIC)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Safety controller internal structure implementing a safety flag weight.
|
||||||
|
*/
|
||||||
struct safety_weight {
|
struct safety_weight {
|
||||||
|
/** @brief Dummy value. This seeds the CRC */
|
||||||
uint32_t start_dummy;
|
uint32_t start_dummy;
|
||||||
|
|
||||||
|
/** @brief The safety flag's weight */
|
||||||
enum config_weight weight;
|
enum config_weight weight;
|
||||||
|
|
||||||
|
/** @brief The enum value of the flag this weight corresponds to */
|
||||||
enum safety_flag flag;
|
enum safety_flag flag;
|
||||||
|
|
||||||
|
/** @brief the flag, this weight corresponds to */
|
||||||
volatile struct error_flag *flag_ptr;
|
volatile struct error_flag *flag_ptr;
|
||||||
|
|
||||||
|
/** @brief Dummy value. This seeds the CRC */
|
||||||
uint32_t end_dummy;
|
uint32_t end_dummy;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct safety_persistency {
|
/**
|
||||||
|
* @brief Safety controller internal struct implementing a flag persistence entry
|
||||||
|
*/
|
||||||
|
struct safety_persistence {
|
||||||
|
/** @brief Dummy value. This seeds the CRC */
|
||||||
uint32_t start_dummy;
|
uint32_t start_dummy;
|
||||||
bool persistency;
|
|
||||||
|
/** @brief Corresponding flag is persistent and cannot be cleared */
|
||||||
|
bool persistence;
|
||||||
|
|
||||||
|
/** @brief Corresponding safety flag's enum value */
|
||||||
enum safety_flag flag;
|
enum safety_flag flag;
|
||||||
|
|
||||||
|
/** @brief Corresponding safety error flag */
|
||||||
volatile struct error_flag *flag_ptr;
|
volatile struct error_flag *flag_ptr;
|
||||||
|
|
||||||
|
/** @brief Dummy value. This seeds the CRC */
|
||||||
uint32_t end_dummy;
|
uint32_t end_dummy;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Safety controller internal struct implementing an error flag
|
||||||
|
*/
|
||||||
struct error_flag {
|
struct error_flag {
|
||||||
|
/** @brief Name of the error flag */
|
||||||
const char *name;
|
const char *name;
|
||||||
|
|
||||||
|
/** @brief Enum value of this safety flag */
|
||||||
enum safety_flag flag;
|
enum safety_flag flag;
|
||||||
|
|
||||||
|
/** @brief The flag's state. True is errorneous. */
|
||||||
bool error_state;
|
bool error_state;
|
||||||
|
|
||||||
|
/** @brief Not the flag's state. This always has to be inverted to @ref error_flag::error_state */
|
||||||
bool error_state_inv;
|
bool error_state_inv;
|
||||||
volatile struct safety_persistency *persistency;
|
|
||||||
|
/** @brief Persistence entry of this flag */
|
||||||
|
volatile struct safety_persistence *persistence;
|
||||||
|
|
||||||
|
/** @brief Weight entry of this flag */
|
||||||
volatile struct safety_weight *weight;
|
volatile struct safety_weight *weight;
|
||||||
|
|
||||||
|
/** @brief Key needed to remove this safety flag. If key == 0, no key is set and
|
||||||
|
* the flag can be cleared by all code
|
||||||
|
*/
|
||||||
uint32_t key;
|
uint32_t key;
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -91,6 +144,9 @@ struct analog_mon {
|
|||||||
uint64_t timestamp;
|
uint64_t timestamp;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief All safety error flags.
|
||||||
|
*/
|
||||||
static volatile struct error_flag IN_SECTION(.ccm.data) flags[] = {
|
static volatile struct error_flag IN_SECTION(.ccm.data) flags[] = {
|
||||||
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_OFF),
|
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_OFF),
|
||||||
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG),
|
ERR_FLAG_ENTRY(ERR_FLAG_MEAS_ADC_WATCHDOG),
|
||||||
@ -109,31 +165,121 @@ static volatile struct error_flag IN_SECTION(.ccm.data) flags[] = {
|
|||||||
ERR_FLAG_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP),
|
ERR_FLAG_ENTRY(ERR_FLAG_TIMING_MAIN_LOOP),
|
||||||
ERR_FLAG_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT),
|
ERR_FLAG_ENTRY(ERR_FLAG_SAFETY_MEM_CORRUPT),
|
||||||
ERR_FLAG_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT),
|
ERR_FLAG_ENTRY(ERR_FLAG_SAFETY_TAB_CORRUPT),
|
||||||
|
ERR_FLAG_ENTRY(ERR_FLAG_AMON_SUPPLY_VOLT),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief All timing monitors
|
||||||
|
*/
|
||||||
static volatile struct timing_mon IN_SECTION(.ccm.data) timings[] = {
|
static volatile struct timing_mon IN_SECTION(.ccm.data) timings[] = {
|
||||||
TIM_MON_ENTRY(ERR_TIMING_PID, 2, 1000, ERR_FLAG_TIMING_PID),
|
TIM_MON_ENTRY(ERR_TIMING_PID, 2, 5000, ERR_FLAG_TIMING_PID),
|
||||||
TIM_MON_ENTRY(ERR_TIMING_MEAS_ADC, 0, 50, ERR_FLAG_TIMING_MEAS_ADC),
|
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 + 1000, ERR_FLAG_SAFETY_ADC),
|
TIM_MON_ENTRY(ERR_TIMING_SAFETY_ADC, 10, SAFETY_CONTROLLER_ADC_DELAY_MS + 1000, ERR_FLAG_SAFETY_ADC),
|
||||||
TIM_MON_ENTRY(ERR_TIMING_MAIN_LOOP, 0, 1000, ERR_FLAG_TIMING_MAIN_LOOP),
|
TIM_MON_ENTRY(ERR_TIMING_MAIN_LOOP, 0, 1000, ERR_FLAG_TIMING_MAIN_LOOP),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief All analog value monitors
|
||||||
|
*/
|
||||||
static volatile struct analog_mon IN_SECTION(.ccm.data) analog_mons[] = {
|
static volatile struct analog_mon IN_SECTION(.ccm.data) analog_mons[] = {
|
||||||
ANA_MON_ENTRY(ERR_AMON_VREF, SAFETY_ADC_VREF_MVOLT - SAFETY_ADC_VREF_TOL_MVOLT,
|
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),
|
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,
|
ANA_MON_ENTRY(ERR_AMON_UC_TEMP, SAFETY_ADC_TEMP_LOW_LIM, SAFETY_ADC_TEMP_HIGH_LIM,
|
||||||
ERR_FLAG_AMON_UC_TEMP),
|
ERR_FLAG_AMON_UC_TEMP),
|
||||||
|
ANA_MON_ENTRY(ERR_AMON_SUPPLY_VOLT, SAFETY_ADC_SUPPLY_MVOLT - SAFETY_ADC_SUPPLY_TOL_MVOLT,
|
||||||
|
SAFETY_ADC_SUPPLY_MVOLT + SAFETY_ADC_SUPPLY_TOL_MVOLT,
|
||||||
|
ERR_FLAG_AMON_SUPPLY_VOLT),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The default flag weights, that are loaded on boot.
|
||||||
|
*/
|
||||||
static const struct safety_weight default_flag_weights[] = { SAFETY_CONFIG_DEFAULT_WEIGHTS };
|
static const struct safety_weight default_flag_weights[] = { SAFETY_CONFIG_DEFAULT_WEIGHTS };
|
||||||
static const struct safety_persistency default_flag_persistencies[] = {SAFETY_CONFIG_DEFAULT_PERSIST};
|
|
||||||
|
|
||||||
static volatile struct safety_persistency IN_SECTION(.ccm.bss) flag_persistencies[COUNT_OF(default_flag_persistencies)];
|
/**
|
||||||
|
* @brief The default flag persistencies, that are loaded on boot.
|
||||||
|
*/
|
||||||
|
static const struct safety_persistence default_flag_persistencies[] = {SAFETY_CONFIG_DEFAULT_PERSIST};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The working copy of the flag persistence table. It is protected by the @ref flag_persistencies_crc
|
||||||
|
* @note This is stored in CCM RAM
|
||||||
|
*/
|
||||||
|
static volatile struct safety_persistence IN_SECTION(.ccm.bss) flag_persistencies[COUNT_OF(default_flag_persistencies)];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The CRC of the flag weight table @ref flag_persistencies.
|
||||||
|
*
|
||||||
|
* The CRC is calculated using the internal CRC module of the STM32F407 controller.
|
||||||
|
* See the refernece manual for the polynomial.
|
||||||
|
*
|
||||||
|
* @note This is stored in CCM RAM.
|
||||||
|
*/
|
||||||
static uint32_t IN_SECTION(.ccm.bss) flag_persistencies_crc;
|
static uint32_t IN_SECTION(.ccm.bss) flag_persistencies_crc;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The working copy of the flag weight table. It is protected by the @ref flag_weight_crc.
|
||||||
|
* @note This is stored in CCM RAM
|
||||||
|
*/
|
||||||
static volatile struct safety_weight IN_SECTION(.ccm.bss) flag_weights[COUNT_OF(default_flag_weights)];
|
static volatile struct safety_weight IN_SECTION(.ccm.bss) flag_weights[COUNT_OF(default_flag_weights)];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The CRC of the flag weight table @ref flag_weights.
|
||||||
|
*
|
||||||
|
* The CRC is calculated using the internal CRC module of the STM32F407 controller.
|
||||||
|
* See the refernece manual for the polynomial.
|
||||||
|
*
|
||||||
|
* @note This is stored in CCM RAM.
|
||||||
|
*/
|
||||||
static uint32_t IN_SECTION(.ccm.bss) flag_weight_crc;
|
static uint32_t IN_SECTION(.ccm.bss) flag_weight_crc;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Convert a flag enum to the flag number.
|
||||||
|
*
|
||||||
|
* Flag numbers are used by the error memory to store flags.
|
||||||
|
* This function will fail and return 0xFF if multiple flags are ORed and
|
||||||
|
* passed as flag parameter.
|
||||||
|
*
|
||||||
|
* @param flag Flag enum
|
||||||
|
* @return Flag number or 0xFF in case of an error
|
||||||
|
*/
|
||||||
|
static uint8_t flag_enum_to_flag_no(enum safety_flag flag)
|
||||||
|
{
|
||||||
|
uint32_t flag_mask;
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
if (!is_power_of_two(flag))
|
||||||
|
return 0xFF;
|
||||||
|
|
||||||
|
flag_mask = (uint32_t)flag;
|
||||||
|
for (i = 0; i < 32; i++) {
|
||||||
|
if ((flag_mask >> i) & 0x1U)
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Convert a safety flag's number to its enum value.
|
||||||
|
*
|
||||||
|
* Flag numbers are used by the error memory to store flags.
|
||||||
|
*
|
||||||
|
* @param no The flag number.
|
||||||
|
* @return Flag enum
|
||||||
|
*/
|
||||||
|
static enum safety_flag flag_no_to_flag_enum(uint8_t no)
|
||||||
|
{
|
||||||
|
if (no >= COUNT_OF(flags))
|
||||||
|
return ERR_FLAG_NO_FLAG;
|
||||||
|
|
||||||
|
return (1U << no);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Check the CRC chacksum of the flag weight table
|
||||||
|
* @return 0 if CRC is valid, else -1;
|
||||||
|
*/
|
||||||
static int flag_weight_table_crc_check(void)
|
static int flag_weight_table_crc_check(void)
|
||||||
{
|
{
|
||||||
/* Check the flag weight table */
|
/* Check the flag weight table */
|
||||||
@ -146,6 +292,10 @@ static int flag_weight_table_crc_check(void)
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Check the CRC chacksum of the flag persistence table
|
||||||
|
* @return 0 if CRC is valid, else -1.
|
||||||
|
*/
|
||||||
static int flag_persistency_table_crc_check(void)
|
static int flag_persistency_table_crc_check(void)
|
||||||
{
|
{
|
||||||
crc_unit_reset();
|
crc_unit_reset();
|
||||||
@ -157,6 +307,15 @@ static int flag_persistency_table_crc_check(void)
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Find the error flag structure for a given safety_flag enum
|
||||||
|
*
|
||||||
|
* Only one flag can be given at a time. Giving multiple flags by ORing them
|
||||||
|
* together, will not math any flag at all.
|
||||||
|
*
|
||||||
|
* @param flag Enum defining the flag.
|
||||||
|
* @return NULL in case nothing matched. Pointer otherwise.
|
||||||
|
*/
|
||||||
static volatile struct error_flag *find_error_flag(enum safety_flag flag)
|
static volatile struct error_flag *find_error_flag(enum safety_flag flag)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
@ -194,20 +353,26 @@ static void init_safety_flag_weight_table_from_default(void)
|
|||||||
flag_weight_crc = crc_unit_get_crc();
|
flag_weight_crc = crc_unit_get_crc();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Initialize the default persistence settings of all safety flags.
|
||||||
|
*
|
||||||
|
* This function copies the default persistence settings of the safety flags defined in
|
||||||
|
* @ref SAFETY_CONFIG_DEFAULT_PERSIST and computes the protection CRC over the settings.
|
||||||
|
*/
|
||||||
static void init_safety_flag_persistencies_from_default(void)
|
static void init_safety_flag_persistencies_from_default(void)
|
||||||
{
|
{
|
||||||
uint32_t index;
|
uint32_t index;
|
||||||
volatile struct safety_persistency *current_persistency;
|
volatile struct safety_persistence *current_persistence;
|
||||||
|
|
||||||
/* Copy values */
|
/* Copy values */
|
||||||
memcpy((void *)flag_persistencies, default_flag_persistencies, sizeof(flag_persistencies));
|
memcpy((void *)flag_persistencies, default_flag_persistencies, sizeof(flag_persistencies));
|
||||||
|
|
||||||
/* Fill in flag pointers */
|
/* Fill in flag pointers */
|
||||||
for (index = 0; index < COUNT_OF(flag_persistencies); index++) {
|
for (index = 0; index < COUNT_OF(flag_persistencies); index++) {
|
||||||
current_persistency = &flag_persistencies[index];
|
current_persistence = &flag_persistencies[index];
|
||||||
current_persistency->flag_ptr = find_error_flag(current_persistency->flag);
|
current_persistence->flag_ptr = find_error_flag(current_persistence->flag);
|
||||||
if (current_persistency->flag_ptr)
|
if (current_persistence->flag_ptr)
|
||||||
current_persistency->flag_ptr->persistency = current_persistency;
|
current_persistence->flag_ptr->persistence = current_persistence;
|
||||||
}
|
}
|
||||||
|
|
||||||
crc_unit_reset();
|
crc_unit_reset();
|
||||||
@ -215,6 +380,69 @@ static void init_safety_flag_persistencies_from_default(void)
|
|||||||
flag_persistencies_crc = crc_unit_get_crc();
|
flag_persistencies_crc = crc_unit_get_crc();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Apply the config overrrides stored in the safety memory.
|
||||||
|
*
|
||||||
|
* The config overrides are read from the safety memory and applied.
|
||||||
|
* The config overrides can override the following things:
|
||||||
|
*
|
||||||
|
* 1) Safety Weights (See @ref config_weight)
|
||||||
|
* 2) Flag Persistence
|
||||||
|
*/
|
||||||
|
static void apply_config_overrides(void)
|
||||||
|
{
|
||||||
|
uint32_t count;
|
||||||
|
uint32_t idx;
|
||||||
|
struct config_override override;
|
||||||
|
int res;
|
||||||
|
enum safety_flag flag_enum;
|
||||||
|
volatile struct error_flag *flag;
|
||||||
|
|
||||||
|
res = safety_memory_get_config_override_count(&count);
|
||||||
|
if (res)
|
||||||
|
return;
|
||||||
|
for (idx = 0; idx < count; idx++) {
|
||||||
|
res = safety_memory_get_config_override(idx, &override);
|
||||||
|
if (res)
|
||||||
|
continue;
|
||||||
|
switch (override.type) {
|
||||||
|
case SAFETY_MEMORY_CONFIG_OVERRIDE_WEIGHT:
|
||||||
|
flag_enum = flag_no_to_flag_enum(override.entry.weight_override.flag);
|
||||||
|
flag = find_error_flag(flag_enum);
|
||||||
|
if (flag && flag->weight) {
|
||||||
|
flag->weight->weight = override.entry.weight_override.weight;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case SAFETY_MEMORY_CONFIG_OVERRIDE_PERSISTENCE:
|
||||||
|
flag_enum = flag_no_to_flag_enum(override.entry.persistance_override.flag);
|
||||||
|
flag = find_error_flag(flag_enum);
|
||||||
|
if (flag && flag->persistence) {
|
||||||
|
flag->persistence->persistence = override.entry.persistance_override.persistance;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Patch new CRCs */
|
||||||
|
crc_unit_reset();
|
||||||
|
crc_unit_input_array((uint32_t *)flag_persistencies, wordsize_of(flag_persistencies));
|
||||||
|
flag_persistencies_crc = crc_unit_get_crc();
|
||||||
|
crc_unit_reset();
|
||||||
|
crc_unit_input_array((uint32_t*)flag_weights, wordsize_of(flag_weights));
|
||||||
|
flag_weight_crc = crc_unit_get_crc();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get the error state of a flag.
|
||||||
|
*
|
||||||
|
* This function takes inbto account that the error_flag::error_state and
|
||||||
|
* error_flag::error_state_inv fileds must never be the same value. In case they are,
|
||||||
|
* the flag is treated as errorneous.
|
||||||
|
* @param flag Flag to check
|
||||||
|
* @return The error state
|
||||||
|
*/
|
||||||
static bool error_flag_get_status(const volatile struct error_flag *flag)
|
static bool error_flag_get_status(const volatile struct error_flag *flag)
|
||||||
{
|
{
|
||||||
if (!flag)
|
if (!flag)
|
||||||
@ -227,6 +455,11 @@ static bool error_flag_get_status(const volatile struct error_flag *flag)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Find a analog value monitor structure by its enum number
|
||||||
|
* @param mon Enum representing the analog monitor
|
||||||
|
* @return NULL incase nothing is found, else pointer to structure.
|
||||||
|
*/
|
||||||
static volatile struct analog_mon *find_analog_mon(enum analog_value_monitor mon)
|
static volatile struct analog_mon *find_analog_mon(enum analog_value_monitor mon)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
@ -240,6 +473,11 @@ static volatile struct analog_mon *find_analog_mon(enum analog_value_monitor mon
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Find a timing monitor structure by its enum number
|
||||||
|
* @param mon Enum representing the timing monitor
|
||||||
|
* @return NULL incase nothing is found, else pointer to structure.
|
||||||
|
*/
|
||||||
static volatile struct timing_mon *find_timing_mon(enum timing_monitor mon)
|
static volatile struct timing_mon *find_timing_mon(enum timing_monitor mon)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
@ -253,6 +491,9 @@ static volatile struct timing_mon *find_timing_mon(enum timing_monitor mon)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Check the active timing monitors and set the appropriate flags in case of an error.
|
||||||
|
*/
|
||||||
static void safety_controller_process_active_timing_mons()
|
static void safety_controller_process_active_timing_mons()
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
@ -271,52 +512,50 @@ static void safety_controller_process_active_timing_mons()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void safety_controller_process_monitor_checks()
|
/**
|
||||||
|
* @brief safety_controller_process_monitor_checks
|
||||||
|
* Process the analog and timing monitors and set the relevant flags in case of a monitor outside its limits.
|
||||||
|
*
|
||||||
|
* The checking of the analog monitors will only be armed after a startup delay of 1000 ms to allow the values to stabilize.
|
||||||
|
*/
|
||||||
|
static void safety_controller_process_monitor_checks(void)
|
||||||
{
|
{
|
||||||
static bool startup_completed = false;
|
static bool startup_completed = false;
|
||||||
enum analog_monitor_status amon_state;
|
struct analog_monitor_info amon_info;
|
||||||
float amon_value;
|
uint32_t idx;
|
||||||
|
uint32_t analog_mon_count;
|
||||||
|
|
||||||
if (!startup_completed && systick_get_global_tick() >= 1000)
|
if (!startup_completed && systick_get_global_tick() >= 1000)
|
||||||
startup_completed = true;
|
startup_completed = true;
|
||||||
|
|
||||||
if (startup_completed) {
|
if (startup_completed) {
|
||||||
amon_state = safety_controller_get_analog_mon_value(ERR_AMON_VREF, &amon_value);
|
analog_mon_count = safety_controller_get_analog_monitor_count();
|
||||||
if (amon_state != ANALOG_MONITOR_OK)
|
for (idx = 0; idx < analog_mon_count; idx++) {
|
||||||
safety_controller_report_error(ERR_FLAG_AMON_VREF);
|
if (safety_controller_get_analog_mon_by_index(idx, &amon_info)) {
|
||||||
amon_state = safety_controller_get_analog_mon_value(ERR_AMON_UC_TEMP, &amon_value);
|
panic_mode();
|
||||||
if (amon_state != ANALOG_MONITOR_OK)
|
}
|
||||||
safety_controller_report_error(ERR_FLAG_AMON_UC_TEMP);
|
|
||||||
|
if (amon_info.status != ANALOG_MONITOR_OK) {
|
||||||
|
safety_controller_report_error(amon_info.associated_flag);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
safety_controller_process_active_timing_mons();
|
safety_controller_process_active_timing_mons();
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint8_t flag_enum_to_flag_no(enum safety_flag flag)
|
/**
|
||||||
{
|
* @brief Internal function for setting an error flag
|
||||||
uint32_t flag_mask;
|
*
|
||||||
uint8_t i;
|
* Multiple flags can be ored together to set them in one go.
|
||||||
|
* The provided key will be set on all of the flags in order to prevent them from being reset by
|
||||||
if (!is_power_of_two(flag))
|
* unauthorized code. If nop key shall be used, set key to zero.
|
||||||
return 0xFF;
|
*
|
||||||
|
* @param flag Enum of the flags to set. This can be an ORed value of multiple error flags.
|
||||||
flag_mask = (uint32_t)flag;
|
* @param key The kex to set on the flag.
|
||||||
for (i = 0; i < 32; i++) {
|
* @param prevent_error_mem_enty Prevent the flag from being stored in the error memory.
|
||||||
if ((flag_mask >> i) & 0x1U)
|
* @return 0 if successful.
|
||||||
break;
|
*/
|
||||||
}
|
|
||||||
|
|
||||||
return i;
|
|
||||||
}
|
|
||||||
|
|
||||||
static enum safety_flag flag_no_to_flag_enum(uint8_t no)
|
|
||||||
{
|
|
||||||
if (no >= COUNT_OF(flags))
|
|
||||||
return ERR_FLAG_NO_FLAG;
|
|
||||||
|
|
||||||
return (1U << no);
|
|
||||||
}
|
|
||||||
|
|
||||||
static int report_error(enum safety_flag flag, uint32_t key, bool prevent_error_mem_enty)
|
static int report_error(enum safety_flag flag, uint32_t key, bool prevent_error_mem_enty)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
@ -332,7 +571,8 @@ static int report_error(enum safety_flag flag, uint32_t key, bool prevent_error_
|
|||||||
flags[i].error_state_inv = !flags[i].error_state;
|
flags[i].error_state_inv = !flags[i].error_state;
|
||||||
flags[i].key = key;
|
flags[i].key = key;
|
||||||
|
|
||||||
if (check_flag_persistent(&flags[i]) && !old_state && !prevent_error_mem_enty) {
|
if ((check_flag_persistent(&flags[i]) && !old_state && !prevent_error_mem_enty) ||
|
||||||
|
get_flag_weight(&flags[i]) == SAFETY_FLAG_CONFIG_WEIGHT_PANIC) {
|
||||||
err_mem_entry.counter = 1;
|
err_mem_entry.counter = 1;
|
||||||
err_mem_entry.flag_num = flag_enum_to_flag_no(flags[i].flag);
|
err_mem_entry.flag_num = flag_enum_to_flag_no(flags[i].flag);
|
||||||
err_mem_entry.type = SAFETY_MEMORY_ERR_ENTRY_FLAG;
|
err_mem_entry.type = SAFETY_MEMORY_ERR_ENTRY_FLAG;
|
||||||
@ -342,6 +582,10 @@ static int report_error(enum safety_flag flag, uint32_t key, bool prevent_error_
|
|||||||
} else {
|
} else {
|
||||||
ret = 0;
|
ret = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
flag &= ~flags[i].flag;
|
||||||
|
if (!flag)
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -401,7 +645,7 @@ void safety_controller_report_analog_value(enum analog_value_monitor monitor, fl
|
|||||||
* @param flags Flags read from error memory
|
* @param flags Flags read from error memory
|
||||||
* @return 0 if ok, != 0 if error
|
* @return 0 if ok, != 0 if error
|
||||||
*/
|
*/
|
||||||
static enum safety_flag get_safety_flags_from_error_mem(enum safety_flag *flags)
|
static int get_safety_flags_from_error_mem(enum safety_flag *flags)
|
||||||
{
|
{
|
||||||
uint32_t count;
|
uint32_t count;
|
||||||
uint32_t idx;
|
uint32_t idx;
|
||||||
@ -427,10 +671,32 @@ static enum safety_flag get_safety_flags_from_error_mem(enum safety_flag *flags)
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Initialize the GPIOs for the external hardware watchdog.
|
||||||
|
*
|
||||||
|
* The external harware watchdog has to be periodically reset or it will reset hte controller.
|
||||||
|
* Because debugging is not possible, when the watchdog is active, it is only activated, if the application is
|
||||||
|
* compiled in release mode. Any interruption of the main programm will then trigger the internal and/or the external watchdog.
|
||||||
|
*
|
||||||
|
* @note When enabled, execute the @ref external_watchdog_toggle function to reset the external watchdog.
|
||||||
|
*/
|
||||||
|
static void safety_controller_init_external_watchdog()
|
||||||
|
{
|
||||||
|
rcc_manager_enable_clock(&RCC->AHB1ENR, BITMASK_TO_BITNO(SAFETY_EXT_WATCHDOG_RCC_MASK));
|
||||||
|
SAFETY_EXT_WATCHDOG_PORT->MODER &= MODER_DELETE(SAFETY_EXT_WATCHDOG_PIN);
|
||||||
|
#ifndef DEBUGBUILD
|
||||||
|
SAFETY_EXT_WATCHDOG_PORT->MODER |= OUTPUT(SAFETY_EXT_WATCHDOG_PIN);
|
||||||
|
SAFETY_EXT_WATCHDOG_PORT->ODR |= (1<<SAFETY_EXT_WATCHDOG_PIN);
|
||||||
|
#endif
|
||||||
|
__DSB();
|
||||||
|
}
|
||||||
|
|
||||||
void safety_controller_init()
|
void safety_controller_init()
|
||||||
{
|
{
|
||||||
enum safety_memory_state found_memory_state;
|
enum safety_memory_state found_memory_state;
|
||||||
enum safety_flag flags_in_err_mem = ERR_FLAG_NO_FLAG;
|
enum safety_flag flags_in_err_mem = ERR_FLAG_NO_FLAG;
|
||||||
|
enum hw_revision hw_rev;
|
||||||
|
|
||||||
int res;
|
int res;
|
||||||
|
|
||||||
/* Init the safety memory */
|
/* Init the safety memory */
|
||||||
@ -444,8 +710,15 @@ void safety_controller_init()
|
|||||||
|
|
||||||
stack_check_init_corruption_detect_area();
|
stack_check_init_corruption_detect_area();
|
||||||
|
|
||||||
|
hw_rev = get_pcb_hardware_version();
|
||||||
|
if (hw_rev == HW_REV_ERROR)
|
||||||
|
panic_mode();
|
||||||
|
if (hw_rev != HW_REV_V1_2)
|
||||||
|
safety_controller_init_external_watchdog();
|
||||||
|
|
||||||
init_safety_flag_weight_table_from_default();
|
init_safety_flag_weight_table_from_default();
|
||||||
init_safety_flag_persistencies_from_default();
|
init_safety_flag_persistencies_from_default();
|
||||||
|
apply_config_overrides();
|
||||||
|
|
||||||
if (found_memory_state == SAFETY_MEMORY_INIT_CORRUPTED)
|
if (found_memory_state == SAFETY_MEMORY_INIT_CORRUPTED)
|
||||||
safety_controller_report_error(ERR_FLAG_SAFETY_MEM_CORRUPT);
|
safety_controller_report_error(ERR_FLAG_SAFETY_MEM_CORRUPT);
|
||||||
@ -465,7 +738,7 @@ void safety_controller_init()
|
|||||||
safety_adc_init();
|
safety_adc_init();
|
||||||
watchdog_setup(WATCHDOG_PRESCALER);
|
watchdog_setup(WATCHDOG_PRESCALER);
|
||||||
|
|
||||||
if (watchdog_check_reset_source())
|
if (rcc_manager_get_reset_cause(false) & RCC_RESET_SOURCE_IWDG)
|
||||||
safety_controller_report_error(ERR_FLAG_WTCHDG_FIRED);
|
safety_controller_report_error(ERR_FLAG_WTCHDG_FIRED);
|
||||||
|
|
||||||
#ifdef DEBUGBUILD
|
#ifdef DEBUGBUILD
|
||||||
@ -473,6 +746,15 @@ void safety_controller_init()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Check the processor's stack
|
||||||
|
*
|
||||||
|
* This function checks the Stack of the application.
|
||||||
|
* The check consists of 2 parts:
|
||||||
|
*
|
||||||
|
* 1) Checking the remaining free space at the moment between stack pointer and top of heap.
|
||||||
|
* 2) Checking The CRC of the corruption detect area between heap and stack
|
||||||
|
*/
|
||||||
static void safety_controller_check_stack()
|
static void safety_controller_check_stack()
|
||||||
{
|
{
|
||||||
int32_t free_stack;
|
int32_t free_stack;
|
||||||
@ -486,52 +768,79 @@ static void safety_controller_check_stack()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handle the Safety ADC
|
||||||
|
*
|
||||||
|
* This function handles the safety ADC.
|
||||||
|
* If the safety ADC ius not executing a measurment and the time since the last measurement has
|
||||||
|
* passed @ref SAFETY_CONTROLLER_ADC_DELAY_MS, the safety ADC is retriggered and will automatically perform a measurement
|
||||||
|
* on all of its channels.
|
||||||
|
* When called again, this function will retrieve the data from the safety ADC and converts it into the
|
||||||
|
* appropriate analog values for the analog value monitors.
|
||||||
|
*
|
||||||
|
* The safety ADC is configured to perform multiple measurmeents of each physical channel. Therefore, this function
|
||||||
|
* fist calculated the mean value before converting them into the physical values.
|
||||||
|
*
|
||||||
|
* The channels, the ssafety ADC will convert is defined in its header file using the define @ref SAFETY_ADC_CHANNELS.
|
||||||
|
*/
|
||||||
static void safety_controller_handle_safety_adc()
|
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;
|
static uint64_t last_result_timestamp = 0;
|
||||||
|
const uint16_t *channels;
|
||||||
|
uint32_t sum;
|
||||||
int poll_result;
|
int poll_result;
|
||||||
uint16_t result;
|
|
||||||
float analog_value;
|
float analog_value;
|
||||||
|
|
||||||
poll_result = safety_adc_poll_result(&result);
|
poll_result = safety_adc_poll_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) {
|
||||||
if (poll_result == -1) {
|
/* Data available */
|
||||||
switch (current_channel) {
|
channels = safety_adc_get_values();
|
||||||
case SAFETY_ADC_MEAS_TEMP:
|
|
||||||
current_channel = SAFETY_ADC_MEAS_VREF;
|
/* Compute average of temp readings */
|
||||||
break;
|
sum = channels[0] + channels[1] + channels[2] + channels[3];
|
||||||
case SAFETY_ADC_MEAS_VREF:
|
sum /= 4;
|
||||||
/* Expected fallthru */
|
|
||||||
default:
|
analog_value = safety_adc_convert_channel(SAFETY_ADC_MEAS_TEMP, (uint16_t)sum);
|
||||||
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);
|
safety_controller_report_analog_value(ERR_AMON_UC_TEMP, analog_value);
|
||||||
break;
|
|
||||||
case SAFETY_ADC_MEAS_VREF:
|
/* Average VREF readings */
|
||||||
|
sum = channels[4] + channels[5] + channels[6] + channels[7];
|
||||||
|
sum /= 4;
|
||||||
|
|
||||||
|
analog_value = safety_adc_convert_channel(SAFETY_ADC_MEAS_VREF, (uint16_t)sum);
|
||||||
safety_controller_report_analog_value(ERR_AMON_VREF, analog_value);
|
safety_controller_report_analog_value(ERR_AMON_VREF, analog_value);
|
||||||
break;
|
|
||||||
default:
|
/* Compute supply voltage reading */
|
||||||
safety_controller_report_error(ERR_FLAG_SAFETY_ADC);
|
sum = channels[8] + channels[9] + channels[10] + channels[11];
|
||||||
break;
|
sum /= 4;
|
||||||
}
|
analog_value = safety_adc_convert_channel(SAFETY_ADC_MEAS_SUPPLY, (uint16_t)sum);
|
||||||
|
|
||||||
|
safety_controller_report_analog_value(ERR_AMON_SUPPLY_VOLT, analog_value);
|
||||||
|
|
||||||
|
last_result_timestamp = systick_get_global_tick();
|
||||||
|
safety_controller_report_timing(ERR_TIMING_SAFETY_ADC);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (systick_ticks_have_passed(last_result_timestamp, SAFETY_CONTROLLER_ADC_DELAY_MS)) {
|
||||||
|
if (poll_result != 1 && poll_result != 0)
|
||||||
|
safety_adc_trigger_meas();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Check the memory structures.
|
* @brief Check the memory structures
|
||||||
|
*
|
||||||
|
* This function checks multiple memory structures.
|
||||||
|
*
|
||||||
|
* 1) The safety memory in the backup RAM is checked using @ref safety_memory_check.
|
||||||
|
* In case of an error, the safety memory is reinitialized and the @ref ERR_FLAG_SAFETY_MEM_CORRUPT
|
||||||
|
* flag is set.
|
||||||
|
* 2) The flag weight table is CRC checked. In case of an error, the @ref ERR_FLAG_SAFETY_TAB_CORRUPT flag is set.
|
||||||
|
* Aditionally, the default flag weights are restored from Flash.
|
||||||
|
* 3) The flag persistency table is CRC checked. In case of an error, the @ref ERR_FLAG_SAFETY_TAB_CORRUPT flag is set.
|
||||||
|
* Aditionally, the default values of the flag persistence is restored from Flash.
|
||||||
*/
|
*/
|
||||||
static void safety_controller_handle_memory_checks(void)
|
static void safety_controller_handle_memory_checks(void)
|
||||||
{
|
{
|
||||||
@ -563,6 +872,12 @@ static void safety_controller_handle_memory_checks(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Check if the systick is ticking.
|
||||||
|
*
|
||||||
|
* If the systick stays constant for more than 1000 calls of this function,
|
||||||
|
* the @ref ERR_FLAG_SYSTICK flag is set.
|
||||||
|
*/
|
||||||
static void safety_controller_do_systick_checking()
|
static void safety_controller_do_systick_checking()
|
||||||
{
|
{
|
||||||
static uint64_t last_systick;
|
static uint64_t last_systick;
|
||||||
@ -580,34 +895,59 @@ static void safety_controller_do_systick_checking()
|
|||||||
last_systick = systick;
|
last_systick = systick;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handle weightet flags.
|
||||||
|
*
|
||||||
|
* This functions loops over all error flags and checks the weights. If a flag
|
||||||
|
* is set, the appropriate action defined by the flag weight is executed.
|
||||||
|
* @note If no flag weigth is present for a given error flag, it is treated as the most critical category
|
||||||
|
* (@ref SAFETY_FLAG_CONFIG_WEIGHT_PANIC)
|
||||||
|
*/
|
||||||
static void safety_controller_handle_weighted_flags()
|
static void safety_controller_handle_weighted_flags()
|
||||||
{
|
{
|
||||||
uint32_t weight_index;
|
uint32_t flag_index;
|
||||||
volatile struct safety_weight *current_weight;
|
volatile struct error_flag *current_flag;
|
||||||
|
enum config_weight flag_weigth;
|
||||||
|
|
||||||
for (weight_index = 0; weight_index < COUNT_OF(flag_weights); weight_index++) {
|
for (flag_index = 0u; flag_index < COUNT_OF(flags); flag_index++) {
|
||||||
current_weight = &flag_weights[weight_index];
|
current_flag = &flags[flag_index];
|
||||||
if (error_flag_get_status(current_weight->flag_ptr)) {
|
|
||||||
switch (current_weight->weight) {
|
/* Continue if this flag is not set */
|
||||||
|
if (!error_flag_get_status(current_flag)) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
flag_weigth = get_flag_weight(current_flag);
|
||||||
|
switch (flag_weigth) {
|
||||||
case SAFETY_FLAG_CONFIG_WEIGHT_NONE:
|
case SAFETY_FLAG_CONFIG_WEIGHT_NONE:
|
||||||
break;
|
break;
|
||||||
case SAFETY_FLAG_CONFIG_WEIGHT_PID:
|
case SAFETY_FLAG_CONFIG_WEIGHT_PID:
|
||||||
oven_pid_abort();
|
oven_pid_abort();
|
||||||
break;
|
break;
|
||||||
case SAFETY_FLAG_CONFIG_WEIGHT_PANIC:
|
case SAFETY_FLAG_CONFIG_WEIGHT_PANIC:
|
||||||
/* Expected fallthrough */
|
/* EXPECTED FALLTHRU */
|
||||||
default:
|
default:
|
||||||
oven_pid_abort();
|
oven_pid_abort();
|
||||||
panic_mode();
|
panic_mode();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifndef DEBUGBUILD
|
||||||
|
static void external_watchdog_toggle()
|
||||||
|
{
|
||||||
|
SAFETY_EXT_WATCHDOG_PORT->ODR ^= (1<<SAFETY_EXT_WATCHDOG_PIN);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
int safety_controller_handle()
|
int safety_controller_handle()
|
||||||
{
|
{
|
||||||
int ret = 0;
|
int ret = 0;
|
||||||
|
#ifndef DEBUGBUILD
|
||||||
|
static uint32_t watchdog_counter = 0UL;
|
||||||
|
#endif
|
||||||
|
|
||||||
safety_controller_check_stack();
|
safety_controller_check_stack();
|
||||||
safety_controller_handle_safety_adc();
|
safety_controller_handle_safety_adc();
|
||||||
@ -618,6 +958,15 @@ int safety_controller_handle()
|
|||||||
|
|
||||||
ret |= watchdog_ack(WATCHDOG_MAGIC_KEY);
|
ret |= watchdog_ack(WATCHDOG_MAGIC_KEY);
|
||||||
|
|
||||||
|
#ifndef DEBUGBUILD
|
||||||
|
if (get_pcb_hardware_version() != HW_REV_V1_2) {
|
||||||
|
watchdog_counter++;
|
||||||
|
if (watchdog_counter > 30) {
|
||||||
|
external_watchdog_toggle();
|
||||||
|
watchdog_counter = 0UL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
return (ret ? -1 : 0);
|
return (ret ? -1 : 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -832,6 +1181,7 @@ int safety_controller_get_analog_mon_by_index(uint32_t index, struct analog_moni
|
|||||||
info->min = mon->min;
|
info->min = mon->min;
|
||||||
info->value = mon->value;
|
info->value = mon->value;
|
||||||
info->timestamp = mon->timestamp;
|
info->timestamp = mon->timestamp;
|
||||||
|
info->associated_flag = mon->associated_flag;
|
||||||
|
|
||||||
if (!mon->valid) {
|
if (!mon->valid) {
|
||||||
info->status = ANALOG_MONITOR_INACTIVE;
|
info->status = ANALOG_MONITOR_INACTIVE;
|
||||||
|
@ -477,11 +477,136 @@ return_value:
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
int safety_memory_insert_config_override(struct config_override *config_override);
|
|
||||||
|
|
||||||
int safety_memory_get_config_override_count(uint32_t *count);
|
static uint32_t convert_config_override_to_word(const struct config_override *conf_override)
|
||||||
|
{
|
||||||
|
uint32_t data = 0;
|
||||||
|
|
||||||
int safety_memory_get_config_override(uint32_t idx, struct config_override *config_override);
|
if (conf_override->type == SAFETY_MEMORY_CONFIG_OVERRIDE_WEIGHT) {
|
||||||
|
data |= 0xAA0000A2UL;
|
||||||
|
data |= ((uint32_t)conf_override->entry.weight_override.flag) << 16;
|
||||||
|
data |= ((uint32_t)conf_override->entry.weight_override.weight) << 8;
|
||||||
|
} else if (conf_override->type == SAFETY_MEMORY_CONFIG_OVERRIDE_PERSISTENCE) {
|
||||||
|
data |= 0xBB00008EUL;
|
||||||
|
data |= ((uint32_t)conf_override->entry.persistance_override.flag) << 16;
|
||||||
|
data |= ((uint32_t)(conf_override->entry.persistance_override.persistance ? 1UL : 0UL)) << 8;
|
||||||
|
}
|
||||||
|
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
int safety_memory_insert_config_override(struct config_override *config_override)
|
||||||
|
{
|
||||||
|
struct safety_memory_header header;
|
||||||
|
uint32_t idx;
|
||||||
|
uint32_t data;
|
||||||
|
int res;
|
||||||
|
int ret = -3;
|
||||||
|
|
||||||
|
if (safety_memory_get_header(&header) != SAFETY_MEMORY_INIT_VALID_MEMORY) {
|
||||||
|
return -2000;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (header.config_overrides_len == 0)
|
||||||
|
return -1;
|
||||||
|
|
||||||
|
for (idx = 0; idx < header.config_overrides_len; idx++) {
|
||||||
|
res = backup_ram_get_data(header.config_overrides_offset + idx, &data, 1UL);
|
||||||
|
if (res)
|
||||||
|
return -2;
|
||||||
|
if (data == 0UL) {
|
||||||
|
data = convert_config_override_to_word(config_override);
|
||||||
|
res = backup_ram_write_data(header.config_overrides_offset + idx, &data, 1UL);
|
||||||
|
if (res)
|
||||||
|
return -4;
|
||||||
|
res = safety_memory_gen_crc();
|
||||||
|
if (res)
|
||||||
|
return -5;
|
||||||
|
ret = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
int safety_memory_get_config_override_count(uint32_t *count)
|
||||||
|
{
|
||||||
|
struct safety_memory_header header;
|
||||||
|
uint32_t iter;
|
||||||
|
uint32_t valid_count;
|
||||||
|
uint32_t data;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
if (!count)
|
||||||
|
return -1001;
|
||||||
|
|
||||||
|
*count = 0UL;
|
||||||
|
|
||||||
|
if (safety_memory_get_header(&header) != SAFETY_MEMORY_INIT_VALID_MEMORY) {
|
||||||
|
return -2000;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (header.config_overrides_len == 0)
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
valid_count = 0;
|
||||||
|
for (iter = 0; iter < header.config_overrides_len; iter++) {
|
||||||
|
res = backup_ram_get_data(header.config_overrides_offset + iter, &data, 1UL);
|
||||||
|
if (res)
|
||||||
|
return -2;
|
||||||
|
|
||||||
|
if (data != 0)
|
||||||
|
valid_count++;
|
||||||
|
else
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
*count = valid_count;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int safety_memory_get_config_override(uint32_t idx, struct config_override *config_override)
|
||||||
|
{
|
||||||
|
struct safety_memory_header header;
|
||||||
|
uint32_t data;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
if (!config_override)
|
||||||
|
return -1002;
|
||||||
|
|
||||||
|
if (safety_memory_get_header(&header) != SAFETY_MEMORY_INIT_VALID_MEMORY) {
|
||||||
|
return -2000;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (idx >= header.config_overrides_len) {
|
||||||
|
return -1001;
|
||||||
|
}
|
||||||
|
|
||||||
|
res = backup_ram_get_data(header.config_overrides_offset + idx, &data, 1UL);
|
||||||
|
if (res) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (data & 0xFF) {
|
||||||
|
case 0xA2:
|
||||||
|
/* Weight override */
|
||||||
|
config_override->type = SAFETY_MEMORY_CONFIG_OVERRIDE_WEIGHT;
|
||||||
|
config_override->entry.weight_override.flag = (data & 0xFF0000UL) >> 16;
|
||||||
|
config_override->entry.weight_override.weight = (data & 0xFF00UL) >> 8;
|
||||||
|
break;
|
||||||
|
case 0x8E:
|
||||||
|
/* persistance override */
|
||||||
|
config_override->type = SAFETY_MEMORY_CONFIG_OVERRIDE_PERSISTENCE;
|
||||||
|
config_override->entry.persistance_override.flag = (data & 0xFF0000UL) >> 16;
|
||||||
|
config_override->entry.persistance_override.persistance = ((data & 0xFF00UL) >> 8) ? true : false;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return -2;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
int safety_memory_dump_base64(char *buffer, size_t buffsize, size_t *used_size)
|
int safety_memory_dump_base64(char *buffer, size_t buffsize, size_t *used_size)
|
||||||
{
|
{
|
||||||
|
@ -105,16 +105,4 @@ int watchdog_ack(uint32_t magic)
|
|||||||
return ret;
|
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;
|
|
||||||
}
|
|
||||||
|
|
||||||
/** @} */
|
/** @} */
|
||||||
|
140
stm-firmware/settings/settings-eeprom.c
Normal file
140
stm-firmware/settings/settings-eeprom.c
Normal file
@ -0,0 +1,140 @@
|
|||||||
|
/* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <reflow-controller/settings/settings-eeprom.h>
|
||||||
|
#include <reflow-controller/settings/spi-eeprom.h>
|
||||||
|
#include <stm-periph/crc-unit.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#define EEPROM_HEADER_MAGIC 0xA5
|
||||||
|
#define EEPROM_HEADER_COMP_VER 0xFF
|
||||||
|
|
||||||
|
static const uint8_t expected_header[2] = {EEPROM_HEADER_MAGIC, EEPROM_HEADER_COMP_VER};
|
||||||
|
|
||||||
|
#define EEPROM_CALIBRATION_BASE_ADDR 0x2
|
||||||
|
struct eeprom_calibration_settings {
|
||||||
|
uint32_t active;
|
||||||
|
float offset;
|
||||||
|
float sens_dev;
|
||||||
|
uint32_t crc;
|
||||||
|
};
|
||||||
|
|
||||||
|
static bool check_eeprom_header(void)
|
||||||
|
{
|
||||||
|
uint8_t header[2] = {0};
|
||||||
|
|
||||||
|
/* Try to read the magic header and the compatible version */
|
||||||
|
spi_eeprom_read(0x0, header, 2);
|
||||||
|
if (memcmp(header, expected_header, 2))
|
||||||
|
return false;
|
||||||
|
else
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void settings_eeprom_zero()
|
||||||
|
{
|
||||||
|
settings_eeprom_save_calibration(0.0f, 0.0f, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool settings_eeprom_detect_and_prepare(void)
|
||||||
|
{
|
||||||
|
bool eeprom_ready = false;;
|
||||||
|
|
||||||
|
int res;
|
||||||
|
|
||||||
|
crc_unit_init();
|
||||||
|
res = spi_eeprom_init();
|
||||||
|
if (res)
|
||||||
|
goto ret_deinit_crc;
|
||||||
|
|
||||||
|
if (!spi_eeprom_check_connected())
|
||||||
|
goto ret_deinit_crc;
|
||||||
|
|
||||||
|
if (check_eeprom_header() == false) {
|
||||||
|
/* Try to write a new header and check it again */
|
||||||
|
spi_eeprom_write(0, expected_header, sizeof(expected_header));
|
||||||
|
while (spi_eeprom_write_in_progress());
|
||||||
|
if (check_eeprom_header() == false) {
|
||||||
|
goto ret_deinit_crc;
|
||||||
|
} else {
|
||||||
|
/* Sucessfully written new header
|
||||||
|
* Zero out the rest of the settings
|
||||||
|
*/
|
||||||
|
settings_eeprom_zero();
|
||||||
|
eeprom_ready = true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
eeprom_ready = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
goto exit;
|
||||||
|
|
||||||
|
ret_deinit_crc:
|
||||||
|
crc_unit_deinit();
|
||||||
|
|
||||||
|
exit:
|
||||||
|
return eeprom_ready;
|
||||||
|
}
|
||||||
|
|
||||||
|
int settings_eeprom_save_calibration(float sens, float offset, bool active)
|
||||||
|
{
|
||||||
|
int res;
|
||||||
|
|
||||||
|
struct eeprom_calibration_settings sett;
|
||||||
|
|
||||||
|
sett.active = (active ? 0xAABBCCDD : 0);
|
||||||
|
sett.offset = offset;
|
||||||
|
sett.sens_dev = sens;
|
||||||
|
|
||||||
|
crc_unit_reset();
|
||||||
|
crc_unit_input_array((const uint32_t *)&sett, (sizeof(sett) / 4)-1);
|
||||||
|
sett.crc = crc_unit_get_crc();
|
||||||
|
|
||||||
|
res = spi_eeprom_write(EEPROM_CALIBRATION_BASE_ADDR, (uint8_t *)&sett, sizeof(sett));
|
||||||
|
|
||||||
|
if (res)
|
||||||
|
return -2;
|
||||||
|
else
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int settings_eeprom_load_calibration(float *sens, float *offset, bool *active)
|
||||||
|
{
|
||||||
|
struct eeprom_calibration_settings sett;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
res = spi_eeprom_read(EEPROM_CALIBRATION_BASE_ADDR, (uint8_t *)&sett, sizeof(sett));
|
||||||
|
if (res)
|
||||||
|
return -2;
|
||||||
|
|
||||||
|
crc_unit_reset();
|
||||||
|
crc_unit_input_array((const uint32_t *)&sett, sizeof(sett) / 4 - 1);
|
||||||
|
if (crc_unit_get_crc() == sett.crc) {
|
||||||
|
if (sens)
|
||||||
|
*sens = sett.sens_dev;
|
||||||
|
if (offset)
|
||||||
|
*offset = sett.offset;
|
||||||
|
if (active)
|
||||||
|
*active = (sett.active ? true : false);
|
||||||
|
return 0;
|
||||||
|
} else {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
@ -136,7 +136,9 @@ int sd_card_settings_try_load_calibration(float *sens_deviation, float *offset)
|
|||||||
|
|
||||||
get_controller_settings_path(path, sizeof(path), "calibration");
|
get_controller_settings_path(path, sizeof(path), "calibration");
|
||||||
p = config_parser_open_file(&parser, false, path, workbuff, sizeof(workbuff));
|
p = config_parser_open_file(&parser, false, path, workbuff, sizeof(workbuff));
|
||||||
status = 0;
|
|
||||||
|
if (!p)
|
||||||
|
return status;
|
||||||
do {
|
do {
|
||||||
res = config_parser_get_line(p, &entry, true);
|
res = config_parser_get_line(p, &entry, true);
|
||||||
if (res == CONFIG_PARSER_OK) {
|
if (res == CONFIG_PARSER_OK) {
|
||||||
@ -149,10 +151,7 @@ int sd_card_settings_try_load_calibration(float *sens_deviation, float *offset)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
} while (res != CONFIG_PARSER_END_REACHED &&
|
} while (!config_parser_ret_is_abort_condition(res));
|
||||||
res != CONFIG_PARSER_GENERIC_ERR &&
|
|
||||||
res != CONFIG_PARSER_IOERR &&
|
|
||||||
res != CONFIG_PARSER_PARAM_ERR);
|
|
||||||
|
|
||||||
config_parser_close_file(p);
|
config_parser_close_file(p);
|
||||||
|
|
||||||
@ -171,6 +170,7 @@ enum settings_load_result sd_card_settings_load_pid_oven_parameters(struct oven_
|
|||||||
enum config_parser_ret parse_result;
|
enum config_parser_ret parse_result;
|
||||||
struct config_parser_entry entry;
|
struct config_parser_entry entry;
|
||||||
bool kp_loaded = false, kd_loaded = false, ki_loaded = false, int_max_loaded = false, t_sample = false;
|
bool kp_loaded = false, kd_loaded = false, ki_loaded = false, int_max_loaded = false, t_sample = false;
|
||||||
|
bool kd_tau_loaded = false;
|
||||||
|
|
||||||
if (!settings) {
|
if (!settings) {
|
||||||
ret = SETT_LOAD_ERR;
|
ret = SETT_LOAD_ERR;
|
||||||
@ -199,16 +199,16 @@ enum settings_load_result sd_card_settings_load_pid_oven_parameters(struct oven_
|
|||||||
} else if (!strcmp(entry.name, "sample_period")) {
|
} else if (!strcmp(entry.name, "sample_period")) {
|
||||||
t_sample = true;
|
t_sample = true;
|
||||||
settings->t_sample = entry.value.float_val / 1000.0f;
|
settings->t_sample = entry.value.float_val / 1000.0f;
|
||||||
|
} else if (!strcmp(entry.name, "kd_tau")) {
|
||||||
|
settings->kd_tau = entry.value.float_val;
|
||||||
|
kd_tau_loaded = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
} while (parse_result != CONFIG_PARSER_END_REACHED &&
|
} while (!config_parser_ret_is_abort_condition(parse_result));
|
||||||
parse_result != CONFIG_PARSER_GENERIC_ERR &&
|
|
||||||
parse_result != CONFIG_PARSER_IOERR &&
|
|
||||||
parse_result != CONFIG_PARSER_PARAM_ERR);
|
|
||||||
|
|
||||||
|
|
||||||
if (kp_loaded && kd_loaded && ki_loaded && t_sample && int_max_loaded)
|
if (kp_loaded && kd_loaded && ki_loaded && t_sample && int_max_loaded && kd_tau_loaded)
|
||||||
ret = SETT_LOAD_SUCCESS;
|
ret = SETT_LOAD_SUCCESS;
|
||||||
|
|
||||||
config_parser_close_file(p);
|
config_parser_close_file(p);
|
||||||
|
@ -20,19 +20,47 @@
|
|||||||
|
|
||||||
#include <reflow-controller/settings/settings.h>
|
#include <reflow-controller/settings/settings.h>
|
||||||
#include <reflow-controller/settings/settings-sd-card.h>
|
#include <reflow-controller/settings/settings-sd-card.h>
|
||||||
|
#include <reflow-controller/settings/settings-eeprom.h>
|
||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
|
|
||||||
|
bool settings_use_eeprom;
|
||||||
|
|
||||||
int settings_save_calibration(float sens_deviation, float offset, bool active)
|
int settings_save_calibration(float sens_deviation, float offset, bool active)
|
||||||
{
|
{
|
||||||
/* There is no other configuration location besides the SD card (yet) */
|
if (settings_use_eeprom)
|
||||||
|
return settings_eeprom_save_calibration(sens_deviation, offset, active);
|
||||||
|
else
|
||||||
return sd_card_settings_save_calibration(sens_deviation, offset, active);
|
return sd_card_settings_save_calibration(sens_deviation, offset, active);
|
||||||
}
|
}
|
||||||
|
|
||||||
int settings_load_calibration(float *sens_dev, float *offset)
|
int settings_load_calibration(float *sens_dev, float *offset)
|
||||||
{
|
{
|
||||||
return sd_card_settings_try_load_calibration(sens_dev, offset);
|
bool active;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
if (settings_use_eeprom) {
|
||||||
|
res =settings_eeprom_load_calibration(sens_dev, offset, &active);
|
||||||
|
if (!res && !active)
|
||||||
|
res = -1;
|
||||||
|
} else {
|
||||||
|
res = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (res)
|
||||||
|
res = sd_card_settings_try_load_calibration(sens_dev, offset);
|
||||||
|
|
||||||
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
enum settings_load_result settings_load_pid_oven_parameters(struct oven_pid_settings *settings)
|
enum settings_load_result settings_load_pid_oven_parameters(struct oven_pid_settings *settings)
|
||||||
{
|
{
|
||||||
return sd_card_settings_load_pid_oven_parameters(settings);
|
return sd_card_settings_load_pid_oven_parameters(settings);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void settings_setup(void)
|
||||||
|
{
|
||||||
|
if (get_pcb_hardware_version() >= HW_REV_V1_3)
|
||||||
|
settings_use_eeprom = settings_eeprom_detect_and_prepare();
|
||||||
|
else
|
||||||
|
settings_use_eeprom = false;
|
||||||
|
}
|
||||||
|
228
stm-firmware/settings/spi-eeprom.c
Normal file
228
stm-firmware/settings/spi-eeprom.c
Normal file
@ -0,0 +1,228 @@
|
|||||||
|
/* 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 <reflow-controller/settings/spi-eeprom.h>
|
||||||
|
#include <stm-periph/spi.h>
|
||||||
|
#include <reflow-controller/periph-config/spi-eeprom-hwcfg.h>
|
||||||
|
#include <stm-periph/rcc-manager.h>
|
||||||
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
#define EEPROM_SIZE 0x200
|
||||||
|
#define EEPROM_PAGE_SIZE 16
|
||||||
|
|
||||||
|
#define EEPROM_STATUS_REG_WIP (0x1U)
|
||||||
|
#define EEPROM_STATUS_REG_WEL (0x1U << 1)
|
||||||
|
#define EEPROM_STATUS_REG_BP0 (0x1U << 2)
|
||||||
|
#define EEPROM_STATUS_REG_BP1 (0x1U << 3)
|
||||||
|
|
||||||
|
#define EEPROM_CMD_READ_STATUS 0x05
|
||||||
|
#define EEPROM_CMD_WRITE_STATUS 0x01
|
||||||
|
#define EEPROM_CMD_READ_DATA 0x3
|
||||||
|
#define EEPROM_CMD_WRITE_DATA 0x2
|
||||||
|
#define EEPROM_CMD_WREN 0x6
|
||||||
|
#define EEPROM_CMD_WRDI 0x4
|
||||||
|
|
||||||
|
static stm_spi_handle eeprom_spi_handle;
|
||||||
|
|
||||||
|
static void eeprom_cs_activate(void)
|
||||||
|
{
|
||||||
|
SPI_EEPROM_SPI_PORT->ODR &= ~(1<<SPI_EEPROM_CS_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void eeprom_cs_deactivate(void)
|
||||||
|
{
|
||||||
|
SPI_EEPROM_SPI_PORT->ODR |= (1<<SPI_EEPROM_CS_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
|
int spi_eeprom_init()
|
||||||
|
{
|
||||||
|
static struct stm_spi_dev spi_dev;
|
||||||
|
struct stm_spi_settings settings;
|
||||||
|
|
||||||
|
rcc_manager_enable_clock(&SPI_EEPROM_SPI_PORT_RCC_REG, BITMASK_TO_BITNO(SPI_EEPROM_SPI_PORT_RCC_MASK));
|
||||||
|
|
||||||
|
SPI_EEPROM_SPI_PORT->MODER &= MODER_DELETE(SPI_EEPROM_CS_PIN) & MODER_DELETE(SPI_EEPROM_MISO_PIN) &
|
||||||
|
MODER_DELETE(SPI_EEPROM_MOSI_PIN) & MODER_DELETE(SPI_EEPROM_SCK_PIN);
|
||||||
|
SPI_EEPROM_SPI_PORT->MODER |= ALTFUNC(SPI_EEPROM_MISO_PIN) | ALTFUNC(SPI_EEPROM_SCK_PIN) | ALTFUNC(SPI_EEPROM_MOSI_PIN);
|
||||||
|
SPI_EEPROM_SPI_PORT->MODER |= OUTPUT(SPI_EEPROM_CS_PIN);
|
||||||
|
|
||||||
|
SETAF(SPI_EEPROM_SPI_PORT, SPI_EEPROM_MISO_PIN, SPI_EEPROM_SPI_ALTFUNC_NO);
|
||||||
|
SETAF(SPI_EEPROM_SPI_PORT, SPI_EEPROM_MOSI_PIN, SPI_EEPROM_SPI_ALTFUNC_NO);
|
||||||
|
SETAF(SPI_EEPROM_SPI_PORT, SPI_EEPROM_SCK_PIN, SPI_EEPROM_SPI_ALTFUNC_NO);
|
||||||
|
|
||||||
|
eeprom_cs_deactivate();
|
||||||
|
|
||||||
|
settings.cpha = false;
|
||||||
|
settings.cpol = false;
|
||||||
|
settings.cs_activate = eeprom_cs_activate;
|
||||||
|
settings.cs_deactivate = eeprom_cs_deactivate;
|
||||||
|
settings.master = true;
|
||||||
|
settings.msb_first = true;
|
||||||
|
settings.prescaler = SPI_PRSC_DIV16;
|
||||||
|
eeprom_spi_handle = spi_init(&spi_dev, SPI1, &settings);
|
||||||
|
|
||||||
|
if (eeprom_spi_handle)
|
||||||
|
return 0;
|
||||||
|
else
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void spi_eeprom_deinit()
|
||||||
|
{
|
||||||
|
spi_deinit(eeprom_spi_handle);
|
||||||
|
|
||||||
|
SPI_EEPROM_SPI_PORT->MODER &= MODER_DELETE(SPI_EEPROM_CS_PIN) & MODER_DELETE(SPI_EEPROM_MISO_PIN) &
|
||||||
|
MODER_DELETE(SPI_EEPROM_MOSI_PIN) & MODER_DELETE(SPI_EEPROM_SCK_PIN);
|
||||||
|
|
||||||
|
rcc_manager_disable_clock(&SPI_EEPROM_SPI_PORT_RCC_REG, BITMASK_TO_BITNO(SPI_EEPROM_SPI_PORT_RCC_MASK));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t spi_eeprom_read_status_reg(void)
|
||||||
|
{
|
||||||
|
uint8_t buff[2] = {0x05, 0x00};
|
||||||
|
|
||||||
|
(void)spi_transfer(eeprom_spi_handle, buff, buff, 2, true);
|
||||||
|
|
||||||
|
return buff[1];
|
||||||
|
}
|
||||||
|
|
||||||
|
static void spi_eeprom_set_write_enable_latch(bool status)
|
||||||
|
{
|
||||||
|
uint8_t cmd;
|
||||||
|
|
||||||
|
if (status)
|
||||||
|
cmd = EEPROM_CMD_WREN;
|
||||||
|
else
|
||||||
|
cmd = EEPROM_CMD_WRDI;
|
||||||
|
|
||||||
|
(void)spi_transfer(eeprom_spi_handle, &cmd, NULL, 1, true);
|
||||||
|
}
|
||||||
|
|
||||||
|
int spi_eeprom_read(uint32_t addr, uint8_t *rx_buff, uint32_t count)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
int retry = 250;
|
||||||
|
uint8_t status_reg;
|
||||||
|
uint8_t cmd[2];
|
||||||
|
|
||||||
|
if (!rx_buff || !count)
|
||||||
|
return -1000;
|
||||||
|
|
||||||
|
if (addr >= EEPROM_SIZE)
|
||||||
|
return -1001;
|
||||||
|
|
||||||
|
do {
|
||||||
|
status_reg = spi_eeprom_read_status_reg();
|
||||||
|
} while ((status_reg & EEPROM_STATUS_REG_WIP) && retry--);
|
||||||
|
|
||||||
|
if (status_reg & EEPROM_STATUS_REG_WIP)
|
||||||
|
return -1;
|
||||||
|
|
||||||
|
cmd[0] = EEPROM_CMD_READ_DATA;
|
||||||
|
if (addr & (1<<8))
|
||||||
|
cmd[0] |= (1U<<3);
|
||||||
|
cmd[1] = (uint8_t)(addr & 0xFF);
|
||||||
|
|
||||||
|
eeprom_cs_activate();
|
||||||
|
spi_transfer(eeprom_spi_handle, cmd, NULL, 2, false);
|
||||||
|
spi_transfer(eeprom_spi_handle, NULL, rx_buff, count, false);
|
||||||
|
eeprom_cs_deactivate();
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spi_eeprom_write_in_progress(void)
|
||||||
|
{
|
||||||
|
uint8_t status_reg;
|
||||||
|
|
||||||
|
status_reg = spi_eeprom_read_status_reg();
|
||||||
|
|
||||||
|
if (status_reg & EEPROM_STATUS_REG_WIP)
|
||||||
|
return true;
|
||||||
|
else
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void spi_eeprom_do_write_page(uint32_t addr, const uint8_t *data, uint8_t len)
|
||||||
|
{
|
||||||
|
uint8_t cmd[2];
|
||||||
|
|
||||||
|
/* Wait for the previous write to finish */
|
||||||
|
while (spi_eeprom_write_in_progress());
|
||||||
|
/* Set the write enable latch */
|
||||||
|
spi_eeprom_set_write_enable_latch(true);
|
||||||
|
|
||||||
|
cmd[0] = EEPROM_CMD_WRITE_DATA | ((addr & (1<<8)) ? (1<<4) : 0);
|
||||||
|
cmd[1] = (uint8_t)(addr & 0xFF);
|
||||||
|
|
||||||
|
eeprom_cs_activate();
|
||||||
|
spi_transfer(eeprom_spi_handle, cmd, NULL, 2, false);
|
||||||
|
spi_transfer(eeprom_spi_handle, data, NULL, len, false);
|
||||||
|
eeprom_cs_deactivate();
|
||||||
|
}
|
||||||
|
|
||||||
|
int spi_eeprom_write(uint32_t addr, const uint8_t *data, uint32_t count)
|
||||||
|
{
|
||||||
|
const uint8_t *ptr = data;
|
||||||
|
uint32_t transfer_len;
|
||||||
|
|
||||||
|
if (!data || !count)
|
||||||
|
return -1000;
|
||||||
|
|
||||||
|
if (addr >= EEPROM_SIZE)
|
||||||
|
return -1001;
|
||||||
|
|
||||||
|
while (count > 0) {
|
||||||
|
/* Calculate size for current page transfer */
|
||||||
|
transfer_len = EEPROM_PAGE_SIZE - (addr % EEPROM_PAGE_SIZE);
|
||||||
|
if (transfer_len > count)
|
||||||
|
transfer_len = count;
|
||||||
|
|
||||||
|
spi_eeprom_do_write_page(addr, ptr, transfer_len);
|
||||||
|
count -= transfer_len;
|
||||||
|
addr += transfer_len;
|
||||||
|
ptr += transfer_len;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spi_eeprom_check_connected(void)
|
||||||
|
{
|
||||||
|
uint8_t status_reg;
|
||||||
|
|
||||||
|
/* Try to set write enable latch */
|
||||||
|
spi_eeprom_set_write_enable_latch(true);
|
||||||
|
|
||||||
|
/* Read back status register */
|
||||||
|
status_reg = spi_eeprom_read_status_reg();
|
||||||
|
if (!(status_reg & EEPROM_STATUS_REG_WEL))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
/* Clear the latch */
|
||||||
|
spi_eeprom_set_write_enable_latch(false);
|
||||||
|
/* Read back status register */
|
||||||
|
status_reg = spi_eeprom_read_status_reg();
|
||||||
|
if ((status_reg & EEPROM_STATUS_REG_WEL))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
@ -40,6 +40,7 @@
|
|||||||
#include <reflow-controller/button.h>
|
#include <reflow-controller/button.h>
|
||||||
#include <reflow-controller/safety/fault.h>
|
#include <reflow-controller/safety/fault.h>
|
||||||
#include <reflow-controller/safety/safety-memory.h>
|
#include <reflow-controller/safety/safety-memory.h>
|
||||||
|
#include <reflow-controller/hw-version-detect.h>
|
||||||
|
|
||||||
#ifndef GIT_VER
|
#ifndef GIT_VER
|
||||||
#define GIT_VER "VERSION NOT SET"
|
#define GIT_VER "VERSION NOT SET"
|
||||||
@ -48,7 +49,7 @@
|
|||||||
extern struct stm_uart shell_uart;
|
extern struct stm_uart shell_uart;
|
||||||
static shellmatta_instance_t shell;
|
static shellmatta_instance_t shell;
|
||||||
static char shell_buffer[512];
|
static char shell_buffer[512];
|
||||||
static char IN_SECTION(.ccm.bss) history_buffer[600];
|
static char IN_SECTION(.ccm.bss) history_buffer[512];
|
||||||
|
|
||||||
static bool check_opt(const char *args, uint32_t len, const char *opt_to_check)
|
static bool check_opt(const char *args, uint32_t len, const char *opt_to_check)
|
||||||
{
|
{
|
||||||
@ -81,12 +82,28 @@ static shellmatta_retCode_t shell_cmd_ver(const shellmatta_handle_t handle,
|
|||||||
uint32_t low_id;
|
uint32_t low_id;
|
||||||
uint32_t mid_id;
|
uint32_t mid_id;
|
||||||
uint32_t high_id;
|
uint32_t high_id;
|
||||||
|
const char *hw_rev_str;
|
||||||
|
enum hw_revision pcb_rev;
|
||||||
|
|
||||||
unique_id_get(&high_id, &mid_id, &low_id);
|
unique_id_get(&high_id, &mid_id, &low_id);
|
||||||
|
|
||||||
shellmatta_printf(handle, "Reflow Oven Controller Firmware " xstr(GIT_VER) "\r\n"
|
shellmatta_printf(handle, "Reflow Oven Controller Firmware " xstr(GIT_VER) "\r\n"
|
||||||
"Compiled: " __DATE__ " at " __TIME__ "\r\n");
|
"Compiled: " __DATE__ " at " __TIME__ "\r\n");
|
||||||
shellmatta_printf(handle, "Serial: %08X-%08X-%08X", high_id, mid_id, low_id);
|
shellmatta_printf(handle, "Serial: %08X-%08X-%08X\r\n", high_id, mid_id, low_id);
|
||||||
|
|
||||||
|
pcb_rev = get_pcb_hardware_version();
|
||||||
|
switch (pcb_rev) {
|
||||||
|
case HW_REV_V1_2:
|
||||||
|
hw_rev_str = "Hardware: v1.2";
|
||||||
|
break;
|
||||||
|
case HW_REV_V1_3:
|
||||||
|
hw_rev_str = "Hardware: v1.3";
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
hw_rev_str = "Hardware: Unknown Revision. You might have to update the firmware!";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
shellmatta_printf(handle, "%s", hw_rev_str);
|
||||||
|
|
||||||
return SHELLMATTA_OK;
|
return SHELLMATTA_OK;
|
||||||
}
|
}
|
||||||
@ -386,7 +403,7 @@ static shellmatta_retCode_t shell_cmd_read_flags(const shellmatta_handle_t handl
|
|||||||
/* Check for the --ack option */
|
/* Check for the --ack option */
|
||||||
tryack = check_opt(arguments, length, "--ack");
|
tryack = check_opt(arguments, length, "--ack");
|
||||||
|
|
||||||
shellmatta_printf(handle, "Error flags\r\n"
|
shellmatta_printf(handle, "Error Flags\r\n"
|
||||||
"-----------\r\n");
|
"-----------\r\n");
|
||||||
|
|
||||||
count = safety_controller_get_flag_count();
|
count = safety_controller_get_flag_count();
|
||||||
@ -440,7 +457,7 @@ static shellmatta_retCode_t shell_cmd_read_flags(const shellmatta_handle_t handl
|
|||||||
}
|
}
|
||||||
|
|
||||||
shellmatta_printf(handle, "\r\nTiming Monitors\r\n"
|
shellmatta_printf(handle, "\r\nTiming Monitors\r\n"
|
||||||
"--------------\r\n");
|
"---------------\r\n");
|
||||||
|
|
||||||
|
|
||||||
count = safety_controller_get_timing_monitor_count();
|
count = safety_controller_get_timing_monitor_count();
|
||||||
@ -659,6 +676,22 @@ shellmatta_retCode_t shell_cmd_reset_cal(const shellmatta_handle_t handle, const
|
|||||||
return SHELLMATTA_OK;
|
return SHELLMATTA_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
shellmatta_retCode_t shell_cmd_update(const shellmatta_handle_t handle, const char *arguments, uint32_t length)
|
||||||
|
{
|
||||||
|
(void)handle;
|
||||||
|
(void)arguments;
|
||||||
|
(void)length;
|
||||||
|
struct safety_memory_boot_status status;
|
||||||
|
|
||||||
|
safety_memory_get_boot_status(&status);
|
||||||
|
status.reboot_to_bootloader = 0xFFFFFFFFUL;
|
||||||
|
safety_memory_set_boot_status(&status);
|
||||||
|
|
||||||
|
NVIC_SystemReset();
|
||||||
|
|
||||||
|
return SHELLMATTA_OK;
|
||||||
|
}
|
||||||
|
|
||||||
//typedef struct shellmatta_cmd
|
//typedef struct shellmatta_cmd
|
||||||
//{
|
//{
|
||||||
// char *cmd; /**< command name */
|
// char *cmd; /**< command name */
|
||||||
@ -668,7 +701,7 @@ shellmatta_retCode_t shell_cmd_reset_cal(const shellmatta_handle_t handle, const
|
|||||||
// shellmatta_cmdFct_t cmdFct; /**< pointer to the cmd callack function */
|
// shellmatta_cmdFct_t cmdFct; /**< pointer to the cmd callack function */
|
||||||
// struct shellmatta_cmd *next; /**< pointer to next command or NULL */
|
// struct shellmatta_cmd *next; /**< pointer to next command or NULL */
|
||||||
//} shellmatta_cmd_t;
|
//} shellmatta_cmd_t;
|
||||||
static shellmatta_cmd_t cmd[19] = {
|
static shellmatta_cmd_t cmd[20] = {
|
||||||
{
|
{
|
||||||
.cmd = "version",
|
.cmd = "version",
|
||||||
.cmdAlias = "ver",
|
.cmdAlias = "ver",
|
||||||
@ -819,7 +852,16 @@ static shellmatta_cmd_t cmd[19] = {
|
|||||||
.helpText = "Reset Calibration",
|
.helpText = "Reset Calibration",
|
||||||
.usageText = "",
|
.usageText = "",
|
||||||
.cmdFct = shell_cmd_reset_cal,
|
.cmdFct = shell_cmd_reset_cal,
|
||||||
|
.next = &cmd[19],
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.cmd = "update",
|
||||||
|
.cmdAlias = NULL,
|
||||||
|
.helpText = "Update Firmware",
|
||||||
|
.usageText = "",
|
||||||
|
.cmdFct = shell_cmd_update,
|
||||||
.next = NULL,
|
.next = NULL,
|
||||||
|
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1 +1 @@
|
|||||||
Subproject commit 1b7cdb1acc0c8d34b10a1e4cd3ae61447c772f4a
|
Subproject commit 28e82c65dee828a9a2f0e5ea3c7160c8b1638271
|
@ -19,7 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stm-periph/backup-ram.h>
|
#include <stm-periph/backup-ram.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
|
|
||||||
|
@ -19,7 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stm-periph/crc-unit.h>
|
#include <stm-periph/crc-unit.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
void crc_unit_init(void)
|
void crc_unit_init(void)
|
||||||
|
@ -29,7 +29,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stm-periph/dma-ring-buffer.h>
|
#include <stm-periph/dma-ring-buffer.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
|
@ -18,9 +18,10 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
struct rcc_enable_count {
|
struct rcc_enable_count {
|
||||||
volatile uint32_t *rcc_reg_addr;
|
volatile uint32_t *rcc_reg_addr;
|
||||||
@ -153,3 +154,30 @@ int rcc_manager_disable_clock(volatile uint32_t *rcc_enable_register, uint8_t bi
|
|||||||
|
|
||||||
return ret_val;
|
return ret_val;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
enum rcc_reset_source rcc_manager_get_reset_cause(bool clear_flags)
|
||||||
|
{
|
||||||
|
enum rcc_reset_source ret = 0;
|
||||||
|
uint32_t rcc_csr;
|
||||||
|
|
||||||
|
rcc_csr = RCC->CSR;
|
||||||
|
if (rcc_csr & RCC_CSR_LPWRRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_LOW_POWER;
|
||||||
|
if (rcc_csr & RCC_CSR_WWDGRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_WWD;
|
||||||
|
if (rcc_csr & RCC_CSR_WDGRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_IWDG;
|
||||||
|
if (rcc_csr & RCC_CSR_SFTRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_SOFTWARE;
|
||||||
|
if (rcc_csr & RCC_CSR_PORRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_POWER_ON;
|
||||||
|
if (rcc_csr & RCC_CSR_PADRSTF)
|
||||||
|
ret |= RCC_RESET_SOURCE_PIN;
|
||||||
|
if (rcc_csr & RCC_CSR_BORRSTF)
|
||||||
|
ret |= RCC_RESET_BOR_POR;
|
||||||
|
|
||||||
|
if (clear_flags)
|
||||||
|
RCC->CSR |= RCC_CSR_RMVF;
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
@ -19,7 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stm-periph/rng.h>
|
#include <stm-periph/rng.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
void random_number_gen_init(bool int_enable)
|
void random_number_gen_init(bool int_enable)
|
||||||
|
167
stm-firmware/stm-periph/spi.c
Normal file
167
stm-firmware/stm-periph/spi.c
Normal file
@ -0,0 +1,167 @@
|
|||||||
|
/* 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/spi.h>
|
||||||
|
#include <helper-macros/helper-macros.h>
|
||||||
|
#include <stm-periph/rcc-manager.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#define STM_SPI_DEV_MAGIC 0x5A678F5CUL
|
||||||
|
|
||||||
|
struct spi_rcc_lookup_pair {
|
||||||
|
SPI_TypeDef *spi_regs;
|
||||||
|
volatile uint32_t *rcc_reg;
|
||||||
|
uint32_t bit_no;
|
||||||
|
};
|
||||||
|
|
||||||
|
const struct spi_rcc_lookup_pair rcc_lookup[3] = {
|
||||||
|
{SPI1, &RCC->APB2ENR, BITMASK_TO_BITNO(RCC_APB2ENR_SPI1EN)},
|
||||||
|
{SPI2, &RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB1ENR_SPI2EN)},
|
||||||
|
{SPI3, &RCC->APB1ENR, BITMASK_TO_BITNO(RCC_APB1ENR_SPI3EN)},
|
||||||
|
};
|
||||||
|
|
||||||
|
static const struct spi_rcc_lookup_pair *spi_find_rcc_reg_and_bit(SPI_TypeDef *spi_regs)
|
||||||
|
{
|
||||||
|
uint32_t i;
|
||||||
|
const struct spi_rcc_lookup_pair *ret = NULL;
|
||||||
|
|
||||||
|
for (i = 0; i < COUNT_OF(rcc_lookup); i++) {
|
||||||
|
if (rcc_lookup[i].spi_regs == spi_regs) {
|
||||||
|
ret = &rcc_lookup[i];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
static struct stm_spi_dev *spi_handle_to_struct(stm_spi_handle handle)
|
||||||
|
{
|
||||||
|
struct stm_spi_dev *dev;
|
||||||
|
|
||||||
|
dev = (struct stm_spi_dev *)handle;
|
||||||
|
if (dev == NULL)
|
||||||
|
return NULL;
|
||||||
|
if (dev->magic != STM_SPI_DEV_MAGIC)
|
||||||
|
return NULL;
|
||||||
|
|
||||||
|
return dev;
|
||||||
|
}
|
||||||
|
|
||||||
|
stm_spi_handle spi_init(struct stm_spi_dev *spi_dev_struct, SPI_TypeDef *spi_regs, const struct stm_spi_settings *settings)
|
||||||
|
{
|
||||||
|
stm_spi_handle ret_handle = NULL;
|
||||||
|
uint32_t reg_val;
|
||||||
|
const struct spi_rcc_lookup_pair *rcc_pair;
|
||||||
|
|
||||||
|
if (!spi_dev_struct || !spi_regs || !settings)
|
||||||
|
goto exit;
|
||||||
|
if (!settings->cs_activate || !settings->cs_deactivate)
|
||||||
|
goto exit;
|
||||||
|
|
||||||
|
rcc_pair = spi_find_rcc_reg_and_bit(spi_regs);
|
||||||
|
if (!rcc_pair)
|
||||||
|
goto exit;
|
||||||
|
|
||||||
|
memcpy(&spi_dev_struct->settings, settings, sizeof(struct stm_spi_settings));
|
||||||
|
spi_dev_struct->spi_regs = spi_regs;
|
||||||
|
|
||||||
|
rcc_manager_enable_clock(rcc_pair->rcc_reg, rcc_pair->bit_no);
|
||||||
|
|
||||||
|
reg_val = 0;
|
||||||
|
if (settings->cpha)
|
||||||
|
reg_val |= SPI_CR1_CPHA;
|
||||||
|
if (settings->cpol)
|
||||||
|
reg_val |= SPI_CR1_CPOL;
|
||||||
|
if (settings->master)
|
||||||
|
reg_val |= SPI_CR1_MSTR;
|
||||||
|
reg_val |= (settings->prescaler & 0x7) << 3;
|
||||||
|
reg_val |= SPI_CR1_SPE | SPI_CR1_SSI | SPI_CR1_SSM;
|
||||||
|
|
||||||
|
if (!settings->msb_first)
|
||||||
|
reg_val |= SPI_CR1_LSBFIRST;
|
||||||
|
|
||||||
|
spi_regs->CR2 = 0UL;
|
||||||
|
spi_regs->CR1 = reg_val;
|
||||||
|
|
||||||
|
ret_handle = spi_dev_struct;
|
||||||
|
|
||||||
|
spi_dev_struct->settings.cs_deactivate();
|
||||||
|
spi_dev_struct->magic = STM_SPI_DEV_MAGIC;
|
||||||
|
|
||||||
|
exit:
|
||||||
|
return ret_handle;
|
||||||
|
}
|
||||||
|
|
||||||
|
void spi_deinit(stm_spi_handle handle)
|
||||||
|
{
|
||||||
|
const struct spi_rcc_lookup_pair *rcc_pair;
|
||||||
|
struct stm_spi_dev *dev;
|
||||||
|
|
||||||
|
dev = spi_handle_to_struct(handle);
|
||||||
|
if (!dev)
|
||||||
|
return;
|
||||||
|
|
||||||
|
dev->magic = 0UL;
|
||||||
|
|
||||||
|
dev->spi_regs->CR1 = 0;
|
||||||
|
dev->spi_regs->CR2 = 0;
|
||||||
|
|
||||||
|
rcc_pair = spi_find_rcc_reg_and_bit(dev->spi_regs);
|
||||||
|
if (!rcc_pair)
|
||||||
|
rcc_manager_disable_clock(rcc_pair->rcc_reg, rcc_pair->bit_no);
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t transfer_byte(uint8_t byte, struct stm_spi_dev *dev)
|
||||||
|
{
|
||||||
|
while (dev->spi_regs->SR & SPI_SR_BSY);
|
||||||
|
dev->spi_regs->DR = (uint16_t)byte;
|
||||||
|
__DSB();
|
||||||
|
while((dev->spi_regs->SR & SPI_SR_BSY) || !(dev->spi_regs->SR & SPI_SR_TXE));
|
||||||
|
|
||||||
|
return (uint8_t)dev->spi_regs->DR;
|
||||||
|
}
|
||||||
|
|
||||||
|
int spi_transfer(stm_spi_handle handle, const uint8_t *tx, uint8_t *rx, uint32_t count, bool handle_cs)
|
||||||
|
{
|
||||||
|
struct stm_spi_dev *dev;
|
||||||
|
uint8_t tx_byte;
|
||||||
|
uint8_t rx_byte;
|
||||||
|
uint32_t idx;
|
||||||
|
|
||||||
|
dev = spi_handle_to_struct(handle);
|
||||||
|
if (!dev)
|
||||||
|
return -1001;
|
||||||
|
|
||||||
|
if (handle_cs)
|
||||||
|
dev->settings.cs_activate();
|
||||||
|
|
||||||
|
for (idx = 0; idx < count; idx++) {
|
||||||
|
tx_byte = (tx ? tx[idx] : 0U);
|
||||||
|
rx_byte = transfer_byte(tx_byte, dev);
|
||||||
|
if (rx)
|
||||||
|
rx[idx] = rx_byte;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (handle_cs)
|
||||||
|
dev->settings.cs_deactivate();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
@ -20,7 +20,7 @@
|
|||||||
|
|
||||||
#include <stm-periph/uart.h>
|
#include <stm-periph/uart.h>
|
||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <stm-periph/dma-ring-buffer.h>
|
#include <stm-periph/dma-ring-buffer.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
@ -20,7 +20,7 @@
|
|||||||
* RAM: 128K
|
* RAM: 128K
|
||||||
* CCM RAM: 64L
|
* CCM RAM: 64L
|
||||||
* FPU: fpv4-sp-d16
|
* FPU: fpv4-sp-d16
|
||||||
*
|
*/
|
||||||
|
|
||||||
/* USER PARAMETERS */
|
/* USER PARAMETERS */
|
||||||
__ld_stack_size = 0x3000;
|
__ld_stack_size = 0x3000;
|
||||||
|
@ -18,13 +18,15 @@
|
|||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <reflow-controller/reflow-menu.h>
|
#include <reflow-controller/ui/gui.h>
|
||||||
|
#include <reflow-controller/ui/gui-config.h>
|
||||||
#include <reflow-controller/ui/menu.h>
|
#include <reflow-controller/ui/menu.h>
|
||||||
#include <reflow-controller/ui/lcd.h>
|
#include <reflow-controller/ui/lcd.h>
|
||||||
#include <reflow-controller/rotary-encoder.h>
|
#include <reflow-controller/rotary-encoder.h>
|
||||||
#include <reflow-controller/systick.h>
|
#include <reflow-controller/systick.h>
|
||||||
#include <reflow-controller/adc-meas.h>
|
#include <reflow-controller/adc-meas.h>
|
||||||
#include <reflow-controller/safety/safety-controller.h>
|
#include <reflow-controller/safety/safety-controller.h>
|
||||||
|
#include <reflow-controller/settings/settings.h>
|
||||||
#include <reflow-controller/temp-converter.h>
|
#include <reflow-controller/temp-converter.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stm-periph/unique-id.h>
|
#include <stm-periph/unique-id.h>
|
||||||
@ -33,6 +35,7 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
#include <reflow-controller/oven-driver.h>
|
||||||
|
|
||||||
static char IN_SECTION(.ccm.bss) display_buffer[4][21] = {0};
|
static char IN_SECTION(.ccm.bss) display_buffer[4][21] = {0};
|
||||||
static struct lcd_menu IN_SECTION(.ccm.bss) reflow_menu;
|
static struct lcd_menu IN_SECTION(.ccm.bss) reflow_menu;
|
||||||
@ -54,7 +57,7 @@ static void update_display_buffer(uint8_t row, const char *data)
|
|||||||
display_buffer[row][i] = 0;
|
display_buffer[row][i] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reflow_menu_monitor(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
static void gui_menu_monitor(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
{
|
{
|
||||||
static void *my_parent;
|
static void *my_parent;
|
||||||
static uint64_t my_timestamp = 0;
|
static uint64_t my_timestamp = 0;
|
||||||
@ -68,7 +71,7 @@ static void reflow_menu_monitor(struct lcd_menu *menu, enum menu_entry_func_entr
|
|||||||
menu_display_clear(menu);
|
menu_display_clear(menu);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (systick_ticks_have_passed(my_timestamp, 250)) {
|
if (systick_ticks_have_passed(my_timestamp, GUI_MONITORING_INTERVAL_MS)) {
|
||||||
my_timestamp = systick_get_global_tick();
|
my_timestamp = systick_get_global_tick();
|
||||||
adc_pt1000_get_current_resistance(&tmp);
|
adc_pt1000_get_current_resistance(&tmp);
|
||||||
snprintf(line, sizeof(line), "Res: %.1f " LCD_OHM_SYMBOL_STRING, tmp);
|
snprintf(line, sizeof(line), "Res: %.1f " LCD_OHM_SYMBOL_STRING, tmp);
|
||||||
@ -104,7 +107,7 @@ static void reflow_menu_monitor(struct lcd_menu *menu, enum menu_entry_func_entr
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reflow_menu_about(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
static void gui_menu_about(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
{
|
{
|
||||||
static void *my_parent;
|
static void *my_parent;
|
||||||
static int page = 0;
|
static int page = 0;
|
||||||
@ -217,7 +220,7 @@ static void reflow_menu_about(struct lcd_menu *menu, enum menu_entry_func_entry
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reflow_menu_err_flags(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
static void gui_menu_err_flags(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
{
|
{
|
||||||
static void *my_parent = NULL;
|
static void *my_parent = NULL;
|
||||||
static uint8_t offset;
|
static uint8_t offset;
|
||||||
@ -297,21 +300,128 @@ static void reflow_menu_err_flags(struct lcd_menu *menu, enum menu_entry_func_en
|
|||||||
timestamp = systick_get_global_tick();
|
timestamp = systick_get_global_tick();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reflow_menu_root_entry(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
static void gui_menu_constant_temperature_driver(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
|
{
|
||||||
|
static void IN_SECTION(.ccm.bss) *my_parent;
|
||||||
|
static int16_t IN_SECTION(.ccm.bss) temperature;
|
||||||
|
static bool IN_SECTION(.ccm.bss) fine;
|
||||||
|
static uint64_t IN_SECTION(.ccm.bss) last_temp_refresh;
|
||||||
|
static float IN_SECTION(.ccm.bss) last_temp;
|
||||||
|
enum button_state button;
|
||||||
|
float current_temp;
|
||||||
|
int status;
|
||||||
|
int16_t rot;
|
||||||
|
int16_t temp_old;
|
||||||
|
|
||||||
|
if (entry_type == MENU_ENTRY_FIRST_ENTER) {
|
||||||
|
my_parent = parent;
|
||||||
|
last_temp = -2000.0f;
|
||||||
|
temperature = 30;
|
||||||
|
menu_display_clear(menu);
|
||||||
|
menu_lcd_outputf(menu, 0, "Temp Controller");
|
||||||
|
temp_old = 0;
|
||||||
|
} else {
|
||||||
|
temp_old = temperature;
|
||||||
|
}
|
||||||
|
if (menu_get_button_ready_state(menu)) {
|
||||||
|
button = menu_get_button_state(menu);
|
||||||
|
rot = menu_get_rotary_delta(menu);
|
||||||
|
if (rot >= 4 || rot <= -4) {
|
||||||
|
menu_ack_rotary_delta(menu);
|
||||||
|
if (rot > 0)
|
||||||
|
temperature += (fine ? 1 : 10);
|
||||||
|
else
|
||||||
|
temperature -= (fine ? 1 : 10);
|
||||||
|
if (temperature > 300)
|
||||||
|
temperature = 300;
|
||||||
|
else if (temperature < 0)
|
||||||
|
temperature = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (button) {
|
||||||
|
case BUTTON_SHORT_RELEASED:
|
||||||
|
fine = !fine;
|
||||||
|
break;
|
||||||
|
case BUTTON_LONG:
|
||||||
|
oven_pid_stop();
|
||||||
|
menu_entry_dropback(menu, my_parent);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (oven_pid_get_status() != OVEN_PID_RUNNING) {
|
||||||
|
menu_lcd_output(menu, 1, "PID stopped!");
|
||||||
|
menu_lcd_output(menu, 2, "Check Flags!");
|
||||||
|
} else {
|
||||||
|
if (temperature != temp_old) {
|
||||||
|
oven_pid_set_target_temperature((float)temperature);
|
||||||
|
menu_lcd_outputf(menu, 1, "Target: %d " LCD_DEGREE_SYMBOL_STRING "C", (int)temperature);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (entry_type == MENU_ENTRY_FIRST_ENTER || systick_ticks_have_passed(last_temp_refresh, GUI_TEMP_DRIVER_REFRESH_MS)) {
|
||||||
|
(void)adc_pt1000_get_current_resistance(¤t_temp);
|
||||||
|
status = temp_converter_convert_resistance_to_temp(current_temp, ¤t_temp);
|
||||||
|
if (current_temp != last_temp) {
|
||||||
|
last_temp = current_temp;
|
||||||
|
menu_lcd_outputf(menu, 2, "Current: %s%.1f", current_temp, (status < 0 ? "<" : status > 0 ? ">" : ""));
|
||||||
|
}
|
||||||
|
last_temp_refresh = systick_get_global_tick();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static void gui_menu_constant_temperature_driver_setup(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
|
{
|
||||||
|
static void IN_SECTION(.ccm.bss) *my_parent;
|
||||||
|
struct oven_pid_settings pid_settings;
|
||||||
|
enum button_state button;
|
||||||
|
struct pid_controller pid_controller;
|
||||||
|
|
||||||
|
if (entry_type == MENU_ENTRY_FIRST_ENTER) {
|
||||||
|
my_parent = parent;
|
||||||
|
|
||||||
|
/* Try loading PID parameters */
|
||||||
|
if (settings_load_pid_oven_parameters(&pid_settings)) {
|
||||||
|
menu_display_clear(menu);
|
||||||
|
menu_lcd_output(menu, 0, "Could not load");
|
||||||
|
menu_lcd_output(menu, 1, "PID parameters");
|
||||||
|
} else {
|
||||||
|
pid_init(&pid_controller, pid_settings.kd, pid_settings.ki, pid_settings.kp, 0, 100,
|
||||||
|
pid_settings.max_integral, pid_settings.kd_tau, pid_settings.t_sample);
|
||||||
|
oven_pid_init(&pid_controller);
|
||||||
|
menu_entry_enter(menu, gui_menu_constant_temperature_driver, true);
|
||||||
|
}
|
||||||
|
} else if (entry_type == MENU_ENTRY_DROPBACK) {
|
||||||
|
menu_entry_dropback(menu, my_parent);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (menu_get_button_ready_state(menu)) {
|
||||||
|
button = menu_get_button_state(menu);
|
||||||
|
if (button == BUTTON_SHORT_RELEASED || button == BUTTON_LONG) {
|
||||||
|
menu_entry_dropback(menu, my_parent);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void gui_menu_root_entry(struct lcd_menu *menu, enum menu_entry_func_entry entry_type, void *parent)
|
||||||
{
|
{
|
||||||
(void)parent;
|
(void)parent;
|
||||||
static struct menu_list list;
|
static struct menu_list list;
|
||||||
bool menu_changed = false;
|
bool menu_changed = false;
|
||||||
static const char * const root_entry_names[] = {
|
static const char * const root_entry_names[] = {
|
||||||
"About",
|
"Constant Temp",
|
||||||
"Monitoring",
|
"Monitoring",
|
||||||
"Error Flags",
|
"Error Flags",
|
||||||
|
"About",
|
||||||
NULL
|
NULL
|
||||||
};
|
};
|
||||||
static const menu_func_t root_entry_funcs[] = {
|
static const menu_func_t root_entry_funcs[] = {
|
||||||
reflow_menu_about,
|
gui_menu_constant_temperature_driver_setup,
|
||||||
reflow_menu_monitor,
|
gui_menu_monitor,
|
||||||
reflow_menu_err_flags,
|
gui_menu_err_flags,
|
||||||
|
gui_menu_about,
|
||||||
};
|
};
|
||||||
enum button_state push_button;
|
enum button_state push_button;
|
||||||
int16_t rot_delta;
|
int16_t rot_delta;
|
||||||
@ -352,7 +462,7 @@ static void reflow_menu_root_entry(struct lcd_menu *menu, enum menu_entry_func_e
|
|||||||
menu_list_display(&list, 1, 3);
|
menu_list_display(&list, 1, 3);
|
||||||
}
|
}
|
||||||
|
|
||||||
int reflow_menu_handle()
|
int gui_handle()
|
||||||
{
|
{
|
||||||
int32_t rot_delta;
|
int32_t rot_delta;
|
||||||
enum button_state button;
|
enum button_state button;
|
||||||
@ -374,11 +484,11 @@ int reflow_menu_handle()
|
|||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void reflow_menu_init()
|
void gui_init()
|
||||||
{
|
{
|
||||||
rotary_encoder_setup();
|
rotary_encoder_setup();
|
||||||
button_init();
|
button_init();
|
||||||
lcd_init();
|
lcd_init();
|
||||||
|
|
||||||
menu_init(reflow_menu_ptr, reflow_menu_root_entry, update_display_buffer);
|
menu_init(reflow_menu_ptr, gui_menu_root_entry, update_display_buffer);
|
||||||
}
|
}
|
@ -26,7 +26,7 @@
|
|||||||
#include <stm32/stm32f4xx.h>
|
#include <stm32/stm32f4xx.h>
|
||||||
#include <reflow-controller/ui/lcd.h>
|
#include <reflow-controller/ui/lcd.h>
|
||||||
#include <reflow-controller/systick.h>
|
#include <reflow-controller/systick.h>
|
||||||
#include <stm-periph/clock-enable-manager.h>
|
#include <stm-periph/rcc-manager.h>
|
||||||
#include <stm-periph/stm32-gpio-macros.h>
|
#include <stm-periph/stm32-gpio-macros.h>
|
||||||
#include <helper-macros/helper-macros.h>
|
#include <helper-macros/helper-macros.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
@ -81,6 +81,8 @@ void menu_entry_dropback(struct lcd_menu *menu, menu_func_t parent_func)
|
|||||||
else
|
else
|
||||||
menu->active_entry = menu->root_entry;
|
menu->active_entry = menu->root_entry;
|
||||||
|
|
||||||
|
menu_ack_rotary_delta(menu);
|
||||||
|
|
||||||
menu->active_entry_type = MENU_ENTRY_DROPBACK;
|
menu->active_entry_type = MENU_ENTRY_DROPBACK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
6
stm-firmware/updater/ram-code/.gitignore
vendored
Normal file
6
stm-firmware/updater/ram-code/.gitignore
vendored
Normal file
@ -0,0 +1,6 @@
|
|||||||
|
obj/*
|
||||||
|
*.bin
|
||||||
|
*.bin.h
|
||||||
|
*.bin.?
|
||||||
|
*.elf
|
||||||
|
*.map
|
82
stm-firmware/updater/ram-code/Makefile
Normal file
82
stm-firmware/updater/ram-code/Makefile
Normal file
@ -0,0 +1,82 @@
|
|||||||
|
RAM_CODE_TARGET = updater-ram-code
|
||||||
|
target = $(RAM_CODE_TARGET)
|
||||||
|
OBJDIR = obj
|
||||||
|
CFILES = main.c startup.c hex-parser.c
|
||||||
|
CFILES += fatfs/ff.c fatfs/diskio.c fatfs/ffsystem.c fatfs/ffunicode.c fatfs/shimatta_sdio_driver/shimatta_sdio.c
|
||||||
|
LINKER_SCRIPT = ram-link.ld
|
||||||
|
MAPFILE = $(RAM_CODE_TARGET)
|
||||||
|
PREFIX = arm-none-eabi-
|
||||||
|
|
||||||
|
CC = $(PREFIX)gcc
|
||||||
|
OBJCOPY = $(PREFIX)objcopy
|
||||||
|
SIZE = $(PREFIX)size
|
||||||
|
|
||||||
|
ifneq ($(VERBOSE),true)
|
||||||
|
QUIET=@
|
||||||
|
else
|
||||||
|
QUIET=
|
||||||
|
endif
|
||||||
|
|
||||||
|
|
||||||
|
DEFINES = -DSTM32F407xx -DSTM32F4XX -DHSE_VALUE=8000000UL
|
||||||
|
INCLUDEPATH = -Iinclude
|
||||||
|
|
||||||
|
LFLAGS = -mlittle-endian -mthumb -mcpu=cortex-m4 -mthumb-interwork
|
||||||
|
LFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 --disable-newlib-supplied-syscalls -nostartfiles
|
||||||
|
LFLAGS += -T$(LINKER_SCRIPT) -Wl,-Map=$(MAPFILE).map -Wl,--print-memory-usage -g3
|
||||||
|
|
||||||
|
CFLAGS = -c -mlittle-endian -mthumb -mcpu=cortex-m4 -mthumb-interwork -Os -g3
|
||||||
|
CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 -nostartfiles
|
||||||
|
CFLAGS += -Wall -Wextra -Wold-style-declaration -Wuninitialized -Wmaybe-uninitialized -Wunused-parameter -Wimplicit-fallthrough=3 -Wsign-compare
|
||||||
|
|
||||||
|
OBJ = $(CFILES:%.c=$(OBJDIR)/%.c.o)
|
||||||
|
|
||||||
|
default: $(RAM_CODE_TARGET).bin.h
|
||||||
|
|
||||||
|
all: $(RAM_CODE_TARGET).bin.h
|
||||||
|
|
||||||
|
%.bin.h: %.bin
|
||||||
|
@echo "[BIN2H] $@"
|
||||||
|
$(QUIET)python bin2carray.py $@ $^
|
||||||
|
|
||||||
|
$(RAM_CODE_TARGET).bin: $(RAM_CODE_TARGET).elf
|
||||||
|
@echo "[ELF2BIN] $@"
|
||||||
|
$(QUIET)$(OBJCOPY) -O binary $^ $@
|
||||||
|
|
||||||
|
$(RAM_CODE_TARGET).elf: $(OBJ) $(LINKER_SCRIPT)
|
||||||
|
@echo [LD] $@
|
||||||
|
$(QUIET)$(CC) $(LFLAGS) $(LIBRARYPATH) -o $@ $(OBJ) $(ASOBJ) $(LIBRARIES)
|
||||||
|
$(QUIET)$(SIZE) $@
|
||||||
|
|
||||||
|
$(OBJ):
|
||||||
|
@echo [CC] $@
|
||||||
|
$(eval OUTPATH=$(dir $@))
|
||||||
|
@mkdir -p $(OUTPATH)
|
||||||
|
$(QUIET)$(CC) $(CFLAGS) -MMD -MT $@ $(INCLUDEPATH) $(DEFINES) -o $@ $(@:$(OBJDIR)/%.c.o=%.c)
|
||||||
|
|
||||||
|
.PHONY: clean qtproject
|
||||||
|
|
||||||
|
clean:
|
||||||
|
@echo [CLEAN]
|
||||||
|
$(QUIET)rm -f $(OBJ) $(MAPFILE).map $(CFILES:%.c=$(OBJDIR)/%.c.d) $(RAM_CODE_TARGET).bin $(RAM_CODE_TARGET).elf $(RAM_CODE_TARGET).bin.c
|
||||||
|
|
||||||
|
qtproject:
|
||||||
|
$(QUIET)rm -f $(target).files $(target).cflags $(target).config $(target).creator $(target).includes $(target).creator.user
|
||||||
|
@echo "Generating source file list"
|
||||||
|
$(QUIET)echo "$(CFILES)" | tr ' ' '\n' > $(target).files
|
||||||
|
@echo -n "Appending found header files from folders "
|
||||||
|
@echo `echo $(INCLUDEPATH) | sed "s/-I//g"`
|
||||||
|
$(QUIET)for dir in `echo $(INCLUDEPATH) | sed "s/-I//g"`; do \
|
||||||
|
find `echo "$${dir}"` -name "*.h" >> $(target).files; \
|
||||||
|
done
|
||||||
|
@echo "Generating $(target).cflags"
|
||||||
|
$(QUIET)echo "" > $(target).cflags
|
||||||
|
@echo "Generating $(target).includes"
|
||||||
|
$(QUIET)echo $(INCLUDEPATH) | sed "s/-I/,/g" | tr , '\n' | sed "/^$$/d" > $(target).includes;
|
||||||
|
@echo "Generating $(target).config"
|
||||||
|
$(QUIET)echo $(DEFINES) | sed "s/-D/,#define /g" | tr , '\n' | sed "/^$$/d" > $(target).config
|
||||||
|
@echo "Generating $(target).creator"
|
||||||
|
$(QUIET)echo "[GENERAL]" > $(target).creator
|
||||||
|
|
||||||
|
-include $(CFILES:%.c=$(OBJDIR)/%.c.d)
|
||||||
|
|
34
stm-firmware/updater/ram-code/bin2carray.py
Executable file
34
stm-firmware/updater/ram-code/bin2carray.py
Executable file
@ -0,0 +1,34 @@
|
|||||||
|
#!env python
|
||||||
|
|
||||||
|
# Convert a file to a c array
|
||||||
|
# bin2carray <output file> <input file>
|
||||||
|
|
||||||
|
import os
|
||||||
|
import sys
|
||||||
|
|
||||||
|
if len(sys.argv) < 3:
|
||||||
|
sys.exit(-1)
|
||||||
|
|
||||||
|
source_file = sys.argv[2]
|
||||||
|
dest_file = sys.argv[1]
|
||||||
|
|
||||||
|
print("%s --> %s" % (source_file, dest_file))
|
||||||
|
|
||||||
|
with open(source_file, "rb") as src:
|
||||||
|
data = src.read()
|
||||||
|
|
||||||
|
with open(dest_file, "w") as dest:
|
||||||
|
header_guard = "__" + dest_file.replace('.', '_').replace('-', '_') + "_H__"
|
||||||
|
dest.write("#ifndef %s\n" % (header_guard))
|
||||||
|
dest.write("#define %s\n" % (header_guard))
|
||||||
|
dest.write("static const char binary_blob[%d] = {\n" % (len(data)))
|
||||||
|
for current,idx in zip(data, range(len(data))):
|
||||||
|
if ((idx+1) % 4 == 0):
|
||||||
|
dest.write(hex(current)+",\n")
|
||||||
|
else:
|
||||||
|
dest.write(hex(current)+",")
|
||||||
|
|
||||||
|
dest.write("};\n")
|
||||||
|
dest.write("#endif /* %s */\n" % (header_guard))
|
||||||
|
|
||||||
|
sys.exit(0)
|
119
stm-firmware/updater/ram-code/fatfs/diskio.c
Normal file
119
stm-firmware/updater/ram-code/fatfs/diskio.c
Normal file
@ -0,0 +1,119 @@
|
|||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Low level disk I/O module skeleton for FatFs (C)ChaN, 2019 */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* If a working storage control module is available, it should be */
|
||||||
|
/* attached to the FatFs via a glue function rather than modifying it. */
|
||||||
|
/* This is an example of glue functions to attach various exsisting */
|
||||||
|
/* storage control modules to the FatFs module with a defined API. */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#include <fatfs/ff.h> /* Obtains integer types */
|
||||||
|
#include <fatfs/diskio.h> /* Declarations of disk functions */
|
||||||
|
#include "shimatta_sdio_driver/shimatta_sdio.h"
|
||||||
|
|
||||||
|
/* Definitions of physical drive number for each drive */
|
||||||
|
#define DEV_SD 0 /* Example: Map MMC/SD card to physical drive 0*/
|
||||||
|
/*
|
||||||
|
DSTATUS SDIO_status();
|
||||||
|
DSTATUS SDIO_initialize();
|
||||||
|
DRESULT SDIO_disk_read(BYTE *buff, DWORD sector, UINT count);
|
||||||
|
DRESULT SDIO_disk_write(const BYTE *buff, DWORD sector, UINT count);
|
||||||
|
DRESULT SDIO_disk_ioctl(BYTE cmd, void* buff);
|
||||||
|
*/
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Get Drive Status */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
DSTATUS disk_status (
|
||||||
|
BYTE pdrv /* Physical drive nmuber to identify the drive */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
|
||||||
|
switch (pdrv) {
|
||||||
|
case DEV_SD:
|
||||||
|
return sdio_status();
|
||||||
|
}
|
||||||
|
return STA_NOINIT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Inidialize a Drive */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
DSTATUS disk_initialize (
|
||||||
|
BYTE pdrv /* Physical drive nmuber to identify the drive */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
switch (pdrv) {
|
||||||
|
case DEV_SD:
|
||||||
|
return sdio_initialize();
|
||||||
|
}
|
||||||
|
return STA_NOINIT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Read Sector(s) */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
DRESULT disk_read (
|
||||||
|
BYTE pdrv, /* Physical drive nmuber to identify the drive */
|
||||||
|
BYTE *buff, /* Data buffer to store read data */
|
||||||
|
LBA_t sector, /* Start sector in LBA */
|
||||||
|
UINT count /* Number of sectors to read */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
switch (pdrv) {
|
||||||
|
case DEV_SD:
|
||||||
|
return sdio_disk_read(buff, sector, count);
|
||||||
|
}
|
||||||
|
return RES_PARERR;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Write Sector(s) */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#if FF_FS_READONLY == 0
|
||||||
|
|
||||||
|
DRESULT disk_write (
|
||||||
|
BYTE pdrv, /* Physical drive nmuber to identify the drive */
|
||||||
|
const BYTE *buff, /* Data to be written */
|
||||||
|
LBA_t sector, /* Start sector in LBA */
|
||||||
|
UINT count /* Number of sectors to write */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
switch (pdrv) {
|
||||||
|
case DEV_SD:
|
||||||
|
return sdio_disk_write(buff, sector, count);
|
||||||
|
}
|
||||||
|
|
||||||
|
return RES_PARERR;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
/* Miscellaneous Functions */
|
||||||
|
/*-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
DRESULT disk_ioctl (
|
||||||
|
BYTE pdrv, /* Physical drive nmuber (0..) */
|
||||||
|
BYTE cmd, /* Control code */
|
||||||
|
void *buff /* Buffer to send/receive control data */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
switch (pdrv) {
|
||||||
|
case DEV_SD:
|
||||||
|
return sdio_disk_ioctl(cmd, buff);
|
||||||
|
}
|
||||||
|
|
||||||
|
return RES_PARERR;
|
||||||
|
}
|
||||||
|
|
6848
stm-firmware/updater/ram-code/fatfs/ff.c
Normal file
6848
stm-firmware/updater/ram-code/fatfs/ff.c
Normal file
File diff suppressed because it is too large
Load Diff
170
stm-firmware/updater/ram-code/fatfs/ffsystem.c
Normal file
170
stm-firmware/updater/ram-code/fatfs/ffsystem.c
Normal file
@ -0,0 +1,170 @@
|
|||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Sample Code of OS Dependent Functions for FatFs */
|
||||||
|
/* (C)ChaN, 2018 */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
#include <fatfs/ff.h>
|
||||||
|
|
||||||
|
|
||||||
|
#if FF_USE_LFN == 3 /* Dynamic memory allocation */
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Allocate a memory block */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
void* ff_memalloc ( /* Returns pointer to the allocated memory block (null if not enough core) */
|
||||||
|
UINT msize /* Number of bytes to allocate */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
return malloc(msize); /* Allocate a new memory block with POSIX API */
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Free a memory block */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
void ff_memfree (
|
||||||
|
void* mblock /* Pointer to the memory block to free (nothing to do if null) */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
free(mblock); /* Free the memory block with POSIX API */
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#if FF_FS_REENTRANT /* Mutal exclusion */
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Create a Synchronization Object */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* This function is called in f_mount() function to create a new
|
||||||
|
/ synchronization object for the volume, such as semaphore and mutex.
|
||||||
|
/ When a 0 is returned, the f_mount() function fails with FR_INT_ERR.
|
||||||
|
*/
|
||||||
|
|
||||||
|
//const osMutexDef_t Mutex[FF_VOLUMES]; /* Table of CMSIS-RTOS mutex */
|
||||||
|
|
||||||
|
|
||||||
|
int ff_cre_syncobj ( /* 1:Function succeeded, 0:Could not create the sync object */
|
||||||
|
BYTE vol, /* Corresponding volume (logical drive number) */
|
||||||
|
FF_SYNC_t* sobj /* Pointer to return the created sync object */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
/* Win32 */
|
||||||
|
*sobj = CreateMutex(NULL, FALSE, NULL);
|
||||||
|
return (int)(*sobj != INVALID_HANDLE_VALUE);
|
||||||
|
|
||||||
|
/* uITRON */
|
||||||
|
// T_CSEM csem = {TA_TPRI,1,1};
|
||||||
|
// *sobj = acre_sem(&csem);
|
||||||
|
// return (int)(*sobj > 0);
|
||||||
|
|
||||||
|
/* uC/OS-II */
|
||||||
|
// OS_ERR err;
|
||||||
|
// *sobj = OSMutexCreate(0, &err);
|
||||||
|
// return (int)(err == OS_NO_ERR);
|
||||||
|
|
||||||
|
/* FreeRTOS */
|
||||||
|
// *sobj = xSemaphoreCreateMutex();
|
||||||
|
// return (int)(*sobj != NULL);
|
||||||
|
|
||||||
|
/* CMSIS-RTOS */
|
||||||
|
// *sobj = osMutexCreate(&Mutex[vol]);
|
||||||
|
// return (int)(*sobj != NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Delete a Synchronization Object */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* This function is called in f_mount() function to delete a synchronization
|
||||||
|
/ object that created with ff_cre_syncobj() function. When a 0 is returned,
|
||||||
|
/ the f_mount() function fails with FR_INT_ERR.
|
||||||
|
*/
|
||||||
|
|
||||||
|
int ff_del_syncobj ( /* 1:Function succeeded, 0:Could not delete due to an error */
|
||||||
|
FF_SYNC_t sobj /* Sync object tied to the logical drive to be deleted */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
/* Win32 */
|
||||||
|
return (int)CloseHandle(sobj);
|
||||||
|
|
||||||
|
/* uITRON */
|
||||||
|
// return (int)(del_sem(sobj) == E_OK);
|
||||||
|
|
||||||
|
/* uC/OS-II */
|
||||||
|
// OS_ERR err;
|
||||||
|
// OSMutexDel(sobj, OS_DEL_ALWAYS, &err);
|
||||||
|
// return (int)(err == OS_NO_ERR);
|
||||||
|
|
||||||
|
/* FreeRTOS */
|
||||||
|
// vSemaphoreDelete(sobj);
|
||||||
|
// return 1;
|
||||||
|
|
||||||
|
/* CMSIS-RTOS */
|
||||||
|
// return (int)(osMutexDelete(sobj) == osOK);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Request Grant to Access the Volume */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* This function is called on entering file functions to lock the volume.
|
||||||
|
/ When a 0 is returned, the file function fails with FR_TIMEOUT.
|
||||||
|
*/
|
||||||
|
|
||||||
|
int ff_req_grant ( /* 1:Got a grant to access the volume, 0:Could not get a grant */
|
||||||
|
FF_SYNC_t sobj /* Sync object to wait */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
/* Win32 */
|
||||||
|
return (int)(WaitForSingleObject(sobj, FF_FS_TIMEOUT) == WAIT_OBJECT_0);
|
||||||
|
|
||||||
|
/* uITRON */
|
||||||
|
// return (int)(wai_sem(sobj) == E_OK);
|
||||||
|
|
||||||
|
/* uC/OS-II */
|
||||||
|
// OS_ERR err;
|
||||||
|
// OSMutexPend(sobj, FF_FS_TIMEOUT, &err));
|
||||||
|
// return (int)(err == OS_NO_ERR);
|
||||||
|
|
||||||
|
/* FreeRTOS */
|
||||||
|
// return (int)(xSemaphoreTake(sobj, FF_FS_TIMEOUT) == pdTRUE);
|
||||||
|
|
||||||
|
/* CMSIS-RTOS */
|
||||||
|
// return (int)(osMutexWait(sobj, FF_FS_TIMEOUT) == osOK);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* Release Grant to Access the Volume */
|
||||||
|
/*------------------------------------------------------------------------*/
|
||||||
|
/* This function is called on leaving file functions to unlock the volume.
|
||||||
|
*/
|
||||||
|
|
||||||
|
void ff_rel_grant (
|
||||||
|
FF_SYNC_t sobj /* Sync object to be signaled */
|
||||||
|
)
|
||||||
|
{
|
||||||
|
/* Win32 */
|
||||||
|
ReleaseMutex(sobj);
|
||||||
|
|
||||||
|
/* uITRON */
|
||||||
|
// sig_sem(sobj);
|
||||||
|
|
||||||
|
/* uC/OS-II */
|
||||||
|
// OSMutexPost(sobj);
|
||||||
|
|
||||||
|
/* FreeRTOS */
|
||||||
|
// xSemaphoreGive(sobj);
|
||||||
|
|
||||||
|
/* CMSIS-RTOS */
|
||||||
|
// osMutexRelease(sobj);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
15593
stm-firmware/updater/ram-code/fatfs/ffunicode.c
Normal file
15593
stm-firmware/updater/ram-code/fatfs/ffunicode.c
Normal file
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,800 @@
|
|||||||
|
#include "shimatta_sdio.h"
|
||||||
|
#include "shimatta_sdio_config.h"
|
||||||
|
#include <cmsis/core_cm4.h>
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
extern void sdio_wait_ms(unsigned int i);
|
||||||
|
|
||||||
|
#define SETAF(PORT,PIN,AF) PORT->AFR[(PIN < 8 ? 0 : 1)] |= AF << ((PIN < 8 ? PIN : (PIN - 8)) * 4)
|
||||||
|
|
||||||
|
#define READCTRL ((BLOCKSIZE << 4) | SDIO_DCTRL_DMAEN)
|
||||||
|
#define DMAP2M (DMA_SxCR_CHSEL_2 | DMA_SxCR_PBURST_0 | DMA_SxCR_MBURST_0 | DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_PFCTRL)
|
||||||
|
#define DMAM2P (DMA_SxCR_CHSEL_2 | DMA_SxCR_PBURST_0 | DMA_SxCR_MBURST_0 | DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_PFCTRL | DMA_SxCR_DIR_0)
|
||||||
|
#define SHORT_ANS 1
|
||||||
|
#define LONG_ANS 3
|
||||||
|
#define NO_ANS 0
|
||||||
|
|
||||||
|
#define CCRCFAIL 1
|
||||||
|
#define CTIMEOUT 2
|
||||||
|
#define CNOTEXPETED 3
|
||||||
|
|
||||||
|
/* OCR Register Masks */
|
||||||
|
#define OCS_CCS (1<<30)
|
||||||
|
#define OCS_BUSY (1<<31)
|
||||||
|
|
||||||
|
enum acmd41_ret {ACMD41_RESP_INIT = 0, ACMD41_RESP_ERR, ACMD41_RESP_SDSC, ACMD41_RESP_SDXC};
|
||||||
|
enum cmd8_ret {CMD8_RESP_TIMEOUT = 0, CMD8_VOLTAGE_ACCEPTED, CMD8_VOLTAGE_DENIED};
|
||||||
|
typedef uint8_t CID_t;
|
||||||
|
|
||||||
|
static struct sd_info card_info; // = {.type = CARD_NONE};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief checkNotInserted
|
||||||
|
* @return return 0 if card is inserted, else 1
|
||||||
|
*/
|
||||||
|
int sdio_check_inserted() {
|
||||||
|
#if SDIO_ENABLE_INS
|
||||||
|
return ((INS_PORT->IDR & (1<<INS_PIN)) == (INS_ACTIVE_LEVEL<<INS_PIN) ? 0 : 1);
|
||||||
|
#else
|
||||||
|
return 0; // Assume Card is inserted
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief checkWriteProtection
|
||||||
|
* @return 0 if card is writable.
|
||||||
|
*/
|
||||||
|
static int sdio_check_write_protection() {
|
||||||
|
#if SDIO_ENABLE_WRITEPROT
|
||||||
|
return ((WRITEPROT_PORT->IDR & (1<<WRITEPROT_PIN)) == (WRITEPROT_ACTIVE_LEVEL<<WRITEPROT_PIN) ? 1 : 0);
|
||||||
|
#else
|
||||||
|
return 0; // Assume Card is not write protected
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void sdio_wait_cmd_sent()
|
||||||
|
{
|
||||||
|
while (!(SDIO->STA & SDIO_STA_CMDSENT));
|
||||||
|
SDIO->ICR |= SDIO_ICR_CMDSENTC;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_cmd(uint8_t cmd, uint32_t arg, uint8_t expected_ans){
|
||||||
|
/* Clear Flags */
|
||||||
|
SDIO->ICR = SDIO_ICR_CCRCFAILC | SDIO_ICR_CMDRENDC | SDIO_ICR_CTIMEOUTC | SDIO_ICR_CMDSENTC;
|
||||||
|
/* Send command */
|
||||||
|
SDIO->ARG = arg;
|
||||||
|
SDIO->CMD = (cmd & SDIO_CMD_CMDINDEX) | SDIO_CMD_CPSMEN | ((expected_ans << 6) & SDIO_CMD_WAITRESP);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_get_response(uint8_t expected_command, uint8_t type_of_answer, uint32_t *response_buffer) {
|
||||||
|
uint32_t sdio_status;
|
||||||
|
|
||||||
|
/* Wait until command isn't active anymore */
|
||||||
|
while (SDIO->STA & SDIO_STA_CMDACT);
|
||||||
|
|
||||||
|
/* Wait for error or success */
|
||||||
|
while (1) {
|
||||||
|
sdio_status = SDIO->STA;
|
||||||
|
|
||||||
|
/* Check if a valid response was received */
|
||||||
|
if (sdio_status & SDIO_STA_CMDREND)
|
||||||
|
break;
|
||||||
|
|
||||||
|
if ((sdio_status & SDIO_STA_CMDSENT) && (type_of_answer == NO_ANS))
|
||||||
|
break; // No response required
|
||||||
|
|
||||||
|
/* Exclude ACMD41 and CMD2 from valid CRC check */
|
||||||
|
if ((sdio_status & SDIO_STA_CCRCFAIL)) {
|
||||||
|
if(expected_command == 0xff) {
|
||||||
|
break;
|
||||||
|
} else {
|
||||||
|
return -CCRCFAIL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sdio_status & SDIO_STA_CTIMEOUT)
|
||||||
|
return -CTIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Valid Respone Received */
|
||||||
|
if (((SDIO->RESPCMD & SDIO_RESPCMD_RESPCMD) != expected_command) && (expected_command != 0xff))
|
||||||
|
return -CNOTEXPETED; //Not the expected respose
|
||||||
|
|
||||||
|
/* If case of a correct Response */
|
||||||
|
*(response_buffer++) = SDIO->RESP1;
|
||||||
|
|
||||||
|
/* Long response */
|
||||||
|
if (type_of_answer == LONG_ANS) {
|
||||||
|
*(response_buffer++) = SDIO->RESP2;
|
||||||
|
*(response_buffer++) = SDIO->RESP3;
|
||||||
|
*(response_buffer++) = SDIO->RESP4;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Switch the card to application mode. It now accepts ACMDXX commands
|
||||||
|
* @return 0 if successfuls
|
||||||
|
*/
|
||||||
|
static int sdio_switch_appmode_cmd55()
|
||||||
|
{
|
||||||
|
int retry = 0x20;
|
||||||
|
union sdio_status_conv converter;
|
||||||
|
uint32_t response;
|
||||||
|
do {
|
||||||
|
/* Execute Command and check for valid response */
|
||||||
|
sdio_send_cmd(55, (card_info.rca<<16)&0xFFFF0000, SHORT_ANS);
|
||||||
|
|
||||||
|
if (!sdio_get_response(55, SHORT_ANS, &response))
|
||||||
|
{
|
||||||
|
/* Response valid. Check if Card has accepted switch to application command mode */
|
||||||
|
converter.value = response;
|
||||||
|
if (converter.statusstruct.APP_CMD == 1)
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
} while (--retry > 0);
|
||||||
|
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum acmd41_ret sdio_init_card_acmd41(uint8_t HCS)
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
int retry = 0x20;
|
||||||
|
if (sdio_switch_appmode_cmd55())
|
||||||
|
return ACMD41_RESP_ERR;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(41, (HCS ? (1<<30) : 0) | (1<<28) | (1<<20) |(1<<21)|(1<<22) |(1<<23)|(1<<19), SHORT_ANS);
|
||||||
|
if (!sdio_get_response(0xFF, SHORT_ANS, &response)) {
|
||||||
|
if (response & OCS_BUSY) {
|
||||||
|
/* Card is ready... Who knows why this bit is called busy */
|
||||||
|
if (response & OCS_CCS) {
|
||||||
|
return ACMD41_RESP_SDXC;
|
||||||
|
} else {
|
||||||
|
return ACMD41_RESP_SDSC;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return ACMD41_RESP_INIT;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} while (--retry > 0);
|
||||||
|
|
||||||
|
return ACMD41_RESP_ERR;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_csd_cmd9(uint16_t rca, uint32_t *response_buffer) {
|
||||||
|
int timeout = 0x20;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(9, (rca<<16)&0xFFFF0000, LONG_ANS);
|
||||||
|
res = sdio_get_response(0xFF, LONG_ANS, response_buffer);
|
||||||
|
if (!res)
|
||||||
|
break;
|
||||||
|
} while (--timeout > 0);
|
||||||
|
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send data buffer to SD card
|
||||||
|
* @param dlen Data length. Must be a multiple of 4 bytes
|
||||||
|
* @param blklen Log2 of block length (9 in case of 512 byte block)
|
||||||
|
* @param buff Buffer to send
|
||||||
|
*/
|
||||||
|
static int sdio_write_buffer(uint32_t dlen, uint32_t log_blklen, const unsigned char *buff)
|
||||||
|
{
|
||||||
|
uint32_t count;
|
||||||
|
int byte_count;
|
||||||
|
int byte_max;
|
||||||
|
uint32_t fifo;
|
||||||
|
uint32_t status_reg;
|
||||||
|
|
||||||
|
SDIO->DLEN = dlen;
|
||||||
|
|
||||||
|
/* Init Transfer */
|
||||||
|
SDIO->ICR = SDIO_ICR_CCRCFAILC | SDIO_ICR_DCRCFAILC | SDIO_ICR_CTIMEOUTC | SDIO_ICR_DTIMEOUTC |
|
||||||
|
SDIO_ICR_TXUNDERRC | SDIO_ICR_RXOVERRC | SDIO_ICR_CMDRENDC | SDIO_ICR_CMDSENTC | SDIO_ICR_DATAENDC |
|
||||||
|
SDIO_ICR_STBITERRC | SDIO_ICR_DBCKENDC | SDIO_ICR_SDIOITC | SDIO_ICR_CEATAENDC;
|
||||||
|
SDIO->DCTRL = (log_blklen<<4) | SDIO_DCTRL_DTEN;
|
||||||
|
|
||||||
|
for (count = 0; count < dlen; count += 4) {
|
||||||
|
fifo = 0;
|
||||||
|
|
||||||
|
if ((dlen - count) < 4)
|
||||||
|
byte_max = dlen - count;
|
||||||
|
else
|
||||||
|
byte_max = 4;
|
||||||
|
|
||||||
|
for (byte_count = 0; byte_count < byte_max; byte_count++) {
|
||||||
|
fifo >>= 8;
|
||||||
|
fifo |= (((uint32_t)*(buff++)) << 24) & 0xFF000000;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Wait as long as FIFO is full */
|
||||||
|
while (SDIO->STA & SDIO_STA_TXFIFOF);
|
||||||
|
|
||||||
|
/* Write data to FIFO */
|
||||||
|
SDIO->FIFO = fifo;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wait for TX to complete */
|
||||||
|
while (SDIO->STA & SDIO_STA_TXACT);
|
||||||
|
|
||||||
|
status_reg = SDIO->STA;
|
||||||
|
if (status_reg & (SDIO_STA_DTIMEOUT | SDIO_STA_TXUNDERR | SDIO_STA_DCRCFAIL)) {
|
||||||
|
SDIO->DCTRL = 0UL;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_write_block_cmd24(uint32_t addr)
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
|
||||||
|
sdio_send_cmd(24, addr, SHORT_ANS);
|
||||||
|
|
||||||
|
return sdio_get_response(24, SHORT_ANS, &response);
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_check_status_register_cmd13(uint16_t rca, uint32_t *status)
|
||||||
|
{
|
||||||
|
int timeout = 0x20;
|
||||||
|
uint32_t response;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
*status = 0UL;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(13, (rca<<16)&0xFFFF0000, SHORT_ANS);
|
||||||
|
if (!(res = sdio_get_response(13, SHORT_ANS, &response))) {
|
||||||
|
*status = response;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} while (--timeout > 0);
|
||||||
|
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_bus_width_acmd6(uint8_t bus_width)
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
int retry = 0x20;
|
||||||
|
int ret;
|
||||||
|
|
||||||
|
if (sdio_switch_appmode_cmd55()) return -1;
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(0x6, (bus_width == 4 ? 0x2 : 0x0), SHORT_ANS);
|
||||||
|
ret = sdio_get_response(0x6, SHORT_ANS, &response);
|
||||||
|
if (!ret)
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
} while (--retry > 0);
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_get_sector_count(uint16_t rca, uint32_t *sector_count)
|
||||||
|
{
|
||||||
|
uint32_t csd[4];
|
||||||
|
int res;
|
||||||
|
uint32_t size, mult, read_len, csd_rev;
|
||||||
|
|
||||||
|
if ((res = sdio_send_csd_cmd9(rca, csd))) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
csd_rev = ((csd[0] >> 30) & (0x3));
|
||||||
|
|
||||||
|
if (csd_rev == 0) {
|
||||||
|
/* SD v1 Card */
|
||||||
|
size = ((csd[1] & 0x3FF) <<2) | (((csd[2]) & ((1<<31) | (1<<30)))>>30);
|
||||||
|
mult = ((csd[2] & ((1<<17)|(1<<16)|(1<<15)))>>15);
|
||||||
|
read_len = (1<<((csd[1] & ((1<<19)|(1<<18)|(1<<17)|(1<<16)))>>16));
|
||||||
|
*sector_count = (((size +1)*(1<<(mult+2))*read_len) >> BLOCKSIZE);
|
||||||
|
} else if (csd_rev == 1) {
|
||||||
|
/* SD v2 Card */
|
||||||
|
size = (((csd[1] & 0x3F)<<16) | ((csd[2] & 0xFFFF0000) >> 16));
|
||||||
|
*sector_count = (size << (19-BLOCKSIZE));
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Switch the SDIo prescaler
|
||||||
|
* @param Prescaler value
|
||||||
|
*/
|
||||||
|
static void sdio_switch_prescaler(uint8_t clkdiv)
|
||||||
|
{
|
||||||
|
uint32_t reg;
|
||||||
|
reg = SDIO->CLKCR;
|
||||||
|
/* Clear prescaler */
|
||||||
|
reg &= ~SDIO_CLKCR_CLKDIV;
|
||||||
|
/* Set bits */
|
||||||
|
reg |= (SDIO_CLKCR_CLKDIV & clkdiv);
|
||||||
|
SDIO->CLKCR = reg;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief initDetectandProtectionPins
|
||||||
|
*/
|
||||||
|
static void sdio_init_detect_pins()
|
||||||
|
{
|
||||||
|
#if SDIO_ENABLE_WRITEPROT==1
|
||||||
|
WRITEPROT_PORT->PUPDR |= ((WRITEPROT_PULLUP ? 1 : 0)<<WRITEPROT_PIN*2);
|
||||||
|
#endif /* SDIO_ENABLE_WRITEPROT */
|
||||||
|
#if SDIO_ENABLE_INS==1
|
||||||
|
INS_PORT->PUPDR |= ((INS_PULLUP? 1 : 0)<<INS_PIN*2);
|
||||||
|
#endif /* SDIO_ENABLE_INS */
|
||||||
|
__DSB();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void sdio_init_hw()
|
||||||
|
{
|
||||||
|
//Init Clocks
|
||||||
|
RCC->AHB1ENR |= PORTCLKMASK | RCC_AHB1ENR_DMA2EN;
|
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_SDIOEN;
|
||||||
|
//Init Alternate Functions
|
||||||
|
CLKPORT->MODER |= (2<<CLKPIN*2);
|
||||||
|
D0PORT->MODER |= (2<<D0PIN*2);
|
||||||
|
D0PORT->PUPDR |= (1<<D0PIN*2);
|
||||||
|
CMDPORT->MODER |= (2<<CMDPIN*2);
|
||||||
|
CMDPORT->PUPDR |= (1<<CMDPIN*2);
|
||||||
|
#if BUSWIDTH==4
|
||||||
|
D1PORT->MODER |= (2<<D1PIN*2);
|
||||||
|
D1PORT->PUPDR |= (1<<D1PIN*2);
|
||||||
|
D2PORT->MODER |= (2<<D2PIN*2);
|
||||||
|
D2PORT->PUPDR |= (1<<D2PIN*2);
|
||||||
|
D3PORT->MODER |= (2<<D3PIN*2);
|
||||||
|
D3PORT->PUPDR |= (1<<D3PIN*2);
|
||||||
|
#endif
|
||||||
|
//CLKPORT->AFR[(CLKPIN < 8 ? 0 : 1)] |= ALTFUNC << ((CLKPIN < 8 ? CLKPIN : (CLKPIN - 8)) * 4);
|
||||||
|
SETAF(CLKPORT, CLKPIN, ALTFUNC);
|
||||||
|
SETAF(CMDPORT, CMDPIN, ALTFUNC);
|
||||||
|
SETAF(D0PORT, D0PIN, ALTFUNC);
|
||||||
|
#if BUSWIDTH==4
|
||||||
|
SETAF(D1PORT, D1PIN, ALTFUNC);
|
||||||
|
SETAF(D2PORT, D2PIN, ALTFUNC);
|
||||||
|
SETAF(D3PORT, D3PIN, ALTFUNC);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
//Init Module
|
||||||
|
|
||||||
|
//Set CLK Control Register
|
||||||
|
SDIO->CLKCR = (HW_FLOW<<14) | ((BUSWIDTH == 4 ? 1 : 0)<<11) | SDIO_CLKCR_CLKEN |
|
||||||
|
(INITCLK & SDIO_CLKCR_CLKDIV);
|
||||||
|
|
||||||
|
//Set Data Timeout
|
||||||
|
SDIO->DTIMER = DTIMEOUT;
|
||||||
|
|
||||||
|
//Set Data Parameters
|
||||||
|
//SDIO->DCTRL = (BLOCKSIZE << 4) | SDIO_DCTRL_DMAEN;
|
||||||
|
//Set Power Register: Power up Card CLK
|
||||||
|
SDIO->POWER = SDIO_POWER_PWRCTRL_0 | SDIO_POWER_PWRCTRL_1;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_read_block_cmd17(uint32_t addr)
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
|
||||||
|
sdio_send_cmd(17, addr, SHORT_ANS);
|
||||||
|
return sdio_get_response(17, SHORT_ANS, &response);
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_all_send_cid_cmd2()
|
||||||
|
{
|
||||||
|
uint32_t response[4];
|
||||||
|
int ret;
|
||||||
|
int retry = 0x20;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(2, 0, LONG_ANS);
|
||||||
|
if (!(ret = sdio_get_response(0xFF, LONG_ANS, response)))
|
||||||
|
return 0;
|
||||||
|
} while (retry-- > 0);
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_relative_address_cmd3(uint16_t* rca)
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
int retry = 0x20;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(3, 0, SHORT_ANS);
|
||||||
|
if (!sdio_get_response(3, SHORT_ANS, &response)) {
|
||||||
|
// TODO: Do some *optional* checking
|
||||||
|
*rca = ((response & 0xFFFF0000) >> 16);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
} while (retry-- > 0);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_go_idle_cmd0() {
|
||||||
|
sdio_send_cmd(0, 0x0, NO_ANS);
|
||||||
|
sdio_wait_cmd_sent();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_stop_transmission_cmd12()
|
||||||
|
{
|
||||||
|
int res;
|
||||||
|
uint32_t response;
|
||||||
|
|
||||||
|
sdio_send_cmd(12, 0, SHORT_ANS);
|
||||||
|
res = sdio_get_response(12, SHORT_ANS, &response);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_write_multiple_blocks_cmd25(uint32_t address)
|
||||||
|
{
|
||||||
|
int res;
|
||||||
|
uint32_t response;
|
||||||
|
|
||||||
|
sdio_send_cmd(25, address, SHORT_ANS);
|
||||||
|
res = sdio_get_response(25, SHORT_ANS, &response);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
static enum cmd8_ret sdio_send_iface_condition_cmd8()
|
||||||
|
{
|
||||||
|
uint32_t response;
|
||||||
|
int res = 0;
|
||||||
|
int retry = 0x20;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(8, 0x1CC, SHORT_ANS); // 3.3V supply requesR
|
||||||
|
res = sdio_get_response(8, SHORT_ANS, &response);
|
||||||
|
if (res == 0) {
|
||||||
|
if (response & 0x100)
|
||||||
|
return CMD8_VOLTAGE_ACCEPTED;
|
||||||
|
else
|
||||||
|
return CMD8_VOLTAGE_DENIED;
|
||||||
|
}
|
||||||
|
} while (retry-- > 0);
|
||||||
|
|
||||||
|
return CMD8_RESP_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_block_length_cmd16(uint32_t blocklen) {
|
||||||
|
int timeout = 0x20;
|
||||||
|
int res;
|
||||||
|
uint32_t response;
|
||||||
|
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(16, blocklen, SHORT_ANS);
|
||||||
|
if (!(res = sdio_get_response(16, SHORT_ANS, &response))) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}while(--timeout > 0);
|
||||||
|
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int sdio_send_select_card_cmd7(uint16_t rca) {
|
||||||
|
int timeout = 0x20;
|
||||||
|
uint32_t response;
|
||||||
|
union sdio_status_conv status;
|
||||||
|
int res;
|
||||||
|
|
||||||
|
/* Send CMD7. Selects card */
|
||||||
|
do {
|
||||||
|
sdio_send_cmd(7, (rca<<16)&0xFFFF0000, SHORT_ANS);
|
||||||
|
if (!(res = sdio_get_response(7, SHORT_ANS, &response))) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} while(--timeout > 0);
|
||||||
|
|
||||||
|
/* Check, if card in in TRANS state */
|
||||||
|
if (sdio_check_status_register_cmd13(rca, &status.value)) {
|
||||||
|
res = -1;
|
||||||
|
goto ret_val;
|
||||||
|
}
|
||||||
|
if (status.statusstruct.CURRENT_STATE != CURRENT_STATE_TRAN)
|
||||||
|
res = -2;
|
||||||
|
|
||||||
|
ret_val:
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
DSTATUS sdio_status()
|
||||||
|
{
|
||||||
|
DSTATUS returnval = 0;
|
||||||
|
|
||||||
|
if (sdio_check_inserted())
|
||||||
|
returnval |= STA_NODISK;
|
||||||
|
|
||||||
|
if (card_info.type == CARD_NONE)
|
||||||
|
returnval |= STA_NOINIT;
|
||||||
|
|
||||||
|
if (sdio_check_write_protection())
|
||||||
|
returnval |= STA_PROTECT;
|
||||||
|
|
||||||
|
return returnval;
|
||||||
|
}
|
||||||
|
|
||||||
|
DRESULT sdio_disk_ioctl(BYTE cmd, void* buff){
|
||||||
|
DRESULT res = RES_OK;
|
||||||
|
|
||||||
|
switch(cmd) {
|
||||||
|
case GET_BLOCK_SIZE:
|
||||||
|
*((DWORD*)buff) = (DWORD)0x01;
|
||||||
|
break;
|
||||||
|
case GET_SECTOR_SIZE:
|
||||||
|
*((WORD*)buff) = (WORD)(1<<BLOCKSIZE);
|
||||||
|
break;
|
||||||
|
case GET_SECTOR_COUNT:
|
||||||
|
if (card_info.type != CARD_NONE) {
|
||||||
|
*((DWORD*)buff) = (DWORD)card_info.sector_count;
|
||||||
|
} else {
|
||||||
|
res = RES_ERROR;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case CTRL_SYNC:
|
||||||
|
res = RES_OK;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
res = RES_PARERR;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
DWORD __attribute__((weak)) get_fattime()
|
||||||
|
{
|
||||||
|
return (1<<16) | (1<<24); // return Jan. 1st 1980 00:00:00
|
||||||
|
}
|
||||||
|
|
||||||
|
DSTATUS sdio_initialize(){
|
||||||
|
int timeout = 0x3000;
|
||||||
|
enum cmd8_ret res8;
|
||||||
|
enum acmd41_ret resa41;
|
||||||
|
uint8_t hcs_flag = 0;
|
||||||
|
card_info.rca = 0;
|
||||||
|
card_info.type = CARD_NONE;
|
||||||
|
enum sdio_card_type detected_card = CARD_NONE;
|
||||||
|
|
||||||
|
sdio_init_hw();
|
||||||
|
sdio_wait_ms(2);
|
||||||
|
sdio_init_detect_pins();
|
||||||
|
if (sdio_check_inserted()) {
|
||||||
|
return STA_NOINIT | STA_NODISK;
|
||||||
|
}
|
||||||
|
|
||||||
|
sdio_send_go_idle_cmd0();
|
||||||
|
|
||||||
|
sdio_wait_ms(2);
|
||||||
|
|
||||||
|
res8 = sdio_send_iface_condition_cmd8();
|
||||||
|
switch (res8) {
|
||||||
|
case CMD8_VOLTAGE_ACCEPTED: // SDV2 Card
|
||||||
|
hcs_flag = 1;
|
||||||
|
break;
|
||||||
|
case CMD8_VOLTAGE_DENIED: // should not happen
|
||||||
|
return STA_NOINIT;
|
||||||
|
break;
|
||||||
|
case CMD8_RESP_TIMEOUT: // SDV1 Card
|
||||||
|
hcs_flag=0;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return STA_NOINIT;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
do {
|
||||||
|
//SDIO_wait_ms(2);
|
||||||
|
resa41 = sdio_init_card_acmd41(hcs_flag);
|
||||||
|
} while ((resa41 == ACMD41_RESP_INIT) && (--timeout > 0));
|
||||||
|
|
||||||
|
switch (resa41) {
|
||||||
|
case ACMD41_RESP_SDSC:
|
||||||
|
detected_card = (hcs_flag ? SD_V2_SC : SD_V1);
|
||||||
|
break;
|
||||||
|
case ACMD41_RESP_SDXC:
|
||||||
|
detected_card = SD_V2_HC;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return STA_NOINIT;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sdio_send_all_send_cid_cmd2())
|
||||||
|
return STA_NOINIT;
|
||||||
|
|
||||||
|
if (sdio_send_relative_address_cmd3(&card_info.rca))
|
||||||
|
return STA_NOINIT;
|
||||||
|
if (sdio_get_sector_count(card_info.rca, &card_info.sector_count))
|
||||||
|
return STA_NOINIT;
|
||||||
|
if (sdio_send_select_card_cmd7(card_info.rca))
|
||||||
|
return STA_NOINIT;
|
||||||
|
|
||||||
|
if (sdio_send_block_length_cmd16((uint32_t)(1<<BLOCKSIZE)))
|
||||||
|
return STA_NOINIT;
|
||||||
|
|
||||||
|
if (sdio_send_bus_width_acmd6(BUSWIDTH))
|
||||||
|
return STA_NOINIT;
|
||||||
|
|
||||||
|
sdio_switch_prescaler(WORKCLK);
|
||||||
|
|
||||||
|
card_info.type = detected_card;
|
||||||
|
|
||||||
|
if (sdio_check_write_protection()) {
|
||||||
|
return STA_PROTECT;
|
||||||
|
} else
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void sdio_stop_clk()
|
||||||
|
{
|
||||||
|
SDIO->POWER = 0UL;
|
||||||
|
}
|
||||||
|
|
||||||
|
DRESULT sdio_disk_read(BYTE *buff, DWORD sector, UINT count){
|
||||||
|
uint32_t addr;
|
||||||
|
uint32_t sdio_status;
|
||||||
|
uint32_t fifo;
|
||||||
|
uint32_t counter;
|
||||||
|
int err;
|
||||||
|
union sdio_status_conv status;
|
||||||
|
|
||||||
|
|
||||||
|
do {
|
||||||
|
err = sdio_check_status_register_cmd13(card_info.rca, &status.value);
|
||||||
|
if (err)
|
||||||
|
return RES_ERROR;
|
||||||
|
} while (status.statusstruct.CURRENT_STATE != CURRENT_STATE_TRAN);
|
||||||
|
|
||||||
|
addr = (card_info.type == SD_V2_HC ? (sector) : (sector*512));
|
||||||
|
for (; count > 0; count--) {
|
||||||
|
|
||||||
|
/* configure read DMA */
|
||||||
|
// DMA2->LIFCR = 0xffffffff;
|
||||||
|
// DMA2->HIFCR = 0xffffffff;
|
||||||
|
// DMASTREAM->NDTR = 0;
|
||||||
|
// DMASTREAM->FCR = DMA_SxFCR_FTH_0 | DMA_SxFCR_FTH_1 | DMA_SxFCR_DMDIS;
|
||||||
|
// DMASTREAM->M0AR = (uint32_t)(buff);
|
||||||
|
// DMASTREAM->PAR = (uint32_t)&(SDIO->FIFO);
|
||||||
|
// DMASTREAM->CR = DMAP2M | DMA_SxCR_PL_1 | DMA_SxCR_PL_1;
|
||||||
|
// DMASTREAM->CR |= DMA_SxCR_EN;
|
||||||
|
|
||||||
|
SDIO->DLEN = (1 << BLOCKSIZE);
|
||||||
|
|
||||||
|
SDIO->ICR = SDIO_ICR_CCRCFAILC | SDIO_ICR_DCRCFAILC | SDIO_ICR_CTIMEOUTC | SDIO_ICR_DTIMEOUTC |
|
||||||
|
SDIO_ICR_TXUNDERRC | SDIO_ICR_RXOVERRC | SDIO_ICR_CMDRENDC | SDIO_ICR_CMDSENTC | SDIO_ICR_DATAENDC |
|
||||||
|
SDIO_ICR_STBITERRC | SDIO_ICR_DBCKENDC | SDIO_ICR_SDIOITC | SDIO_ICR_CEATAENDC;
|
||||||
|
SDIO->DCTRL = (BLOCKSIZE<<4) | SDIO_DCTRL_DTDIR | /*SDIO_DCTRL_DMAEN |*/ SDIO_DCTRL_DTEN;
|
||||||
|
|
||||||
|
/* Init Transfer */
|
||||||
|
err = sdio_send_read_block_cmd17(addr);
|
||||||
|
if (err) {
|
||||||
|
return RES_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
counter = 0;
|
||||||
|
while (counter < (1<<(BLOCKSIZE-2)) || !(SDIO->STA & (SDIO_STA_DBCKEND | SDIO_STA_DATAEND))) {
|
||||||
|
/* TODO: Handle errors */
|
||||||
|
if (SDIO->STA & (SDIO_STA_DCRCFAIL | SDIO_STA_DTIMEOUT | SDIO_STA_STBITERR))
|
||||||
|
{
|
||||||
|
return RES_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (SDIO->STA & SDIO_STA_RXDAVL) {
|
||||||
|
counter++;
|
||||||
|
fifo = SDIO->FIFO;
|
||||||
|
*(buff++) = (BYTE)(fifo & 0xFF);
|
||||||
|
fifo >>= 8;
|
||||||
|
*(buff++) = (BYTE)(fifo & 0xFF);
|
||||||
|
fifo >>= 8;
|
||||||
|
*(buff++) = (BYTE)(fifo & 0xFF);
|
||||||
|
fifo >>= 8;
|
||||||
|
*(buff++) = (BYTE)(fifo & 0xFF);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
if (SDIO->STA & SDIO_STA_DCRCFAIL) return RES_ERROR;
|
||||||
|
|
||||||
|
//while(DMASTREAM->CR & DMA_SxCR_EN);
|
||||||
|
while(1) {
|
||||||
|
__DSB();
|
||||||
|
__DMB();
|
||||||
|
sdio_status = SDIO->STA;
|
||||||
|
if (sdio_status & SDIO_STA_DCRCFAIL) {
|
||||||
|
return RES_ERROR;
|
||||||
|
}
|
||||||
|
if (sdio_status & SDIO_STA_DTIMEOUT) {
|
||||||
|
return RES_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sdio_status & SDIO_STA_DATAEND) {
|
||||||
|
|
||||||
|
if (!(sdio_status & SDIO_STA_RXACT)) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (card_info.type == SD_V2_HC) {
|
||||||
|
addr++;
|
||||||
|
} else {
|
||||||
|
addr += (1<<BLOCKSIZE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RES_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief SDIO_disk_write
|
||||||
|
* @param buff
|
||||||
|
* @param sector
|
||||||
|
* @param count
|
||||||
|
* @warning Not yet implemented
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
DRESULT sdio_disk_write(const BYTE *buff, DWORD sector, UINT count)
|
||||||
|
{
|
||||||
|
uint32_t addr;
|
||||||
|
union sdio_status_conv status;
|
||||||
|
uint32_t buff_offset = 0;
|
||||||
|
int ret;
|
||||||
|
UINT count_backup = count;
|
||||||
|
uint32_t retry_counter = 512;
|
||||||
|
|
||||||
|
if (sdio_check_write_protection())
|
||||||
|
return RES_WRPRT;
|
||||||
|
|
||||||
|
addr = (card_info.type == SD_V2_HC ? (sector) : (sector * 512));
|
||||||
|
|
||||||
|
ret = sdio_check_status_register_cmd13(card_info.rca, &status.value);
|
||||||
|
if (ret)
|
||||||
|
return RES_ERROR;
|
||||||
|
|
||||||
|
if (status.statusstruct.CURRENT_STATE == CURRENT_STATE_STBY) {
|
||||||
|
if (sdio_send_select_card_cmd7(card_info.rca))
|
||||||
|
return RES_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
ret = sdio_check_status_register_cmd13(card_info.rca, &status.value);
|
||||||
|
if (ret)
|
||||||
|
return RES_ERROR;
|
||||||
|
|
||||||
|
if (status.statusstruct.CURRENT_STATE == CURRENT_STATE_TRAN)
|
||||||
|
break;
|
||||||
|
|
||||||
|
if (--retry_counter == 0)
|
||||||
|
return RES_ERROR;
|
||||||
|
|
||||||
|
sdio_wait_ms(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (count > 1)
|
||||||
|
ret = sdio_send_write_multiple_blocks_cmd25(addr);
|
||||||
|
else if (count == 1)
|
||||||
|
ret = sdio_send_write_block_cmd24(addr);
|
||||||
|
else
|
||||||
|
ret = RES_PARERR;
|
||||||
|
if (ret)
|
||||||
|
return RES_ERROR;
|
||||||
|
|
||||||
|
ret = 0;
|
||||||
|
ret = sdio_write_buffer((count * 512UL), 9, &buff[buff_offset]);
|
||||||
|
|
||||||
|
if (count_backup > 1)
|
||||||
|
(void)sdio_send_stop_transmission_cmd12();
|
||||||
|
|
||||||
|
return (ret ? RES_ERROR : RES_OK);
|
||||||
|
}
|
@ -0,0 +1,79 @@
|
|||||||
|
/*
|
||||||
|
* shimatta_sdio-driver.h
|
||||||
|
*
|
||||||
|
* Created on: Apr 26, 2015
|
||||||
|
* Mario Hüttel
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_
|
||||||
|
#define FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_
|
||||||
|
|
||||||
|
#include <fatfs/diskio.h>
|
||||||
|
#include <fatfs/ff.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
DSTATUS sdio_status();
|
||||||
|
DSTATUS sdio_initialize();
|
||||||
|
|
||||||
|
DRESULT sdio_disk_read(BYTE *buff, DWORD sector, UINT count);
|
||||||
|
DRESULT sdio_disk_write(const BYTE *buff, DWORD sector, UINT count);
|
||||||
|
DRESULT sdio_disk_ioctl(BYTE cmd, void* buff);
|
||||||
|
DWORD get_fattime();
|
||||||
|
|
||||||
|
int sdio_check_inserted();
|
||||||
|
void sdio_stop_clk();
|
||||||
|
|
||||||
|
//Defines for Card Status in struct _CardStatus
|
||||||
|
#define CURRENT_STATE_IDLE 0
|
||||||
|
#define CURRENT_STATE_READY 1
|
||||||
|
#define CURRENT_STATE_IDENT 2
|
||||||
|
#define CURRENT_STATE_STBY 3
|
||||||
|
#define CURRENT_STATE_TRAN 4
|
||||||
|
#define CURRENT_STATE_DATA 5
|
||||||
|
#define CURRENT_STATE_RCV 6
|
||||||
|
#define CURRENT_STATE_PRG 7
|
||||||
|
#define CURRENT_STATE_DIS 8
|
||||||
|
|
||||||
|
struct sd_card_status {
|
||||||
|
uint32_t reserved : 3;
|
||||||
|
uint32_t AKE_SEQ_ERROR : 1;
|
||||||
|
uint32_t reserved_2 : 1;
|
||||||
|
uint32_t APP_CMD : 1;
|
||||||
|
uint32_t reserved_3 : 2;
|
||||||
|
uint32_t READY_FOR_DATA : 1;
|
||||||
|
uint32_t CURRENT_STATE : 4;
|
||||||
|
uint32_t ERASE_RESET : 1;
|
||||||
|
uint32_t CARD_ECC_DIABLED : 1;
|
||||||
|
uint32_t WP_ERASE_SKIP : 1;
|
||||||
|
uint32_t CSD_OVERWRITE : 1;
|
||||||
|
uint32_t reserved17 : 1;
|
||||||
|
uint32_t reserved18 : 1;
|
||||||
|
uint32_t ERROR : 1;
|
||||||
|
uint32_t CC_ERROR : 1;
|
||||||
|
uint32_t CARD_ECC_FAILED : 1;
|
||||||
|
uint32_t ILLEGAL_COMMAND : 1;
|
||||||
|
uint32_t COM_CRC_ERROR : 1;
|
||||||
|
uint32_t LOCK_UNLOCK_FAILED : 1;
|
||||||
|
uint32_t CARD_IS_LOCKED : 1;
|
||||||
|
uint32_t WP_VIOLATION : 1;
|
||||||
|
uint32_t ERASE_PARAM : 1;
|
||||||
|
uint32_t ERASE_SEQ_ERROR : 1;
|
||||||
|
uint32_t BLOCK_LEN_ERROR : 1;
|
||||||
|
uint32_t ADDRESS_ERROR : 1;
|
||||||
|
uint32_t OUT_OF_RANGE : 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
enum sdio_card_type {CARD_NONE = 0, MMC, SD_V1, SD_V2_SC, SD_V2_HC};
|
||||||
|
// MMC not supported
|
||||||
|
struct sd_info {
|
||||||
|
uint16_t rca;
|
||||||
|
enum sdio_card_type type;
|
||||||
|
uint32_t sector_count;
|
||||||
|
};
|
||||||
|
|
||||||
|
union sdio_status_conv {
|
||||||
|
struct sd_card_status statusstruct;
|
||||||
|
uint32_t value;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_DRIVER_H_ */
|
@ -0,0 +1,65 @@
|
|||||||
|
#ifndef FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_CONFIG_H_
|
||||||
|
#define FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_CONFIG_H_
|
||||||
|
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
|
||||||
|
#define SDIO_CLOCK_FREQ 42000000UL
|
||||||
|
|
||||||
|
//General Definitions
|
||||||
|
//Blocksize: 512 = 2^9 => 9
|
||||||
|
#define BLOCKSIZE 9 //9
|
||||||
|
//Hardware Flow: Prevents over- and underruns.
|
||||||
|
#define HW_FLOW 0 //0
|
||||||
|
//1 bit: !=4
|
||||||
|
//4 bit: 4
|
||||||
|
#define BUSWIDTH 4 //4
|
||||||
|
//Initial Transfer CLK (ca. 400kHz)
|
||||||
|
#define INITCLK 140UL //120
|
||||||
|
//Working CLK (Maximum)
|
||||||
|
#define WORKCLK 30UL //0
|
||||||
|
//Data Timeout in CLK Cycles
|
||||||
|
|
||||||
|
#define DATA_TIMEOUT_MS 250UL // 250
|
||||||
|
|
||||||
|
#define DTIMEOUT (((SDIO_CLOCK_FREQ / (WORKCLK+2))) * DATA_TIMEOUT_MS / 1000UL)
|
||||||
|
//DMA Stream used for TX and RX DMA2 Stream 3 or 6 possible
|
||||||
|
// Currently not used due to possible misalignment of the data buffer.
|
||||||
|
//#define DMASTREAM DMA2_Stream6
|
||||||
|
|
||||||
|
|
||||||
|
/* Port Definitions */
|
||||||
|
|
||||||
|
#define PORTCLKMASK (RCC_AHB1ENR_GPIODEN | RCC_AHB1ENR_GPIOCEN | RCC_AHB1ENR_GPIOAEN)
|
||||||
|
|
||||||
|
#define ALTFUNC 12
|
||||||
|
|
||||||
|
#define CLKPORT GPIOC
|
||||||
|
#define D0PORT GPIOC
|
||||||
|
#define D1PORT GPIOC
|
||||||
|
#define D2PORT GPIOC
|
||||||
|
#define D3PORT GPIOC
|
||||||
|
#define CMDPORT GPIOD
|
||||||
|
|
||||||
|
#define CLKPIN 12
|
||||||
|
#define D0PIN 8
|
||||||
|
#define D1PIN 9
|
||||||
|
#define D2PIN 10
|
||||||
|
#define D3PIN 11
|
||||||
|
#define CMDPIN 2
|
||||||
|
|
||||||
|
// Write Protection
|
||||||
|
#define SDIO_ENABLE_WRITEPROT 0
|
||||||
|
#define WRITEPROT_PORT GPIOD // Add this port to port clock mask!
|
||||||
|
#define WRITEPROT_PIN 0
|
||||||
|
#define WRITEPROT_PULLUP 0
|
||||||
|
#define WRITEPROT_ACTIVE_LEVEL 0
|
||||||
|
|
||||||
|
// Card inserted pin
|
||||||
|
#define SDIO_ENABLE_INS 1
|
||||||
|
#define INS_PORT GPIOA // Add this port to port clock mask!
|
||||||
|
#define INS_PIN 8
|
||||||
|
#define INS_PULLUP 1
|
||||||
|
#define INS_ACTIVE_LEVEL 0
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* FATFS_SHIMATTA_SDIO_DRIVER_SHIMATTA_SDIO_CONFIG_H_ */
|
95
stm-firmware/updater/ram-code/hex-parser.c
Normal file
95
stm-firmware/updater/ram-code/hex-parser.c
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
#include "hex-parser.h"
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
static int convert_hex_char_to_value(char c, uint32_t *out)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
uint32_t value = 0;
|
||||||
|
|
||||||
|
if (!out)
|
||||||
|
return -1002;
|
||||||
|
|
||||||
|
switch (c) {
|
||||||
|
case '0' ... '9':
|
||||||
|
value = (uint32_t)c - (uint32_t)'0';
|
||||||
|
break;
|
||||||
|
case 'a' ... 'f':
|
||||||
|
/* Convert to upper */
|
||||||
|
c -= 0x20;
|
||||||
|
/* FALLTHRU */
|
||||||
|
case 'A' ... 'F':
|
||||||
|
value = (uint32_t)c - (uint32_t)'A' + 10UL;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
ret = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ret == 0)
|
||||||
|
*out = value;
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int convert_big_endian_hex_string_to_val(const char *string, size_t len, uint32_t *out)
|
||||||
|
{
|
||||||
|
int ret_val = -1;
|
||||||
|
uint32_t converted_value = 0UL;
|
||||||
|
uint32_t digit;
|
||||||
|
int res;
|
||||||
|
unsigned int i;
|
||||||
|
|
||||||
|
/* Return error in case of an input error */
|
||||||
|
if (!string || !len)
|
||||||
|
goto exit;
|
||||||
|
|
||||||
|
if (!out)
|
||||||
|
return -1003;
|
||||||
|
|
||||||
|
/* we don't support strings larger than 8 chars */
|
||||||
|
if (len > 8)
|
||||||
|
goto exit;
|
||||||
|
|
||||||
|
|
||||||
|
for (i = 0; i < len && string[i] != '\0'; i++) {
|
||||||
|
/* Convert current character to number */
|
||||||
|
res = convert_hex_char_to_value(string[i], &digit);
|
||||||
|
if (res) {
|
||||||
|
/* Not a hex number */
|
||||||
|
ret_val = -2;
|
||||||
|
goto exit;
|
||||||
|
}
|
||||||
|
|
||||||
|
converted_value *= 0x10;
|
||||||
|
converted_value += digit;
|
||||||
|
}
|
||||||
|
|
||||||
|
*out = converted_value;
|
||||||
|
|
||||||
|
exit:
|
||||||
|
return ret_val;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_open(struct hex_parser *parser, const char *file_name)
|
||||||
|
{
|
||||||
|
FRESULT fres;
|
||||||
|
|
||||||
|
if (!parser || !file_name)
|
||||||
|
return HEX_PARSER_ERROR;
|
||||||
|
|
||||||
|
parser->current_address_offset = 0UL;
|
||||||
|
fres = f_open(&parser->file, file_name, FA_READ);
|
||||||
|
if (fres != FR_OK) {
|
||||||
|
return HEX_PARSER_ERROR;
|
||||||
|
}
|
||||||
|
|
||||||
|
return HEX_PARSER_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_parse(struct hex_parser *parser, uint32_t *address, char *data, size_t data_len);
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_close(struct hex_parser *parser) {
|
||||||
|
if (!parser)
|
||||||
|
return HEX_PARSER_ERROR;
|
||||||
|
f_close(&parser->file);
|
||||||
|
return HEX_PARSER_OK;
|
||||||
|
}
|
26
stm-firmware/updater/ram-code/hex-parser.h
Normal file
26
stm-firmware/updater/ram-code/hex-parser.h
Normal file
@ -0,0 +1,26 @@
|
|||||||
|
#ifndef _HEX_PARSER_H_
|
||||||
|
#define _HEX_PARSER_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <fatfs/ff.h>
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
enum hex_parser_ret {
|
||||||
|
HEX_PARSER_OK,
|
||||||
|
HEX_PARSER_DATA_OK,
|
||||||
|
HEX_PARSER_ERROR,
|
||||||
|
HEX_PARSER_FILE_END,
|
||||||
|
};
|
||||||
|
|
||||||
|
struct hex_parser {
|
||||||
|
FIL file;
|
||||||
|
uint32_t current_address_offset;
|
||||||
|
};
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_open(struct hex_parser *parser, const char *file_name);
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_parse(struct hex_parser *parser, uint32_t *address, char *data, size_t data_len);
|
||||||
|
|
||||||
|
enum hex_parser_ret hex_parser_close(struct hex_parser *parser);
|
||||||
|
|
||||||
|
#endif /* _HEX_PARSER_H_ */
|
1757
stm-firmware/updater/ram-code/include/cmsis/core_cm4.h
Normal file
1757
stm-firmware/updater/ram-code/include/cmsis/core_cm4.h
Normal file
File diff suppressed because it is too large
Load Diff
649
stm-firmware/updater/ram-code/include/cmsis/core_cm4_simd.h
Normal file
649
stm-firmware/updater/ram-code/include/cmsis/core_cm4_simd.h
Normal file
@ -0,0 +1,649 @@
|
|||||||
|
/**************************************************************************//**
|
||||||
|
* @file core_cm4_simd.h
|
||||||
|
* @brief CMSIS Cortex-M4 SIMD Header File
|
||||||
|
* @version V3.01
|
||||||
|
* @date 06. March 2012
|
||||||
|
*
|
||||||
|
* @note
|
||||||
|
* Copyright (C) 2010-2012 ARM Limited. All rights reserved.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* ARM Limited (ARM) is supplying this software for use with Cortex-M
|
||||||
|
* processor based microcontrollers. This file can be freely distributed
|
||||||
|
* within development tools that are supporting such ARM based processors.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
|
||||||
|
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
|
||||||
|
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
|
||||||
|
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
|
||||||
|
*
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef __CORE_CM4_SIMD_H
|
||||||
|
#define __CORE_CM4_SIMD_H
|
||||||
|
|
||||||
|
|
||||||
|
/*******************************************************************************
|
||||||
|
* Hardware Abstraction Layer
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
/* ################### Compiler specific Intrinsics ########################### */
|
||||||
|
/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
|
||||||
|
Access to dedicated SIMD instructions
|
||||||
|
@{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
|
||||||
|
/* ARM armcc specific functions */
|
||||||
|
|
||||||
|
/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
#define __SADD8 __sadd8
|
||||||
|
#define __QADD8 __qadd8
|
||||||
|
#define __SHADD8 __shadd8
|
||||||
|
#define __UADD8 __uadd8
|
||||||
|
#define __UQADD8 __uqadd8
|
||||||
|
#define __UHADD8 __uhadd8
|
||||||
|
#define __SSUB8 __ssub8
|
||||||
|
#define __QSUB8 __qsub8
|
||||||
|
#define __SHSUB8 __shsub8
|
||||||
|
#define __USUB8 __usub8
|
||||||
|
#define __UQSUB8 __uqsub8
|
||||||
|
#define __UHSUB8 __uhsub8
|
||||||
|
#define __SADD16 __sadd16
|
||||||
|
#define __QADD16 __qadd16
|
||||||
|
#define __SHADD16 __shadd16
|
||||||
|
#define __UADD16 __uadd16
|
||||||
|
#define __UQADD16 __uqadd16
|
||||||
|
#define __UHADD16 __uhadd16
|
||||||
|
#define __SSUB16 __ssub16
|
||||||
|
#define __QSUB16 __qsub16
|
||||||
|
#define __SHSUB16 __shsub16
|
||||||
|
#define __USUB16 __usub16
|
||||||
|
#define __UQSUB16 __uqsub16
|
||||||
|
#define __UHSUB16 __uhsub16
|
||||||
|
#define __SASX __sasx
|
||||||
|
#define __QASX __qasx
|
||||||
|
#define __SHASX __shasx
|
||||||
|
#define __UASX __uasx
|
||||||
|
#define __UQASX __uqasx
|
||||||
|
#define __UHASX __uhasx
|
||||||
|
#define __SSAX __ssax
|
||||||
|
#define __QSAX __qsax
|
||||||
|
#define __SHSAX __shsax
|
||||||
|
#define __USAX __usax
|
||||||
|
#define __UQSAX __uqsax
|
||||||
|
#define __UHSAX __uhsax
|
||||||
|
#define __USAD8 __usad8
|
||||||
|
#define __USADA8 __usada8
|
||||||
|
#define __SSAT16 __ssat16
|
||||||
|
#define __USAT16 __usat16
|
||||||
|
#define __UXTB16 __uxtb16
|
||||||
|
#define __UXTAB16 __uxtab16
|
||||||
|
#define __SXTB16 __sxtb16
|
||||||
|
#define __SXTAB16 __sxtab16
|
||||||
|
#define __SMUAD __smuad
|
||||||
|
#define __SMUADX __smuadx
|
||||||
|
#define __SMLAD __smlad
|
||||||
|
#define __SMLADX __smladx
|
||||||
|
#define __SMLALD __smlald
|
||||||
|
#define __SMLALDX __smlaldx
|
||||||
|
#define __SMUSD __smusd
|
||||||
|
#define __SMUSDX __smusdx
|
||||||
|
#define __SMLSD __smlsd
|
||||||
|
#define __SMLSDX __smlsdx
|
||||||
|
#define __SMLSLD __smlsld
|
||||||
|
#define __SMLSLDX __smlsldx
|
||||||
|
#define __SEL __sel
|
||||||
|
#define __QADD __qadd
|
||||||
|
#define __QSUB __qsub
|
||||||
|
|
||||||
|
#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
|
||||||
|
((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
|
||||||
|
|
||||||
|
#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
|
||||||
|
((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
|
||||||
|
|
||||||
|
|
||||||
|
/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
|
||||||
|
/* IAR iccarm specific functions */
|
||||||
|
|
||||||
|
/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
#include <cmsis_iar.h>
|
||||||
|
|
||||||
|
/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
|
||||||
|
/* TI CCS specific functions */
|
||||||
|
|
||||||
|
/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
#include <cmsis_ccs.h>
|
||||||
|
|
||||||
|
/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
|
||||||
|
/* GNU gcc specific functions */
|
||||||
|
|
||||||
|
/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define __SSAT16(ARG1,ARG2) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1); \
|
||||||
|
__ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
#define __USAT16(ARG1,ARG2) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1); \
|
||||||
|
__ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1));
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1));
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define __SMLALD(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
|
||||||
|
__ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
|
||||||
|
(uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
|
||||||
|
})
|
||||||
|
|
||||||
|
#define __SMLALDX(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
|
||||||
|
__ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
|
||||||
|
(uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
|
||||||
|
})
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define __SMLSLD(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
|
||||||
|
__ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
|
||||||
|
(uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
|
||||||
|
})
|
||||||
|
|
||||||
|
#define __SMLSLDX(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
|
||||||
|
__ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
|
||||||
|
(uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
|
||||||
|
})
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define __PKHBT(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
|
||||||
|
__ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
#define __PKHTB(ARG1,ARG2,ARG3) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
|
||||||
|
if (ARG3 == 0) \
|
||||||
|
__ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \
|
||||||
|
else \
|
||||||
|
__ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
|
||||||
|
/* TASKING carm specific functions */
|
||||||
|
|
||||||
|
|
||||||
|
/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
/* not yet supported */
|
||||||
|
/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*@} end of group CMSIS_SIMD_intrinsics */
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* __CORE_CM4_SIMD_H */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
616
stm-firmware/updater/ram-code/include/cmsis/core_cmFunc.h
Normal file
616
stm-firmware/updater/ram-code/include/cmsis/core_cmFunc.h
Normal file
@ -0,0 +1,616 @@
|
|||||||
|
/**************************************************************************//**
|
||||||
|
* @file core_cmFunc.h
|
||||||
|
* @brief CMSIS Cortex-M Core Function Access Header File
|
||||||
|
* @version V3.01
|
||||||
|
* @date 06. March 2012
|
||||||
|
*
|
||||||
|
* @note
|
||||||
|
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* ARM Limited (ARM) is supplying this software for use with Cortex-M
|
||||||
|
* processor based microcontrollers. This file can be freely distributed
|
||||||
|
* within development tools that are supporting such ARM based processors.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
|
||||||
|
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
|
||||||
|
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
|
||||||
|
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
|
||||||
|
*
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#ifndef __CORE_CMFUNC_H
|
||||||
|
#define __CORE_CMFUNC_H
|
||||||
|
|
||||||
|
|
||||||
|
/* ########################### Core Function Access ########################### */
|
||||||
|
/** \ingroup CMSIS_Core_FunctionInterface
|
||||||
|
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
|
||||||
|
@{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
|
||||||
|
/* ARM armcc specific functions */
|
||||||
|
|
||||||
|
#if (__ARMCC_VERSION < 400677)
|
||||||
|
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* intrinsic void __enable_irq(); */
|
||||||
|
/* intrinsic void __disable_irq(); */
|
||||||
|
|
||||||
|
/** \brief Get Control Register
|
||||||
|
|
||||||
|
This function returns the content of the Control Register.
|
||||||
|
|
||||||
|
\return Control Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_CONTROL(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regControl __ASM("control");
|
||||||
|
return(__regControl);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Control Register
|
||||||
|
|
||||||
|
This function writes the given value to the Control Register.
|
||||||
|
|
||||||
|
\param [in] control Control Register value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_CONTROL(uint32_t control)
|
||||||
|
{
|
||||||
|
register uint32_t __regControl __ASM("control");
|
||||||
|
__regControl = control;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get IPSR Register
|
||||||
|
|
||||||
|
This function returns the content of the IPSR Register.
|
||||||
|
|
||||||
|
\return IPSR Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_IPSR(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regIPSR __ASM("ipsr");
|
||||||
|
return(__regIPSR);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get APSR Register
|
||||||
|
|
||||||
|
This function returns the content of the APSR Register.
|
||||||
|
|
||||||
|
\return APSR Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_APSR(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regAPSR __ASM("apsr");
|
||||||
|
return(__regAPSR);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get xPSR Register
|
||||||
|
|
||||||
|
This function returns the content of the xPSR Register.
|
||||||
|
|
||||||
|
\return xPSR Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_xPSR(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regXPSR __ASM("xpsr");
|
||||||
|
return(__regXPSR);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Process Stack Pointer
|
||||||
|
|
||||||
|
This function returns the current value of the Process Stack Pointer (PSP).
|
||||||
|
|
||||||
|
\return PSP Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_PSP(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regProcessStackPointer __ASM("psp");
|
||||||
|
return(__regProcessStackPointer);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Process Stack Pointer
|
||||||
|
|
||||||
|
This function assigns the given value to the Process Stack Pointer (PSP).
|
||||||
|
|
||||||
|
\param [in] topOfProcStack Process Stack Pointer value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||||
|
{
|
||||||
|
register uint32_t __regProcessStackPointer __ASM("psp");
|
||||||
|
__regProcessStackPointer = topOfProcStack;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Main Stack Pointer
|
||||||
|
|
||||||
|
This function returns the current value of the Main Stack Pointer (MSP).
|
||||||
|
|
||||||
|
\return MSP Register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_MSP(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regMainStackPointer __ASM("msp");
|
||||||
|
return(__regMainStackPointer);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Main Stack Pointer
|
||||||
|
|
||||||
|
This function assigns the given value to the Main Stack Pointer (MSP).
|
||||||
|
|
||||||
|
\param [in] topOfMainStack Main Stack Pointer value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||||
|
{
|
||||||
|
register uint32_t __regMainStackPointer __ASM("msp");
|
||||||
|
__regMainStackPointer = topOfMainStack;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Priority Mask
|
||||||
|
|
||||||
|
This function returns the current state of the priority mask bit from the Priority Mask Register.
|
||||||
|
|
||||||
|
\return Priority Mask value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_PRIMASK(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regPriMask __ASM("primask");
|
||||||
|
return(__regPriMask);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Priority Mask
|
||||||
|
|
||||||
|
This function assigns the given value to the Priority Mask Register.
|
||||||
|
|
||||||
|
\param [in] priMask Priority Mask
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
|
||||||
|
{
|
||||||
|
register uint32_t __regPriMask __ASM("primask");
|
||||||
|
__regPriMask = (priMask);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M >= 0x03)
|
||||||
|
|
||||||
|
/** \brief Enable FIQ
|
||||||
|
|
||||||
|
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
#define __enable_fault_irq __enable_fiq
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Disable FIQ
|
||||||
|
|
||||||
|
This function disables FIQ interrupts by setting the F-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
#define __disable_fault_irq __disable_fiq
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Base Priority
|
||||||
|
|
||||||
|
This function returns the current value of the Base Priority register.
|
||||||
|
|
||||||
|
\return Base Priority register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_BASEPRI(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regBasePri __ASM("basepri");
|
||||||
|
return(__regBasePri);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Base Priority
|
||||||
|
|
||||||
|
This function assigns the given value to the Base Priority register.
|
||||||
|
|
||||||
|
\param [in] basePri Base Priority value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
|
||||||
|
{
|
||||||
|
register uint32_t __regBasePri __ASM("basepri");
|
||||||
|
__regBasePri = (basePri & 0xff);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Fault Mask
|
||||||
|
|
||||||
|
This function returns the current value of the Fault Mask register.
|
||||||
|
|
||||||
|
\return Fault Mask register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_FAULTMASK(void)
|
||||||
|
{
|
||||||
|
register uint32_t __regFaultMask __ASM("faultmask");
|
||||||
|
return(__regFaultMask);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Fault Mask
|
||||||
|
|
||||||
|
This function assigns the given value to the Fault Mask register.
|
||||||
|
|
||||||
|
\param [in] faultMask Fault Mask value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
|
||||||
|
{
|
||||||
|
register uint32_t __regFaultMask __ASM("faultmask");
|
||||||
|
__regFaultMask = (faultMask & (uint32_t)1);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M >= 0x03) */
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M == 0x04)
|
||||||
|
|
||||||
|
/** \brief Get FPSCR
|
||||||
|
|
||||||
|
This function returns the current value of the Floating Point Status/Control register.
|
||||||
|
|
||||||
|
\return Floating Point Status/Control register value
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE uint32_t __get_FPSCR(void)
|
||||||
|
{
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
register uint32_t __regfpscr __ASM("fpscr");
|
||||||
|
return(__regfpscr);
|
||||||
|
#else
|
||||||
|
return(0);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set FPSCR
|
||||||
|
|
||||||
|
This function assigns the given value to the Floating Point Status/Control register.
|
||||||
|
|
||||||
|
\param [in] fpscr Floating Point Status/Control value to set
|
||||||
|
*/
|
||||||
|
__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
|
||||||
|
{
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
register uint32_t __regfpscr __ASM("fpscr");
|
||||||
|
__regfpscr = (fpscr);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M == 0x04) */
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
|
||||||
|
/* IAR iccarm specific functions */
|
||||||
|
|
||||||
|
#include <cmsis_iar.h>
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
|
||||||
|
/* TI CCS specific functions */
|
||||||
|
|
||||||
|
#include <cmsis_ccs.h>
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
|
||||||
|
/* GNU gcc specific functions */
|
||||||
|
|
||||||
|
/** \brief Enable IRQ Interrupts
|
||||||
|
|
||||||
|
This function enables IRQ interrupts by clearing the I-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("cpsie i");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Disable IRQ Interrupts
|
||||||
|
|
||||||
|
This function disables IRQ interrupts by setting the I-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("cpsid i");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Control Register
|
||||||
|
|
||||||
|
This function returns the content of the Control Register.
|
||||||
|
|
||||||
|
\return Control Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, control" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Control Register
|
||||||
|
|
||||||
|
This function writes the given value to the Control Register.
|
||||||
|
|
||||||
|
\param [in] control Control Register value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR control, %0" : : "r" (control) );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get IPSR Register
|
||||||
|
|
||||||
|
This function returns the content of the IPSR Register.
|
||||||
|
|
||||||
|
\return IPSR Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, ipsr" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get APSR Register
|
||||||
|
|
||||||
|
This function returns the content of the APSR Register.
|
||||||
|
|
||||||
|
\return APSR Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, apsr" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get xPSR Register
|
||||||
|
|
||||||
|
This function returns the content of the xPSR Register.
|
||||||
|
|
||||||
|
\return xPSR Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, xpsr" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Process Stack Pointer
|
||||||
|
|
||||||
|
This function returns the current value of the Process Stack Pointer (PSP).
|
||||||
|
|
||||||
|
\return PSP Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
|
||||||
|
{
|
||||||
|
register uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, psp\n" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Process Stack Pointer
|
||||||
|
|
||||||
|
This function assigns the given value to the Process Stack Pointer (PSP).
|
||||||
|
|
||||||
|
\param [in] topOfProcStack Process Stack Pointer value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Main Stack Pointer
|
||||||
|
|
||||||
|
This function returns the current value of the Main Stack Pointer (MSP).
|
||||||
|
|
||||||
|
\return MSP Register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
|
||||||
|
{
|
||||||
|
register uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, msp\n" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Main Stack Pointer
|
||||||
|
|
||||||
|
This function assigns the given value to the Main Stack Pointer (MSP).
|
||||||
|
|
||||||
|
\param [in] topOfMainStack Main Stack Pointer value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Priority Mask
|
||||||
|
|
||||||
|
This function returns the current state of the priority mask bit from the Priority Mask Register.
|
||||||
|
|
||||||
|
\return Priority Mask value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, primask" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Priority Mask
|
||||||
|
|
||||||
|
This function assigns the given value to the Priority Mask Register.
|
||||||
|
|
||||||
|
\param [in] priMask Priority Mask
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR primask, %0" : : "r" (priMask) );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M >= 0x03)
|
||||||
|
|
||||||
|
/** \brief Enable FIQ
|
||||||
|
|
||||||
|
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("cpsie f");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Disable FIQ
|
||||||
|
|
||||||
|
This function disables FIQ interrupts by setting the F-bit in the CPSR.
|
||||||
|
Can only be executed in Privileged modes.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("cpsid f");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Base Priority
|
||||||
|
|
||||||
|
This function returns the current value of the Base Priority register.
|
||||||
|
|
||||||
|
\return Base Priority register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Base Priority
|
||||||
|
|
||||||
|
This function assigns the given value to the Base Priority register.
|
||||||
|
|
||||||
|
\param [in] basePri Base Priority value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR basepri, %0" : : "r" (value) );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Get Fault Mask
|
||||||
|
|
||||||
|
This function returns the current value of the Fault Mask register.
|
||||||
|
|
||||||
|
\return Fault Mask register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("MRS %0, faultmask" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set Fault Mask
|
||||||
|
|
||||||
|
This function assigns the given value to the Fault Mask register.
|
||||||
|
|
||||||
|
\param [in] faultMask Fault Mask value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
|
||||||
|
{
|
||||||
|
__ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M >= 0x03) */
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M == 0x04)
|
||||||
|
|
||||||
|
/** \brief Get FPSCR
|
||||||
|
|
||||||
|
This function returns the current value of the Floating Point Status/Control register.
|
||||||
|
|
||||||
|
\return Floating Point Status/Control register value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void)
|
||||||
|
{
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
|
||||||
|
return(result);
|
||||||
|
#else
|
||||||
|
return(0);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Set FPSCR
|
||||||
|
|
||||||
|
This function assigns the given value to the Floating Point Status/Control register.
|
||||||
|
|
||||||
|
\param [in] fpscr Floating Point Status/Control value to set
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
|
||||||
|
{
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
__ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) );
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M == 0x04) */
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
|
||||||
|
/* TASKING carm specific functions */
|
||||||
|
|
||||||
|
/*
|
||||||
|
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||||
|
* Please use "carm -?i" to get an up to date list of all instrinsics,
|
||||||
|
* Including the CMSIS ones.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*@} end of CMSIS_Core_RegAccFunctions */
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* __CORE_CMFUNC_H */
|
618
stm-firmware/updater/ram-code/include/cmsis/core_cmInstr.h
Normal file
618
stm-firmware/updater/ram-code/include/cmsis/core_cmInstr.h
Normal file
@ -0,0 +1,618 @@
|
|||||||
|
/**************************************************************************//**
|
||||||
|
* @file core_cmInstr.h
|
||||||
|
* @brief CMSIS Cortex-M Core Instruction Access Header File
|
||||||
|
* @version V3.01
|
||||||
|
* @date 06. March 2012
|
||||||
|
*
|
||||||
|
* @note
|
||||||
|
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* ARM Limited (ARM) is supplying this software for use with Cortex-M
|
||||||
|
* processor based microcontrollers. This file can be freely distributed
|
||||||
|
* within development tools that are supporting such ARM based processors.
|
||||||
|
*
|
||||||
|
* @par
|
||||||
|
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
|
||||||
|
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
|
||||||
|
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
|
||||||
|
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
|
||||||
|
*
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#ifndef __CORE_CMINSTR_H
|
||||||
|
#define __CORE_CMINSTR_H
|
||||||
|
|
||||||
|
|
||||||
|
/* ########################## Core Instruction Access ######################### */
|
||||||
|
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
|
||||||
|
Access to dedicated instructions
|
||||||
|
@{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
|
||||||
|
/* ARM armcc specific functions */
|
||||||
|
|
||||||
|
#if (__ARMCC_VERSION < 400677)
|
||||||
|
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief No Operation
|
||||||
|
|
||||||
|
No Operation does nothing. This instruction can be used for code alignment purposes.
|
||||||
|
*/
|
||||||
|
#define __NOP __nop
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Wait For Interrupt
|
||||||
|
|
||||||
|
Wait For Interrupt is a hint instruction that suspends execution
|
||||||
|
until one of a number of events occurs.
|
||||||
|
*/
|
||||||
|
#define __WFI __wfi
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Wait For Event
|
||||||
|
|
||||||
|
Wait For Event is a hint instruction that permits the processor to enter
|
||||||
|
a low-power state until one of a number of events occurs.
|
||||||
|
*/
|
||||||
|
#define __WFE __wfe
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Send Event
|
||||||
|
|
||||||
|
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
|
||||||
|
*/
|
||||||
|
#define __SEV __sev
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Instruction Synchronization Barrier
|
||||||
|
|
||||||
|
Instruction Synchronization Barrier flushes the pipeline in the processor,
|
||||||
|
so that all instructions following the ISB are fetched from cache or
|
||||||
|
memory, after the instruction has been completed.
|
||||||
|
*/
|
||||||
|
#define __ISB() __isb(0xF)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Data Synchronization Barrier
|
||||||
|
|
||||||
|
This function acts as a special kind of Data Memory Barrier.
|
||||||
|
It completes when all explicit memory accesses before this instruction complete.
|
||||||
|
*/
|
||||||
|
#define __DSB() __dsb(0xF)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Data Memory Barrier
|
||||||
|
|
||||||
|
This function ensures the apparent order of the explicit memory operations before
|
||||||
|
and after the instruction, without ensuring their completion.
|
||||||
|
*/
|
||||||
|
#define __DMB() __dmb(0xF)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order (32 bit)
|
||||||
|
|
||||||
|
This function reverses the byte order in integer value.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
#define __REV __rev
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order (16 bit)
|
||||||
|
|
||||||
|
This function reverses the byte order in two unsigned short values.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
|
||||||
|
{
|
||||||
|
rev16 r0, r0
|
||||||
|
bx lr
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order in signed short value
|
||||||
|
|
||||||
|
This function reverses the byte order in a signed short value with sign extension to integer.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
|
||||||
|
{
|
||||||
|
revsh r0, r0
|
||||||
|
bx lr
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Rotate Right in unsigned value (32 bit)
|
||||||
|
|
||||||
|
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
|
||||||
|
|
||||||
|
\param [in] value Value to rotate
|
||||||
|
\param [in] value Number of Bits to rotate
|
||||||
|
\return Rotated value
|
||||||
|
*/
|
||||||
|
#define __ROR __ror
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M >= 0x03)
|
||||||
|
|
||||||
|
/** \brief Reverse bit order of value
|
||||||
|
|
||||||
|
This function reverses the bit order of the given value.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
#define __RBIT __rbit
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (8 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 8 bit value.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint8_t at (*ptr)
|
||||||
|
*/
|
||||||
|
#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (16 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 16 bit values.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint16_t at (*ptr)
|
||||||
|
*/
|
||||||
|
#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (32 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 32 bit values.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint32_t at (*ptr)
|
||||||
|
*/
|
||||||
|
#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (8 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 8 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
#define __STREXB(value, ptr) __strex(value, ptr)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (16 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 16 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
#define __STREXH(value, ptr) __strex(value, ptr)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (32 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 32 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
#define __STREXW(value, ptr) __strex(value, ptr)
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Remove the exclusive lock
|
||||||
|
|
||||||
|
This function removes the exclusive lock which is created by LDREX.
|
||||||
|
|
||||||
|
*/
|
||||||
|
#define __CLREX __clrex
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Signed Saturate
|
||||||
|
|
||||||
|
This function saturates a signed value.
|
||||||
|
|
||||||
|
\param [in] value Value to be saturated
|
||||||
|
\param [in] sat Bit position to saturate to (1..32)
|
||||||
|
\return Saturated value
|
||||||
|
*/
|
||||||
|
#define __SSAT __ssat
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Unsigned Saturate
|
||||||
|
|
||||||
|
This function saturates an unsigned value.
|
||||||
|
|
||||||
|
\param [in] value Value to be saturated
|
||||||
|
\param [in] sat Bit position to saturate to (0..31)
|
||||||
|
\return Saturated value
|
||||||
|
*/
|
||||||
|
#define __USAT __usat
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Count leading zeros
|
||||||
|
|
||||||
|
This function counts the number of leading zeros of a data value.
|
||||||
|
|
||||||
|
\param [in] value Value to count the leading zeros
|
||||||
|
\return number of leading zeros in value
|
||||||
|
*/
|
||||||
|
#define __CLZ __clz
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M >= 0x03) */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
|
||||||
|
/* IAR iccarm specific functions */
|
||||||
|
|
||||||
|
#include <cmsis_iar.h>
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
|
||||||
|
/* TI CCS specific functions */
|
||||||
|
|
||||||
|
#include <cmsis_ccs.h>
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
|
||||||
|
/* GNU gcc specific functions */
|
||||||
|
|
||||||
|
/** \brief No Operation
|
||||||
|
|
||||||
|
No Operation does nothing. This instruction can be used for code alignment purposes.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("nop");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Wait For Interrupt
|
||||||
|
|
||||||
|
Wait For Interrupt is a hint instruction that suspends execution
|
||||||
|
until one of a number of events occurs.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("wfi");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Wait For Event
|
||||||
|
|
||||||
|
Wait For Event is a hint instruction that permits the processor to enter
|
||||||
|
a low-power state until one of a number of events occurs.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("wfe");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Send Event
|
||||||
|
|
||||||
|
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("sev");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Instruction Synchronization Barrier
|
||||||
|
|
||||||
|
Instruction Synchronization Barrier flushes the pipeline in the processor,
|
||||||
|
so that all instructions following the ISB are fetched from cache or
|
||||||
|
memory, after the instruction has been completed.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("isb");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Data Synchronization Barrier
|
||||||
|
|
||||||
|
This function acts as a special kind of Data Memory Barrier.
|
||||||
|
It completes when all explicit memory accesses before this instruction complete.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("dsb");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Data Memory Barrier
|
||||||
|
|
||||||
|
This function ensures the apparent order of the explicit memory operations before
|
||||||
|
and after the instruction, without ensuring their completion.
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("dmb");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order (32 bit)
|
||||||
|
|
||||||
|
This function reverses the byte order in integer value.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order (16 bit)
|
||||||
|
|
||||||
|
This function reverses the byte order in two unsigned short values.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Reverse byte order in signed short value
|
||||||
|
|
||||||
|
This function reverses the byte order in a signed short value with sign extension to integer.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Rotate Right in unsigned value (32 bit)
|
||||||
|
|
||||||
|
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
|
||||||
|
|
||||||
|
\param [in] value Value to rotate
|
||||||
|
\param [in] value Number of Bits to rotate
|
||||||
|
\return Rotated value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
|
||||||
|
{
|
||||||
|
|
||||||
|
__ASM volatile ("ror %0, %0, %1" : "+r" (op1) : "r" (op2) );
|
||||||
|
return(op1);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if (__CORTEX_M >= 0x03)
|
||||||
|
|
||||||
|
/** \brief Reverse bit order of value
|
||||||
|
|
||||||
|
This function reverses the bit order of the given value.
|
||||||
|
|
||||||
|
\param [in] value Value to reverse
|
||||||
|
\return Reversed value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (8 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 8 bit value.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint8_t at (*ptr)
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
|
||||||
|
{
|
||||||
|
uint8_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (16 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 16 bit values.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint16_t at (*ptr)
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
|
||||||
|
{
|
||||||
|
uint16_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief LDR Exclusive (32 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive LDR command for 32 bit values.
|
||||||
|
|
||||||
|
\param [in] ptr Pointer to data
|
||||||
|
\return value of type uint32_t at (*ptr)
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (8 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 8 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (16 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 16 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief STR Exclusive (32 bit)
|
||||||
|
|
||||||
|
This function performs a exclusive STR command for 32 bit values.
|
||||||
|
|
||||||
|
\param [in] value Value to store
|
||||||
|
\param [in] ptr Pointer to location
|
||||||
|
\return 0 Function succeeded
|
||||||
|
\return 1 Function failed
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
|
||||||
|
{
|
||||||
|
uint32_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Remove the exclusive lock
|
||||||
|
|
||||||
|
This function removes the exclusive lock which is created by LDREX.
|
||||||
|
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void)
|
||||||
|
{
|
||||||
|
__ASM volatile ("clrex");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Signed Saturate
|
||||||
|
|
||||||
|
This function saturates a signed value.
|
||||||
|
|
||||||
|
\param [in] value Value to be saturated
|
||||||
|
\param [in] sat Bit position to saturate to (1..32)
|
||||||
|
\return Saturated value
|
||||||
|
*/
|
||||||
|
#define __SSAT(ARG1,ARG2) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1); \
|
||||||
|
__ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Unsigned Saturate
|
||||||
|
|
||||||
|
This function saturates an unsigned value.
|
||||||
|
|
||||||
|
\param [in] value Value to be saturated
|
||||||
|
\param [in] sat Bit position to saturate to (0..31)
|
||||||
|
\return Saturated value
|
||||||
|
*/
|
||||||
|
#define __USAT(ARG1,ARG2) \
|
||||||
|
({ \
|
||||||
|
uint32_t __RES, __ARG1 = (ARG1); \
|
||||||
|
__ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
|
||||||
|
__RES; \
|
||||||
|
})
|
||||||
|
|
||||||
|
|
||||||
|
/** \brief Count leading zeros
|
||||||
|
|
||||||
|
This function counts the number of leading zeros of a data value.
|
||||||
|
|
||||||
|
\param [in] value Value to count the leading zeros
|
||||||
|
\return number of leading zeros in value
|
||||||
|
*/
|
||||||
|
__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
|
||||||
|
{
|
||||||
|
uint8_t result;
|
||||||
|
|
||||||
|
__ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
|
||||||
|
return(result);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* (__CORTEX_M >= 0x03) */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
|
||||||
|
/* TASKING carm specific functions */
|
||||||
|
|
||||||
|
/*
|
||||||
|
* The CMSIS functions have been implemented as intrinsics in the compiler.
|
||||||
|
* Please use "carm -?i" to get an up to date list of all intrinsics,
|
||||||
|
* Including the CMSIS ones.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
|
||||||
|
|
||||||
|
#endif /* __CORE_CMINSTR_H */
|
79
stm-firmware/updater/ram-code/include/fatfs/diskio.h
Normal file
79
stm-firmware/updater/ram-code/include/fatfs/diskio.h
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
/*-----------------------------------------------------------------------/
|
||||||
|
/ Low level disk interface modlue include file (C)ChaN, 2019 /
|
||||||
|
/-----------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#ifndef _DISKIO_DEFINED
|
||||||
|
#define _DISKIO_DEFINED
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <fatfs/ff.h>
|
||||||
|
|
||||||
|
/* Status of Disk Functions */
|
||||||
|
typedef BYTE DSTATUS;
|
||||||
|
|
||||||
|
/* Results of Disk Functions */
|
||||||
|
typedef enum {
|
||||||
|
RES_OK = 0, /* 0: Successful */
|
||||||
|
RES_ERROR, /* 1: R/W Error */
|
||||||
|
RES_WRPRT, /* 2: Write Protected */
|
||||||
|
RES_NOTRDY, /* 3: Not Ready */
|
||||||
|
RES_PARERR /* 4: Invalid Parameter */
|
||||||
|
} DRESULT;
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------*/
|
||||||
|
/* Prototypes for disk control functions */
|
||||||
|
|
||||||
|
|
||||||
|
DSTATUS disk_initialize (BYTE pdrv);
|
||||||
|
DSTATUS disk_status (BYTE pdrv);
|
||||||
|
DRESULT disk_read (BYTE pdrv, BYTE* buff, LBA_t sector, UINT count);
|
||||||
|
DRESULT disk_write (BYTE pdrv, const BYTE* buff, LBA_t sector, UINT count);
|
||||||
|
DRESULT disk_ioctl (BYTE pdrv, BYTE cmd, void* buff);
|
||||||
|
|
||||||
|
|
||||||
|
/* Disk Status Bits (DSTATUS) */
|
||||||
|
|
||||||
|
#define STA_NOINIT 0x01 /* Drive not initialized */
|
||||||
|
#define STA_NODISK 0x02 /* No medium in the drive */
|
||||||
|
#define STA_PROTECT 0x04 /* Write protected */
|
||||||
|
|
||||||
|
|
||||||
|
/* Command code for disk_ioctrl fucntion */
|
||||||
|
|
||||||
|
/* Generic command (Used by FatFs) */
|
||||||
|
#define CTRL_SYNC 0 /* Complete pending write process (needed at FF_FS_READONLY == 0) */
|
||||||
|
#define GET_SECTOR_COUNT 1 /* Get media size (needed at FF_USE_MKFS == 1) */
|
||||||
|
#define GET_SECTOR_SIZE 2 /* Get sector size (needed at FF_MAX_SS != FF_MIN_SS) */
|
||||||
|
#define GET_BLOCK_SIZE 3 /* Get erase block size (needed at FF_USE_MKFS == 1) */
|
||||||
|
#define CTRL_TRIM 4 /* Inform device that the data on the block of sectors is no longer used (needed at FF_USE_TRIM == 1) */
|
||||||
|
|
||||||
|
/* Generic command (Not used by FatFs) */
|
||||||
|
#define CTRL_POWER 5 /* Get/Set power status */
|
||||||
|
#define CTRL_LOCK 6 /* Lock/Unlock media removal */
|
||||||
|
#define CTRL_EJECT 7 /* Eject media */
|
||||||
|
#define CTRL_FORMAT 8 /* Create physical format on the media */
|
||||||
|
|
||||||
|
/* MMC/SDC specific ioctl command */
|
||||||
|
#define MMC_GET_TYPE 10 /* Get card type */
|
||||||
|
#define MMC_GET_CSD 11 /* Get CSD */
|
||||||
|
#define MMC_GET_CID 12 /* Get CID */
|
||||||
|
#define MMC_GET_OCR 13 /* Get OCR */
|
||||||
|
#define MMC_GET_SDSTAT 14 /* Get SD status */
|
||||||
|
#define ISDIO_READ 55 /* Read data form SD iSDIO register */
|
||||||
|
#define ISDIO_WRITE 56 /* Write data to SD iSDIO register */
|
||||||
|
#define ISDIO_MRITE 57 /* Masked write data to SD iSDIO register */
|
||||||
|
|
||||||
|
/* ATA/CF specific ioctl command */
|
||||||
|
#define ATA_GET_REV 20 /* Get F/W revision */
|
||||||
|
#define ATA_GET_MODEL 21 /* Get model name */
|
||||||
|
#define ATA_GET_SN 22 /* Get serial number */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
426
stm-firmware/updater/ram-code/include/fatfs/ff.h
Normal file
426
stm-firmware/updater/ram-code/include/fatfs/ff.h
Normal file
@ -0,0 +1,426 @@
|
|||||||
|
/*----------------------------------------------------------------------------/
|
||||||
|
/ FatFs - Generic FAT Filesystem module R0.14 /
|
||||||
|
/-----------------------------------------------------------------------------/
|
||||||
|
/
|
||||||
|
/ Copyright (C) 2019, ChaN, all right reserved.
|
||||||
|
/
|
||||||
|
/ FatFs module is an open source software. Redistribution and use of FatFs in
|
||||||
|
/ source and binary forms, with or without modification, are permitted provided
|
||||||
|
/ that the following condition is met:
|
||||||
|
|
||||||
|
/ 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
/ this condition and the following disclaimer.
|
||||||
|
/
|
||||||
|
/ This software is provided by the copyright holder and contributors "AS IS"
|
||||||
|
/ and any warranties related to this software are DISCLAIMED.
|
||||||
|
/ The copyright owner or contributors be NOT LIABLE for any damages caused
|
||||||
|
/ by use of this software.
|
||||||
|
/
|
||||||
|
/----------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef FF_DEFINED
|
||||||
|
#define FF_DEFINED 86606 /* Revision ID */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "ffconf.h" /* FatFs configuration options */
|
||||||
|
|
||||||
|
#if FF_DEFINED != FFCONF_DEF
|
||||||
|
#error Wrong configuration file (ffconf.h).
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/* Integer types used for FatFs API */
|
||||||
|
|
||||||
|
#if defined(_WIN32) /* Main development platform */
|
||||||
|
#define FF_INTDEF 2
|
||||||
|
#include <windows.h>
|
||||||
|
typedef unsigned __int64 QWORD;
|
||||||
|
#elif (defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L) || defined(__cplusplus) /* C99 or later */
|
||||||
|
#define FF_INTDEF 2
|
||||||
|
#include <stdint.h>
|
||||||
|
typedef unsigned int UINT; /* int must be 16-bit or 32-bit */
|
||||||
|
typedef unsigned char BYTE; /* char must be 8-bit */
|
||||||
|
typedef uint16_t WORD; /* 16-bit unsigned integer */
|
||||||
|
typedef uint32_t DWORD; /* 32-bit unsigned integer */
|
||||||
|
typedef uint64_t QWORD; /* 64-bit unsigned integer */
|
||||||
|
typedef WORD WCHAR; /* UTF-16 character type */
|
||||||
|
#else /* Earlier than C99 */
|
||||||
|
#define FF_INTDEF 1
|
||||||
|
typedef unsigned int UINT; /* int must be 16-bit or 32-bit */
|
||||||
|
typedef unsigned char BYTE; /* char must be 8-bit */
|
||||||
|
typedef unsigned short WORD; /* 16-bit unsigned integer */
|
||||||
|
typedef unsigned long DWORD; /* 32-bit unsigned integer */
|
||||||
|
typedef WORD WCHAR; /* UTF-16 character type */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/* Definitions of volume management */
|
||||||
|
|
||||||
|
#if FF_MULTI_PARTITION /* Multiple partition configuration */
|
||||||
|
typedef struct {
|
||||||
|
BYTE pd; /* Physical drive number */
|
||||||
|
BYTE pt; /* Partition: 0:Auto detect, 1-4:Forced partition) */
|
||||||
|
} PARTITION;
|
||||||
|
extern PARTITION VolToPart[]; /* Volume - Partition mapping table */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if FF_STR_VOLUME_ID
|
||||||
|
#ifndef FF_VOLUME_STRS
|
||||||
|
extern const char* VolumeStr[FF_VOLUMES]; /* User defied volume ID */
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Type of path name strings on FatFs API */
|
||||||
|
|
||||||
|
#ifndef _INC_TCHAR
|
||||||
|
#define _INC_TCHAR
|
||||||
|
|
||||||
|
#if FF_USE_LFN && FF_LFN_UNICODE == 1 /* Unicode in UTF-16 encoding */
|
||||||
|
typedef WCHAR TCHAR;
|
||||||
|
#define _T(x) L ## x
|
||||||
|
#define _TEXT(x) L ## x
|
||||||
|
#elif FF_USE_LFN && FF_LFN_UNICODE == 2 /* Unicode in UTF-8 encoding */
|
||||||
|
typedef char TCHAR;
|
||||||
|
#define _T(x) u8 ## x
|
||||||
|
#define _TEXT(x) u8 ## x
|
||||||
|
#elif FF_USE_LFN && FF_LFN_UNICODE == 3 /* Unicode in UTF-32 encoding */
|
||||||
|
typedef DWORD TCHAR;
|
||||||
|
#define _T(x) U ## x
|
||||||
|
#define _TEXT(x) U ## x
|
||||||
|
#elif FF_USE_LFN && (FF_LFN_UNICODE < 0 || FF_LFN_UNICODE > 3)
|
||||||
|
#error Wrong FF_LFN_UNICODE setting
|
||||||
|
#else /* ANSI/OEM code in SBCS/DBCS */
|
||||||
|
typedef char TCHAR;
|
||||||
|
#define _T(x) x
|
||||||
|
#define _TEXT(x) x
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Type of file size and LBA variables */
|
||||||
|
|
||||||
|
#if FF_FS_EXFAT
|
||||||
|
#if FF_INTDEF != 2
|
||||||
|
#error exFAT feature wants C99 or later
|
||||||
|
#endif
|
||||||
|
typedef QWORD FSIZE_t;
|
||||||
|
#if FF_LBA64
|
||||||
|
typedef QWORD LBA_t;
|
||||||
|
#else
|
||||||
|
typedef DWORD LBA_t;
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#if FF_LBA64
|
||||||
|
#error exFAT needs to be enabled when enable 64-bit LBA
|
||||||
|
#endif
|
||||||
|
typedef DWORD FSIZE_t;
|
||||||
|
typedef DWORD LBA_t;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Filesystem object structure (FATFS) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
BYTE fs_type; /* Filesystem type (0:not mounted) */
|
||||||
|
BYTE pdrv; /* Associated physical drive */
|
||||||
|
BYTE n_fats; /* Number of FATs (1 or 2) */
|
||||||
|
BYTE wflag; /* win[] flag (b0:dirty) */
|
||||||
|
BYTE fsi_flag; /* FSINFO flags (b7:disabled, b0:dirty) */
|
||||||
|
WORD id; /* Volume mount ID */
|
||||||
|
WORD n_rootdir; /* Number of root directory entries (FAT12/16) */
|
||||||
|
WORD csize; /* Cluster size [sectors] */
|
||||||
|
#if FF_MAX_SS != FF_MIN_SS
|
||||||
|
WORD ssize; /* Sector size (512, 1024, 2048 or 4096) */
|
||||||
|
#endif
|
||||||
|
#if FF_USE_LFN
|
||||||
|
WCHAR* lfnbuf; /* LFN working buffer */
|
||||||
|
#endif
|
||||||
|
#if FF_FS_EXFAT
|
||||||
|
BYTE* dirbuf; /* Directory entry block scratchpad buffer for exFAT */
|
||||||
|
#endif
|
||||||
|
#if FF_FS_REENTRANT
|
||||||
|
FF_SYNC_t sobj; /* Identifier of sync object */
|
||||||
|
#endif
|
||||||
|
#if !FF_FS_READONLY
|
||||||
|
DWORD last_clst; /* Last allocated cluster */
|
||||||
|
DWORD free_clst; /* Number of free clusters */
|
||||||
|
#endif
|
||||||
|
#if FF_FS_RPATH
|
||||||
|
DWORD cdir; /* Current directory start cluster (0:root) */
|
||||||
|
#if FF_FS_EXFAT
|
||||||
|
DWORD cdc_scl; /* Containing directory start cluster (invalid when cdir is 0) */
|
||||||
|
DWORD cdc_size; /* b31-b8:Size of containing directory, b7-b0: Chain status */
|
||||||
|
DWORD cdc_ofs; /* Offset in the containing directory (invalid when cdir is 0) */
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
DWORD n_fatent; /* Number of FAT entries (number of clusters + 2) */
|
||||||
|
DWORD fsize; /* Size of an FAT [sectors] */
|
||||||
|
LBA_t volbase; /* Volume base sector */
|
||||||
|
LBA_t fatbase; /* FAT base sector */
|
||||||
|
LBA_t dirbase; /* Root directory base sector/cluster */
|
||||||
|
LBA_t database; /* Data base sector */
|
||||||
|
#if FF_FS_EXFAT
|
||||||
|
LBA_t bitbase; /* Allocation bitmap base sector */
|
||||||
|
#endif
|
||||||
|
LBA_t winsect; /* Current sector appearing in the win[] */
|
||||||
|
BYTE win[FF_MAX_SS]; /* Disk access window for Directory, FAT (and file data at tiny cfg) */
|
||||||
|
} FATFS;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Object ID and allocation information (FFOBJID) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FATFS* fs; /* Pointer to the hosting volume of this object */
|
||||||
|
WORD id; /* Hosting volume mount ID */
|
||||||
|
BYTE attr; /* Object attribute */
|
||||||
|
BYTE stat; /* Object chain status (b1-0: =0:not contiguous, =2:contiguous, =3:fragmented in this session, b2:sub-directory stretched) */
|
||||||
|
DWORD sclust; /* Object data start cluster (0:no cluster or root directory) */
|
||||||
|
FSIZE_t objsize; /* Object size (valid when sclust != 0) */
|
||||||
|
#if FF_FS_EXFAT
|
||||||
|
DWORD n_cont; /* Size of first fragment - 1 (valid when stat == 3) */
|
||||||
|
DWORD n_frag; /* Size of last fragment needs to be written to FAT (valid when not zero) */
|
||||||
|
DWORD c_scl; /* Containing directory start cluster (valid when sclust != 0) */
|
||||||
|
DWORD c_size; /* b31-b8:Size of containing directory, b7-b0: Chain status (valid when c_scl != 0) */
|
||||||
|
DWORD c_ofs; /* Offset in the containing directory (valid when file object and sclust != 0) */
|
||||||
|
#endif
|
||||||
|
#if FF_FS_LOCK
|
||||||
|
UINT lockid; /* File lock ID origin from 1 (index of file semaphore table Files[]) */
|
||||||
|
#endif
|
||||||
|
} FFOBJID;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* File object structure (FIL) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FFOBJID obj; /* Object identifier (must be the 1st member to detect invalid object pointer) */
|
||||||
|
BYTE flag; /* File status flags */
|
||||||
|
BYTE err; /* Abort flag (error code) */
|
||||||
|
FSIZE_t fptr; /* File read/write pointer (Zeroed on file open) */
|
||||||
|
DWORD clust; /* Current cluster of fpter (invalid when fptr is 0) */
|
||||||
|
LBA_t sect; /* Sector number appearing in buf[] (0:invalid) */
|
||||||
|
#if !FF_FS_READONLY
|
||||||
|
LBA_t dir_sect; /* Sector number containing the directory entry (not used at exFAT) */
|
||||||
|
BYTE* dir_ptr; /* Pointer to the directory entry in the win[] (not used at exFAT) */
|
||||||
|
#endif
|
||||||
|
#if FF_USE_FASTSEEK
|
||||||
|
DWORD* cltbl; /* Pointer to the cluster link map table (nulled on open, set by application) */
|
||||||
|
#endif
|
||||||
|
#if !FF_FS_TINY
|
||||||
|
BYTE buf[FF_MAX_SS]; /* File private data read/write window */
|
||||||
|
#endif
|
||||||
|
} FIL;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Directory object structure (DIR) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FFOBJID obj; /* Object identifier */
|
||||||
|
DWORD dptr; /* Current read/write offset */
|
||||||
|
DWORD clust; /* Current cluster */
|
||||||
|
LBA_t sect; /* Current sector (0:Read operation has terminated) */
|
||||||
|
BYTE* dir; /* Pointer to the directory item in the win[] */
|
||||||
|
BYTE fn[12]; /* SFN (in/out) {body[8],ext[3],status[1]} */
|
||||||
|
#if FF_USE_LFN
|
||||||
|
DWORD blk_ofs; /* Offset of current entry block being processed (0xFFFFFFFF:Invalid) */
|
||||||
|
#endif
|
||||||
|
#if FF_USE_FIND
|
||||||
|
const TCHAR* pat; /* Pointer to the name matching pattern */
|
||||||
|
#endif
|
||||||
|
} DIR;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* File information structure (FILINFO) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FSIZE_t fsize; /* File size */
|
||||||
|
WORD fdate; /* Modified date */
|
||||||
|
WORD ftime; /* Modified time */
|
||||||
|
BYTE fattrib; /* File attribute */
|
||||||
|
#if FF_USE_LFN
|
||||||
|
TCHAR altname[FF_SFN_BUF + 1];/* Altenative file name */
|
||||||
|
TCHAR fname[FF_LFN_BUF + 1]; /* Primary file name */
|
||||||
|
#else
|
||||||
|
TCHAR fname[12 + 1]; /* File name */
|
||||||
|
#endif
|
||||||
|
} FILINFO;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Format parameter structure (MKFS_PARM) */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
BYTE fmt; /* Format option (FM_FAT, FM_FAT32, FM_EXFAT and FM_SFD) */
|
||||||
|
BYTE n_fat; /* Number of FATs */
|
||||||
|
UINT align; /* Data area alignment (sector) */
|
||||||
|
UINT n_root; /* Number of root directory entries */
|
||||||
|
DWORD au_size; /* Cluster size (byte) */
|
||||||
|
} MKFS_PARM;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* File function return code (FRESULT) */
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
FR_OK = 0, /* (0) Succeeded */
|
||||||
|
FR_DISK_ERR, /* (1) A hard error occurred in the low level disk I/O layer */
|
||||||
|
FR_INT_ERR, /* (2) Assertion failed */
|
||||||
|
FR_NOT_READY, /* (3) The physical drive cannot work */
|
||||||
|
FR_NO_FILE, /* (4) Could not find the file */
|
||||||
|
FR_NO_PATH, /* (5) Could not find the path */
|
||||||
|
FR_INVALID_NAME, /* (6) The path name format is invalid */
|
||||||
|
FR_DENIED, /* (7) Access denied due to prohibited access or directory full */
|
||||||
|
FR_EXIST, /* (8) Access denied due to prohibited access */
|
||||||
|
FR_INVALID_OBJECT, /* (9) The file/directory object is invalid */
|
||||||
|
FR_WRITE_PROTECTED, /* (10) The physical drive is write protected */
|
||||||
|
FR_INVALID_DRIVE, /* (11) The logical drive number is invalid */
|
||||||
|
FR_NOT_ENABLED, /* (12) The volume has no work area */
|
||||||
|
FR_NO_FILESYSTEM, /* (13) There is no valid FAT volume */
|
||||||
|
FR_MKFS_ABORTED, /* (14) The f_mkfs() aborted due to any problem */
|
||||||
|
FR_TIMEOUT, /* (15) Could not get a grant to access the volume within defined period */
|
||||||
|
FR_LOCKED, /* (16) The operation is rejected according to the file sharing policy */
|
||||||
|
FR_NOT_ENOUGH_CORE, /* (17) LFN working buffer could not be allocated */
|
||||||
|
FR_TOO_MANY_OPEN_FILES, /* (18) Number of open files > FF_FS_LOCK */
|
||||||
|
FR_INVALID_PARAMETER /* (19) Given parameter is invalid */
|
||||||
|
} FRESULT;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*--------------------------------------------------------------*/
|
||||||
|
/* FatFs module application interface */
|
||||||
|
|
||||||
|
FRESULT f_open (FIL* fp, const TCHAR* path, BYTE mode); /* Open or create a file */
|
||||||
|
FRESULT f_close (FIL* fp); /* Close an open file object */
|
||||||
|
FRESULT f_read (FIL* fp, void* buff, UINT btr, UINT* br); /* Read data from the file */
|
||||||
|
FRESULT f_write (FIL* fp, const void* buff, UINT btw, UINT* bw); /* Write data to the file */
|
||||||
|
FRESULT f_lseek (FIL* fp, FSIZE_t ofs); /* Move file pointer of the file object */
|
||||||
|
FRESULT f_truncate (FIL* fp); /* Truncate the file */
|
||||||
|
FRESULT f_sync (FIL* fp); /* Flush cached data of the writing file */
|
||||||
|
FRESULT f_opendir (DIR* dp, const TCHAR* path); /* Open a directory */
|
||||||
|
FRESULT f_closedir (DIR* dp); /* Close an open directory */
|
||||||
|
FRESULT f_readdir (DIR* dp, FILINFO* fno); /* Read a directory item */
|
||||||
|
FRESULT f_findfirst (DIR* dp, FILINFO* fno, const TCHAR* path, const TCHAR* pattern); /* Find first file */
|
||||||
|
FRESULT f_findnext (DIR* dp, FILINFO* fno); /* Find next file */
|
||||||
|
FRESULT f_mkdir (const TCHAR* path); /* Create a sub directory */
|
||||||
|
FRESULT f_unlink (const TCHAR* path); /* Delete an existing file or directory */
|
||||||
|
FRESULT f_rename (const TCHAR* path_old, const TCHAR* path_new); /* Rename/Move a file or directory */
|
||||||
|
FRESULT f_stat (const TCHAR* path, FILINFO* fno); /* Get file status */
|
||||||
|
FRESULT f_chmod (const TCHAR* path, BYTE attr, BYTE mask); /* Change attribute of a file/dir */
|
||||||
|
FRESULT f_utime (const TCHAR* path, const FILINFO* fno); /* Change timestamp of a file/dir */
|
||||||
|
FRESULT f_chdir (const TCHAR* path); /* Change current directory */
|
||||||
|
FRESULT f_chdrive (const TCHAR* path); /* Change current drive */
|
||||||
|
FRESULT f_getcwd (TCHAR* buff, UINT len); /* Get current directory */
|
||||||
|
FRESULT f_getfree (const TCHAR* path, DWORD* nclst, FATFS** fatfs); /* Get number of free clusters on the drive */
|
||||||
|
FRESULT f_getlabel (const TCHAR* path, TCHAR* label, DWORD* vsn); /* Get volume label */
|
||||||
|
FRESULT f_setlabel (const TCHAR* label); /* Set volume label */
|
||||||
|
FRESULT f_forward (FIL* fp, UINT(*func)(const BYTE*,UINT), UINT btf, UINT* bf); /* Forward data to the stream */
|
||||||
|
FRESULT f_expand (FIL* fp, FSIZE_t fsz, BYTE opt); /* Allocate a contiguous block to the file */
|
||||||
|
FRESULT f_mount (FATFS* fs, const TCHAR* path, BYTE opt); /* Mount/Unmount a logical drive */
|
||||||
|
FRESULT f_mkfs (const TCHAR* path, const MKFS_PARM* opt, void* work, UINT len); /* Create a FAT volume */
|
||||||
|
FRESULT f_fdisk (BYTE pdrv, const LBA_t ptbl[], void* work); /* Divide a physical drive into some partitions */
|
||||||
|
FRESULT f_setcp (WORD cp); /* Set current code page */
|
||||||
|
int f_putc (TCHAR c, FIL* fp); /* Put a character to the file */
|
||||||
|
int f_puts (const TCHAR* str, FIL* cp); /* Put a string to the file */
|
||||||
|
int f_printf (FIL* fp, const TCHAR* str, ...); /* Put a formatted string to the file */
|
||||||
|
TCHAR* f_gets (TCHAR* buff, int len, FIL* fp); /* Get a string from the file */
|
||||||
|
|
||||||
|
#define f_eof(fp) ((int)((fp)->fptr == (fp)->obj.objsize))
|
||||||
|
#define f_error(fp) ((fp)->err)
|
||||||
|
#define f_tell(fp) ((fp)->fptr)
|
||||||
|
#define f_size(fp) ((fp)->obj.objsize)
|
||||||
|
#define f_rewind(fp) f_lseek((fp), 0)
|
||||||
|
#define f_rewinddir(dp) f_readdir((dp), 0)
|
||||||
|
#define f_rmdir(path) f_unlink(path)
|
||||||
|
#define f_unmount(path) f_mount(0, path, 0)
|
||||||
|
|
||||||
|
#ifndef EOF
|
||||||
|
#define EOF (-1)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*--------------------------------------------------------------*/
|
||||||
|
/* Additional user defined functions */
|
||||||
|
|
||||||
|
/* RTC function */
|
||||||
|
#if !FF_FS_READONLY && !FF_FS_NORTC
|
||||||
|
DWORD get_fattime (void);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* LFN support functions */
|
||||||
|
#if FF_USE_LFN >= 1 /* Code conversion (defined in unicode.c) */
|
||||||
|
WCHAR ff_oem2uni (WCHAR oem, WORD cp); /* OEM code to Unicode conversion */
|
||||||
|
WCHAR ff_uni2oem (DWORD uni, WORD cp); /* Unicode to OEM code conversion */
|
||||||
|
DWORD ff_wtoupper (DWORD uni); /* Unicode upper-case conversion */
|
||||||
|
#endif
|
||||||
|
#if FF_USE_LFN == 3 /* Dynamic memory allocation */
|
||||||
|
void* ff_memalloc (UINT msize); /* Allocate memory block */
|
||||||
|
void ff_memfree (void* mblock); /* Free memory block */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Sync functions */
|
||||||
|
#if FF_FS_REENTRANT
|
||||||
|
int ff_cre_syncobj (BYTE vol, FF_SYNC_t* sobj); /* Create a sync object */
|
||||||
|
int ff_req_grant (FF_SYNC_t sobj); /* Lock sync object */
|
||||||
|
void ff_rel_grant (FF_SYNC_t sobj); /* Unlock sync object */
|
||||||
|
int ff_del_syncobj (FF_SYNC_t sobj); /* Delete a sync object */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*--------------------------------------------------------------*/
|
||||||
|
/* Flags and offset address */
|
||||||
|
|
||||||
|
|
||||||
|
/* File access mode and open method flags (3rd argument of f_open) */
|
||||||
|
#define FA_READ 0x01
|
||||||
|
#define FA_WRITE 0x02
|
||||||
|
#define FA_OPEN_EXISTING 0x00
|
||||||
|
#define FA_CREATE_NEW 0x04
|
||||||
|
#define FA_CREATE_ALWAYS 0x08
|
||||||
|
#define FA_OPEN_ALWAYS 0x10
|
||||||
|
#define FA_OPEN_APPEND 0x30
|
||||||
|
|
||||||
|
/* Fast seek controls (2nd argument of f_lseek) */
|
||||||
|
#define CREATE_LINKMAP ((FSIZE_t)0 - 1)
|
||||||
|
|
||||||
|
/* Format options (2nd argument of f_mkfs) */
|
||||||
|
#define FM_FAT 0x01
|
||||||
|
#define FM_FAT32 0x02
|
||||||
|
#define FM_EXFAT 0x04
|
||||||
|
#define FM_ANY 0x07
|
||||||
|
#define FM_SFD 0x08
|
||||||
|
|
||||||
|
/* Filesystem type (FATFS.fs_type) */
|
||||||
|
#define FS_FAT12 1
|
||||||
|
#define FS_FAT16 2
|
||||||
|
#define FS_FAT32 3
|
||||||
|
#define FS_EXFAT 4
|
||||||
|
|
||||||
|
/* File attribute bits for directory entry (FILINFO.fattrib) */
|
||||||
|
#define AM_RDO 0x01 /* Read only */
|
||||||
|
#define AM_HID 0x02 /* Hidden */
|
||||||
|
#define AM_SYS 0x04 /* System */
|
||||||
|
#define AM_DIR 0x10 /* Directory */
|
||||||
|
#define AM_ARC 0x20 /* Archive */
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* FF_DEFINED */
|
298
stm-firmware/updater/ram-code/include/fatfs/ffconf.h
Normal file
298
stm-firmware/updater/ram-code/include/fatfs/ffconf.h
Normal file
@ -0,0 +1,298 @@
|
|||||||
|
/*---------------------------------------------------------------------------/
|
||||||
|
/ FatFs Functional Configurations
|
||||||
|
/---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#define FFCONF_DEF 86606 /* Revision ID */
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------/
|
||||||
|
/ Function Configurations
|
||||||
|
/---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#define FF_FS_READONLY 1
|
||||||
|
/* This option switches read-only configuration. (0:Read/Write or 1:Read-only)
|
||||||
|
/ Read-only configuration removes writing API functions, f_write(), f_sync(),
|
||||||
|
/ f_unlink(), f_mkdir(), f_chmod(), f_rename(), f_truncate(), f_getfree()
|
||||||
|
/ and optional writing functions as well. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_MINIMIZE 2
|
||||||
|
/* This option defines minimization level to remove some basic API functions.
|
||||||
|
/
|
||||||
|
/ 0: Basic functions are fully enabled.
|
||||||
|
/ 1: f_stat(), f_getfree(), f_unlink(), f_mkdir(), f_truncate() and f_rename()
|
||||||
|
/ are removed.
|
||||||
|
/ 2: f_opendir(), f_readdir() and f_closedir() are removed in addition to 1.
|
||||||
|
/ 3: f_lseek() function is removed in addition to 2. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_STRFUNC 1
|
||||||
|
/* This option switches string functions, f_gets(), f_putc(), f_puts() and f_printf().
|
||||||
|
/
|
||||||
|
/ 0: Disable string functions.
|
||||||
|
/ 1: Enable without LF-CRLF conversion.
|
||||||
|
/ 2: Enable with LF-CRLF conversion. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_FIND 0
|
||||||
|
/* This option switches filtered directory read functions, f_findfirst() and
|
||||||
|
/ f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_MKFS 0
|
||||||
|
/* This option switches f_mkfs() function. (0:Disable or 1:Enable) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_FASTSEEK 0
|
||||||
|
/* This option switches fast seek function. (0:Disable or 1:Enable) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_EXPAND 0
|
||||||
|
/* This option switches f_expand function. (0:Disable or 1:Enable) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_CHMOD 0
|
||||||
|
/* This option switches attribute manipulation functions, f_chmod() and f_utime().
|
||||||
|
/ (0:Disable or 1:Enable) Also FF_FS_READONLY needs to be 0 to enable this option. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_LABEL 0
|
||||||
|
/* This option switches volume label functions, f_getlabel() and f_setlabel().
|
||||||
|
/ (0:Disable or 1:Enable) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_FORWARD 0
|
||||||
|
/* This option switches f_forward() function. (0:Disable or 1:Enable) */
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------/
|
||||||
|
/ Locale and Namespace Configurations
|
||||||
|
/---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#define FF_CODE_PAGE 850
|
||||||
|
/* This option specifies the OEM code page to be used on the target system.
|
||||||
|
/ Incorrect code page setting can cause a file open failure.
|
||||||
|
/
|
||||||
|
/ 437 - U.S.
|
||||||
|
/ 720 - Arabic
|
||||||
|
/ 737 - Greek
|
||||||
|
/ 771 - KBL
|
||||||
|
/ 775 - Baltic
|
||||||
|
/ 850 - Latin 1
|
||||||
|
/ 852 - Latin 2
|
||||||
|
/ 855 - Cyrillic
|
||||||
|
/ 857 - Turkish
|
||||||
|
/ 860 - Portuguese
|
||||||
|
/ 861 - Icelandic
|
||||||
|
/ 862 - Hebrew
|
||||||
|
/ 863 - Canadian French
|
||||||
|
/ 864 - Arabic
|
||||||
|
/ 865 - Nordic
|
||||||
|
/ 866 - Russian
|
||||||
|
/ 869 - Greek 2
|
||||||
|
/ 932 - Japanese (DBCS)
|
||||||
|
/ 936 - Simplified Chinese (DBCS)
|
||||||
|
/ 949 - Korean (DBCS)
|
||||||
|
/ 950 - Traditional Chinese (DBCS)
|
||||||
|
/ 0 - Include all code pages above and configured by f_setcp()
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_LFN 1
|
||||||
|
#define FF_MAX_LFN 255
|
||||||
|
/* The FF_USE_LFN switches the support for LFN (long file name).
|
||||||
|
/
|
||||||
|
/ 0: Disable LFN. FF_MAX_LFN has no effect.
|
||||||
|
/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
|
||||||
|
/ 2: Enable LFN with dynamic working buffer on the STACK.
|
||||||
|
/ 3: Enable LFN with dynamic working buffer on the HEAP.
|
||||||
|
/
|
||||||
|
/ To enable the LFN, ffunicode.c needs to be added to the project. The LFN function
|
||||||
|
/ requiers certain internal working buffer occupies (FF_MAX_LFN + 1) * 2 bytes and
|
||||||
|
/ additional (FF_MAX_LFN + 44) / 15 * 32 bytes when exFAT is enabled.
|
||||||
|
/ The FF_MAX_LFN defines size of the working buffer in UTF-16 code unit and it can
|
||||||
|
/ be in range of 12 to 255. It is recommended to be set it 255 to fully support LFN
|
||||||
|
/ specification.
|
||||||
|
/ When use stack for the working buffer, take care on stack overflow. When use heap
|
||||||
|
/ memory for the working buffer, memory management functions, ff_memalloc() and
|
||||||
|
/ ff_memfree() exemplified in ffsystem.c, need to be added to the project. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_LFN_UNICODE 0
|
||||||
|
/* This option switches the character encoding on the API when LFN is enabled.
|
||||||
|
/
|
||||||
|
/ 0: ANSI/OEM in current CP (TCHAR = char)
|
||||||
|
/ 1: Unicode in UTF-16 (TCHAR = WCHAR)
|
||||||
|
/ 2: Unicode in UTF-8 (TCHAR = char)
|
||||||
|
/ 3: Unicode in UTF-32 (TCHAR = DWORD)
|
||||||
|
/
|
||||||
|
/ Also behavior of string I/O functions will be affected by this option.
|
||||||
|
/ When LFN is not enabled, this option has no effect. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_LFN_BUF 255
|
||||||
|
#define FF_SFN_BUF 12
|
||||||
|
/* This set of options defines size of file name members in the FILINFO structure
|
||||||
|
/ which is used to read out directory items. These values should be suffcient for
|
||||||
|
/ the file names to read. The maximum possible length of the read file name depends
|
||||||
|
/ on character encoding. When LFN is not enabled, these options have no effect. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_STRF_ENCODE 3
|
||||||
|
/* When FF_LFN_UNICODE >= 1 with LFN enabled, string I/O functions, f_gets(),
|
||||||
|
/ f_putc(), f_puts and f_printf() convert the character encoding in it.
|
||||||
|
/ This option selects assumption of character encoding ON THE FILE to be
|
||||||
|
/ read/written via those functions.
|
||||||
|
/
|
||||||
|
/ 0: ANSI/OEM in current CP
|
||||||
|
/ 1: Unicode in UTF-16LE
|
||||||
|
/ 2: Unicode in UTF-16BE
|
||||||
|
/ 3: Unicode in UTF-8
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_RPATH 0
|
||||||
|
/* This option configures support for relative path.
|
||||||
|
/
|
||||||
|
/ 0: Disable relative path and remove related functions.
|
||||||
|
/ 1: Enable relative path. f_chdir() and f_chdrive() are available.
|
||||||
|
/ 2: f_getcwd() function is available in addition to 1.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------/
|
||||||
|
/ Drive/Volume Configurations
|
||||||
|
/---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#define FF_VOLUMES 1
|
||||||
|
/* Number of volumes (logical drives) to be used. (1-10) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_STR_VOLUME_ID 1
|
||||||
|
#define FF_VOLUME_STRS "SD"
|
||||||
|
/* FF_STR_VOLUME_ID switches support for volume ID in arbitrary strings.
|
||||||
|
/ When FF_STR_VOLUME_ID is set to 1 or 2, arbitrary strings can be used as drive
|
||||||
|
/ number in the path name. FF_VOLUME_STRS defines the volume ID strings for each
|
||||||
|
/ logical drives. Number of items must not be less than FF_VOLUMES. Valid
|
||||||
|
/ characters for the volume ID strings are A-Z, a-z and 0-9, however, they are
|
||||||
|
/ compared in case-insensitive. If FF_STR_VOLUME_ID >= 1 and FF_VOLUME_STRS is
|
||||||
|
/ not defined, a user defined volume string table needs to be defined as:
|
||||||
|
/
|
||||||
|
/ const char* VolumeStr[FF_VOLUMES] = {"ram","flash","sd","usb",...
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_MULTI_PARTITION 0
|
||||||
|
/* This option switches support for multiple volumes on the physical drive.
|
||||||
|
/ By default (0), each logical drive number is bound to the same physical drive
|
||||||
|
/ number and only an FAT volume found on the physical drive will be mounted.
|
||||||
|
/ When this function is enabled (1), each logical drive number can be bound to
|
||||||
|
/ arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk()
|
||||||
|
/ funciton will be available. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_MIN_SS 512
|
||||||
|
#define FF_MAX_SS 512
|
||||||
|
/* This set of options configures the range of sector size to be supported. (512,
|
||||||
|
/ 1024, 2048 or 4096) Always set both 512 for most systems, generic memory card and
|
||||||
|
/ harddisk. But a larger value may be required for on-board flash memory and some
|
||||||
|
/ type of optical media. When FF_MAX_SS is larger than FF_MIN_SS, FatFs is configured
|
||||||
|
/ for variable sector size mode and disk_ioctl() function needs to implement
|
||||||
|
/ GET_SECTOR_SIZE command. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_LBA64 0
|
||||||
|
/* This option switches support for 64-bit LBA. (0:Disable or 1:Enable)
|
||||||
|
/ To enable the 64-bit LBA, also exFAT needs to be enabled. (FF_FS_EXFAT == 1) */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_MIN_GPT 0x100000000
|
||||||
|
/* Minimum number of sectors to switch GPT format to create partition in f_mkfs and
|
||||||
|
/ f_fdisk function. 0x100000000 max. This option has no effect when FF_LBA64 == 0. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_USE_TRIM 0
|
||||||
|
/* This option switches support for ATA-TRIM. (0:Disable or 1:Enable)
|
||||||
|
/ To enable Trim function, also CTRL_TRIM command should be implemented to the
|
||||||
|
/ disk_ioctl() function. */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------/
|
||||||
|
/ System Configurations
|
||||||
|
/---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#define FF_FS_TINY 0
|
||||||
|
/* This option switches tiny buffer configuration. (0:Normal or 1:Tiny)
|
||||||
|
/ At the tiny configuration, size of file object (FIL) is shrinked FF_MAX_SS bytes.
|
||||||
|
/ Instead of private sector buffer eliminated from the file object, common sector
|
||||||
|
/ buffer in the filesystem object (FATFS) is used for the file data transfer. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_EXFAT 0
|
||||||
|
/* This option switches support for exFAT filesystem. (0:Disable or 1:Enable)
|
||||||
|
/ To enable exFAT, also LFN needs to be enabled. (FF_USE_LFN >= 1)
|
||||||
|
/ Note that enabling exFAT discards ANSI C (C89) compatibility. */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_NORTC 0
|
||||||
|
#define FF_NORTC_MON 1
|
||||||
|
#define FF_NORTC_MDAY 1
|
||||||
|
#define FF_NORTC_YEAR 2019
|
||||||
|
/* The option FF_FS_NORTC switches timestamp functiton. If the system does not have
|
||||||
|
/ any RTC function or valid timestamp is not needed, set FF_FS_NORTC = 1 to disable
|
||||||
|
/ the timestamp function. Every object modified by FatFs will have a fixed timestamp
|
||||||
|
/ defined by FF_NORTC_MON, FF_NORTC_MDAY and FF_NORTC_YEAR in local time.
|
||||||
|
/ To enable timestamp function (FF_FS_NORTC = 0), get_fattime() function need to be
|
||||||
|
/ added to the project to read current time form real-time clock. FF_NORTC_MON,
|
||||||
|
/ FF_NORTC_MDAY and FF_NORTC_YEAR have no effect.
|
||||||
|
/ These options have no effect in read-only configuration (FF_FS_READONLY = 1). */
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_NOFSINFO 0
|
||||||
|
/* If you need to know correct free space on the FAT32 volume, set bit 0 of this
|
||||||
|
/ option, and f_getfree() function at first time after volume mount will force
|
||||||
|
/ a full FAT scan. Bit 1 controls the use of last allocated cluster number.
|
||||||
|
/
|
||||||
|
/ bit0=0: Use free cluster count in the FSINFO if available.
|
||||||
|
/ bit0=1: Do not trust free cluster count in the FSINFO.
|
||||||
|
/ bit1=0: Use last allocated cluster number in the FSINFO if available.
|
||||||
|
/ bit1=1: Do not trust last allocated cluster number in the FSINFO.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#define FF_FS_LOCK 0
|
||||||
|
/* The option FF_FS_LOCK switches file lock function to control duplicated file open
|
||||||
|
/ and illegal operation to open objects. This option must be 0 when FF_FS_READONLY
|
||||||
|
/ is 1.
|
||||||
|
/
|
||||||
|
/ 0: Disable file lock function. To avoid volume corruption, application program
|
||||||
|
/ should avoid illegal open, remove and rename to the open objects.
|
||||||
|
/ >0: Enable file lock function. The value defines how many files/sub-directories
|
||||||
|
/ can be opened simultaneously under file lock control. Note that the file
|
||||||
|
/ lock control is independent of re-entrancy. */
|
||||||
|
|
||||||
|
|
||||||
|
/* #include <somertos.h> // O/S definitions */
|
||||||
|
#define FF_FS_REENTRANT 0
|
||||||
|
#define FF_FS_TIMEOUT 1000
|
||||||
|
#define FF_SYNC_t HANDLE
|
||||||
|
/* The option FF_FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
|
||||||
|
/ module itself. Note that regardless of this option, file access to different
|
||||||
|
/ volume is always re-entrant and volume control functions, f_mount(), f_mkfs()
|
||||||
|
/ and f_fdisk() function, are always not re-entrant. Only file/directory access
|
||||||
|
/ to the same volume is under control of this function.
|
||||||
|
/
|
||||||
|
/ 0: Disable re-entrancy. FF_FS_TIMEOUT and FF_SYNC_t have no effect.
|
||||||
|
/ 1: Enable re-entrancy. Also user provided synchronization handlers,
|
||||||
|
/ ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj()
|
||||||
|
/ function, must be added to the project. Samples are available in
|
||||||
|
/ option/syscall.c.
|
||||||
|
/
|
||||||
|
/ The FF_FS_TIMEOUT defines timeout period in unit of time tick.
|
||||||
|
/ The FF_SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
|
||||||
|
/ SemaphoreHandle_t and etc. A header file for O/S definitions needs to be
|
||||||
|
/ included somewhere in the scope of ff.h. */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*--- End of configuration options ---*/
|
8045
stm-firmware/updater/ram-code/include/stm32/stm32f407xx.h
Normal file
8045
stm-firmware/updater/ram-code/include/stm32/stm32f407xx.h
Normal file
File diff suppressed because it is too large
Load Diff
254
stm-firmware/updater/ram-code/include/stm32/stm32f4xx.h
Normal file
254
stm-firmware/updater/ram-code/include/stm32/stm32f4xx.h
Normal file
@ -0,0 +1,254 @@
|
|||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file stm32f4xx.h
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V2.2.0
|
||||||
|
* @date 15-December-2014
|
||||||
|
* @brief CMSIS STM32F4xx Device Peripheral Access Layer Header File.
|
||||||
|
*
|
||||||
|
* The file is the unique include file that the application programmer
|
||||||
|
* is using in the C source code, usually in main.c. This file contains:
|
||||||
|
* - Configuration section that allows to select:
|
||||||
|
* - The STM32F4xx device used in the target application
|
||||||
|
* - To use or not the peripheral’s drivers in application code(i.e.
|
||||||
|
* code will be based on direct access to peripheral’s registers
|
||||||
|
* rather than drivers API), this option is controlled by
|
||||||
|
* "#define USE_HAL_DRIVER"
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
* are permitted provided that the following conditions are met:
|
||||||
|
* 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer in the documentation
|
||||||
|
* and/or other materials provided with the distribution.
|
||||||
|
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||||
|
* may be used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||||
|
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||||
|
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||||
|
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup CMSIS
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup stm32f4xx
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __STM32F4xx_H
|
||||||
|
#define __STM32F4xx_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif /* __cplusplus */
|
||||||
|
|
||||||
|
/** @addtogroup Library_configuration_section
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief In the following line adjust the value of External High Speed oscillator (HSE)
|
||||||
|
used in your application
|
||||||
|
|
||||||
|
Tip: To avoid modifying this file each time you need to use different HSE, you
|
||||||
|
can define the HSE value in your toolchain compiler preprocessor.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if !defined (HSE_VALUE)
|
||||||
|
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
|
||||||
|
#endif /* HSE_VALUE */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
|
||||||
|
Timeout value
|
||||||
|
*/
|
||||||
|
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||||
|
#define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */
|
||||||
|
#endif /* HSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
#if !defined (HSI_VALUE)
|
||||||
|
#define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
|
||||||
|
#endif /* HSI_VALUE */
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief STM32 Family
|
||||||
|
*/
|
||||||
|
#if !defined (STM32F4)
|
||||||
|
#define STM32F4
|
||||||
|
#endif /* STM32F4 */
|
||||||
|
|
||||||
|
/* Uncomment the line below according to the target STM32 device used in your
|
||||||
|
application
|
||||||
|
*/
|
||||||
|
#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \
|
||||||
|
!defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \
|
||||||
|
!defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F411xE)
|
||||||
|
/* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */
|
||||||
|
/* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */
|
||||||
|
/* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */
|
||||||
|
/* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */
|
||||||
|
/* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */
|
||||||
|
/* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */
|
||||||
|
/* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG,
|
||||||
|
STM32F439NI, STM32F429IG and STM32F429II Devices */
|
||||||
|
/* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG,
|
||||||
|
STM32F439NI, STM32F439IG and STM32F439II Devices */
|
||||||
|
/* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */
|
||||||
|
/* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */
|
||||||
|
/* #define STM32F411xE */ /*!< STM32F411CD, STM32F411RD, STM32F411VD, STM32F411CE, STM32F411RE and STM32F411VE Devices */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Tip: To avoid modifying this file each time you need to switch between these
|
||||||
|
devices, you can define the device in your toolchain compiler preprocessor.
|
||||||
|
*/
|
||||||
|
#if !defined (USE_HAL_DRIVER)
|
||||||
|
/**
|
||||||
|
* @brief Comment the line below if you will not use the peripherals drivers.
|
||||||
|
In this case, these drivers will not be included and the application code will
|
||||||
|
be based on direct access to peripherals registers
|
||||||
|
*/
|
||||||
|
/*#define USE_HAL_DRIVER */
|
||||||
|
#endif /* USE_HAL_DRIVER */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief CMSIS Device version number V2.2.0
|
||||||
|
*/
|
||||||
|
#define __STM32F4xx_CMSIS_DEVICE_VERSION_MAIN (0x02) /*!< [31:24] main version */
|
||||||
|
#define __STM32F4xx_CMSIS_DEVICE_VERSION_SUB1 (0x02) /*!< [23:16] sub1 version */
|
||||||
|
#define __STM32F4xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */
|
||||||
|
#define __STM32F4xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */
|
||||||
|
#define __STM32F4xx_CMSIS_DEVICE_VERSION ((__STM32F4xx_CMSIS_DEVICE_VERSION_MAIN << 24)\
|
||||||
|
|(__STM32F4xx_CMSIS_DEVICE_VERSION_SUB1 << 16)\
|
||||||
|
|(__STM32F4xx_CMSIS_DEVICE_VERSION_SUB2 << 8 )\
|
||||||
|
|(__STM32F4xx_CMSIS_DEVICE_VERSION))
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup Device_Included
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined(STM32F405xx)
|
||||||
|
#include "stm32f405xx.h"
|
||||||
|
#elif defined(STM32F415xx)
|
||||||
|
#include "stm32f415xx.h"
|
||||||
|
#elif defined(STM32F407xx)
|
||||||
|
#include "stm32f407xx.h"
|
||||||
|
#elif defined(STM32F417xx)
|
||||||
|
#include "stm32f417xx.h"
|
||||||
|
#elif defined(STM32F427xx)
|
||||||
|
#include "stm32f427xx.h"
|
||||||
|
#elif defined(STM32F437xx)
|
||||||
|
#include "stm32f437xx.h"
|
||||||
|
#elif defined(STM32F429xx)
|
||||||
|
#include "stm32f429xx.h"
|
||||||
|
#elif defined(STM32F439xx)
|
||||||
|
#include "stm32f439xx.h"
|
||||||
|
#elif defined(STM32F401xC)
|
||||||
|
#include "stm32f401xc.h"
|
||||||
|
#elif defined(STM32F401xE)
|
||||||
|
#include "stm32f401xe.h"
|
||||||
|
#elif defined(STM32F411xE)
|
||||||
|
#include "stm32f411xe.h"
|
||||||
|
#else
|
||||||
|
#error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup Exported_types
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
RESET = 0,
|
||||||
|
SET = !RESET
|
||||||
|
} FlagStatus, ITStatus;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DISABLE = 0,
|
||||||
|
ENABLE = !DISABLE
|
||||||
|
} FunctionalState;
|
||||||
|
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
ERROR = 0,
|
||||||
|
SUCCESS = !ERROR
|
||||||
|
} ErrorStatus;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/** @addtogroup Exported_macro
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define SET_BIT(REG, BIT) ((REG) |= (BIT))
|
||||||
|
|
||||||
|
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
|
||||||
|
|
||||||
|
#define READ_BIT(REG, BIT) ((REG) & (BIT))
|
||||||
|
|
||||||
|
#define CLEAR_REG(REG) ((REG) = (0x0))
|
||||||
|
|
||||||
|
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
|
||||||
|
|
||||||
|
#define READ_REG(REG) ((REG))
|
||||||
|
|
||||||
|
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
|
||||||
|
|
||||||
|
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined (USE_HAL_DRIVER)
|
||||||
|
#include "stm32f4xx_hal.h"
|
||||||
|
#endif /* USE_HAL_DRIVER */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif /* __cplusplus */
|
||||||
|
|
||||||
|
#endif /* __STM32F4xx_H */
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
62
stm-firmware/updater/ram-code/main.c
Normal file
62
stm-firmware/updater/ram-code/main.c
Normal file
@ -0,0 +1,62 @@
|
|||||||
|
#include <stdint.h>
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
#include <cmsis/core_cm4.h>
|
||||||
|
#include "hex-parser.h"
|
||||||
|
#include <fatfs/ff.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
static volatile unsigned int wait_tick;
|
||||||
|
|
||||||
|
static void watchdog_ack(void)
|
||||||
|
{
|
||||||
|
IWDG->KR = 0xAAAA;
|
||||||
|
}
|
||||||
|
|
||||||
|
void sdio_wait_ms(unsigned int ms)
|
||||||
|
{
|
||||||
|
wait_tick = 0;
|
||||||
|
while (wait_tick < ms);
|
||||||
|
}
|
||||||
|
|
||||||
|
static FATFS _fs;
|
||||||
|
#define fs (&_fs)
|
||||||
|
|
||||||
|
static void __attribute__((noreturn)) ram_code_exit(bool updated)
|
||||||
|
{
|
||||||
|
(void)updated;
|
||||||
|
|
||||||
|
NVIC_SystemReset();
|
||||||
|
while(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
int ram_code_main(void)
|
||||||
|
{
|
||||||
|
FRESULT fres;
|
||||||
|
|
||||||
|
SysTick_Config(168000UL);
|
||||||
|
__enable_irq();
|
||||||
|
|
||||||
|
fres = f_mount(fs, "0:/", 1);
|
||||||
|
if (fres != FR_OK) {
|
||||||
|
ram_code_exit(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
while(1) {
|
||||||
|
__WFI();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SysTick_Handler(void)
|
||||||
|
{
|
||||||
|
static uint32_t tick_cnt = 0;
|
||||||
|
|
||||||
|
wait_tick++;
|
||||||
|
tick_cnt++;
|
||||||
|
watchdog_ack();
|
||||||
|
if (tick_cnt >= 250) {
|
||||||
|
GPIOB->ODR ^= (1<<2);
|
||||||
|
tick_cnt = 0;
|
||||||
|
}
|
||||||
|
}
|
79
stm-firmware/updater/ram-code/ram-link.ld
Normal file
79
stm-firmware/updater/ram-code/ram-link.ld
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
/*
|
||||||
|
* STM32F407VE Linkerscript for updater RAM code execution
|
||||||
|
* Copyright (C) 2020 Mario Hüttel <mario.huettel@gmx.net>
|
||||||
|
*
|
||||||
|
* This file is part of 'Shimatta Reflow Controller'.
|
||||||
|
*
|
||||||
|
* It is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, version 2 of the License.
|
||||||
|
*
|
||||||
|
* This code 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 this template. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
* --------------------------------------------------------------------
|
||||||
|
* FLASH: 512K
|
||||||
|
* RAM: 128K
|
||||||
|
* CCM RAM: 64L
|
||||||
|
* FPU: fpv4-sp-d16
|
||||||
|
*/
|
||||||
|
|
||||||
|
ENTRY(Reset_Handler)
|
||||||
|
__ld_top_of_stack = 0x20020000; /* One byte above the end of the SRAM. Stack is pre-decrewmenting, so this is okay */
|
||||||
|
|
||||||
|
/* Available memory areas */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
FLASH (xr) : ORIGIN = 0x08000000, LENGTH = 512K
|
||||||
|
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||||
|
}
|
||||||
|
|
||||||
|
SECTIONS
|
||||||
|
{
|
||||||
|
.vectors :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
__ld_vector_start = .;
|
||||||
|
KEEP(*(.vectors));
|
||||||
|
. = ALIGN(4);
|
||||||
|
} > RAM
|
||||||
|
|
||||||
|
.text :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.text) /* .text sections (code) */
|
||||||
|
*(.text*) /* .text* sections (code) */
|
||||||
|
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||||
|
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||||
|
*(.glue_7) /* glue arm to thumb code */
|
||||||
|
*(.glue_7t) /* glue thumb to arm code */
|
||||||
|
*(.eh_frame)
|
||||||
|
KEEP(*(.init)) /* Constructors */
|
||||||
|
KEEP(*(.fini)) /* Destructors */
|
||||||
|
} > RAM
|
||||||
|
|
||||||
|
.data :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.data)
|
||||||
|
*(.data*)
|
||||||
|
. = ALIGN(4);
|
||||||
|
} > RAM
|
||||||
|
|
||||||
|
.bss (NOLOAD) :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
__ld_sbss = .;
|
||||||
|
*(.bss)
|
||||||
|
*(.bss*)
|
||||||
|
*(COMMON)
|
||||||
|
. = ALIGN(4);
|
||||||
|
__ld_ebss = .;
|
||||||
|
} > RAM
|
||||||
|
|
||||||
|
}
|
295
stm-firmware/updater/ram-code/startup.c
Normal file
295
stm-firmware/updater/ram-code/startup.c
Normal file
@ -0,0 +1,295 @@
|
|||||||
|
/*
|
||||||
|
* STM32F4 Startup Code for STM32F407 devices
|
||||||
|
* Copyright (C) 2017 Mario Hüttel <mario.huettel@gmx.net>
|
||||||
|
*
|
||||||
|
* This file is part of 'STM32F4 code template'.
|
||||||
|
*
|
||||||
|
* It is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, version 2 of the License.
|
||||||
|
*
|
||||||
|
* This code 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 this template. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
* ------------------------------------------------------------------------
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
/* C++ library init */
|
||||||
|
# if defined(__cplusplus)
|
||||||
|
extern "C" {
|
||||||
|
extern void __libc_init_array(void);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Defines for weak default handlers */
|
||||||
|
#define WEAK __attribute__((weak))
|
||||||
|
#define ALIAS(func) __attribute__ ((weak, alias (#func)))
|
||||||
|
|
||||||
|
/* Define for section mapping */
|
||||||
|
#define SECTION(sec) __attribute__((section(sec)))
|
||||||
|
|
||||||
|
/* Handler prototypes */
|
||||||
|
#if defined(_cplusplus)
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/* Interrupt Defualt handler */
|
||||||
|
WEAK void __int_default_handler(void);
|
||||||
|
|
||||||
|
/* Core Interrupts */
|
||||||
|
void Reset_Handler(void);
|
||||||
|
void NMI_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void HardFault_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void MemManage_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void BusFault_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void UsageFault_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void SVC_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void DebugMon_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void PendSV_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
void SysTick_Handler(void) ALIAS(__int_default_handler);
|
||||||
|
|
||||||
|
/* Peripheral Interrupts (by default mapped onto Default Handler) */
|
||||||
|
void WWDG_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void PVD_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TAMP_STAMP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void RTC_WKUP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void FLASH_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void RCC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI0_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI4_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream0_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream4_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream5_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream6_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void ADC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN1_TX_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN1_RX0_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN1_RX1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN1_SCE_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI9_5_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM1_BRK_TIM9_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM1_UP_TIM10_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM1_TRG_COM_TIM11_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM1_CC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM4_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C1_EV_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C1_ER_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C2_EV_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C2_ER_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void SPI1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void SPI2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void USART1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void USART2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void USART3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void EXTI15_10_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void RTC_Alarm_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_FS_WKUP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM8_BRK_TIM12_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM8_UP_TIM13_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM8_TRG_COM_TIM14_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM8_CC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA1_Stream7_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void FSMC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void SDIO_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM5_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void SPI3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void UART4_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void UART5_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM6_DAC_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void TIM7_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream0_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream2_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream3_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream4_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void ETH_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void ETH_WKUP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN2_TX_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN2_RX0_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN2_RX1_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CAN2_SCE_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_FS_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream5_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream6_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DMA2_Stream7_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void USART6_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C3_EV_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void I2C3_ER_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_HS_EP1_OUT_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_HS_EP1_IN_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_HS_WKUP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void OTG_HS_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void DCMI_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void CRYP_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void HASH_RNG_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
void FPU_IRQHandler(void) ALIAS(__int_default_handler);
|
||||||
|
|
||||||
|
extern int ram_code_main(void);
|
||||||
|
extern void SystemInit(void);
|
||||||
|
|
||||||
|
extern void __ld_top_of_stack(void);
|
||||||
|
#if defined(_cplusplus)
|
||||||
|
extern "C" }
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void (* const vector_table[])(void) SECTION(".vectors") = {
|
||||||
|
&__ld_top_of_stack,
|
||||||
|
/* Core Interrupts */
|
||||||
|
Reset_Handler,
|
||||||
|
NMI_Handler,
|
||||||
|
HardFault_Handler,
|
||||||
|
MemManage_Handler,
|
||||||
|
BusFault_Handler,
|
||||||
|
UsageFault_Handler,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
SVC_Handler,
|
||||||
|
DebugMon_Handler,
|
||||||
|
0,
|
||||||
|
PendSV_Handler,
|
||||||
|
SysTick_Handler,
|
||||||
|
/* Peripheral Interrupts */
|
||||||
|
WWDG_IRQHandler,
|
||||||
|
PVD_IRQHandler,
|
||||||
|
TAMP_STAMP_IRQHandler,
|
||||||
|
RTC_WKUP_IRQHandler,
|
||||||
|
FLASH_IRQHandler,
|
||||||
|
RCC_IRQHandler,
|
||||||
|
EXTI0_IRQHandler,
|
||||||
|
EXTI1_IRQHandler,
|
||||||
|
EXTI2_IRQHandler,
|
||||||
|
EXTI3_IRQHandler,
|
||||||
|
EXTI4_IRQHandler,
|
||||||
|
DMA1_Stream0_IRQHandler,
|
||||||
|
DMA1_Stream1_IRQHandler,
|
||||||
|
DMA1_Stream2_IRQHandler,
|
||||||
|
DMA1_Stream3_IRQHandler,
|
||||||
|
DMA1_Stream4_IRQHandler,
|
||||||
|
DMA1_Stream5_IRQHandler,
|
||||||
|
DMA1_Stream6_IRQHandler,
|
||||||
|
ADC_IRQHandler,
|
||||||
|
CAN1_TX_IRQHandler,
|
||||||
|
CAN1_RX0_IRQHandler,
|
||||||
|
CAN1_RX1_IRQHandler,
|
||||||
|
CAN1_SCE_IRQHandler,
|
||||||
|
EXTI9_5_IRQHandler,
|
||||||
|
TIM1_BRK_TIM9_IRQHandler,
|
||||||
|
TIM1_UP_TIM10_IRQHandler,
|
||||||
|
TIM1_TRG_COM_TIM11_IRQHandler,
|
||||||
|
TIM1_CC_IRQHandler,
|
||||||
|
TIM2_IRQHandler,
|
||||||
|
TIM3_IRQHandler,
|
||||||
|
TIM4_IRQHandler,
|
||||||
|
I2C1_EV_IRQHandler,
|
||||||
|
I2C1_ER_IRQHandler,
|
||||||
|
I2C2_EV_IRQHandler,
|
||||||
|
I2C2_ER_IRQHandler,
|
||||||
|
SPI1_IRQHandler,
|
||||||
|
SPI2_IRQHandler,
|
||||||
|
USART1_IRQHandler,
|
||||||
|
USART2_IRQHandler,
|
||||||
|
USART3_IRQHandler,
|
||||||
|
EXTI15_10_IRQHandler,
|
||||||
|
RTC_Alarm_IRQHandler,
|
||||||
|
OTG_FS_WKUP_IRQHandler,
|
||||||
|
TIM8_BRK_TIM12_IRQHandler,
|
||||||
|
TIM8_UP_TIM13_IRQHandler,
|
||||||
|
TIM8_TRG_COM_TIM14_IRQHandler,
|
||||||
|
TIM8_CC_IRQHandler,
|
||||||
|
DMA1_Stream7_IRQHandler,
|
||||||
|
FSMC_IRQHandler,
|
||||||
|
SDIO_IRQHandler,
|
||||||
|
TIM5_IRQHandler,
|
||||||
|
SPI3_IRQHandler,
|
||||||
|
UART4_IRQHandler,
|
||||||
|
UART5_IRQHandler,
|
||||||
|
TIM6_DAC_IRQHandler,
|
||||||
|
TIM7_IRQHandler,
|
||||||
|
DMA2_Stream0_IRQHandler,
|
||||||
|
DMA2_Stream1_IRQHandler,
|
||||||
|
DMA2_Stream2_IRQHandler,
|
||||||
|
DMA2_Stream3_IRQHandler,
|
||||||
|
DMA2_Stream4_IRQHandler,
|
||||||
|
ETH_IRQHandler,
|
||||||
|
ETH_WKUP_IRQHandler,
|
||||||
|
CAN2_TX_IRQHandler,
|
||||||
|
CAN2_RX0_IRQHandler,
|
||||||
|
CAN2_RX1_IRQHandler,
|
||||||
|
CAN2_SCE_IRQHandler,
|
||||||
|
OTG_FS_IRQHandler,
|
||||||
|
DMA2_Stream5_IRQHandler,
|
||||||
|
DMA2_Stream6_IRQHandler,
|
||||||
|
DMA2_Stream7_IRQHandler,
|
||||||
|
USART6_IRQHandler,
|
||||||
|
I2C3_EV_IRQHandler,
|
||||||
|
I2C3_ER_IRQHandler,
|
||||||
|
OTG_HS_EP1_OUT_IRQHandler,
|
||||||
|
OTG_HS_EP1_IN_IRQHandler,
|
||||||
|
OTG_HS_WKUP_IRQHandler,
|
||||||
|
OTG_HS_IRQHandler,
|
||||||
|
DCMI_IRQHandler,
|
||||||
|
CRYP_IRQHandler,
|
||||||
|
HASH_RNG_IRQHandler,
|
||||||
|
FPU_IRQHandler
|
||||||
|
};
|
||||||
|
|
||||||
|
static void __fill_zero(unsigned int *start, unsigned int *end) {
|
||||||
|
while ((unsigned int) start < (unsigned int)end) {
|
||||||
|
*(start++) = 0x00000000;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
extern unsigned int __ld_vector_start;
|
||||||
|
extern unsigned int __ld_sbss;
|
||||||
|
extern unsigned int __ld_ebss;
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef CPACR
|
||||||
|
#undef CPACR
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define CPACR (*((volatile uint32_t *)0xE000ED88))
|
||||||
|
|
||||||
|
void Reset_Handler(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
/* The first thing we do here, is to initialize the FPU
|
||||||
|
* When this code is compiled optimized with hardfpu abi,
|
||||||
|
* GCC tends to generate FPU instructions for data copying
|
||||||
|
*/
|
||||||
|
CPACR |= (0xF << 20);
|
||||||
|
/* Reset the stack pointer to top of stack. SP is not required to be inside the clobber list! */
|
||||||
|
__asm__ __volatile__ ("mov sp, %0\n\t" :: "r"(&__ld_top_of_stack) :);
|
||||||
|
|
||||||
|
/* Fill bss with zero */
|
||||||
|
__fill_zero(&__ld_sbss, &__ld_ebss);
|
||||||
|
/* Fill Heap with zero */
|
||||||
|
|
||||||
|
ram_code_main();
|
||||||
|
|
||||||
|
/* Catch return from main() */
|
||||||
|
while(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
WEAK void __int_default_handler(void)
|
||||||
|
{
|
||||||
|
while(1);
|
||||||
|
}
|
59
stm-firmware/updater/updater.c
Normal file
59
stm-firmware/updater/updater.c
Normal file
@ -0,0 +1,59 @@
|
|||||||
|
/* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <reflow-controller/updater/updater.h>
|
||||||
|
#include <reflow-controller/safety/watchdog.h>
|
||||||
|
#include "ram-code/updater-ram-code.bin.h"
|
||||||
|
#include <stm32/stm32f4xx.h>
|
||||||
|
#include <cmsis/core_cm4.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
void __attribute__((noreturn)) start_updater(void)
|
||||||
|
{
|
||||||
|
const char *updater_src = binary_blob;
|
||||||
|
char *dest_ptr = (char *)UPDATER_RAM_CODE_BASE_ADDRESS;
|
||||||
|
uint32_t *dest_ptr_words = (uint32_t *)UPDATER_RAM_CODE_BASE_ADDRESS;
|
||||||
|
uint32_t updater_size = (uint32_t)sizeof(binary_blob);
|
||||||
|
uint32_t i;
|
||||||
|
void (*reset_ptr)(void);
|
||||||
|
|
||||||
|
/* This function will never return
|
||||||
|
* because it corrupts memory by copying the ram code for updating
|
||||||
|
* Therefore we have to make sure to only use stack in this function
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Disable all IRQs and ack the watchdog */
|
||||||
|
__disable_irq();
|
||||||
|
watchdog_ack(WATCHDOG_MAGIC_KEY);
|
||||||
|
|
||||||
|
for (i = 0UL; i < updater_size; i++)
|
||||||
|
*(dest_ptr++) = *(updater_src++);
|
||||||
|
|
||||||
|
/* Load the reset vector of the RAM code */
|
||||||
|
reset_ptr = (void (*)(void))dest_ptr_words[1];
|
||||||
|
|
||||||
|
/* Move the interrupt vector table to ram code */
|
||||||
|
SCB->VTOR = UPDATER_RAM_CODE_BASE_ADDRESS;
|
||||||
|
|
||||||
|
reset_ptr();
|
||||||
|
|
||||||
|
while(1);
|
||||||
|
}
|
Loading…
Reference in New Issue
Block a user