git-subtree-dir: panda git-subtree-split: 3b35621671aaa6de3fc66d85d30e4208a77e2489pull/950/head
commit
b0b7a768f0
370 changed files with 70350 additions and 0 deletions
@ -0,0 +1,118 @@ |
|||||||
|
version: 2 |
||||||
|
jobs: |
||||||
|
safety: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t panda_safety -f tests/safety/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Run safety test |
||||||
|
command: | |
||||||
|
docker run panda_safety /bin/bash -c "cd /panda/tests/safety; PYTHONPATH=/ ./test.sh" |
||||||
|
|
||||||
|
misra-c2012: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t panda_misra -f tests/misra/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Run Misra C 2012 test |
||||||
|
command: | |
||||||
|
mkdir /tmp/misra |
||||||
|
docker run -v /tmp/misra:/tmp/misra panda_misra /bin/bash -c "cd /panda/tests/misra; ./test_misra.sh" |
||||||
|
- store_artifacts: |
||||||
|
name: Store cppcheck test output |
||||||
|
path: /tmp/misra/cppcheck_output.txt |
||||||
|
- store_artifacts: |
||||||
|
name: Store misra test output |
||||||
|
path: /tmp/misra/misra_output.txt |
||||||
|
|
||||||
|
build: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t panda_build -f tests/build/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Test python package installer |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda; python setup.py install" |
||||||
|
- run: |
||||||
|
name: Build Panda STM image |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda/board; make bin" |
||||||
|
- run: |
||||||
|
name: Build Panda STM bootstub image |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda/board; make obj/bootstub.panda.bin" |
||||||
|
- run: |
||||||
|
name: Build Pedal STM image |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/comma.bin" |
||||||
|
- run: |
||||||
|
name: Build Pedal STM bootstub image |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/bootstub.bin" |
||||||
|
- run: |
||||||
|
name: Build ESP image |
||||||
|
command: | |
||||||
|
docker run panda_build /bin/bash -c "cd /panda/boardesp; ./get_sdk.sh; make user1.bin" |
||||||
|
|
||||||
|
safety_replay: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t panda_safety_replay -f tests/safety_replay/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Replay drives |
||||||
|
command: | |
||||||
|
docker run panda_safety_replay /bin/bash -c "cd /openpilot/panda/tests/safety_replay; PYTHONPATH=/openpilot ./test_safety_replay.py" |
||||||
|
|
||||||
|
language_check: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t language_check -f tests/language/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Check code for bad language |
||||||
|
command: | |
||||||
|
docker run language_check /bin/bash -c "cd /panda/tests/language; ./test_language.py" |
||||||
|
|
||||||
|
linter_python: |
||||||
|
machine: |
||||||
|
docker_layer_caching: true |
||||||
|
steps: |
||||||
|
- checkout |
||||||
|
- run: |
||||||
|
name: Build image |
||||||
|
command: "docker build -t linter_python -f tests/linter_python/Dockerfile ." |
||||||
|
- run: |
||||||
|
name: Run linter python test |
||||||
|
command: | |
||||||
|
docker run linter_python /bin/bash -c "cd /panda/tests/linter_python; PYTHONPATH=/ ./flake8_panda.sh" |
||||||
|
docker run linter_python /bin/bash -c "cd /panda/tests/linter_python; PYTHONPATH=/ ./pylint_panda.sh" |
||||||
|
|
||||||
|
workflows: |
||||||
|
version: 2 |
||||||
|
main: |
||||||
|
jobs: |
||||||
|
- safety |
||||||
|
- misra-c2012 |
||||||
|
- build |
||||||
|
- safety_replay |
||||||
|
- language_check |
||||||
|
- linter_python |
@ -0,0 +1,3 @@ |
|||||||
|
.git |
||||||
|
.DS_Store |
||||||
|
boardesp/esp-open-sdk |
@ -0,0 +1,17 @@ |
|||||||
|
*.pyc |
||||||
|
.*.swp |
||||||
|
.*.swo |
||||||
|
*.o |
||||||
|
*.so |
||||||
|
*.d |
||||||
|
*.dump |
||||||
|
a.out |
||||||
|
*~ |
||||||
|
.#* |
||||||
|
dist/ |
||||||
|
pandacan.egg-info/ |
||||||
|
board/obj/ |
||||||
|
examples/output.csv |
||||||
|
.DS_Store |
||||||
|
.vscode |
||||||
|
nosetests.xml |
@ -0,0 +1,83 @@ |
|||||||
|
FROM ubuntu:16.04 |
||||||
|
ENV PYTHONUNBUFFERED 1 |
||||||
|
|
||||||
|
RUN apt-get update && apt-get install -y \ |
||||||
|
autoconf \ |
||||||
|
automake \ |
||||||
|
bash \ |
||||||
|
bison \ |
||||||
|
bzip2 \ |
||||||
|
curl \ |
||||||
|
dfu-util \ |
||||||
|
flex \ |
||||||
|
g++ \ |
||||||
|
gawk \ |
||||||
|
gcc \ |
||||||
|
git \ |
||||||
|
gperf \ |
||||||
|
help2man \ |
||||||
|
iputils-ping \ |
||||||
|
libbz2-dev \ |
||||||
|
libexpat-dev \ |
||||||
|
libffi-dev \ |
||||||
|
libssl-dev \ |
||||||
|
libstdc++-arm-none-eabi-newlib \ |
||||||
|
libtool \ |
||||||
|
libtool-bin \ |
||||||
|
libusb-1.0-0 \ |
||||||
|
locales \ |
||||||
|
make \ |
||||||
|
ncurses-dev \ |
||||||
|
network-manager \ |
||||||
|
python-dev \ |
||||||
|
python-serial \ |
||||||
|
sed \ |
||||||
|
texinfo \ |
||||||
|
unrar-free \ |
||||||
|
unzip \ |
||||||
|
wget \ |
||||||
|
build-essential \ |
||||||
|
python-dev \ |
||||||
|
python-pip \ |
||||||
|
screen \ |
||||||
|
vim \ |
||||||
|
wget \ |
||||||
|
wireless-tools \ |
||||||
|
zlib1g-dev |
||||||
|
|
||||||
|
RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen |
||||||
|
ENV LANG en_US.UTF-8 |
||||||
|
ENV LANGUAGE en_US:en |
||||||
|
ENV LC_ALL en_US.UTF-8 |
||||||
|
|
||||||
|
RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash |
||||||
|
|
||||||
|
ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" |
||||||
|
RUN pyenv install 3.7.3 |
||||||
|
RUN pyenv install 2.7.12 |
||||||
|
RUN pyenv global 3.7.3 |
||||||
|
RUN pyenv rehash |
||||||
|
|
||||||
|
RUN pip install --upgrade pip==18.0 |
||||||
|
|
||||||
|
COPY requirements.txt /tmp/ |
||||||
|
RUN pip install -r /tmp/requirements.txt |
||||||
|
|
||||||
|
RUN mkdir -p /home/batman |
||||||
|
ENV HOME /home/batman |
||||||
|
|
||||||
|
ENV PYTHONPATH /tmp:$PYTHONPATH |
||||||
|
|
||||||
|
COPY ./boardesp/get_sdk_ci.sh /tmp/panda/boardesp/ |
||||||
|
COPY ./boardesp/python2_make.py /tmp/panda/boardesp/ |
||||||
|
|
||||||
|
COPY ./panda_jungle /tmp/panda_jungle |
||||||
|
|
||||||
|
RUN useradd --system -s /sbin/nologin pandauser |
||||||
|
RUN mkdir -p /tmp/panda/boardesp/esp-open-sdk |
||||||
|
RUN chown pandauser /tmp/panda/boardesp/esp-open-sdk |
||||||
|
USER pandauser |
||||||
|
RUN cd /tmp/panda/boardesp && ./get_sdk_ci.sh |
||||||
|
USER root |
||||||
|
|
||||||
|
ADD ./panda.tar.gz /tmp/panda |
@ -0,0 +1,80 @@ |
|||||||
|
pipeline { |
||||||
|
agent any |
||||||
|
environment { |
||||||
|
AUTHOR = """${sh( |
||||||
|
returnStdout: true, |
||||||
|
script: "git --no-pager show -s --format='%an' ${GIT_COMMIT}" |
||||||
|
).trim()}""" |
||||||
|
|
||||||
|
DOCKER_IMAGE_TAG = "panda:build-${env.GIT_COMMIT}" |
||||||
|
DOCKER_NAME = "panda-test-${env.GIT_COMMIT}" |
||||||
|
} |
||||||
|
stages { |
||||||
|
stage('Build Docker Image') { |
||||||
|
steps { |
||||||
|
timeout(time: 60, unit: 'MINUTES') { |
||||||
|
script { |
||||||
|
try { |
||||||
|
sh 'cp -R /home/batman/panda_jungle .' |
||||||
|
} catch (err) { |
||||||
|
echo "Folder already exists" |
||||||
|
} |
||||||
|
sh 'git archive -v -o panda.tar.gz --format=tar.gz HEAD' |
||||||
|
dockerImage = docker.build("${env.DOCKER_IMAGE_TAG}") |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
stage('Test Dev Build (no WIFI)') { |
||||||
|
steps { |
||||||
|
lock(resource: "Pandas", inversePrecedence: true, quantity: 1){ |
||||||
|
timeout(time: 60, unit: 'MINUTES') { |
||||||
|
script { |
||||||
|
sh "docker run --name ${env.DOCKER_NAME} --privileged --volume /dev/bus/usb:/dev/bus/usb --volume /var/run/dbus:/var/run/dbus --net host ${env.DOCKER_IMAGE_TAG} bash -c 'cd /tmp/panda; SKIPWIFI=1 ./run_automated_tests.sh'" |
||||||
|
sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_dev_nowifi.xml" |
||||||
|
sh "docker rm ${env.DOCKER_NAME}" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
stage('Test EON Build') { |
||||||
|
steps { |
||||||
|
lock(resource: "Pandas", inversePrecedence: true, quantity: 1){ |
||||||
|
timeout(time: 60, unit: 'MINUTES') { |
||||||
|
script { |
||||||
|
sh "docker run --name ${env.DOCKER_NAME} --privileged --volume /dev/bus/usb:/dev/bus/usb --volume /var/run/dbus:/var/run/dbus --net host ${env.DOCKER_IMAGE_TAG} bash -c 'touch /EON; cd /tmp/panda; ./run_automated_tests.sh'" |
||||||
|
sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_eon.xml" |
||||||
|
sh "docker rm ${env.DOCKER_NAME}" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
/* |
||||||
|
stage('Test Dev Build (WIFI)') { |
||||||
|
steps { |
||||||
|
lock(resource: "Pandas", inversePrecedence: true, quantity: 1){ |
||||||
|
timeout(time: 60, unit: 'MINUTES') { |
||||||
|
script { |
||||||
|
sh "docker run --name ${env.DOCKER_NAME} --privileged --volume /dev/bus/usb:/dev/bus/usb --volume /var/run/dbus:/var/run/dbus --net host ${env.DOCKER_IMAGE_TAG} bash -c 'cd /tmp/panda; ./run_automated_tests.sh'" |
||||||
|
sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_dev.xml" |
||||||
|
sh "docker rm ${env.DOCKER_NAME}" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
*/ |
||||||
|
} |
||||||
|
post { |
||||||
|
failure { |
||||||
|
script { |
||||||
|
sh "docker rm ${env.DOCKER_NAME} || true" |
||||||
|
} |
||||||
|
} |
||||||
|
always { |
||||||
|
junit "test_results*.xml" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,7 @@ |
|||||||
|
Copyright (c) 2016, Comma.ai, Inc. |
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: |
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. |
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. |
@ -0,0 +1,31 @@ |
|||||||
|
** Projects ** |
||||||
|
|
||||||
|
== ELM327 Emulator == |
||||||
|
|
||||||
|
Write an elm327 emulator in boardesp/elm327.c and make it work with Torque |
||||||
|
|
||||||
|
You'll find a start at this in the "elm327" branch. |
||||||
|
|
||||||
|
== socketcan Kernel Driver == |
||||||
|
|
||||||
|
Write a kernel driver version of lib/panda.py that exposes the Panda on socketcan and makes it work with those tools. |
||||||
|
|
||||||
|
You may want to switch to interrupt endpoint first. Should LIN be exposed as a serial interface? |
||||||
|
|
||||||
|
== Windows J2534 DLL == |
||||||
|
|
||||||
|
Write a Windows DLL that exposes the J2534 API. |
||||||
|
|
||||||
|
Will make the Panda work with car diagnostic software. |
||||||
|
|
||||||
|
|
||||||
|
** Refactors ** |
||||||
|
|
||||||
|
== USB Interrupt Endpoint == |
||||||
|
|
||||||
|
Switch USB to use an interrupt endpoint instead of a bulk endpoint for can recv |
||||||
|
|
||||||
|
== WebSocket Support == |
||||||
|
|
||||||
|
Add CAN streaming over WebSocket to the ELM code in addition to the UDP pipe. |
||||||
|
|
@ -0,0 +1,9 @@ |
|||||||
|
# Updating your panda |
||||||
|
|
||||||
|
Panda should update automatically via the [openpilot](http://openpilot.comma.ai/). |
||||||
|
|
||||||
|
On Linux or Mac OSX, you can manually update it using: |
||||||
|
``` |
||||||
|
sudo pip install --upgrade pandacan` |
||||||
|
PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` |
||||||
|
``` |
@ -0,0 +1 @@ |
|||||||
|
from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial # noqa: F401 |
@ -0,0 +1,8 @@ |
|||||||
|
PROJ_NAME = panda
|
||||||
|
CFLAGS = -g -Wall -Wextra -Wstrict-prototypes -Werror
|
||||||
|
|
||||||
|
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m4
|
||||||
|
CFLAGS += -mhard-float -DSTM32F4 -DSTM32F413xx -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||||
|
STARTUP_FILE = startup_stm32f413xx
|
||||||
|
|
||||||
|
include build.mk |
@ -0,0 +1,36 @@ |
|||||||
|
Dependencies |
||||||
|
-------- |
||||||
|
|
||||||
|
**Mac** |
||||||
|
|
||||||
|
``` |
||||||
|
xcode-select --install |
||||||
|
./get_sdk_mac.sh |
||||||
|
``` |
||||||
|
|
||||||
|
**Debian / Ubuntu** |
||||||
|
|
||||||
|
``` |
||||||
|
./get_sdk.sh |
||||||
|
``` |
||||||
|
|
||||||
|
|
||||||
|
Programming |
||||||
|
---- |
||||||
|
|
||||||
|
**Panda** |
||||||
|
|
||||||
|
``` |
||||||
|
make |
||||||
|
``` |
||||||
|
|
||||||
|
Troubleshooting |
||||||
|
---- |
||||||
|
|
||||||
|
If your panda will not flash and is quickly blinking a single Green LED, use: |
||||||
|
``` |
||||||
|
make recover |
||||||
|
``` |
||||||
|
|
||||||
|
|
||||||
|
[dfu-util](http://github.com/dsigma/dfu-util.git) for flashing |
@ -0,0 +1,94 @@ |
|||||||
|
// ///////////////////////////////////////////////////////////// //
|
||||||
|
// Hardware abstraction layer for all different supported boards //
|
||||||
|
// ///////////////////////////////////////////////////////////// //
|
||||||
|
#include "board_declarations.h" |
||||||
|
#include "boards/common.h" |
||||||
|
|
||||||
|
// ///// Board definition and detection ///// //
|
||||||
|
#include "drivers/harness.h" |
||||||
|
#ifdef PANDA |
||||||
|
#include "drivers/fan.h" |
||||||
|
#include "drivers/rtc.h" |
||||||
|
#include "boards/white.h" |
||||||
|
#include "boards/grey.h" |
||||||
|
#include "boards/black.h" |
||||||
|
#include "boards/uno.h" |
||||||
|
#else |
||||||
|
#include "boards/pedal.h" |
||||||
|
#endif |
||||||
|
|
||||||
|
void detect_board_type(void) { |
||||||
|
#ifdef PANDA |
||||||
|
// SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART)
|
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 1); |
||||||
|
if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ |
||||||
|
hw_type = HW_TYPE_WHITE_PANDA; |
||||||
|
current_board = &board_white; |
||||||
|
} else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K
|
||||||
|
hw_type = HW_TYPE_GREY_PANDA; |
||||||
|
current_board = &board_grey; |
||||||
|
} else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { |
||||||
|
hw_type = HW_TYPE_UNO; |
||||||
|
current_board = &board_uno; |
||||||
|
} else { |
||||||
|
hw_type = HW_TYPE_BLACK_PANDA; |
||||||
|
current_board = &board_black; |
||||||
|
} |
||||||
|
#else |
||||||
|
#ifdef PEDAL |
||||||
|
hw_type = HW_TYPE_PEDAL; |
||||||
|
current_board = &board_pedal; |
||||||
|
#else |
||||||
|
hw_type = HW_TYPE_UNKNOWN; |
||||||
|
puts("Hardware type is UNKNOWN!\n"); |
||||||
|
#endif |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
// ///// Configuration detection ///// //
|
||||||
|
bool has_external_debug_serial = 0; |
||||||
|
bool is_entering_bootmode = 0; |
||||||
|
|
||||||
|
void detect_configuration(void) { |
||||||
|
// detect if external serial debugging is present
|
||||||
|
has_external_debug_serial = detect_with_pull(GPIOA, 3, PULL_DOWN); |
||||||
|
|
||||||
|
#ifdef PANDA |
||||||
|
if(hw_type == HW_TYPE_WHITE_PANDA) { |
||||||
|
// check if the ESP is trying to put me in boot mode
|
||||||
|
is_entering_bootmode = !detect_with_pull(GPIOB, 0, PULL_UP); |
||||||
|
} else { |
||||||
|
is_entering_bootmode = 0; |
||||||
|
} |
||||||
|
#else |
||||||
|
is_entering_bootmode = 0; |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
// ///// Board functions ///// //
|
||||||
|
// TODO: Make these config options in the board struct
|
||||||
|
bool board_has_gps(void) { |
||||||
|
return ((hw_type == HW_TYPE_GREY_PANDA) || (hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); |
||||||
|
} |
||||||
|
|
||||||
|
bool board_has_gmlan(void) { |
||||||
|
return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); |
||||||
|
} |
||||||
|
|
||||||
|
bool board_has_obd(void) { |
||||||
|
return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); |
||||||
|
} |
||||||
|
|
||||||
|
bool board_has_lin(void) { |
||||||
|
return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); |
||||||
|
} |
||||||
|
|
||||||
|
bool board_has_rtc(void) { |
||||||
|
return (hw_type == HW_TYPE_UNO); |
||||||
|
} |
||||||
|
|
||||||
|
bool board_has_relay(void) { |
||||||
|
return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); |
||||||
|
} |
@ -0,0 +1,74 @@ |
|||||||
|
// ******************** Prototypes ********************
|
||||||
|
typedef void (*board_init)(void); |
||||||
|
typedef void (*board_enable_can_transciever)(uint8_t transciever, bool enabled); |
||||||
|
typedef void (*board_enable_can_transcievers)(bool enabled); |
||||||
|
typedef void (*board_set_led)(uint8_t color, bool enabled); |
||||||
|
typedef void (*board_set_usb_power_mode)(uint8_t mode); |
||||||
|
typedef void (*board_set_esp_gps_mode)(uint8_t mode); |
||||||
|
typedef void (*board_set_can_mode)(uint8_t mode); |
||||||
|
typedef void (*board_usb_power_mode_tick)(uint32_t uptime); |
||||||
|
typedef bool (*board_check_ignition)(void); |
||||||
|
typedef uint32_t (*board_read_current)(void); |
||||||
|
typedef void (*board_set_ir_power)(uint8_t percentage); |
||||||
|
typedef void (*board_set_fan_power)(uint8_t percentage); |
||||||
|
typedef void (*board_set_phone_power)(bool enabled); |
||||||
|
|
||||||
|
struct board { |
||||||
|
const char *board_type; |
||||||
|
const harness_configuration *harness_config; |
||||||
|
board_init init; |
||||||
|
board_enable_can_transciever enable_can_transciever; |
||||||
|
board_enable_can_transcievers enable_can_transcievers; |
||||||
|
board_set_led set_led; |
||||||
|
board_set_usb_power_mode set_usb_power_mode; |
||||||
|
board_set_esp_gps_mode set_esp_gps_mode; |
||||||
|
board_set_can_mode set_can_mode; |
||||||
|
board_usb_power_mode_tick usb_power_mode_tick; |
||||||
|
board_check_ignition check_ignition; |
||||||
|
board_read_current read_current; |
||||||
|
board_set_ir_power set_ir_power; |
||||||
|
board_set_fan_power set_fan_power; |
||||||
|
board_set_phone_power set_phone_power; |
||||||
|
}; |
||||||
|
|
||||||
|
// ******************* Definitions ********************
|
||||||
|
// These should match the enums in cereal/log.capnp and __init__.py
|
||||||
|
#define HW_TYPE_UNKNOWN 0U |
||||||
|
#define HW_TYPE_WHITE_PANDA 1U |
||||||
|
#define HW_TYPE_GREY_PANDA 2U |
||||||
|
#define HW_TYPE_BLACK_PANDA 3U |
||||||
|
#define HW_TYPE_PEDAL 4U |
||||||
|
#define HW_TYPE_UNO 5U |
||||||
|
|
||||||
|
// LED colors
|
||||||
|
#define LED_RED 0U |
||||||
|
#define LED_GREEN 1U |
||||||
|
#define LED_BLUE 2U |
||||||
|
|
||||||
|
// USB power modes (from cereal.log.health)
|
||||||
|
#define USB_POWER_NONE 0U |
||||||
|
#define USB_POWER_CLIENT 1U |
||||||
|
#define USB_POWER_CDP 2U |
||||||
|
#define USB_POWER_DCP 3U |
||||||
|
|
||||||
|
// ESP modes
|
||||||
|
#define ESP_GPS_DISABLED 0U |
||||||
|
#define ESP_GPS_ENABLED 1U |
||||||
|
#define ESP_GPS_BOOTMODE 2U |
||||||
|
|
||||||
|
// CAN modes
|
||||||
|
#define CAN_MODE_NORMAL 0U |
||||||
|
#define CAN_MODE_GMLAN_CAN2 1U |
||||||
|
#define CAN_MODE_GMLAN_CAN3 2U |
||||||
|
#define CAN_MODE_OBD_CAN2 3U |
||||||
|
|
||||||
|
// ********************* Globals **********************
|
||||||
|
uint8_t usb_power_mode = USB_POWER_NONE; |
||||||
|
|
||||||
|
// ************ Board function prototypes *************
|
||||||
|
bool board_has_gps(void); |
||||||
|
bool board_has_gmlan(void); |
||||||
|
bool board_has_obd(void); |
||||||
|
bool board_has_lin(void); |
||||||
|
bool board_has_rtc(void); |
||||||
|
bool board_has_relay(void); |
@ -0,0 +1,239 @@ |
|||||||
|
// ///////////////////// //
|
||||||
|
// Black Panda + Harness //
|
||||||
|
// ///////////////////// //
|
||||||
|
|
||||||
|
void black_enable_can_transciever(uint8_t transciever, bool enabled) { |
||||||
|
switch (transciever){ |
||||||
|
case 1U: |
||||||
|
set_gpio_output(GPIOC, 1, !enabled); |
||||||
|
break; |
||||||
|
case 2U: |
||||||
|
set_gpio_output(GPIOC, 13, !enabled); |
||||||
|
break; |
||||||
|
case 3U: |
||||||
|
set_gpio_output(GPIOA, 0, !enabled); |
||||||
|
break; |
||||||
|
case 4U: |
||||||
|
set_gpio_output(GPIOB, 10, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_enable_can_transcievers(bool enabled) { |
||||||
|
uint8_t t1 = enabled ? 1U : 2U; // leave transciever 1 enabled to detect CAN ignition
|
||||||
|
for(uint8_t i=t1; i<=4U; i++) { |
||||||
|
black_enable_can_transciever(i, enabled); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_led(uint8_t color, bool enabled) { |
||||||
|
switch (color){ |
||||||
|
case LED_RED: |
||||||
|
set_gpio_output(GPIOC, 9, !enabled); |
||||||
|
break; |
||||||
|
case LED_GREEN: |
||||||
|
set_gpio_output(GPIOC, 7, !enabled); |
||||||
|
break; |
||||||
|
case LED_BLUE: |
||||||
|
set_gpio_output(GPIOC, 6, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_gps_load_switch(bool enabled) { |
||||||
|
set_gpio_output(GPIOC, 12, enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_usb_load_switch(bool enabled) { |
||||||
|
set_gpio_output(GPIOB, 1, !enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_usb_power_mode(uint8_t mode) { |
||||||
|
bool valid = false; |
||||||
|
switch (mode) { |
||||||
|
case USB_POWER_CLIENT: |
||||||
|
black_set_usb_load_switch(false); |
||||||
|
valid = true; |
||||||
|
break; |
||||||
|
case USB_POWER_CDP: |
||||||
|
black_set_usb_load_switch(true); |
||||||
|
valid = true; |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid USB power mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
if (valid) { |
||||||
|
usb_power_mode = mode; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_esp_gps_mode(uint8_t mode) { |
||||||
|
switch (mode) { |
||||||
|
case ESP_GPS_DISABLED: |
||||||
|
// GPS OFF
|
||||||
|
set_gpio_output(GPIOC, 14, 0); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
case ESP_GPS_ENABLED: |
||||||
|
// GPS ON
|
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 1); |
||||||
|
break; |
||||||
|
case ESP_GPS_BOOTMODE: |
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid ESP/GPS mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_can_mode(uint8_t mode){ |
||||||
|
switch (mode) { |
||||||
|
case CAN_MODE_NORMAL: |
||||||
|
case CAN_MODE_OBD_CAN2: |
||||||
|
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(car_harness_status == HARNESS_STATUS_NORMAL)) { |
||||||
|
// B12,B13: disable OBD mode
|
||||||
|
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
|
||||||
|
// B5,B6: normal CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||||
|
} else { |
||||||
|
// B5,B6: disable normal CAN2 mode
|
||||||
|
set_gpio_mode(GPIOB, 5, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 6, MODE_INPUT); |
||||||
|
|
||||||
|
// B12,B13: OBD mode
|
||||||
|
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); |
||||||
|
} |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void black_usb_power_mode_tick(uint32_t uptime){ |
||||||
|
UNUSED(uptime); |
||||||
|
// Not applicable
|
||||||
|
} |
||||||
|
|
||||||
|
bool black_check_ignition(void){ |
||||||
|
// ignition is checked through harness
|
||||||
|
return harness_check_ignition(); |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t black_read_current(void){ |
||||||
|
// No current sense on black panda
|
||||||
|
return 0U; |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_ir_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_fan_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void black_set_phone_power(bool enabled){ |
||||||
|
UNUSED(enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void black_init(void) { |
||||||
|
common_init_gpio(); |
||||||
|
|
||||||
|
// A8,A15: normal CAN3 mode
|
||||||
|
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); |
||||||
|
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); |
||||||
|
|
||||||
|
// C0: OBD_SBU1 (orientation detection)
|
||||||
|
// C3: OBD_SBU2 (orientation detection)
|
||||||
|
set_gpio_mode(GPIOC, 0, MODE_ANALOG); |
||||||
|
set_gpio_mode(GPIOC, 3, MODE_ANALOG); |
||||||
|
|
||||||
|
// Set default state of GPS
|
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
|
||||||
|
// C10: OBD_SBU1_RELAY (harness relay driving output)
|
||||||
|
// C11: OBD_SBU2_RELAY (harness relay driving output)
|
||||||
|
set_gpio_mode(GPIOC, 10, MODE_OUTPUT); |
||||||
|
set_gpio_mode(GPIOC, 11, MODE_OUTPUT); |
||||||
|
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); |
||||||
|
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); |
||||||
|
set_gpio_output(GPIOC, 10, 1); |
||||||
|
set_gpio_output(GPIOC, 11, 1); |
||||||
|
|
||||||
|
// Turn on GPS load switch.
|
||||||
|
black_set_gps_load_switch(true); |
||||||
|
|
||||||
|
// Turn on USB load switch.
|
||||||
|
black_set_usb_load_switch(true); |
||||||
|
|
||||||
|
// Set right power mode
|
||||||
|
black_set_usb_power_mode(USB_POWER_CDP); |
||||||
|
|
||||||
|
// Initialize harness
|
||||||
|
harness_init(); |
||||||
|
|
||||||
|
// Enable CAN transcievers
|
||||||
|
black_enable_can_transcievers(true); |
||||||
|
|
||||||
|
// Disable LEDs
|
||||||
|
black_set_led(LED_RED, false); |
||||||
|
black_set_led(LED_GREEN, false); |
||||||
|
black_set_led(LED_BLUE, false); |
||||||
|
|
||||||
|
// Set normal CAN mode
|
||||||
|
black_set_can_mode(CAN_MODE_NORMAL); |
||||||
|
|
||||||
|
// flip CAN0 and CAN2 if we are flipped
|
||||||
|
if (car_harness_status == HARNESS_STATUS_NORMAL) { |
||||||
|
can_flip_buses(0, 2); |
||||||
|
} |
||||||
|
|
||||||
|
// init multiplexer
|
||||||
|
can_set_obd(car_harness_status, false); |
||||||
|
} |
||||||
|
|
||||||
|
const harness_configuration black_harness_config = { |
||||||
|
.has_harness = true, |
||||||
|
.GPIO_SBU1 = GPIOC, |
||||||
|
.GPIO_SBU2 = GPIOC, |
||||||
|
.GPIO_relay_normal = GPIOC, |
||||||
|
.GPIO_relay_flipped = GPIOC, |
||||||
|
.pin_SBU1 = 0, |
||||||
|
.pin_SBU2 = 3, |
||||||
|
.pin_relay_normal = 10, |
||||||
|
.pin_relay_flipped = 11, |
||||||
|
.adc_channel_SBU1 = 10, |
||||||
|
.adc_channel_SBU2 = 13 |
||||||
|
}; |
||||||
|
|
||||||
|
const board board_black = { |
||||||
|
.board_type = "Black", |
||||||
|
.harness_config = &black_harness_config, |
||||||
|
.init = black_init, |
||||||
|
.enable_can_transciever = black_enable_can_transciever, |
||||||
|
.enable_can_transcievers = black_enable_can_transcievers, |
||||||
|
.set_led = black_set_led, |
||||||
|
.set_usb_power_mode = black_set_usb_power_mode, |
||||||
|
.set_esp_gps_mode = black_set_esp_gps_mode, |
||||||
|
.set_can_mode = black_set_can_mode, |
||||||
|
.usb_power_mode_tick = black_usb_power_mode_tick, |
||||||
|
.check_ignition = black_check_ignition, |
||||||
|
.read_current = black_read_current, |
||||||
|
.set_fan_power = black_set_fan_power, |
||||||
|
.set_ir_power = black_set_ir_power, |
||||||
|
.set_phone_power = black_set_phone_power |
||||||
|
}; |
@ -0,0 +1,84 @@ |
|||||||
|
#ifdef STM32F4 |
||||||
|
#include "stm32f4xx_hal_gpio_ex.h" |
||||||
|
#else |
||||||
|
#include "stm32f2xx_hal_gpio_ex.h" |
||||||
|
#endif |
||||||
|
|
||||||
|
// Common GPIO initialization
|
||||||
|
void common_init_gpio(void){ |
||||||
|
// TODO: Is this block actually doing something???
|
||||||
|
// pull low to hold ESP in reset??
|
||||||
|
// enable OTG out tied to ground
|
||||||
|
GPIOA->ODR = 0; |
||||||
|
GPIOB->ODR = 0; |
||||||
|
GPIOA->PUPDR = 0; |
||||||
|
GPIOB->AFR[0] = 0; |
||||||
|
GPIOB->AFR[1] = 0; |
||||||
|
|
||||||
|
// C2: Voltage sense line
|
||||||
|
set_gpio_mode(GPIOC, 2, MODE_ANALOG); |
||||||
|
|
||||||
|
// A11,A12: USB
|
||||||
|
set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); |
||||||
|
set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); |
||||||
|
GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; |
||||||
|
|
||||||
|
// A9,A10: USART 1 for talking to the ESP / GPS
|
||||||
|
set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1); |
||||||
|
set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1); |
||||||
|
|
||||||
|
// B8,B9: CAN 1
|
||||||
|
#ifdef STM32F4 |
||||||
|
set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); |
||||||
|
set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); |
||||||
|
#else |
||||||
|
set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); |
||||||
|
set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
// Peripheral initialization
|
||||||
|
void peripherals_init(void){ |
||||||
|
// enable GPIOB, UART2, CAN, USB clock
|
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; |
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; |
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; |
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; |
||||||
|
|
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_USART2EN; |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_USART3EN; |
||||||
|
#ifdef PANDA |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_UART5EN; |
||||||
|
#endif |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; |
||||||
|
#ifdef CAN3 |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; |
||||||
|
#endif |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_DACEN; |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; // main counter
|
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; // pedal and fan PWM
|
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; // gmlan_alt and IR PWM
|
||||||
|
//RCC->APB1ENR |= RCC_APB1ENR_TIM5EN;
|
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_TIM6EN; // interrupt timer
|
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_PWREN; // for RTC config
|
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_USART1EN; |
||||||
|
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; |
||||||
|
//RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
|
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; |
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; |
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; |
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_TIM9EN; // slow loop
|
||||||
|
} |
||||||
|
|
||||||
|
// Detection with internal pullup
|
||||||
|
#define PULL_EFFECTIVE_DELAY 10 |
||||||
|
bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { |
||||||
|
set_gpio_mode(GPIO, pin, MODE_INPUT); |
||||||
|
set_gpio_pullup(GPIO, pin, mode); |
||||||
|
for (volatile int i=0; i<PULL_EFFECTIVE_DELAY; i++); |
||||||
|
bool ret = get_gpio_input(GPIO, pin); |
||||||
|
set_gpio_pullup(GPIO, pin, PULL_NONE); |
||||||
|
return ret; |
||||||
|
} |
@ -0,0 +1,52 @@ |
|||||||
|
// ////////// //
|
||||||
|
// Grey Panda //
|
||||||
|
// ////////// //
|
||||||
|
|
||||||
|
// Most hardware functionality is similar to white panda
|
||||||
|
|
||||||
|
void grey_init(void) { |
||||||
|
white_grey_common_init(); |
||||||
|
|
||||||
|
// Set default state of GPS
|
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
} |
||||||
|
|
||||||
|
void grey_set_esp_gps_mode(uint8_t mode) { |
||||||
|
switch (mode) { |
||||||
|
case ESP_GPS_DISABLED: |
||||||
|
// GPS OFF
|
||||||
|
set_gpio_output(GPIOC, 14, 0); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
case ESP_GPS_ENABLED: |
||||||
|
// GPS ON
|
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 1); |
||||||
|
break; |
||||||
|
case ESP_GPS_BOOTMODE: |
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid ESP/GPS mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
const board board_grey = { |
||||||
|
.board_type = "Grey", |
||||||
|
.harness_config = &white_harness_config, |
||||||
|
.init = grey_init, |
||||||
|
.enable_can_transciever = white_enable_can_transciever, |
||||||
|
.enable_can_transcievers = white_enable_can_transcievers, |
||||||
|
.set_led = white_set_led, |
||||||
|
.set_usb_power_mode = white_set_usb_power_mode, |
||||||
|
.set_esp_gps_mode = grey_set_esp_gps_mode, |
||||||
|
.set_can_mode = white_set_can_mode, |
||||||
|
.usb_power_mode_tick = white_usb_power_mode_tick, |
||||||
|
.check_ignition = white_check_ignition, |
||||||
|
.read_current = white_read_current, |
||||||
|
.set_fan_power = white_set_fan_power, |
||||||
|
.set_ir_power = white_set_ir_power, |
||||||
|
.set_phone_power = white_set_phone_power |
||||||
|
}; |
@ -0,0 +1,117 @@ |
|||||||
|
// ///// //
|
||||||
|
// Pedal //
|
||||||
|
// ///// //
|
||||||
|
|
||||||
|
void pedal_enable_can_transciever(uint8_t transciever, bool enabled) { |
||||||
|
switch (transciever){ |
||||||
|
case 1: |
||||||
|
set_gpio_output(GPIOB, 3, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_enable_can_transcievers(bool enabled) { |
||||||
|
pedal_enable_can_transciever(1U, enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_led(uint8_t color, bool enabled) { |
||||||
|
switch (color){ |
||||||
|
case LED_RED: |
||||||
|
set_gpio_output(GPIOB, 10, !enabled); |
||||||
|
break; |
||||||
|
case LED_GREEN: |
||||||
|
set_gpio_output(GPIOB, 11, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_usb_power_mode(uint8_t mode){ |
||||||
|
usb_power_mode = mode; |
||||||
|
puts("Trying to set USB power mode on pedal. This is not supported.\n"); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_esp_gps_mode(uint8_t mode) { |
||||||
|
UNUSED(mode); |
||||||
|
puts("Trying to set ESP/GPS mode on pedal. This is not supported.\n"); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_can_mode(uint8_t mode){ |
||||||
|
switch (mode) { |
||||||
|
case CAN_MODE_NORMAL: |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_usb_power_mode_tick(uint32_t uptime){ |
||||||
|
UNUSED(uptime); |
||||||
|
// Not applicable
|
||||||
|
} |
||||||
|
|
||||||
|
bool pedal_check_ignition(void){ |
||||||
|
// not supported on pedal
|
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t pedal_read_current(void){ |
||||||
|
// No current sense on pedal
|
||||||
|
return 0U; |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_ir_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_fan_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_set_phone_power(bool enabled){ |
||||||
|
UNUSED(enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void pedal_init(void) { |
||||||
|
common_init_gpio(); |
||||||
|
|
||||||
|
// C0, C1: Throttle inputs
|
||||||
|
set_gpio_mode(GPIOC, 0, MODE_ANALOG); |
||||||
|
set_gpio_mode(GPIOC, 1, MODE_ANALOG); |
||||||
|
// DAC outputs on A4 and A5
|
||||||
|
// apparently they don't need GPIO setup
|
||||||
|
|
||||||
|
// Enable transciever
|
||||||
|
pedal_enable_can_transcievers(true); |
||||||
|
|
||||||
|
// Disable LEDs
|
||||||
|
pedal_set_led(LED_RED, false); |
||||||
|
pedal_set_led(LED_GREEN, false); |
||||||
|
} |
||||||
|
|
||||||
|
const harness_configuration pedal_harness_config = { |
||||||
|
.has_harness = false |
||||||
|
}; |
||||||
|
|
||||||
|
const board board_pedal = { |
||||||
|
.board_type = "Pedal", |
||||||
|
.harness_config = &pedal_harness_config, |
||||||
|
.init = pedal_init, |
||||||
|
.enable_can_transciever = pedal_enable_can_transciever, |
||||||
|
.enable_can_transcievers = pedal_enable_can_transcievers, |
||||||
|
.set_led = pedal_set_led, |
||||||
|
.set_usb_power_mode = pedal_set_usb_power_mode, |
||||||
|
.set_esp_gps_mode = pedal_set_esp_gps_mode, |
||||||
|
.set_can_mode = pedal_set_can_mode, |
||||||
|
.usb_power_mode_tick = pedal_usb_power_mode_tick, |
||||||
|
.check_ignition = pedal_check_ignition, |
||||||
|
.read_current = pedal_read_current, |
||||||
|
.set_fan_power = pedal_set_fan_power, |
||||||
|
.set_ir_power = pedal_set_ir_power, |
||||||
|
.set_phone_power = pedal_set_phone_power |
||||||
|
}; |
@ -0,0 +1,281 @@ |
|||||||
|
// ///////////// //
|
||||||
|
// Uno + Harness //
|
||||||
|
// ///////////// //
|
||||||
|
#define BOOTKICK_TIME 3U |
||||||
|
uint8_t bootkick_timer = 0U; |
||||||
|
|
||||||
|
void uno_enable_can_transciever(uint8_t transciever, bool enabled) { |
||||||
|
switch (transciever){ |
||||||
|
case 1U: |
||||||
|
set_gpio_output(GPIOC, 1, !enabled); |
||||||
|
break; |
||||||
|
case 2U: |
||||||
|
set_gpio_output(GPIOC, 13, !enabled); |
||||||
|
break; |
||||||
|
case 3U: |
||||||
|
set_gpio_output(GPIOA, 0, !enabled); |
||||||
|
break; |
||||||
|
case 4U: |
||||||
|
set_gpio_output(GPIOB, 10, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_enable_can_transcievers(bool enabled) { |
||||||
|
for(uint8_t i=1U; i<=4U; i++){ |
||||||
|
uno_enable_can_transciever(i, enabled); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_led(uint8_t color, bool enabled) { |
||||||
|
switch (color){ |
||||||
|
case LED_RED: |
||||||
|
set_gpio_output(GPIOC, 9, !enabled); |
||||||
|
break; |
||||||
|
case LED_GREEN: |
||||||
|
set_gpio_output(GPIOC, 7, !enabled); |
||||||
|
break; |
||||||
|
case LED_BLUE: |
||||||
|
set_gpio_output(GPIOC, 6, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_gps_load_switch(bool enabled) { |
||||||
|
set_gpio_output(GPIOC, 12, enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_bootkick(bool enabled){ |
||||||
|
set_gpio_output(GPIOB, 14, !enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_bootkick(void) { |
||||||
|
bootkick_timer = BOOTKICK_TIME; |
||||||
|
uno_set_bootkick(true); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_phone_power(bool enabled){ |
||||||
|
set_gpio_output(GPIOB, 4, enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_usb_power_mode(uint8_t mode) { |
||||||
|
bool valid = false; |
||||||
|
switch (mode) { |
||||||
|
case USB_POWER_CLIENT: |
||||||
|
uno_set_phone_power(false); |
||||||
|
valid = true; |
||||||
|
break; |
||||||
|
case USB_POWER_CDP: |
||||||
|
uno_set_phone_power(true); |
||||||
|
uno_bootkick(); |
||||||
|
valid = true; |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid USB power mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
if (valid) { |
||||||
|
usb_power_mode = mode; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_esp_gps_mode(uint8_t mode) { |
||||||
|
switch (mode) { |
||||||
|
case ESP_GPS_DISABLED: |
||||||
|
// GPS OFF
|
||||||
|
set_gpio_output(GPIOB, 1, 0); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
uno_set_gps_load_switch(false); |
||||||
|
break; |
||||||
|
case ESP_GPS_ENABLED: |
||||||
|
// GPS ON
|
||||||
|
set_gpio_output(GPIOB, 1, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 1); |
||||||
|
uno_set_gps_load_switch(true); |
||||||
|
break; |
||||||
|
case ESP_GPS_BOOTMODE: |
||||||
|
set_gpio_output(GPIOB, 1, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
uno_set_gps_load_switch(true); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid ESP/GPS mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_can_mode(uint8_t mode){ |
||||||
|
switch (mode) { |
||||||
|
case CAN_MODE_NORMAL: |
||||||
|
case CAN_MODE_OBD_CAN2: |
||||||
|
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(car_harness_status == HARNESS_STATUS_NORMAL)) { |
||||||
|
// B12,B13: disable OBD mode
|
||||||
|
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
|
||||||
|
// B5,B6: normal CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||||
|
} else { |
||||||
|
// B5,B6: disable normal CAN2 mode
|
||||||
|
set_gpio_mode(GPIOB, 5, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 6, MODE_INPUT); |
||||||
|
|
||||||
|
// B12,B13: OBD mode
|
||||||
|
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); |
||||||
|
} |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uno_usb_power_mode_tick(uint32_t uptime){ |
||||||
|
UNUSED(uptime); |
||||||
|
if(bootkick_timer != 0U){ |
||||||
|
bootkick_timer--; |
||||||
|
} else { |
||||||
|
uno_set_bootkick(false); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool uno_check_ignition(void){ |
||||||
|
// ignition is checked through harness
|
||||||
|
return harness_check_ignition(); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_usb_switch(bool phone){ |
||||||
|
set_gpio_output(GPIOB, 3, phone); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_ir_power(uint8_t percentage){ |
||||||
|
pwm_set(TIM4, 2, percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void uno_set_fan_power(uint8_t percentage){ |
||||||
|
// Enable fan power only if percentage is non-zero.
|
||||||
|
set_gpio_output(GPIOA, 1, (percentage != 0U)); |
||||||
|
fan_set_power(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t uno_read_current(void){ |
||||||
|
// No current sense on Uno
|
||||||
|
return 0U; |
||||||
|
} |
||||||
|
|
||||||
|
void uno_init(void) { |
||||||
|
common_init_gpio(); |
||||||
|
|
||||||
|
// A8,A15: normal CAN3 mode
|
||||||
|
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); |
||||||
|
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); |
||||||
|
|
||||||
|
// C0: OBD_SBU1 (orientation detection)
|
||||||
|
// C3: OBD_SBU2 (orientation detection)
|
||||||
|
set_gpio_mode(GPIOC, 0, MODE_ANALOG); |
||||||
|
set_gpio_mode(GPIOC, 3, MODE_ANALOG); |
||||||
|
|
||||||
|
// Set default state of GPS
|
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
|
||||||
|
// C10: OBD_SBU1_RELAY (harness relay driving output)
|
||||||
|
// C11: OBD_SBU2_RELAY (harness relay driving output)
|
||||||
|
set_gpio_mode(GPIOC, 10, MODE_OUTPUT); |
||||||
|
set_gpio_mode(GPIOC, 11, MODE_OUTPUT); |
||||||
|
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); |
||||||
|
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); |
||||||
|
set_gpio_output(GPIOC, 10, 1); |
||||||
|
set_gpio_output(GPIOC, 11, 1); |
||||||
|
|
||||||
|
// C8: FAN PWM aka TIM3_CH3
|
||||||
|
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); |
||||||
|
|
||||||
|
// Turn on GPS load switch.
|
||||||
|
uno_set_gps_load_switch(true); |
||||||
|
|
||||||
|
// Turn on phone regulator
|
||||||
|
uno_set_phone_power(true); |
||||||
|
|
||||||
|
// Initialize IR PWM and set to 0%
|
||||||
|
set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); |
||||||
|
pwm_init(TIM4, 2); |
||||||
|
uno_set_ir_power(0U); |
||||||
|
|
||||||
|
// Initialize fan and set to 0%
|
||||||
|
fan_init(); |
||||||
|
uno_set_fan_power(0U); |
||||||
|
|
||||||
|
// Initialize harness
|
||||||
|
harness_init(); |
||||||
|
|
||||||
|
// Initialize RTC
|
||||||
|
rtc_init(); |
||||||
|
|
||||||
|
// Enable CAN transcievers
|
||||||
|
uno_enable_can_transcievers(true); |
||||||
|
|
||||||
|
// Disable LEDs
|
||||||
|
uno_set_led(LED_RED, false); |
||||||
|
uno_set_led(LED_GREEN, false); |
||||||
|
uno_set_led(LED_BLUE, false); |
||||||
|
|
||||||
|
// Set normal CAN mode
|
||||||
|
uno_set_can_mode(CAN_MODE_NORMAL); |
||||||
|
|
||||||
|
// flip CAN0 and CAN2 if we are flipped
|
||||||
|
if (car_harness_status == HARNESS_STATUS_NORMAL) { |
||||||
|
can_flip_buses(0, 2); |
||||||
|
} |
||||||
|
|
||||||
|
// init multiplexer
|
||||||
|
can_set_obd(car_harness_status, false); |
||||||
|
|
||||||
|
// Switch to phone usb mode if harness connection is powered by less than 7V
|
||||||
|
if(adc_get_voltage() < 7000U){ |
||||||
|
uno_set_usb_switch(true); |
||||||
|
} else { |
||||||
|
uno_set_usb_switch(false); |
||||||
|
} |
||||||
|
|
||||||
|
// Bootkick phone
|
||||||
|
uno_bootkick(); |
||||||
|
} |
||||||
|
|
||||||
|
const harness_configuration uno_harness_config = { |
||||||
|
.has_harness = true, |
||||||
|
.GPIO_SBU1 = GPIOC, |
||||||
|
.GPIO_SBU2 = GPIOC, |
||||||
|
.GPIO_relay_normal = GPIOC, |
||||||
|
.GPIO_relay_flipped = GPIOC, |
||||||
|
.pin_SBU1 = 0, |
||||||
|
.pin_SBU2 = 3, |
||||||
|
.pin_relay_normal = 10, |
||||||
|
.pin_relay_flipped = 11, |
||||||
|
.adc_channel_SBU1 = 10, |
||||||
|
.adc_channel_SBU2 = 13 |
||||||
|
}; |
||||||
|
|
||||||
|
const board board_uno = { |
||||||
|
.board_type = "Uno", |
||||||
|
.harness_config = &uno_harness_config, |
||||||
|
.init = uno_init, |
||||||
|
.enable_can_transciever = uno_enable_can_transciever, |
||||||
|
.enable_can_transcievers = uno_enable_can_transcievers, |
||||||
|
.set_led = uno_set_led, |
||||||
|
.set_usb_power_mode = uno_set_usb_power_mode, |
||||||
|
.set_esp_gps_mode = uno_set_esp_gps_mode, |
||||||
|
.set_can_mode = uno_set_can_mode, |
||||||
|
.usb_power_mode_tick = uno_usb_power_mode_tick, |
||||||
|
.check_ignition = uno_check_ignition, |
||||||
|
.read_current = uno_read_current, |
||||||
|
.set_fan_power = uno_set_fan_power, |
||||||
|
.set_ir_power = uno_set_ir_power, |
||||||
|
.set_phone_power = uno_set_phone_power |
||||||
|
}; |
@ -0,0 +1,347 @@ |
|||||||
|
// /////////// //
|
||||||
|
// White Panda //
|
||||||
|
// /////////// //
|
||||||
|
|
||||||
|
void white_enable_can_transciever(uint8_t transciever, bool enabled) { |
||||||
|
switch (transciever){ |
||||||
|
case 1U: |
||||||
|
set_gpio_output(GPIOC, 1, !enabled); |
||||||
|
break; |
||||||
|
case 2U: |
||||||
|
set_gpio_output(GPIOC, 13, !enabled); |
||||||
|
break; |
||||||
|
case 3U: |
||||||
|
set_gpio_output(GPIOA, 0, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_enable_can_transcievers(bool enabled) { |
||||||
|
uint8_t t1 = enabled ? 1U : 2U; // leave transciever 1 enabled to detect CAN ignition
|
||||||
|
for(uint8_t i=t1; i<=3U; i++) { |
||||||
|
white_enable_can_transciever(i, enabled); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_led(uint8_t color, bool enabled) { |
||||||
|
switch (color){ |
||||||
|
case LED_RED: |
||||||
|
set_gpio_output(GPIOC, 9, !enabled); |
||||||
|
break; |
||||||
|
case LED_GREEN: |
||||||
|
set_gpio_output(GPIOC, 7, !enabled); |
||||||
|
break; |
||||||
|
case LED_BLUE: |
||||||
|
set_gpio_output(GPIOC, 6, !enabled); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_usb_power_mode(uint8_t mode){ |
||||||
|
bool valid_mode = true; |
||||||
|
switch (mode) { |
||||||
|
case USB_POWER_CLIENT: |
||||||
|
// B2,A13: set client mode
|
||||||
|
set_gpio_output(GPIOB, 2, 0); |
||||||
|
set_gpio_output(GPIOA, 13, 1); |
||||||
|
break; |
||||||
|
case USB_POWER_CDP: |
||||||
|
// B2,A13: set CDP mode
|
||||||
|
set_gpio_output(GPIOB, 2, 1); |
||||||
|
set_gpio_output(GPIOA, 13, 1); |
||||||
|
break; |
||||||
|
case USB_POWER_DCP: |
||||||
|
// B2,A13: set DCP mode on the charger (breaks USB!)
|
||||||
|
set_gpio_output(GPIOB, 2, 0); |
||||||
|
set_gpio_output(GPIOA, 13, 0); |
||||||
|
break; |
||||||
|
default: |
||||||
|
valid_mode = false; |
||||||
|
puts("Invalid usb power mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
if (valid_mode) { |
||||||
|
usb_power_mode = mode; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_esp_gps_mode(uint8_t mode) { |
||||||
|
switch (mode) { |
||||||
|
case ESP_GPS_DISABLED: |
||||||
|
// ESP OFF
|
||||||
|
set_gpio_output(GPIOC, 14, 0); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
#ifndef EON |
||||||
|
case ESP_GPS_ENABLED: |
||||||
|
// ESP ON
|
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 1); |
||||||
|
break; |
||||||
|
#endif |
||||||
|
case ESP_GPS_BOOTMODE: |
||||||
|
set_gpio_output(GPIOC, 14, 1); |
||||||
|
set_gpio_output(GPIOC, 5, 0); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Invalid ESP/GPS mode\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_can_mode(uint8_t mode){ |
||||||
|
switch (mode) { |
||||||
|
case CAN_MODE_NORMAL: |
||||||
|
// B12,B13: disable GMLAN mode
|
||||||
|
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
|
||||||
|
// B3,B4: disable GMLAN mode
|
||||||
|
set_gpio_mode(GPIOB, 3, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 4, MODE_INPUT); |
||||||
|
|
||||||
|
// B5,B6: normal CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||||
|
|
||||||
|
// A8,A15: normal CAN3 mode
|
||||||
|
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); |
||||||
|
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); |
||||||
|
break; |
||||||
|
case CAN_MODE_GMLAN_CAN2: |
||||||
|
// B5,B6: disable CAN2 mode
|
||||||
|
set_gpio_mode(GPIOB, 5, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 6, MODE_INPUT); |
||||||
|
|
||||||
|
// B3,B4: disable GMLAN mode
|
||||||
|
set_gpio_mode(GPIOB, 3, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 4, MODE_INPUT); |
||||||
|
|
||||||
|
// B12,B13: GMLAN mode
|
||||||
|
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); |
||||||
|
|
||||||
|
// A8,A15: normal CAN3 mode
|
||||||
|
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); |
||||||
|
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); |
||||||
|
break; |
||||||
|
case CAN_MODE_GMLAN_CAN3: |
||||||
|
// A8,A15: disable CAN3 mode
|
||||||
|
set_gpio_mode(GPIOA, 8, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOA, 15, MODE_INPUT); |
||||||
|
|
||||||
|
// B12,B13: disable GMLAN mode
|
||||||
|
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
|
||||||
|
// B3,B4: GMLAN mode
|
||||||
|
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3); |
||||||
|
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3); |
||||||
|
|
||||||
|
// B5,B6: normal CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t white_read_current(void){ |
||||||
|
return adc_get(ADCCHAN_CURRENT); |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t marker = 0; |
||||||
|
void white_usb_power_mode_tick(uint32_t uptime){ |
||||||
|
|
||||||
|
// on EON or BOOTSTUB, no state machine
|
||||||
|
#if !defined(BOOTSTUB) && !defined(EON) |
||||||
|
#define CURRENT_THRESHOLD 0xF00U |
||||||
|
#define CLICKS 5U // 5 seconds to switch modes
|
||||||
|
|
||||||
|
uint32_t current = white_read_current(); |
||||||
|
|
||||||
|
// ~0x9a = 500 ma
|
||||||
|
// puth(current); puts("\n");
|
||||||
|
|
||||||
|
switch (usb_power_mode) { |
||||||
|
case USB_POWER_CLIENT: |
||||||
|
if ((uptime - marker) >= CLICKS) { |
||||||
|
if (!is_enumerated) { |
||||||
|
puts("USBP: didn't enumerate, switching to CDP mode\n"); |
||||||
|
// switch to CDP
|
||||||
|
white_set_usb_power_mode(USB_POWER_CDP); |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
} |
||||||
|
// keep resetting the timer if it's enumerated
|
||||||
|
if (is_enumerated) { |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
break; |
||||||
|
case USB_POWER_CDP: |
||||||
|
// been CLICKS clicks since we switched to CDP
|
||||||
|
if ((uptime - marker) >= CLICKS) { |
||||||
|
// measure current draw, if positive and no enumeration, switch to DCP
|
||||||
|
if (!is_enumerated && (current < CURRENT_THRESHOLD)) { |
||||||
|
puts("USBP: no enumeration with current draw, switching to DCP mode\n"); |
||||||
|
white_set_usb_power_mode(USB_POWER_DCP); |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
} |
||||||
|
// keep resetting the timer if there's no current draw in CDP
|
||||||
|
if (current >= CURRENT_THRESHOLD) { |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
break; |
||||||
|
case USB_POWER_DCP: |
||||||
|
// been at least CLICKS clicks since we switched to DCP
|
||||||
|
if ((uptime - marker) >= CLICKS) { |
||||||
|
// if no current draw, switch back to CDP
|
||||||
|
if (current >= CURRENT_THRESHOLD) { |
||||||
|
puts("USBP: no current draw, switching back to CDP mode\n"); |
||||||
|
white_set_usb_power_mode(USB_POWER_CDP); |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
} |
||||||
|
// keep resetting the timer if there's current draw in DCP
|
||||||
|
if (current < CURRENT_THRESHOLD) { |
||||||
|
marker = uptime; |
||||||
|
} |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("USB power mode invalid\n"); // set_usb_power_mode prevents assigning invalid values
|
||||||
|
break; |
||||||
|
} |
||||||
|
#else |
||||||
|
UNUSED(uptime); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_ir_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_fan_power(uint8_t percentage){ |
||||||
|
UNUSED(percentage); |
||||||
|
} |
||||||
|
|
||||||
|
bool white_check_ignition(void){ |
||||||
|
// ignition is on PA1
|
||||||
|
return !get_gpio_input(GPIOA, 1); |
||||||
|
} |
||||||
|
|
||||||
|
void white_set_phone_power(bool enabled){ |
||||||
|
UNUSED(enabled); |
||||||
|
} |
||||||
|
|
||||||
|
void white_grey_common_init(void) { |
||||||
|
common_init_gpio(); |
||||||
|
|
||||||
|
// C3: current sense
|
||||||
|
set_gpio_mode(GPIOC, 3, MODE_ANALOG); |
||||||
|
|
||||||
|
// A1: started_alt
|
||||||
|
set_gpio_pullup(GPIOA, 1, PULL_UP); |
||||||
|
|
||||||
|
// A2, A3: USART 2 for debugging
|
||||||
|
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); |
||||||
|
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); |
||||||
|
|
||||||
|
// A4, A5, A6, A7: SPI
|
||||||
|
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); |
||||||
|
|
||||||
|
// B12: GMLAN, ignition sense, pull up
|
||||||
|
set_gpio_pullup(GPIOB, 12, PULL_UP); |
||||||
|
|
||||||
|
/* GMLAN mode pins:
|
||||||
|
M0(B15) M1(B14) mode |
||||||
|
======================= |
||||||
|
0 0 sleep |
||||||
|
1 0 100kbit |
||||||
|
0 1 high voltage wakeup |
||||||
|
1 1 33kbit (normal) |
||||||
|
*/ |
||||||
|
set_gpio_output(GPIOB, 14, 1); |
||||||
|
set_gpio_output(GPIOB, 15, 1); |
||||||
|
|
||||||
|
// B7: K-line enable
|
||||||
|
set_gpio_output(GPIOB, 7, 1); |
||||||
|
|
||||||
|
// C12, D2: Setup K-line (UART5)
|
||||||
|
set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5); |
||||||
|
set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5); |
||||||
|
set_gpio_pullup(GPIOD, 2, PULL_UP); |
||||||
|
|
||||||
|
// L-line enable
|
||||||
|
set_gpio_output(GPIOA, 14, 1); |
||||||
|
|
||||||
|
// C10, C11: L-Line setup (USART3)
|
||||||
|
set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3); |
||||||
|
set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); |
||||||
|
set_gpio_pullup(GPIOC, 11, PULL_UP); |
||||||
|
|
||||||
|
// Enable CAN transcievers
|
||||||
|
white_enable_can_transcievers(true); |
||||||
|
|
||||||
|
// Disable LEDs
|
||||||
|
white_set_led(LED_RED, false); |
||||||
|
white_set_led(LED_GREEN, false); |
||||||
|
white_set_led(LED_BLUE, false); |
||||||
|
|
||||||
|
// Set normal CAN mode
|
||||||
|
white_set_can_mode(CAN_MODE_NORMAL); |
||||||
|
|
||||||
|
// Init usb power mode
|
||||||
|
uint32_t voltage = adc_get_voltage(); |
||||||
|
// Init in CDP mode only if panda is powered by 12V.
|
||||||
|
// Otherwise a PC would not be able to flash a standalone panda with EON build
|
||||||
|
if (voltage > 8000U) { // 8V threshold
|
||||||
|
white_set_usb_power_mode(USB_POWER_CDP); |
||||||
|
} else { |
||||||
|
white_set_usb_power_mode(USB_POWER_CLIENT); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void white_init(void) { |
||||||
|
white_grey_common_init(); |
||||||
|
|
||||||
|
// Set default state of ESP
|
||||||
|
#ifdef EON |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_DISABLED); |
||||||
|
#else |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
const harness_configuration white_harness_config = { |
||||||
|
.has_harness = false |
||||||
|
}; |
||||||
|
|
||||||
|
const board board_white = { |
||||||
|
.board_type = "White", |
||||||
|
.harness_config = &white_harness_config, |
||||||
|
.init = white_init, |
||||||
|
.enable_can_transciever = white_enable_can_transciever, |
||||||
|
.enable_can_transcievers = white_enable_can_transcievers, |
||||||
|
.set_led = white_set_led, |
||||||
|
.set_usb_power_mode = white_set_usb_power_mode, |
||||||
|
.set_esp_gps_mode = white_set_esp_gps_mode, |
||||||
|
.set_can_mode = white_set_can_mode, |
||||||
|
.usb_power_mode_tick = white_usb_power_mode_tick, |
||||||
|
.check_ignition = white_check_ignition, |
||||||
|
.read_current = white_read_current, |
||||||
|
.set_fan_power = white_set_fan_power, |
||||||
|
.set_ir_power = white_set_ir_power, |
||||||
|
.set_phone_power = white_set_phone_power |
||||||
|
}; |
@ -0,0 +1,124 @@ |
|||||||
|
#define BOOTSTUB |
||||||
|
|
||||||
|
#define VERS_TAG 0x53524556 |
||||||
|
#define MIN_VERSION 2 |
||||||
|
|
||||||
|
#include "config.h" |
||||||
|
#include "obj/gitversion.h" |
||||||
|
|
||||||
|
#ifdef STM32F4 |
||||||
|
#define PANDA |
||||||
|
#include "stm32f4xx.h" |
||||||
|
#include "stm32f4xx_hal_gpio_ex.h" |
||||||
|
#else |
||||||
|
#include "stm32f2xx.h" |
||||||
|
#include "stm32f2xx_hal_gpio_ex.h" |
||||||
|
#endif |
||||||
|
|
||||||
|
// ******************** Prototypes ********************
|
||||||
|
void puts(const char *a){ UNUSED(a); } |
||||||
|
void puth(unsigned int i){ UNUSED(i); } |
||||||
|
void puth2(unsigned int i){ UNUSED(i); } |
||||||
|
typedef struct board board; |
||||||
|
typedef struct harness_configuration harness_configuration; |
||||||
|
// No CAN support on bootloader
|
||||||
|
void can_flip_buses(uint8_t bus1, uint8_t bus2){UNUSED(bus1); UNUSED(bus2);} |
||||||
|
void can_set_obd(int harness_orientation, bool obd){UNUSED(harness_orientation); UNUSED(obd);} |
||||||
|
|
||||||
|
// ********************* Globals **********************
|
||||||
|
int hw_type = 0; |
||||||
|
const board *current_board; |
||||||
|
|
||||||
|
// ********************* Includes *********************
|
||||||
|
#include "libc.h" |
||||||
|
#include "provision.h" |
||||||
|
#include "critical.h" |
||||||
|
#include "faults.h" |
||||||
|
|
||||||
|
#include "drivers/registers.h" |
||||||
|
#include "drivers/interrupts.h" |
||||||
|
#include "drivers/clock.h" |
||||||
|
#include "drivers/llgpio.h" |
||||||
|
#include "drivers/adc.h" |
||||||
|
#include "drivers/pwm.h" |
||||||
|
|
||||||
|
#include "board.h" |
||||||
|
|
||||||
|
#include "gpio.h" |
||||||
|
|
||||||
|
#include "drivers/spi.h" |
||||||
|
#include "drivers/usb.h" |
||||||
|
//#include "drivers/uart.h"
|
||||||
|
|
||||||
|
#include "crypto/rsa.h" |
||||||
|
#include "crypto/sha.h" |
||||||
|
|
||||||
|
#include "obj/cert.h" |
||||||
|
|
||||||
|
#include "spi_flasher.h" |
||||||
|
|
||||||
|
void __initialize_hardware_early(void) { |
||||||
|
early(); |
||||||
|
} |
||||||
|
|
||||||
|
void fail(void) { |
||||||
|
soft_flasher_start(); |
||||||
|
} |
||||||
|
|
||||||
|
// know where to sig check
|
||||||
|
extern void *_app_start[]; |
||||||
|
|
||||||
|
// FIXME: sometimes your panda will fail flashing and will quickly blink a single Green LED
|
||||||
|
// BOUNTY: $200 coupon on shop.comma.ai or $100 check.
|
||||||
|
|
||||||
|
int main(void) { |
||||||
|
// Init interrupt table
|
||||||
|
init_interrupts(true); |
||||||
|
|
||||||
|
disable_interrupts(); |
||||||
|
clock_init(); |
||||||
|
detect_configuration(); |
||||||
|
detect_board_type(); |
||||||
|
|
||||||
|
if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { |
||||||
|
enter_bootloader_mode = 0; |
||||||
|
soft_flasher_start(); |
||||||
|
} |
||||||
|
|
||||||
|
// validate length
|
||||||
|
int len = (int)_app_start[0]; |
||||||
|
if ((len < 8) || (len > (0x1000000 - 0x4000 - 4 - RSANUMBYTES))) goto fail; |
||||||
|
|
||||||
|
// compute SHA hash
|
||||||
|
uint8_t digest[SHA_DIGEST_SIZE]; |
||||||
|
SHA_hash(&_app_start[1], len-4, digest); |
||||||
|
|
||||||
|
// verify version, last bytes in the signed area
|
||||||
|
uint32_t vers[2] = {0}; |
||||||
|
memcpy(&vers, ((void*)&_app_start[0]) + len - sizeof(vers), sizeof(vers)); |
||||||
|
if (vers[0] != VERS_TAG || vers[1] < MIN_VERSION) { |
||||||
|
goto fail; |
||||||
|
} |
||||||
|
|
||||||
|
// verify RSA signature
|
||||||
|
if (RSA_verify(&release_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { |
||||||
|
goto good; |
||||||
|
} |
||||||
|
|
||||||
|
// allow debug if built from source
|
||||||
|
#ifdef ALLOW_DEBUG |
||||||
|
if (RSA_verify(&debug_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { |
||||||
|
goto good; |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
// here is a failure
|
||||||
|
fail: |
||||||
|
fail(); |
||||||
|
return 0; |
||||||
|
good: |
||||||
|
// jump to flash
|
||||||
|
((void(*)(void)) _app_start[1])(); |
||||||
|
return 0; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,84 @@ |
|||||||
|
CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -Os
|
||||||
|
|
||||||
|
CFLAGS += -Tstm32_flash.ld
|
||||||
|
|
||||||
|
DFU_UTIL = "dfu-util"
|
||||||
|
|
||||||
|
# Compile fast charge (DCP) only not on EON
|
||||||
|
ifeq (,$(wildcard /EON)) |
||||||
|
BUILDER = DEV
|
||||||
|
else |
||||||
|
CFLAGS += "-DEON"
|
||||||
|
BUILDER = EON
|
||||||
|
DFU_UTIL = "tools/dfu-util-aarch64"
|
||||||
|
endif |
||||||
|
|
||||||
|
CC = arm-none-eabi-gcc
|
||||||
|
OBJCOPY = arm-none-eabi-objcopy
|
||||||
|
OBJDUMP = arm-none-eabi-objdump
|
||||||
|
|
||||||
|
ifeq ($(RELEASE),1) |
||||||
|
CERT = ../../pandaextra/certs/release
|
||||||
|
else |
||||||
|
# enable the debug cert
|
||||||
|
CERT = ../certs/debug
|
||||||
|
CFLAGS += "-DALLOW_DEBUG"
|
||||||
|
endif |
||||||
|
|
||||||
|
|
||||||
|
DEPDIR = generated_dependencies
|
||||||
|
$(shell mkdir -p -m 777 $(DEPDIR) >/dev/null) |
||||||
|
DEPFLAGS = -MT $@ -MMD -MP -MF $(DEPDIR)/$*.Td
|
||||||
|
POSTCOMPILE = @mv -f $(DEPDIR)/$*.Td $(DEPDIR)/$*.d && touch $@
|
||||||
|
|
||||||
|
# this no longer pushes the bootstub
|
||||||
|
flash: obj/$(PROJ_NAME).bin |
||||||
|
PYTHONPATH=../ python3 -c "from python import Panda; Panda().flash('obj/$(PROJ_NAME).bin')"
|
||||||
|
|
||||||
|
ota: obj/$(PROJ_NAME).bin |
||||||
|
curl http://192.168.0.10/stupdate --upload-file $<
|
||||||
|
|
||||||
|
bin: obj/$(PROJ_NAME).bin |
||||||
|
|
||||||
|
# this flashes everything
|
||||||
|
recover: obj/bootstub.$(PROJ_NAME).bin obj/$(PROJ_NAME).bin |
||||||
|
-PYTHONPATH=../ python3 -c "from python import Panda; Panda().reset(enter_bootloader=True)"
|
||||||
|
sleep 1.0
|
||||||
|
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||||
|
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.$(PROJ_NAME).bin
|
||||||
|
|
||||||
|
include ../common/version.mk |
||||||
|
|
||||||
|
obj/cert.h: ../crypto/getcertheader.py |
||||||
|
../crypto/getcertheader.py ../certs/debug.pub ../certs/release.pub > $@
|
||||||
|
|
||||||
|
obj/%.$(PROJ_NAME).o: %.c obj/gitversion.h obj/cert.h $(DEPDIR)/%.d |
||||||
|
$(CC) $(DEPFLAGS) $(CFLAGS) -o $@ -c $<
|
||||||
|
$(POSTCOMPILE)
|
||||||
|
|
||||||
|
obj/%.$(PROJ_NAME).o: ../crypto/%.c |
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/$(STARTUP_FILE).o: $(STARTUP_FILE).s |
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o |
||||||
|
# hack
|
||||||
|
$(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
|
||||||
|
$(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin
|
||||||
|
SETLEN=1 ../crypto/sign.py obj/code.bin $@ $(CERT)
|
||||||
|
@BINSIZE=$$(du -b "obj/$(PROJ_NAME).bin" | cut -f 1) ; \
|
||||||
|
if [ $$BINSIZE -ge 49152 ]; then echo "ERROR obj/$(PROJ_NAME).bin is too big!"; exit 1; fi;
|
||||||
|
|
||||||
|
obj/bootstub.$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/bootstub.$(PROJ_NAME).o obj/sha.$(PROJ_NAME).o obj/rsa.$(PROJ_NAME).o |
||||||
|
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
|
||||||
|
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
|
||||||
|
|
||||||
|
$(DEPDIR)/%.d: ; |
||||||
|
.PRECIOUS: $(DEPDIR)/%.d |
||||||
|
|
||||||
|
include $(wildcard $(patsubst %,$(DEPDIR)/%.d,$(basename $(wildcard *.c)))) |
||||||
|
|
||||||
|
clean: |
||||||
|
@$(RM) obj/*
|
||||||
|
@rm -rf $(DEPDIR)
|
@ -0,0 +1,45 @@ |
|||||||
|
#ifndef PANDA_CONFIG_H |
||||||
|
#define PANDA_CONFIG_H |
||||||
|
|
||||||
|
//#define DEBUG
|
||||||
|
//#define DEBUG_UART
|
||||||
|
//#define DEBUG_USB
|
||||||
|
//#define DEBUG_SPI
|
||||||
|
//#define DEBUG_FAULTS
|
||||||
|
|
||||||
|
#ifdef STM32F4 |
||||||
|
#define PANDA |
||||||
|
#include "stm32f4xx.h" |
||||||
|
#else |
||||||
|
#include "stm32f2xx.h" |
||||||
|
#endif |
||||||
|
|
||||||
|
#define USB_VID 0xbbaaU |
||||||
|
|
||||||
|
#ifdef BOOTSTUB |
||||||
|
#define USB_PID 0xddeeU |
||||||
|
#else |
||||||
|
#define USB_PID 0xddccU |
||||||
|
#endif |
||||||
|
|
||||||
|
#include <stdbool.h> |
||||||
|
#define NULL ((void*)0) |
||||||
|
#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) |
||||||
|
|
||||||
|
#define MIN(a,b) \ |
||||||
|
({ __typeof__ (a) _a = (a); \
|
||||||
|
__typeof__ (b) _b = (b); \
|
||||||
|
(_a < _b) ? _a : _b; }) |
||||||
|
|
||||||
|
#define MAX(a,b) \ |
||||||
|
({ __typeof__ (a) _a = (a); \
|
||||||
|
__typeof__ (b) _b = (b); \
|
||||||
|
(_a > _b) ? _a : _b; }) |
||||||
|
|
||||||
|
#define MAX_RESP_LEN 0x40U |
||||||
|
|
||||||
|
// Around (1Mbps / 8 bits/byte / 12 bytes per message)
|
||||||
|
#define CAN_INTERRUPT_RATE 12000U |
||||||
|
|
||||||
|
#endif |
||||||
|
|
@ -0,0 +1,23 @@ |
|||||||
|
// ********************* Critical section helpers *********************
|
||||||
|
volatile bool interrupts_enabled = false; |
||||||
|
|
||||||
|
void enable_interrupts(void) { |
||||||
|
interrupts_enabled = true; |
||||||
|
__enable_irq(); |
||||||
|
} |
||||||
|
|
||||||
|
void disable_interrupts(void) { |
||||||
|
interrupts_enabled = false; |
||||||
|
__disable_irq(); |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t global_critical_depth = 0U; |
||||||
|
#define ENTER_CRITICAL() \ |
||||||
|
__disable_irq(); \
|
||||||
|
global_critical_depth += 1U; |
||||||
|
|
||||||
|
#define EXIT_CRITICAL() \ |
||||||
|
global_critical_depth -= 1U; \
|
||||||
|
if ((global_critical_depth == 0U) && interrupts_enabled) { \
|
||||||
|
__enable_irq(); \
|
||||||
|
} |
@ -0,0 +1,38 @@ |
|||||||
|
// ACCEL1 = ADC10
|
||||||
|
// ACCEL2 = ADC11
|
||||||
|
// VOLT_S = ADC12
|
||||||
|
// CURR_S = ADC13
|
||||||
|
|
||||||
|
#define ADCCHAN_ACCEL0 10 |
||||||
|
#define ADCCHAN_ACCEL1 11 |
||||||
|
#define ADCCHAN_VOLTAGE 12 |
||||||
|
#define ADCCHAN_CURRENT 13 |
||||||
|
|
||||||
|
void adc_init(void) { |
||||||
|
register_set(&(ADC->CCR), ADC_CCR_TSVREFE | ADC_CCR_VBATE, 0xC30000U); |
||||||
|
register_set(&(ADC1->CR2), ADC_CR2_ADON, 0xFF7F0F03U); |
||||||
|
register_set(&(ADC1->SMPR1), ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13, 0x7FFFFFFU); |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t adc_get(unsigned int channel) { |
||||||
|
// Select channel
|
||||||
|
register_set(&(ADC1->JSQR), (channel << 15U), 0x3FFFFFU); |
||||||
|
|
||||||
|
// Start conversion
|
||||||
|
ADC1->SR &= ~(ADC_SR_JEOC); |
||||||
|
ADC1->CR2 |= ADC_CR2_JSWSTART; |
||||||
|
while (!(ADC1->SR & ADC_SR_JEOC)); |
||||||
|
|
||||||
|
return ADC1->JDR1; |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t adc_get_voltage(void) { |
||||||
|
// REVC has a 10, 1 (1/11) voltage divider
|
||||||
|
// Here is the calculation for the scale (s)
|
||||||
|
// ADCV = VIN_S * (1/11) * (4095/3.3)
|
||||||
|
// RETVAL = ADCV * s = VIN_S*1000
|
||||||
|
// s = 1000/((4095/3.3)*(1/11)) = 8.8623046875
|
||||||
|
|
||||||
|
// Avoid needing floating point math, so output in mV
|
||||||
|
return (adc_get(ADCCHAN_VOLTAGE) * 8862U) / 1000U; |
||||||
|
} |
@ -0,0 +1,449 @@ |
|||||||
|
// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE
|
||||||
|
// CAN2_TX, CAN2_RX0, CAN2_SCE
|
||||||
|
// CAN3_TX, CAN3_RX0, CAN3_SCE
|
||||||
|
|
||||||
|
typedef struct { |
||||||
|
volatile uint32_t w_ptr; |
||||||
|
volatile uint32_t r_ptr; |
||||||
|
uint32_t fifo_size; |
||||||
|
CAN_FIFOMailBox_TypeDef *elems; |
||||||
|
} can_ring; |
||||||
|
|
||||||
|
#define CAN_BUS_RET_FLAG 0x80U |
||||||
|
#define CAN_BUS_NUM_MASK 0x7FU |
||||||
|
|
||||||
|
#define BUS_MAX 4U |
||||||
|
|
||||||
|
uint32_t can_rx_errs = 0; |
||||||
|
uint32_t can_send_errs = 0; |
||||||
|
uint32_t can_fwd_errs = 0; |
||||||
|
uint32_t gmlan_send_errs = 0; |
||||||
|
extern int can_live, pending_can_live; |
||||||
|
|
||||||
|
// must reinit after changing these
|
||||||
|
extern int can_loopback, can_silent; |
||||||
|
extern uint32_t can_speed[4]; |
||||||
|
|
||||||
|
void can_set_forwarding(int from, int to); |
||||||
|
|
||||||
|
void can_init(uint8_t can_number); |
||||||
|
void can_init_all(void); |
||||||
|
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number, bool skip_tx_hook); |
||||||
|
bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem); |
||||||
|
|
||||||
|
// Ignition detected from CAN meessages
|
||||||
|
bool ignition_can = false; |
||||||
|
uint32_t ignition_can_cnt = 0U; |
||||||
|
|
||||||
|
// end API
|
||||||
|
|
||||||
|
#define ALL_CAN_SILENT 0xFF |
||||||
|
#define ALL_CAN_LIVE 0 |
||||||
|
|
||||||
|
int can_live = 0, pending_can_live = 0, can_loopback = 0, can_silent = ALL_CAN_SILENT; |
||||||
|
|
||||||
|
// ********************* instantiate queues *********************
|
||||||
|
|
||||||
|
#define can_buffer(x, size) \ |
||||||
|
CAN_FIFOMailBox_TypeDef elems_##x[size]; \
|
||||||
|
can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x }; |
||||||
|
|
||||||
|
can_buffer(rx_q, 0x1000) |
||||||
|
can_buffer(tx1_q, 0x100) |
||||||
|
can_buffer(tx2_q, 0x100) |
||||||
|
can_buffer(tx3_q, 0x100) |
||||||
|
can_buffer(txgmlan_q, 0x100) |
||||||
|
can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; |
||||||
|
|
||||||
|
// global CAN stats
|
||||||
|
int can_rx_cnt = 0; |
||||||
|
int can_tx_cnt = 0; |
||||||
|
int can_txd_cnt = 0; |
||||||
|
int can_err_cnt = 0; |
||||||
|
int can_overflow_cnt = 0; |
||||||
|
|
||||||
|
// ********************* interrupt safe queue *********************
|
||||||
|
|
||||||
|
bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { |
||||||
|
bool ret = 0; |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
if (q->w_ptr != q->r_ptr) { |
||||||
|
*elem = q->elems[q->r_ptr]; |
||||||
|
if ((q->r_ptr + 1U) == q->fifo_size) { |
||||||
|
q->r_ptr = 0; |
||||||
|
} else { |
||||||
|
q->r_ptr += 1U; |
||||||
|
} |
||||||
|
ret = 1; |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { |
||||||
|
bool ret = false; |
||||||
|
uint32_t next_w_ptr; |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
if ((q->w_ptr + 1U) == q->fifo_size) { |
||||||
|
next_w_ptr = 0; |
||||||
|
} else { |
||||||
|
next_w_ptr = q->w_ptr + 1U; |
||||||
|
} |
||||||
|
if (next_w_ptr != q->r_ptr) { |
||||||
|
q->elems[q->w_ptr] = *elem; |
||||||
|
q->w_ptr = next_w_ptr; |
||||||
|
ret = true; |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
if (!ret) { |
||||||
|
can_overflow_cnt++; |
||||||
|
#ifdef DEBUG |
||||||
|
puts("can_push failed!\n"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
void can_clear(can_ring *q) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
q->w_ptr = 0; |
||||||
|
q->r_ptr = 0; |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
// assign CAN numbering
|
||||||
|
// bus num: Can bus number on ODB connector. Sent to/from USB
|
||||||
|
// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1)
|
||||||
|
// cans: Look up MCU can interface from bus number
|
||||||
|
// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc);
|
||||||
|
// bus_lookup: Translates from 'can number' to 'bus number'.
|
||||||
|
// can_num_lookup: Translates from 'bus number' to 'can number'.
|
||||||
|
// can_forwarding: Given a bus num, lookup bus num to forward to. -1 means no forward.
|
||||||
|
|
||||||
|
// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3
|
||||||
|
CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3}; |
||||||
|
uint8_t bus_lookup[] = {0,1,2}; |
||||||
|
uint8_t can_num_lookup[] = {0,1,2,-1}; |
||||||
|
int8_t can_forwarding[] = {-1,-1,-1,-1}; |
||||||
|
uint32_t can_speed[] = {5000, 5000, 5000, 333}; |
||||||
|
#define CAN_MAX 3U |
||||||
|
|
||||||
|
#define CANIF_FROM_CAN_NUM(num) (cans[num]) |
||||||
|
#define CAN_NUM_FROM_CANIF(CAN) ((CAN)==CAN1 ? 0 : ((CAN) == CAN2 ? 1 : 2)) |
||||||
|
#define CAN_NAME_FROM_CANIF(CAN) ((CAN)==CAN1 ? "CAN1" : ((CAN) == CAN2 ? "CAN2" : "CAN3")) |
||||||
|
#define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num]) |
||||||
|
#define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num]) |
||||||
|
|
||||||
|
void process_can(uint8_t can_number); |
||||||
|
|
||||||
|
void can_set_speed(uint8_t can_number) { |
||||||
|
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); |
||||||
|
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); |
||||||
|
|
||||||
|
if (!llcan_set_speed(CAN, can_speed[bus_number], can_loopback, (unsigned int)(can_silent) & (1U << can_number))) { |
||||||
|
puts("CAN init FAILED!!!!!\n"); |
||||||
|
puth(can_number); puts(" "); |
||||||
|
puth(BUS_NUM_FROM_CAN_NUM(can_number)); puts("\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void can_init_all(void) { |
||||||
|
for (uint8_t i=0U; i < CAN_MAX; i++) { |
||||||
|
can_init(i); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void can_flip_buses(uint8_t bus1, uint8_t bus2){ |
||||||
|
bus_lookup[bus1] = bus2; |
||||||
|
bus_lookup[bus2] = bus1; |
||||||
|
can_num_lookup[bus1] = bus2; |
||||||
|
can_num_lookup[bus2] = bus1; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: Cleanup with new abstraction
|
||||||
|
void can_set_gmlan(uint8_t bus) { |
||||||
|
if(board_has_gmlan()){ |
||||||
|
// first, disable GMLAN on prev bus
|
||||||
|
uint8_t prev_bus = can_num_lookup[3]; |
||||||
|
if (bus != prev_bus) { |
||||||
|
switch (prev_bus) { |
||||||
|
case 1: |
||||||
|
case 2: |
||||||
|
puts("Disable GMLAN on CAN"); |
||||||
|
puth(prev_bus + 1U); |
||||||
|
puts("\n"); |
||||||
|
current_board->set_can_mode(CAN_MODE_NORMAL); |
||||||
|
bus_lookup[prev_bus] = prev_bus; |
||||||
|
can_num_lookup[prev_bus] = prev_bus; |
||||||
|
can_num_lookup[3] = -1; |
||||||
|
can_init(prev_bus); |
||||||
|
break; |
||||||
|
default: |
||||||
|
// GMLAN was not set on either BUS 1 or 2
|
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// now enable GMLAN on the new bus
|
||||||
|
switch (bus) { |
||||||
|
case 1: |
||||||
|
case 2: |
||||||
|
puts("Enable GMLAN on CAN"); |
||||||
|
puth(bus + 1U); |
||||||
|
puts("\n"); |
||||||
|
current_board->set_can_mode((bus == 1U) ? CAN_MODE_GMLAN_CAN2 : CAN_MODE_GMLAN_CAN3); |
||||||
|
bus_lookup[bus] = 3; |
||||||
|
can_num_lookup[bus] = -1; |
||||||
|
can_num_lookup[3] = bus; |
||||||
|
can_init(bus); |
||||||
|
break; |
||||||
|
case 0xFF: //-1 unsigned
|
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("GMLAN can only be set on CAN2 or CAN3\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
} else { |
||||||
|
puts("GMLAN not available on black panda\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: remove
|
||||||
|
void can_set_obd(uint8_t harness_orientation, bool obd){ |
||||||
|
if(obd){ |
||||||
|
puts("setting CAN2 to be OBD\n"); |
||||||
|
} else { |
||||||
|
puts("setting CAN2 to be normal\n"); |
||||||
|
} |
||||||
|
if(board_has_obd()){ |
||||||
|
if(obd != (bool)(harness_orientation == HARNESS_STATUS_NORMAL)){ |
||||||
|
// B5,B6: disable normal mode
|
||||||
|
set_gpio_mode(GPIOB, 5, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 6, MODE_INPUT); |
||||||
|
// B12,B13: CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); |
||||||
|
} else { |
||||||
|
// B5,B6: CAN2 mode
|
||||||
|
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||||
|
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||||
|
// B12,B13: disable normal mode
|
||||||
|
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
} |
||||||
|
} else { |
||||||
|
puts("OBD CAN not available on this board\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// CAN error
|
||||||
|
void can_sce(CAN_TypeDef *CAN) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
|
||||||
|
#ifdef DEBUG |
||||||
|
if (CAN==CAN1) puts("CAN1: "); |
||||||
|
if (CAN==CAN2) puts("CAN2: "); |
||||||
|
#ifdef CAN3 |
||||||
|
if (CAN==CAN3) puts("CAN3: "); |
||||||
|
#endif |
||||||
|
puts("MSR:"); |
||||||
|
puth(CAN->MSR); |
||||||
|
puts(" TSR:"); |
||||||
|
puth(CAN->TSR); |
||||||
|
puts(" RF0R:"); |
||||||
|
puth(CAN->RF0R); |
||||||
|
puts(" RF1R:"); |
||||||
|
puth(CAN->RF1R); |
||||||
|
puts(" ESR:"); |
||||||
|
puth(CAN->ESR); |
||||||
|
puts("\n"); |
||||||
|
#endif |
||||||
|
|
||||||
|
can_err_cnt += 1; |
||||||
|
llcan_clear_send(CAN); |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** CAN *****************************
|
||||||
|
|
||||||
|
void process_can(uint8_t can_number) { |
||||||
|
if (can_number != 0xffU) { |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
|
||||||
|
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); |
||||||
|
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); |
||||||
|
|
||||||
|
// check for empty mailbox
|
||||||
|
CAN_FIFOMailBox_TypeDef to_send; |
||||||
|
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { |
||||||
|
// add successfully transmitted message to my fifo
|
||||||
|
if ((CAN->TSR & CAN_TSR_RQCP0) == CAN_TSR_RQCP0) { |
||||||
|
can_txd_cnt += 1; |
||||||
|
|
||||||
|
if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) { |
||||||
|
CAN_FIFOMailBox_TypeDef to_push; |
||||||
|
to_push.RIR = CAN->sTxMailBox[0].TIR; |
||||||
|
to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000FU) | ((CAN_BUS_RET_FLAG | bus_number) << 4); |
||||||
|
to_push.RDLR = CAN->sTxMailBox[0].TDLR; |
||||||
|
to_push.RDHR = CAN->sTxMailBox[0].TDHR; |
||||||
|
can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; |
||||||
|
} |
||||||
|
|
||||||
|
if ((CAN->TSR & CAN_TSR_TERR0) == CAN_TSR_TERR0) { |
||||||
|
#ifdef DEBUG |
||||||
|
puts("CAN TX ERROR!\n"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
if ((CAN->TSR & CAN_TSR_ALST0) == CAN_TSR_ALST0) { |
||||||
|
#ifdef DEBUG |
||||||
|
puts("CAN TX ARBITRATION LOST!\n"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
// clear interrupt
|
||||||
|
// careful, this can also be cleared by requesting a transmission
|
||||||
|
CAN->TSR |= CAN_TSR_RQCP0; |
||||||
|
} |
||||||
|
|
||||||
|
if (can_pop(can_queues[bus_number], &to_send)) { |
||||||
|
can_tx_cnt += 1; |
||||||
|
// only send if we have received a packet
|
||||||
|
CAN->sTxMailBox[0].TDLR = to_send.RDLR; |
||||||
|
CAN->sTxMailBox[0].TDHR = to_send.RDHR; |
||||||
|
CAN->sTxMailBox[0].TDTR = to_send.RDTR; |
||||||
|
CAN->sTxMailBox[0].TIR = to_send.RIR; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void ignition_can_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
int len = GET_LEN(to_push); |
||||||
|
|
||||||
|
ignition_can_cnt = 0U; // reset counter
|
||||||
|
|
||||||
|
if (bus == 0) { |
||||||
|
// GM exception
|
||||||
|
if ((addr == 0x1F1) && (len == 8)) { |
||||||
|
//Bit 5 is ignition "on"
|
||||||
|
ignition_can = (GET_BYTE(to_push, 0) & 0x20) != 0; |
||||||
|
} |
||||||
|
// Tesla exception
|
||||||
|
if ((addr == 0x348) && (len == 8)) { |
||||||
|
// GTW_status
|
||||||
|
ignition_can = (GET_BYTE(to_push, 0) & 0x1) != 0; |
||||||
|
} |
||||||
|
// Cadillac exception
|
||||||
|
if ((addr == 0x160) && (len == 5)) { |
||||||
|
// this message isn't all zeros when ignition is on
|
||||||
|
ignition_can = GET_BYTES_04(to_push) != 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// CAN receive handlers
|
||||||
|
// blink blue when we are receiving CAN messages
|
||||||
|
void can_rx(uint8_t can_number) { |
||||||
|
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); |
||||||
|
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); |
||||||
|
while ((CAN->RF0R & CAN_RF0R_FMP0) != 0) { |
||||||
|
can_rx_cnt += 1; |
||||||
|
|
||||||
|
// can is live
|
||||||
|
pending_can_live = 1; |
||||||
|
|
||||||
|
// add to my fifo
|
||||||
|
CAN_FIFOMailBox_TypeDef to_push; |
||||||
|
to_push.RIR = CAN->sFIFOMailBox[0].RIR; |
||||||
|
to_push.RDTR = CAN->sFIFOMailBox[0].RDTR; |
||||||
|
to_push.RDLR = CAN->sFIFOMailBox[0].RDLR; |
||||||
|
to_push.RDHR = CAN->sFIFOMailBox[0].RDHR; |
||||||
|
|
||||||
|
// modify RDTR for our API
|
||||||
|
to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4); |
||||||
|
|
||||||
|
// forwarding (panda only)
|
||||||
|
int bus_fwd_num = (can_forwarding[bus_number] != -1) ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push); |
||||||
|
if (bus_fwd_num != -1) { |
||||||
|
CAN_FIFOMailBox_TypeDef to_send; |
||||||
|
to_send.RIR = to_push.RIR | 1; // TXRQ
|
||||||
|
to_send.RDTR = to_push.RDTR; |
||||||
|
to_send.RDLR = to_push.RDLR; |
||||||
|
to_send.RDHR = to_push.RDHR; |
||||||
|
can_send(&to_send, bus_fwd_num, true); |
||||||
|
} |
||||||
|
|
||||||
|
can_rx_errs += safety_rx_hook(&to_push) ? 0U : 1U; |
||||||
|
ignition_can_hook(&to_push); |
||||||
|
|
||||||
|
current_board->set_led(LED_BLUE, true); |
||||||
|
can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; |
||||||
|
|
||||||
|
// next
|
||||||
|
CAN->RF0R |= CAN_RF0R_RFOM0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void CAN1_TX_IRQ_Handler(void) { process_can(0); } |
||||||
|
void CAN1_RX0_IRQ_Handler(void) { can_rx(0); } |
||||||
|
void CAN1_SCE_IRQ_Handler(void) { can_sce(CAN1); } |
||||||
|
|
||||||
|
void CAN2_TX_IRQ_Handler(void) { process_can(1); } |
||||||
|
void CAN2_RX0_IRQ_Handler(void) { can_rx(1); } |
||||||
|
void CAN2_SCE_IRQ_Handler(void) { can_sce(CAN2); } |
||||||
|
|
||||||
|
void CAN3_TX_IRQ_Handler(void) { process_can(2); } |
||||||
|
void CAN3_RX0_IRQ_Handler(void) { can_rx(2); } |
||||||
|
void CAN3_SCE_IRQ_Handler(void) { can_sce(CAN3); } |
||||||
|
|
||||||
|
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number, bool skip_tx_hook) { |
||||||
|
if (skip_tx_hook || safety_tx_hook(to_push) != 0) { |
||||||
|
if (bus_number < BUS_MAX) { |
||||||
|
// add CAN packet to send queue
|
||||||
|
// bus number isn't passed through
|
||||||
|
to_push->RDTR &= 0xF; |
||||||
|
if ((bus_number == 3U) && (can_num_lookup[3] == 0xFFU)) { |
||||||
|
gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; |
||||||
|
} else { |
||||||
|
can_fwd_errs += can_push(can_queues[bus_number], to_push) ? 0U : 1U; |
||||||
|
process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void can_set_forwarding(int from, int to) { |
||||||
|
can_forwarding[from] = to; |
||||||
|
} |
||||||
|
|
||||||
|
void can_init(uint8_t can_number) { |
||||||
|
REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN2_TX_IRQn, CAN2_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) |
||||||
|
REGISTER_INTERRUPT(CAN2_RX0_IRQn, CAN2_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) |
||||||
|
REGISTER_INTERRUPT(CAN2_SCE_IRQn, CAN2_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) |
||||||
|
REGISTER_INTERRUPT(CAN3_TX_IRQn, CAN3_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) |
||||||
|
REGISTER_INTERRUPT(CAN3_RX0_IRQn, CAN3_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) |
||||||
|
REGISTER_INTERRUPT(CAN3_SCE_IRQn, CAN3_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) |
||||||
|
|
||||||
|
if (can_number != 0xffU) { |
||||||
|
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); |
||||||
|
can_set_speed(can_number); |
||||||
|
|
||||||
|
llcan_init(CAN); |
||||||
|
|
||||||
|
// in case there are queued up messages
|
||||||
|
process_can(can_number); |
||||||
|
} |
||||||
|
} |
||||||
|
|
@ -0,0 +1,40 @@ |
|||||||
|
void clock_init(void) { |
||||||
|
// enable external oscillator
|
||||||
|
register_set_bits(&(RCC->CR), RCC_CR_HSEON); |
||||||
|
while ((RCC->CR & RCC_CR_HSERDY) == 0); |
||||||
|
|
||||||
|
// divide things
|
||||||
|
register_set(&(RCC->CFGR), RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4, 0xFF7FFCF3U); |
||||||
|
|
||||||
|
// 16mhz crystal
|
||||||
|
register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE, 0x7F437FFFU); |
||||||
|
|
||||||
|
// start PLL
|
||||||
|
register_set_bits(&(RCC->CR), RCC_CR_PLLON); |
||||||
|
while ((RCC->CR & RCC_CR_PLLRDY) == 0); |
||||||
|
|
||||||
|
// Configure Flash prefetch, Instruction cache, Data cache and wait state
|
||||||
|
// *** without this, it breaks ***
|
||||||
|
register_set(&(FLASH->ACR), FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS, 0x1F0FU); |
||||||
|
|
||||||
|
// switch to PLL
|
||||||
|
register_set_bits(&(RCC->CFGR), RCC_CFGR_SW_PLL); |
||||||
|
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); |
||||||
|
|
||||||
|
// *** running on PLL ***
|
||||||
|
} |
||||||
|
|
||||||
|
void watchdog_init(void) { |
||||||
|
// setup watchdog
|
||||||
|
IWDG->KR = 0x5555U; |
||||||
|
register_set(&(IWDG->PR), 0x0U, 0x7U); // divider/4
|
||||||
|
|
||||||
|
// 0 = 0.125 ms, let's have a 50ms watchdog
|
||||||
|
register_set(&(IWDG->RLR), (400U-1U), 0xFFFU); |
||||||
|
IWDG->KR = 0xCCCCU; |
||||||
|
} |
||||||
|
|
||||||
|
void watchdog_feed(void) { |
||||||
|
IWDG->KR = 0xAAAAU; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,20 @@ |
|||||||
|
void puth(unsigned int i); |
||||||
|
void puts(const char *a); |
||||||
|
|
||||||
|
void dac_init(void) { |
||||||
|
// No buffers required since we have an opamp
|
||||||
|
register_set(&(DAC->DHR12R1), 0U, 0xFFFU); |
||||||
|
register_set(&(DAC->DHR12R2), 0U, 0xFFFU); |
||||||
|
register_set(&(DAC->CR), DAC_CR_EN1 | DAC_CR_EN2, 0x3FFF3FFFU); |
||||||
|
} |
||||||
|
|
||||||
|
void dac_set(int channel, uint32_t value) { |
||||||
|
if (channel == 0) { |
||||||
|
register_set(&(DAC->DHR12R1), value, 0xFFFU); |
||||||
|
} else if (channel == 1) { |
||||||
|
register_set(&(DAC->DHR12R2), value, 0xFFFU); |
||||||
|
} else { |
||||||
|
puts("Failed to set DAC: invalid channel value: 0x"); puth(value); puts("\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
@ -0,0 +1,39 @@ |
|||||||
|
void fan_set_power(uint8_t percentage){ |
||||||
|
pwm_set(TIM3, 3, percentage); |
||||||
|
} |
||||||
|
|
||||||
|
uint16_t fan_tach_counter = 0U; |
||||||
|
uint16_t fan_rpm = 0U; |
||||||
|
|
||||||
|
// Can be way more acurate than this, but this is probably good enough for our purposes.
|
||||||
|
|
||||||
|
// Call this every second
|
||||||
|
void fan_tick(void){ |
||||||
|
// 4 interrupts per rotation
|
||||||
|
fan_rpm = fan_tach_counter * 15U; |
||||||
|
fan_tach_counter = 0U; |
||||||
|
} |
||||||
|
|
||||||
|
// TACH interrupt handler
|
||||||
|
void EXTI2_IRQ_Handler(void) { |
||||||
|
volatile unsigned int pr = EXTI->PR & (1U << 2); |
||||||
|
if ((pr & (1U << 2)) != 0U) { |
||||||
|
fan_tach_counter++; |
||||||
|
} |
||||||
|
EXTI->PR = (1U << 2); |
||||||
|
} |
||||||
|
|
||||||
|
void fan_init(void){ |
||||||
|
// 5000RPM * 4 tach edges / 60 seconds
|
||||||
|
REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) |
||||||
|
|
||||||
|
// Init PWM speed control
|
||||||
|
pwm_init(TIM3, 3); |
||||||
|
|
||||||
|
// Init TACH interrupt
|
||||||
|
register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI2_PD, 0xF00U); |
||||||
|
register_set_bits(&(EXTI->IMR), (1U << 2)); |
||||||
|
register_set_bits(&(EXTI->RTSR), (1U << 2)); |
||||||
|
register_set_bits(&(EXTI->FTSR), (1U << 2)); |
||||||
|
NVIC_EnableIRQ(EXTI2_IRQn); |
||||||
|
} |
@ -0,0 +1,288 @@ |
|||||||
|
#define GMLAN_TICKS_PER_SECOND 33300 //1sec @ 33.3kbps
|
||||||
|
#define GMLAN_TICKS_PER_TIMEOUT_TICKLE 500 //15ms @ 33.3kbps
|
||||||
|
#define GMLAN_HIGH 0 //0 is high on bus (dominant)
|
||||||
|
#define GMLAN_LOW 1 //1 is low on bus
|
||||||
|
|
||||||
|
#define DISABLED -1 |
||||||
|
#define BITBANG 0 |
||||||
|
#define GPIO_SWITCH 1 |
||||||
|
|
||||||
|
#define MAX_BITS_CAN_PACKET (200) |
||||||
|
|
||||||
|
int gmlan_alt_mode = DISABLED; |
||||||
|
|
||||||
|
// returns out_len
|
||||||
|
int do_bitstuff(char *out, char *in, int in_len) { |
||||||
|
int last_bit = -1; |
||||||
|
int bit_cnt = 0; |
||||||
|
int j = 0; |
||||||
|
for (int i = 0; i < in_len; i++) { |
||||||
|
char bit = in[i]; |
||||||
|
out[j] = bit; |
||||||
|
j++; |
||||||
|
|
||||||
|
// do the stuffing
|
||||||
|
if (bit == last_bit) { |
||||||
|
bit_cnt++; |
||||||
|
if (bit_cnt == 5) { |
||||||
|
// 5 in a row the same, do stuff
|
||||||
|
last_bit = !bit; |
||||||
|
out[j] = last_bit; |
||||||
|
j++; |
||||||
|
bit_cnt = 1; |
||||||
|
} |
||||||
|
} else { |
||||||
|
// this is a new bit
|
||||||
|
last_bit = bit; |
||||||
|
bit_cnt = 1; |
||||||
|
} |
||||||
|
} |
||||||
|
return j; |
||||||
|
} |
||||||
|
|
||||||
|
int append_crc(char *in, int in_len) { |
||||||
|
unsigned int crc = 0; |
||||||
|
for (int i = 0; i < in_len; i++) { |
||||||
|
crc <<= 1; |
||||||
|
if (((unsigned int)(in[i]) ^ ((crc >> 15) & 1U)) != 0U) { |
||||||
|
crc = crc ^ 0x4599U; |
||||||
|
} |
||||||
|
crc &= 0x7fffU; |
||||||
|
} |
||||||
|
int in_len_copy = in_len; |
||||||
|
for (int i = 14; i >= 0; i--) { |
||||||
|
in[in_len_copy] = (crc >> (unsigned int)(i)) & 1U; |
||||||
|
in_len_copy++; |
||||||
|
} |
||||||
|
return in_len_copy; |
||||||
|
} |
||||||
|
|
||||||
|
int append_bits(char *in, int in_len, char *app, int app_len) { |
||||||
|
int in_len_copy = in_len; |
||||||
|
for (int i = 0; i < app_len; i++) { |
||||||
|
in[in_len_copy] = app[i]; |
||||||
|
in_len_copy++; |
||||||
|
} |
||||||
|
return in_len_copy; |
||||||
|
} |
||||||
|
|
||||||
|
int append_int(char *in, int in_len, int val, int val_len) { |
||||||
|
int in_len_copy = in_len; |
||||||
|
for (int i = val_len - 1; i >= 0; i--) { |
||||||
|
in[in_len_copy] = ((unsigned int)(val) & (1U << (unsigned int)(i))) != 0U; |
||||||
|
in_len_copy++; |
||||||
|
} |
||||||
|
return in_len_copy; |
||||||
|
} |
||||||
|
|
||||||
|
int get_bit_message(char *out, CAN_FIFOMailBox_TypeDef *to_bang) { |
||||||
|
char pkt[MAX_BITS_CAN_PACKET]; |
||||||
|
char footer[] = { |
||||||
|
1, // CRC delimiter
|
||||||
|
1, // ACK
|
||||||
|
1, // ACK delimiter
|
||||||
|
1,1,1,1,1,1,1, // EOF
|
||||||
|
1,1,1, // IFS
|
||||||
|
}; |
||||||
|
|
||||||
|
int len = 0; |
||||||
|
|
||||||
|
// test packet
|
||||||
|
int dlc_len = to_bang->RDTR & 0xF; |
||||||
|
len = append_int(pkt, len, 0, 1); // Start-of-frame
|
||||||
|
|
||||||
|
if ((to_bang->RIR & 4) != 0) { |
||||||
|
// extended identifier
|
||||||
|
len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier
|
||||||
|
len = append_int(pkt, len, 3, 2); // SRR+IDE
|
||||||
|
len = append_int(pkt, len, (to_bang->RIR >> 3) & ((1U << 18) - 1U), 18); // Identifier
|
||||||
|
len = append_int(pkt, len, 0, 3); // RTR+r1+r0
|
||||||
|
} else { |
||||||
|
// standard identifier
|
||||||
|
len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier
|
||||||
|
len = append_int(pkt, len, 0, 3); // RTR+IDE+reserved
|
||||||
|
} |
||||||
|
|
||||||
|
len = append_int(pkt, len, dlc_len, 4); // Data length code
|
||||||
|
|
||||||
|
// append data
|
||||||
|
for (int i = 0; i < dlc_len; i++) { |
||||||
|
unsigned char dat = ((unsigned char *)(&(to_bang->RDLR)))[i]; |
||||||
|
len = append_int(pkt, len, dat, 8); |
||||||
|
} |
||||||
|
|
||||||
|
// append crc
|
||||||
|
len = append_crc(pkt, len); |
||||||
|
|
||||||
|
// do bitstuffing
|
||||||
|
len = do_bitstuff(out, pkt, len); |
||||||
|
|
||||||
|
// append footer
|
||||||
|
len = append_bits(out, len, footer, sizeof(footer)); |
||||||
|
return len; |
||||||
|
} |
||||||
|
|
||||||
|
void setup_timer4(void) { |
||||||
|
// setup
|
||||||
|
register_set(&(TIM4->PSC), (48-1), 0xFFFFU); // Tick on 1 us
|
||||||
|
register_set(&(TIM4->CR1), TIM_CR1_CEN, 0x3FU); // Enable
|
||||||
|
register_set(&(TIM4->ARR), (30-1), 0xFFFFU); // 33.3 kbps
|
||||||
|
|
||||||
|
// in case it's disabled
|
||||||
|
NVIC_EnableIRQ(TIM4_IRQn); |
||||||
|
|
||||||
|
// run the interrupt
|
||||||
|
register_set(&(TIM4->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt
|
||||||
|
TIM4->SR = 0; |
||||||
|
} |
||||||
|
|
||||||
|
int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms
|
||||||
|
int can_timeout_counter = GMLAN_TICKS_PER_SECOND; //1 second
|
||||||
|
|
||||||
|
int inverted_bit_to_send = GMLAN_HIGH; |
||||||
|
int gmlan_switch_below_timeout = -1; |
||||||
|
int gmlan_switch_timeout_enable = 0; |
||||||
|
|
||||||
|
void gmlan_switch_init(int timeout_enable) { |
||||||
|
gmlan_switch_timeout_enable = timeout_enable; |
||||||
|
gmlan_alt_mode = GPIO_SWITCH; |
||||||
|
gmlan_switch_below_timeout = 1; |
||||||
|
set_gpio_mode(GPIOB, 13, MODE_OUTPUT); |
||||||
|
|
||||||
|
setup_timer4(); |
||||||
|
|
||||||
|
inverted_bit_to_send = GMLAN_LOW; //We got initialized, set the output low
|
||||||
|
} |
||||||
|
|
||||||
|
void set_gmlan_digital_output(int to_set) { |
||||||
|
inverted_bit_to_send = to_set; |
||||||
|
/*
|
||||||
|
puts("Writing "); |
||||||
|
puth(inverted_bit_to_send); |
||||||
|
puts("\n"); |
||||||
|
*/ |
||||||
|
} |
||||||
|
|
||||||
|
void reset_gmlan_switch_timeout(void) { |
||||||
|
can_timeout_counter = GMLAN_TICKS_PER_SECOND; |
||||||
|
gmlan_switch_below_timeout = 1; |
||||||
|
gmlan_alt_mode = GPIO_SWITCH; |
||||||
|
} |
||||||
|
|
||||||
|
void set_bitbanged_gmlan(int val) { |
||||||
|
if (val != 0) { |
||||||
|
register_set_bits(&(GPIOB->ODR), (1U << 13)); |
||||||
|
} else { |
||||||
|
register_clear_bits(&(GPIOB->ODR), (1U << 13)); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
char pkt_stuffed[MAX_BITS_CAN_PACKET]; |
||||||
|
int gmlan_sending = -1; |
||||||
|
int gmlan_sendmax = -1; |
||||||
|
bool gmlan_send_ok = true; |
||||||
|
|
||||||
|
int gmlan_silent_count = 0; |
||||||
|
int gmlan_fail_count = 0; |
||||||
|
#define REQUIRED_SILENT_TIME 10 |
||||||
|
#define MAX_FAIL_COUNT 10 |
||||||
|
|
||||||
|
void TIM4_IRQ_Handler(void) { |
||||||
|
if (gmlan_alt_mode == BITBANG) { |
||||||
|
if ((TIM4->SR & TIM_SR_UIF) && (gmlan_sendmax != -1)) { |
||||||
|
int read = get_gpio_input(GPIOB, 12); |
||||||
|
if (gmlan_silent_count < REQUIRED_SILENT_TIME) { |
||||||
|
if (read == 0) { |
||||||
|
gmlan_silent_count = 0; |
||||||
|
} else { |
||||||
|
gmlan_silent_count++; |
||||||
|
} |
||||||
|
} else { |
||||||
|
bool retry = 0; |
||||||
|
// in send loop
|
||||||
|
if ((gmlan_sending > 0) && // not first bit
|
||||||
|
((read == 0) && (pkt_stuffed[gmlan_sending-1] == 1)) && // bus wrongly dominant
|
||||||
|
(gmlan_sending != (gmlan_sendmax - 11))) { //not ack bit
|
||||||
|
puts("GMLAN ERR: bus driven at "); |
||||||
|
puth(gmlan_sending); |
||||||
|
puts("\n"); |
||||||
|
retry = 1; |
||||||
|
} else if ((read == 1) && (gmlan_sending == (gmlan_sendmax - 11))) { // recessive during ACK
|
||||||
|
puts("GMLAN ERR: didn't recv ACK\n"); |
||||||
|
retry = 1; |
||||||
|
} else { |
||||||
|
// do not retry
|
||||||
|
} |
||||||
|
if (retry) { |
||||||
|
// reset sender (retry after 7 silent)
|
||||||
|
set_bitbanged_gmlan(1); // recessive
|
||||||
|
gmlan_silent_count = 0; |
||||||
|
gmlan_sending = 0; |
||||||
|
gmlan_fail_count++; |
||||||
|
if (gmlan_fail_count == MAX_FAIL_COUNT) { |
||||||
|
puts("GMLAN ERR: giving up send\n"); |
||||||
|
gmlan_send_ok = false; |
||||||
|
} |
||||||
|
} else { |
||||||
|
set_bitbanged_gmlan(pkt_stuffed[gmlan_sending]); |
||||||
|
gmlan_sending++; |
||||||
|
} |
||||||
|
} |
||||||
|
if ((gmlan_sending == gmlan_sendmax) || (gmlan_fail_count == MAX_FAIL_COUNT)) { |
||||||
|
set_bitbanged_gmlan(1); // recessive
|
||||||
|
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||||
|
register_clear_bits(&(TIM4->DIER), TIM_DIER_UIE); // No update interrupt
|
||||||
|
register_set(&(TIM4->CR1), 0U, 0x3FU); // Disable timer
|
||||||
|
gmlan_sendmax = -1; // exit
|
||||||
|
} |
||||||
|
} |
||||||
|
TIM4->SR = 0; |
||||||
|
} else if (gmlan_alt_mode == GPIO_SWITCH) { |
||||||
|
if ((TIM4->SR & TIM_SR_UIF) && (gmlan_switch_below_timeout != -1)) { |
||||||
|
if ((can_timeout_counter == 0) && gmlan_switch_timeout_enable) { |
||||||
|
//it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output
|
||||||
|
set_gpio_output(GPIOB, 13, GMLAN_LOW); |
||||||
|
gmlan_switch_below_timeout = -1; |
||||||
|
gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; |
||||||
|
gmlan_alt_mode = DISABLED; |
||||||
|
} |
||||||
|
else { |
||||||
|
can_timeout_counter--; |
||||||
|
if (gmlan_timeout_counter == 0) { |
||||||
|
//Send a 1 (bus low) every 15ms to reset the GMLAN transceivers timeout
|
||||||
|
gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; |
||||||
|
set_gpio_output(GPIOB, 13, GMLAN_LOW); |
||||||
|
} |
||||||
|
else { |
||||||
|
set_gpio_output(GPIOB, 13, inverted_bit_to_send); |
||||||
|
gmlan_timeout_counter--; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
TIM4->SR = 0; |
||||||
|
} else { |
||||||
|
puts("invalid gmlan_alt_mode\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) { |
||||||
|
gmlan_send_ok = true; |
||||||
|
gmlan_alt_mode = BITBANG; |
||||||
|
|
||||||
|
if (gmlan_sendmax == -1) { |
||||||
|
int len = get_bit_message(pkt_stuffed, to_bang); |
||||||
|
gmlan_fail_count = 0; |
||||||
|
gmlan_silent_count = 0; |
||||||
|
gmlan_sending = 0; |
||||||
|
gmlan_sendmax = len; |
||||||
|
// setup for bitbang loop
|
||||||
|
set_bitbanged_gmlan(1); // recessive
|
||||||
|
set_gpio_mode(GPIOB, 13, MODE_OUTPUT); |
||||||
|
|
||||||
|
// 33kbps
|
||||||
|
REGISTER_INTERRUPT(TIM4_IRQn, TIM4_IRQ_Handler, 40000U, FAULT_INTERRUPT_RATE_GMLAN) |
||||||
|
setup_timer4(); |
||||||
|
} |
||||||
|
return gmlan_send_ok; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,105 @@ |
|||||||
|
uint8_t car_harness_status = 0U; |
||||||
|
#define HARNESS_STATUS_NC 0U |
||||||
|
#define HARNESS_STATUS_NORMAL 1U |
||||||
|
#define HARNESS_STATUS_FLIPPED 2U |
||||||
|
|
||||||
|
// Threshold voltage (mV) for either of the SBUs to be below before deciding harness is connected
|
||||||
|
#define HARNESS_CONNECTED_THRESHOLD 2500U |
||||||
|
|
||||||
|
struct harness_configuration { |
||||||
|
const bool has_harness; |
||||||
|
GPIO_TypeDef *GPIO_SBU1; |
||||||
|
GPIO_TypeDef *GPIO_SBU2; |
||||||
|
GPIO_TypeDef *GPIO_relay_normal; |
||||||
|
GPIO_TypeDef *GPIO_relay_flipped; |
||||||
|
uint8_t pin_SBU1; |
||||||
|
uint8_t pin_SBU2; |
||||||
|
uint8_t pin_relay_normal; |
||||||
|
uint8_t pin_relay_flipped; |
||||||
|
uint8_t adc_channel_SBU1; |
||||||
|
uint8_t adc_channel_SBU2; |
||||||
|
}; |
||||||
|
|
||||||
|
// this function will be the API for tici
|
||||||
|
void set_intercept_relay(bool intercept) { |
||||||
|
if (car_harness_status != HARNESS_STATUS_NC) { |
||||||
|
if (intercept) { |
||||||
|
puts("switching harness to intercept (relay on)\n"); |
||||||
|
} else { |
||||||
|
puts("switching harness to passthrough (relay off)\n"); |
||||||
|
} |
||||||
|
|
||||||
|
if(car_harness_status == HARNESS_STATUS_NORMAL){ |
||||||
|
set_gpio_output(current_board->harness_config->GPIO_relay_normal, current_board->harness_config->pin_relay_normal, !intercept); |
||||||
|
} else { |
||||||
|
set_gpio_output(current_board->harness_config->GPIO_relay_flipped, current_board->harness_config->pin_relay_flipped, !intercept); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool harness_check_ignition(void) { |
||||||
|
bool ret = false; |
||||||
|
switch(car_harness_status){ |
||||||
|
case HARNESS_STATUS_NORMAL: |
||||||
|
ret = !get_gpio_input(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2); |
||||||
|
break; |
||||||
|
case HARNESS_STATUS_FLIPPED: |
||||||
|
ret = !get_gpio_input(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t harness_detect_orientation(void) { |
||||||
|
uint8_t ret = HARNESS_STATUS_NC; |
||||||
|
|
||||||
|
#ifndef BOOTSTUB |
||||||
|
uint32_t sbu1_voltage = adc_get(current_board->harness_config->adc_channel_SBU1); |
||||||
|
uint32_t sbu2_voltage = adc_get(current_board->harness_config->adc_channel_SBU2); |
||||||
|
|
||||||
|
// Detect connection and orientation
|
||||||
|
if((sbu1_voltage < HARNESS_CONNECTED_THRESHOLD) || (sbu2_voltage < HARNESS_CONNECTED_THRESHOLD)){ |
||||||
|
if (sbu1_voltage < sbu2_voltage) { |
||||||
|
// orientation normal
|
||||||
|
ret = HARNESS_STATUS_NORMAL; |
||||||
|
} else { |
||||||
|
// orientation flipped
|
||||||
|
ret = HARNESS_STATUS_FLIPPED; |
||||||
|
} |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
void harness_init(void) { |
||||||
|
// delay such that the connection is fully made before trying orientation detection
|
||||||
|
current_board->set_led(LED_BLUE, true); |
||||||
|
delay(10000000); |
||||||
|
current_board->set_led(LED_BLUE, false); |
||||||
|
|
||||||
|
// try to detect orientation
|
||||||
|
uint8_t ret = harness_detect_orientation(); |
||||||
|
if (ret != HARNESS_STATUS_NC) { |
||||||
|
puts("detected car harness with orientation "); puth2(ret); puts("\n"); |
||||||
|
car_harness_status = ret; |
||||||
|
|
||||||
|
// set the SBU lines to be inputs before using the relay. The lines are not 5V tolerant in ADC mode!
|
||||||
|
set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_INPUT); |
||||||
|
set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_INPUT); |
||||||
|
|
||||||
|
// now we have orientation, set pin ignition detection
|
||||||
|
if(car_harness_status == HARNESS_STATUS_NORMAL){ |
||||||
|
set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_INPUT); |
||||||
|
} else { |
||||||
|
set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_INPUT); |
||||||
|
} |
||||||
|
|
||||||
|
// keep busses connected by default
|
||||||
|
set_intercept_relay(false); |
||||||
|
} else { |
||||||
|
puts("failed to detect car harness!\n"); |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,164 @@ |
|||||||
|
typedef struct interrupt { |
||||||
|
IRQn_Type irq_type; |
||||||
|
void (*handler)(void); |
||||||
|
uint32_t call_counter; |
||||||
|
uint32_t max_call_rate; // Call rate is defined as the amount of calls each second
|
||||||
|
uint32_t call_rate_fault; |
||||||
|
} interrupt; |
||||||
|
|
||||||
|
void unused_interrupt_handler(void) { |
||||||
|
// Something is wrong if this handler is called!
|
||||||
|
puts("Unused interrupt handler called!\n"); |
||||||
|
fault_occurred(FAULT_UNUSED_INTERRUPT_HANDLED); |
||||||
|
} |
||||||
|
|
||||||
|
#define NUM_INTERRUPTS 102U // There are 102 external interrupt sources (see stm32f413.h)
|
||||||
|
interrupt interrupts[NUM_INTERRUPTS]; |
||||||
|
|
||||||
|
#define REGISTER_INTERRUPT(irq_num, func_ptr, call_rate, rate_fault) \ |
||||||
|
interrupts[irq_num].irq_type = irq_num; \
|
||||||
|
interrupts[irq_num].handler = func_ptr; \
|
||||||
|
interrupts[irq_num].call_counter = 0U; \
|
||||||
|
interrupts[irq_num].max_call_rate = call_rate; \
|
||||||
|
interrupts[irq_num].call_rate_fault = rate_fault; |
||||||
|
|
||||||
|
bool check_interrupt_rate = false; |
||||||
|
|
||||||
|
void handle_interrupt(IRQn_Type irq_type){ |
||||||
|
interrupts[irq_type].call_counter++; |
||||||
|
interrupts[irq_type].handler(); |
||||||
|
|
||||||
|
// Check that the interrupts don't fire too often
|
||||||
|
if(check_interrupt_rate && (interrupts[irq_type].call_counter > interrupts[irq_type].max_call_rate)){ |
||||||
|
puts("Interrupt 0x"); puth(irq_type); puts(" fired too often (0x"); puth(interrupts[irq_type].call_counter); puts("/s)!\n"); |
||||||
|
fault_occurred(interrupts[irq_type].call_rate_fault); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// Reset interrupt counter every second
|
||||||
|
void TIM6_DAC_IRQ_Handler(void) { |
||||||
|
if (TIM6->SR != 0) { |
||||||
|
for(uint16_t i=0U; i<NUM_INTERRUPTS; i++){ |
||||||
|
interrupts[i].call_counter = 0U; |
||||||
|
} |
||||||
|
} |
||||||
|
TIM6->SR = 0; |
||||||
|
} |
||||||
|
|
||||||
|
void init_interrupts(bool check_rate_limit){ |
||||||
|
check_interrupt_rate = check_rate_limit; |
||||||
|
|
||||||
|
for(uint16_t i=0U; i<NUM_INTERRUPTS; i++){ |
||||||
|
interrupts[i].handler = unused_interrupt_handler; |
||||||
|
} |
||||||
|
|
||||||
|
// Init timer 10 for a 1s interval
|
||||||
|
register_set_bits(&(RCC->APB1ENR), RCC_APB1ENR_TIM6EN); // Enable interrupt timer peripheral
|
||||||
|
REGISTER_INTERRUPT(TIM6_DAC_IRQn, TIM6_DAC_IRQ_Handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS) |
||||||
|
register_set(&(TIM6->PSC), (732-1), 0xFFFFU); |
||||||
|
register_set(&(TIM6->DIER), TIM_DIER_UIE, 0x5F5FU); |
||||||
|
register_set(&(TIM6->CR1), TIM_CR1_CEN, 0x3FU); |
||||||
|
TIM6->SR = 0; |
||||||
|
NVIC_EnableIRQ(TIM6_DAC_IRQn); |
||||||
|
} |
||||||
|
|
||||||
|
// ********************* Bare interrupt handlers *********************
|
||||||
|
// Only implemented the STM32F413 interrupts for now, the STM32F203 specific ones do not fall into the scope of SIL2
|
||||||
|
|
||||||
|
void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} |
||||||
|
void PVD_IRQHandler(void) {handle_interrupt(PVD_IRQn);} |
||||||
|
void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} |
||||||
|
void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} |
||||||
|
void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} |
||||||
|
void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} |
||||||
|
void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} |
||||||
|
void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} |
||||||
|
void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} |
||||||
|
void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} |
||||||
|
void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} |
||||||
|
void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} |
||||||
|
void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} |
||||||
|
void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} |
||||||
|
void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} |
||||||
|
void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} |
||||||
|
void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} |
||||||
|
void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} |
||||||
|
void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} |
||||||
|
void CAN1_TX_IRQHandler(void) {handle_interrupt(CAN1_TX_IRQn);} |
||||||
|
void CAN1_RX0_IRQHandler(void) {handle_interrupt(CAN1_RX0_IRQn);} |
||||||
|
void CAN1_RX1_IRQHandler(void) {handle_interrupt(CAN1_RX1_IRQn);} |
||||||
|
void CAN1_SCE_IRQHandler(void) {handle_interrupt(CAN1_SCE_IRQn);} |
||||||
|
void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} |
||||||
|
void TIM1_BRK_TIM9_IRQHandler(void) {handle_interrupt(TIM1_BRK_TIM9_IRQn);} |
||||||
|
void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} |
||||||
|
void TIM1_TRG_COM_TIM11_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_TIM11_IRQn);} |
||||||
|
void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} |
||||||
|
void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} |
||||||
|
void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} |
||||||
|
void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} |
||||||
|
void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} |
||||||
|
void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} |
||||||
|
void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} |
||||||
|
void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} |
||||||
|
void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} |
||||||
|
void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} |
||||||
|
void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} |
||||||
|
void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} |
||||||
|
void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} |
||||||
|
void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} |
||||||
|
void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} |
||||||
|
void OTG_FS_WKUP_IRQHandler(void) {handle_interrupt(OTG_FS_WKUP_IRQn);} |
||||||
|
void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} |
||||||
|
void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} |
||||||
|
void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} |
||||||
|
void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} |
||||||
|
void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} |
||||||
|
void FSMC_IRQHandler(void) {handle_interrupt(FSMC_IRQn);} |
||||||
|
void SDIO_IRQHandler(void) {handle_interrupt(SDIO_IRQn);} |
||||||
|
void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} |
||||||
|
void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} |
||||||
|
void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} |
||||||
|
void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} |
||||||
|
void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} |
||||||
|
void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} |
||||||
|
void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} |
||||||
|
void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} |
||||||
|
void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} |
||||||
|
void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} |
||||||
|
void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} |
||||||
|
void CAN2_TX_IRQHandler(void) {handle_interrupt(CAN2_TX_IRQn);} |
||||||
|
void CAN2_RX0_IRQHandler(void) {handle_interrupt(CAN2_RX0_IRQn);} |
||||||
|
void CAN2_RX1_IRQHandler(void) {handle_interrupt(CAN2_RX1_IRQn);} |
||||||
|
void CAN2_SCE_IRQHandler(void) {handle_interrupt(CAN2_SCE_IRQn);} |
||||||
|
void OTG_FS_IRQHandler(void) {handle_interrupt(OTG_FS_IRQn);} |
||||||
|
void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} |
||||||
|
void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} |
||||||
|
void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} |
||||||
|
void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} |
||||||
|
void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} |
||||||
|
void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} |
||||||
|
#ifdef STM32F4 |
||||||
|
void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} |
||||||
|
void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} |
||||||
|
void CAN3_TX_IRQHandler(void) {handle_interrupt(CAN3_TX_IRQn);} |
||||||
|
void CAN3_RX0_IRQHandler(void) {handle_interrupt(CAN3_RX0_IRQn);} |
||||||
|
void CAN3_RX1_IRQHandler(void) {handle_interrupt(CAN3_RX1_IRQn);} |
||||||
|
void CAN3_SCE_IRQHandler(void) {handle_interrupt(CAN3_SCE_IRQn);} |
||||||
|
void RNG_IRQHandler(void) {handle_interrupt(RNG_IRQn);} |
||||||
|
void FPU_IRQHandler(void) {handle_interrupt(FPU_IRQn);} |
||||||
|
void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} |
||||||
|
void UART8_IRQHandler(void) {handle_interrupt(UART8_IRQn);} |
||||||
|
void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} |
||||||
|
void SPI5_IRQHandler(void) {handle_interrupt(SPI5_IRQn);} |
||||||
|
void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} |
||||||
|
void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} |
||||||
|
void UART10_IRQHandler(void) {handle_interrupt(UART10_IRQn);} |
||||||
|
void QUADSPI_IRQHandler(void) {handle_interrupt(QUADSPI_IRQn);} |
||||||
|
void FMPI2C1_EV_IRQHandler(void) {handle_interrupt(FMPI2C1_EV_IRQn);} |
||||||
|
void FMPI2C1_ER_IRQHandler(void) {handle_interrupt(FMPI2C1_ER_IRQn);} |
||||||
|
void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} |
||||||
|
void DFSDM2_FLT0_IRQHandler(void) {handle_interrupt(DFSDM2_FLT0_IRQn);} |
||||||
|
void DFSDM2_FLT1_IRQHandler(void) {handle_interrupt(DFSDM2_FLT1_IRQn);} |
||||||
|
void DFSDM2_FLT2_IRQHandler(void) {handle_interrupt(DFSDM2_FLT2_IRQn);} |
||||||
|
void DFSDM2_FLT3_IRQHandler(void) {handle_interrupt(DFSDM2_FLT3_IRQn);} |
||||||
|
#endif |
@ -0,0 +1,98 @@ |
|||||||
|
// this is needed for 1 mbps support
|
||||||
|
#define CAN_QUANTA 8U |
||||||
|
#define CAN_SEQ1 6 // roundf(quanta * 0.875f) - 1;
|
||||||
|
#define CAN_SEQ2 1 // roundf(quanta * 0.125f);
|
||||||
|
|
||||||
|
#define CAN_PCLK 24000U |
||||||
|
// 333 = 33.3 kbps
|
||||||
|
// 5000 = 500 kbps
|
||||||
|
#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) |
||||||
|
|
||||||
|
#define GET_BUS(msg) (((msg)->RDTR >> 4) & 0xFF) |
||||||
|
#define GET_LEN(msg) ((msg)->RDTR & 0xF) |
||||||
|
#define GET_ADDR(msg) ((((msg)->RIR & 4) != 0) ? ((msg)->RIR >> 3) : ((msg)->RIR >> 21)) |
||||||
|
#define GET_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0XFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) |
||||||
|
#define GET_BYTES_04(msg) ((msg)->RDLR) |
||||||
|
#define GET_BYTES_48(msg) ((msg)->RDHR) |
||||||
|
|
||||||
|
void puts(const char *a); |
||||||
|
|
||||||
|
bool llcan_set_speed(CAN_TypeDef *CAN_obj, uint32_t speed, bool loopback, bool silent) { |
||||||
|
// initialization mode
|
||||||
|
register_set(&(CAN_obj->MCR), CAN_MCR_TTCM | CAN_MCR_INRQ, 0x180FFU); |
||||||
|
while((CAN_obj->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); |
||||||
|
|
||||||
|
// set time quanta from defines
|
||||||
|
register_set(&(CAN_obj->BTR), ((CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | |
||||||
|
(CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | |
||||||
|
(can_speed_to_prescaler(speed) - 1U)), 0xC37F03FFU); |
||||||
|
|
||||||
|
// silent loopback mode for debugging
|
||||||
|
if (loopback) { |
||||||
|
register_set_bits(&(CAN_obj->BTR), CAN_BTR_SILM | CAN_BTR_LBKM); |
||||||
|
} |
||||||
|
if (silent) { |
||||||
|
register_set_bits(&(CAN_obj->BTR), CAN_BTR_SILM); |
||||||
|
} |
||||||
|
|
||||||
|
// reset
|
||||||
|
register_set(&(CAN_obj->MCR), CAN_MCR_TTCM | CAN_MCR_ABOM, 0x180FFU); |
||||||
|
|
||||||
|
#define CAN_TIMEOUT 1000000 |
||||||
|
int tmp = 0; |
||||||
|
bool ret = false; |
||||||
|
while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (tmp < CAN_TIMEOUT)) tmp++; |
||||||
|
if (tmp < CAN_TIMEOUT) { |
||||||
|
ret = true; |
||||||
|
} |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
void llcan_init(CAN_TypeDef *CAN_obj) { |
||||||
|
// Enter init mode
|
||||||
|
register_set_bits(&(CAN_obj->FMR), CAN_FMR_FINIT); |
||||||
|
|
||||||
|
// Wait for INAK bit to be set
|
||||||
|
while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) {} |
||||||
|
|
||||||
|
// no mask
|
||||||
|
// For some weird reason some of these registers do not want to set properly on CAN2 and CAN3. Probably something to do with the single/dual mode and their different filters.
|
||||||
|
CAN_obj->sFilterRegister[0].FR1 = 0U; |
||||||
|
CAN_obj->sFilterRegister[0].FR2 = 0U; |
||||||
|
CAN_obj->sFilterRegister[14].FR1 = 0U; |
||||||
|
CAN_obj->sFilterRegister[14].FR2 = 0U; |
||||||
|
CAN_obj->FA1R |= 1U | (1U << 14); |
||||||
|
|
||||||
|
// Exit init mode, do not wait
|
||||||
|
register_clear_bits(&(CAN_obj->FMR), CAN_FMR_FINIT); |
||||||
|
|
||||||
|
// enable certain CAN interrupts
|
||||||
|
register_set_bits(&(CAN_obj->IER), CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_WKUIE); |
||||||
|
|
||||||
|
if (CAN_obj == CAN1) { |
||||||
|
NVIC_EnableIRQ(CAN1_TX_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN1_RX0_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN1_SCE_IRQn); |
||||||
|
} else if (CAN_obj == CAN2) { |
||||||
|
NVIC_EnableIRQ(CAN2_TX_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN2_RX0_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN2_SCE_IRQn); |
||||||
|
#ifdef CAN3 |
||||||
|
} else if (CAN_obj == CAN3) { |
||||||
|
NVIC_EnableIRQ(CAN3_TX_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN3_RX0_IRQn); |
||||||
|
NVIC_EnableIRQ(CAN3_SCE_IRQn); |
||||||
|
#endif |
||||||
|
} else { |
||||||
|
puts("Invalid CAN: initialization failed\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void llcan_clear_send(CAN_TypeDef *CAN_obj) { |
||||||
|
CAN_obj->TSR |= CAN_TSR_ABRQ0; |
||||||
|
register_clear_bits(&(CAN_obj->MSR), CAN_MSR_ERRI); |
||||||
|
// cppcheck-suppress selfAssignment ; needed to clear the register
|
||||||
|
CAN_obj->MSR = CAN_obj->MSR; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,65 @@ |
|||||||
|
#define MODE_INPUT 0 |
||||||
|
#define MODE_OUTPUT 1 |
||||||
|
#define MODE_ALTERNATE 2 |
||||||
|
#define MODE_ANALOG 3 |
||||||
|
|
||||||
|
#define PULL_NONE 0 |
||||||
|
#define PULL_UP 1 |
||||||
|
#define PULL_DOWN 2 |
||||||
|
|
||||||
|
#define OUTPUT_TYPE_PUSH_PULL 0U |
||||||
|
#define OUTPUT_TYPE_OPEN_DRAIN 1U |
||||||
|
|
||||||
|
void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
uint32_t tmp = GPIO->MODER; |
||||||
|
tmp &= ~(3U << (pin * 2U)); |
||||||
|
tmp |= (mode << (pin * 2U)); |
||||||
|
register_set(&(GPIO->MODER), tmp, 0xFFFFFFFFU); |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
if (enabled) { |
||||||
|
register_set_bits(&(GPIO->ODR), (1U << pin)); |
||||||
|
} else { |
||||||
|
register_clear_bits(&(GPIO->ODR), (1U << pin)); |
||||||
|
} |
||||||
|
set_gpio_mode(GPIO, pin, MODE_OUTPUT); |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void set_gpio_output_type(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int output_type){ |
||||||
|
ENTER_CRITICAL(); |
||||||
|
if(output_type == OUTPUT_TYPE_OPEN_DRAIN) { |
||||||
|
register_set_bits(&(GPIO->OTYPER), (1U << pin)); |
||||||
|
} else { |
||||||
|
register_clear_bits(&(GPIO->OTYPER), (1U << pin)); |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void set_gpio_alternate(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
uint32_t tmp = GPIO->AFR[pin >> 3U]; |
||||||
|
tmp &= ~(0xFU << ((pin & 7U) * 4U)); |
||||||
|
tmp |= mode << ((pin & 7U) * 4U); |
||||||
|
register_set(&(GPIO->AFR[pin >> 3]), tmp, 0xFFFFFFFFU); |
||||||
|
set_gpio_mode(GPIO, pin, MODE_ALTERNATE); |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
uint32_t tmp = GPIO->PUPDR; |
||||||
|
tmp &= ~(3U << (pin * 2U)); |
||||||
|
tmp |= (mode << (pin * 2U)); |
||||||
|
register_set(&(GPIO->PUPDR), tmp, 0xFFFFFFFFU); |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
int get_gpio_input(GPIO_TypeDef *GPIO, unsigned int pin) { |
||||||
|
return (GPIO->IDR & (1U << pin)) == (1U << pin); |
||||||
|
} |
||||||
|
|
@ -0,0 +1,56 @@ |
|||||||
|
#define PWM_COUNTER_OVERFLOW 2000U // To get ~50kHz
|
||||||
|
|
||||||
|
// TODO: Implement for 32-bit timers
|
||||||
|
|
||||||
|
void pwm_init(TIM_TypeDef *TIM, uint8_t channel){ |
||||||
|
// Enable timer and auto-reload
|
||||||
|
register_set(&(TIM->CR1), TIM_CR1_CEN | TIM_CR1_ARPE, 0x3FU); |
||||||
|
|
||||||
|
// Set channel as PWM mode 1 and enable output
|
||||||
|
switch(channel){ |
||||||
|
case 1U: |
||||||
|
register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE)); |
||||||
|
register_set_bits(&(TIM->CCER), TIM_CCER_CC1E); |
||||||
|
break; |
||||||
|
case 2U: |
||||||
|
register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE)); |
||||||
|
register_set_bits(&(TIM->CCER), TIM_CCER_CC2E); |
||||||
|
break; |
||||||
|
case 3U: |
||||||
|
register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE)); |
||||||
|
register_set_bits(&(TIM->CCER), TIM_CCER_CC3E); |
||||||
|
break; |
||||||
|
case 4U: |
||||||
|
register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4PE)); |
||||||
|
register_set_bits(&(TIM->CCER), TIM_CCER_CC4E); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
// Set max counter value
|
||||||
|
register_set(&(TIM->ARR), PWM_COUNTER_OVERFLOW, 0xFFFFU); |
||||||
|
|
||||||
|
// Update registers and clear counter
|
||||||
|
TIM->EGR |= TIM_EGR_UG; |
||||||
|
} |
||||||
|
|
||||||
|
void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){ |
||||||
|
uint16_t comp_value = (((uint16_t) percentage * PWM_COUNTER_OVERFLOW) / 100U); |
||||||
|
switch(channel){ |
||||||
|
case 1U: |
||||||
|
register_set(&(TIM->CCR1), comp_value, 0xFFFFU); |
||||||
|
break; |
||||||
|
case 2U: |
||||||
|
register_set(&(TIM->CCR2), comp_value, 0xFFFFU); |
||||||
|
break; |
||||||
|
case 3U: |
||||||
|
register_set(&(TIM->CCR3), comp_value, 0xFFFFU); |
||||||
|
break; |
||||||
|
case 4U: |
||||||
|
register_set(&(TIM->CCR4), comp_value, 0xFFFFU); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,81 @@ |
|||||||
|
|
||||||
|
typedef struct reg { |
||||||
|
volatile uint32_t *address; |
||||||
|
uint32_t value; |
||||||
|
uint32_t check_mask; |
||||||
|
} reg; |
||||||
|
|
||||||
|
// 10 bit hash with 23 as a prime
|
||||||
|
#define REGISTER_MAP_SIZE 0x3FFU |
||||||
|
#define HASHING_PRIME 23U |
||||||
|
#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != addr)) |
||||||
|
|
||||||
|
reg register_map[REGISTER_MAP_SIZE]; |
||||||
|
|
||||||
|
// Hash spread in first and second iterations seems to be reasonable.
|
||||||
|
// See: tests/development/register_hashmap_spread.py
|
||||||
|
// Also, check the collision warnings in the debug output, and minimize those.
|
||||||
|
uint16_t hash_addr(uint32_t input){ |
||||||
|
return (((input >> 16U) ^ ((((input + 1U) & 0xFFFFU) * HASHING_PRIME) & 0xFFFFU)) & REGISTER_MAP_SIZE); |
||||||
|
} |
||||||
|
|
||||||
|
// Do not put bits in the check mask that get changed by the hardware
|
||||||
|
void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask){ |
||||||
|
ENTER_CRITICAL() |
||||||
|
// Set bits in register that are also in the mask
|
||||||
|
(*addr) = ((*addr) & (~mask)) | (val & mask); |
||||||
|
|
||||||
|
// Add these values to the map
|
||||||
|
uint16_t hash = hash_addr((uint32_t) addr); |
||||||
|
uint16_t tries = REGISTER_MAP_SIZE; |
||||||
|
while(CHECK_COLLISION(hash, addr) && (tries > 0U)) { hash = hash_addr((uint32_t) hash); tries--;} |
||||||
|
if (tries != 0U){ |
||||||
|
register_map[hash].address = addr; |
||||||
|
register_map[hash].value = (register_map[hash].value & (~mask)) | (val & mask); |
||||||
|
register_map[hash].check_mask |= mask; |
||||||
|
} else { |
||||||
|
#ifdef DEBUG_FAULTS |
||||||
|
puts("Hash collision: address 0x"); puth((uint32_t) addr); puts("!\n"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
EXIT_CRITICAL() |
||||||
|
} |
||||||
|
|
||||||
|
// Set individual bits. Also add them to the check_mask.
|
||||||
|
// Do not use this to change bits that get reset by the hardware
|
||||||
|
void register_set_bits(volatile uint32_t *addr, uint32_t val) { |
||||||
|
return register_set(addr, val, val); |
||||||
|
} |
||||||
|
|
||||||
|
// Clear individual bits. Also add them to the check_mask.
|
||||||
|
// Do not use this to clear bits that get set by the hardware
|
||||||
|
void register_clear_bits(volatile uint32_t *addr, uint32_t val) { |
||||||
|
return register_set(addr, (~val), val); |
||||||
|
} |
||||||
|
|
||||||
|
// To be called periodically
|
||||||
|
void check_registers(void){ |
||||||
|
for(uint16_t i=0U; i<REGISTER_MAP_SIZE; i++){ |
||||||
|
if((uint32_t) register_map[i].address != 0U){ |
||||||
|
ENTER_CRITICAL() |
||||||
|
if((*(register_map[i].address) & register_map[i].check_mask) != (register_map[i].value & register_map[i].check_mask)){ |
||||||
|
#ifdef DEBUG_FAULTS |
||||||
|
puts("Register at address 0x"); puth((uint32_t) register_map[i].address); puts(" is divergent!"); |
||||||
|
puts(" Map: 0x"); puth(register_map[i].value); |
||||||
|
puts(" Register: 0x"); puth(*(register_map[i].address)); |
||||||
|
puts(" Mask: 0x"); puth(register_map[i].check_mask); |
||||||
|
puts("\n"); |
||||||
|
#endif |
||||||
|
fault_occurred(FAULT_REGISTER_DIVERGENT); |
||||||
|
} |
||||||
|
EXIT_CRITICAL() |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void init_registers(void) { |
||||||
|
for(uint16_t i=0U; i<REGISTER_MAP_SIZE; i++){ |
||||||
|
register_map[i].address = (volatile uint32_t *) 0U; |
||||||
|
register_map[i].check_mask = 0U; |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,108 @@ |
|||||||
|
#define RCC_BDCR_OPTIONS (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) |
||||||
|
#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) |
||||||
|
|
||||||
|
#define YEAR_OFFSET 2000U |
||||||
|
|
||||||
|
typedef struct __attribute__((packed)) timestamp_t { |
||||||
|
uint16_t year; |
||||||
|
uint8_t month; |
||||||
|
uint8_t day; |
||||||
|
uint8_t weekday; |
||||||
|
uint8_t hour; |
||||||
|
uint8_t minute; |
||||||
|
uint8_t second; |
||||||
|
} timestamp_t; |
||||||
|
|
||||||
|
uint8_t to_bcd(uint16_t value){ |
||||||
|
return (((value / 10U) & 0x0FU) << 4U) | ((value % 10U) & 0x0FU); |
||||||
|
} |
||||||
|
|
||||||
|
uint16_t from_bcd(uint8_t value){ |
||||||
|
return (((value & 0xF0U) >> 4U) * 10U) + (value & 0x0FU); |
||||||
|
} |
||||||
|
|
||||||
|
void rtc_init(void){ |
||||||
|
if(board_has_rtc()){ |
||||||
|
// Initialize RTC module and clock if not done already.
|
||||||
|
if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ |
||||||
|
puts("Initializing RTC\n"); |
||||||
|
// Reset backup domain
|
||||||
|
register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); |
||||||
|
|
||||||
|
// Disable write protection
|
||||||
|
register_set_bits(&(PWR->CR), PWR_CR_DBP); |
||||||
|
|
||||||
|
// Clear backup domain reset
|
||||||
|
register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); |
||||||
|
|
||||||
|
// Set RTC options
|
||||||
|
register_set(&(RCC->BDCR), RCC_BDCR_OPTIONS, RCC_BDCR_MASK); |
||||||
|
|
||||||
|
// Enable write protection
|
||||||
|
register_clear_bits(&(PWR->CR), PWR_CR_DBP); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void rtc_set_time(timestamp_t time){ |
||||||
|
if(board_has_rtc()){ |
||||||
|
puts("Setting RTC time\n"); |
||||||
|
|
||||||
|
// Disable write protection
|
||||||
|
register_set_bits(&(PWR->CR), PWR_CR_DBP); |
||||||
|
RTC->WPR = 0xCA; |
||||||
|
RTC->WPR = 0x53; |
||||||
|
|
||||||
|
// Enable initialization mode
|
||||||
|
register_set_bits(&(RTC->ISR), RTC_ISR_INIT); |
||||||
|
while((RTC->ISR & RTC_ISR_INITF) == 0){} |
||||||
|
|
||||||
|
// Set time
|
||||||
|
RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); |
||||||
|
RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); |
||||||
|
|
||||||
|
// Set options
|
||||||
|
register_set(&(RTC->CR), 0U, 0xFCFFFFU); |
||||||
|
|
||||||
|
// Disable initalization mode
|
||||||
|
register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); |
||||||
|
|
||||||
|
// Wait for synchronization
|
||||||
|
while((RTC->ISR & RTC_ISR_RSF) == 0){} |
||||||
|
|
||||||
|
// Re-enable write protection
|
||||||
|
RTC->WPR = 0x00; |
||||||
|
register_clear_bits(&(PWR->CR), PWR_CR_DBP); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
timestamp_t rtc_get_time(void){ |
||||||
|
timestamp_t result; |
||||||
|
// Init with zero values in case there is no RTC running
|
||||||
|
result.year = 0U; |
||||||
|
result.month = 0U; |
||||||
|
result.day = 0U; |
||||||
|
result.weekday = 0U; |
||||||
|
result.hour = 0U; |
||||||
|
result.minute = 0U; |
||||||
|
result.second = 0U; |
||||||
|
|
||||||
|
if(board_has_rtc()){ |
||||||
|
// Wait until the register sync flag is set
|
||||||
|
while((RTC->ISR & RTC_ISR_RSF) == 0){} |
||||||
|
|
||||||
|
// Read time and date registers. Since our HSE > 7*LSE, this should be fine.
|
||||||
|
uint32_t time = RTC->TR; |
||||||
|
uint32_t date = RTC->DR; |
||||||
|
|
||||||
|
// Parse values
|
||||||
|
result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; |
||||||
|
result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); |
||||||
|
result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); |
||||||
|
result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); |
||||||
|
result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); |
||||||
|
result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); |
||||||
|
result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); |
||||||
|
} |
||||||
|
return result; |
||||||
|
} |
@ -0,0 +1,131 @@ |
|||||||
|
// IRQs: DMA2_Stream2, DMA2_Stream3, EXTI4
|
||||||
|
|
||||||
|
void spi_init(void); |
||||||
|
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out); |
||||||
|
|
||||||
|
// end API
|
||||||
|
|
||||||
|
#define SPI_BUF_SIZE 256 |
||||||
|
uint8_t spi_buf[SPI_BUF_SIZE]; |
||||||
|
int spi_buf_count = 0; |
||||||
|
int spi_total_count = 0; |
||||||
|
|
||||||
|
void spi_tx_dma(void *addr, int len) { |
||||||
|
// disable DMA
|
||||||
|
register_clear_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); |
||||||
|
register_clear_bits(&(DMA2_Stream3->CR), DMA_SxCR_EN); |
||||||
|
|
||||||
|
// DMA2, stream 3, channel 3
|
||||||
|
register_set(&(DMA2_Stream3->M0AR), (uint32_t)addr, 0xFFFFFFFFU); |
||||||
|
DMA2_Stream3->NDTR = len; |
||||||
|
register_set(&(DMA2_Stream3->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); |
||||||
|
|
||||||
|
// channel3, increment memory, memory -> periph, enable
|
||||||
|
register_set(&(DMA2_Stream3->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN), 0x1E077EFEU); |
||||||
|
delay(0); |
||||||
|
register_set_bits(&(DMA2_Stream3->CR), DMA_SxCR_TCIE); |
||||||
|
|
||||||
|
register_set_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); |
||||||
|
|
||||||
|
// signal data is ready by driving low
|
||||||
|
// esp must be configured as input by this point
|
||||||
|
set_gpio_output(GPIOB, 0, 0); |
||||||
|
} |
||||||
|
|
||||||
|
void spi_rx_dma(void *addr, int len) { |
||||||
|
// disable DMA
|
||||||
|
register_clear_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); |
||||||
|
register_clear_bits(&(DMA2_Stream2->CR), DMA_SxCR_EN); |
||||||
|
|
||||||
|
// drain the bus
|
||||||
|
volatile uint8_t dat = SPI1->DR; |
||||||
|
(void)dat; |
||||||
|
|
||||||
|
// DMA2, stream 2, channel 3
|
||||||
|
register_set(&(DMA2_Stream2->M0AR), (uint32_t)addr, 0xFFFFFFFFU); |
||||||
|
DMA2_Stream2->NDTR = len; |
||||||
|
register_set(&(DMA2_Stream2->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); |
||||||
|
|
||||||
|
// channel3, increment memory, periph -> memory, enable
|
||||||
|
register_set(&(DMA2_Stream2->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_EN), 0x1E077EFEU); |
||||||
|
delay(0); |
||||||
|
register_set_bits(&(DMA2_Stream2->CR), DMA_SxCR_TCIE); |
||||||
|
|
||||||
|
register_set_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** SPI IRQs *****************************
|
||||||
|
// can't go on the stack cause it's DMAed
|
||||||
|
uint8_t spi_tx_buf[0x44]; |
||||||
|
|
||||||
|
// SPI RX
|
||||||
|
void DMA2_Stream2_IRQ_Handler(void) { |
||||||
|
int *resp_len = (int*)spi_tx_buf; |
||||||
|
(void)memset(spi_tx_buf, 0xaa, 0x44); |
||||||
|
*resp_len = spi_cb_rx(spi_buf, 0x14, spi_tx_buf+4); |
||||||
|
#ifdef DEBUG_SPI |
||||||
|
puts("SPI write: "); |
||||||
|
puth(*resp_len); |
||||||
|
puts("\n"); |
||||||
|
#endif |
||||||
|
spi_tx_dma(spi_tx_buf, *resp_len + 4); |
||||||
|
|
||||||
|
// ack
|
||||||
|
DMA2->LIFCR = DMA_LIFCR_CTCIF2; |
||||||
|
} |
||||||
|
|
||||||
|
// SPI TX
|
||||||
|
void DMA2_Stream3_IRQ_Handler(void) { |
||||||
|
#ifdef DEBUG_SPI |
||||||
|
puts("SPI handshake\n"); |
||||||
|
#endif |
||||||
|
|
||||||
|
// reset handshake back to pull up
|
||||||
|
set_gpio_mode(GPIOB, 0, MODE_INPUT); |
||||||
|
set_gpio_pullup(GPIOB, 0, PULL_UP); |
||||||
|
|
||||||
|
// ack
|
||||||
|
DMA2->LIFCR = DMA_LIFCR_CTCIF3; |
||||||
|
} |
||||||
|
|
||||||
|
void EXTI4_IRQ_Handler(void) { |
||||||
|
volatile unsigned int pr = EXTI->PR & (1U << 4); |
||||||
|
#ifdef DEBUG_SPI |
||||||
|
puts("exti4\n"); |
||||||
|
#endif |
||||||
|
// SPI CS falling
|
||||||
|
if ((pr & (1U << 4)) != 0U) { |
||||||
|
spi_total_count = 0; |
||||||
|
spi_rx_dma(spi_buf, 0x14); |
||||||
|
} |
||||||
|
EXTI->PR = pr; |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** SPI init *****************************
|
||||||
|
void spi_init(void) { |
||||||
|
// Max SPI clock the ESP can produce is 80MHz. At buffer size of 256 bytes, that's a max of about 40k buffers per second
|
||||||
|
REGISTER_INTERRUPT(DMA2_Stream2_IRQn, DMA2_Stream2_IRQ_Handler, 50000U, FAULT_INTERRUPT_RATE_SPI_DMA) |
||||||
|
REGISTER_INTERRUPT(DMA2_Stream3_IRQn, DMA2_Stream3_IRQ_Handler, 50000U, FAULT_INTERRUPT_RATE_SPI_DMA) |
||||||
|
REGISTER_INTERRUPT(EXTI4_IRQn, EXTI4_IRQ_Handler, 50000U, FAULT_INTERRUPT_RATE_SPI_CS) // TODO: Figure out if this is a reasonable limit
|
||||||
|
|
||||||
|
//puts("SPI init\n");
|
||||||
|
register_set(&(SPI1->CR1), SPI_CR1_SPE, 0xFFFFU); |
||||||
|
|
||||||
|
// enable SPI interrupts
|
||||||
|
//SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE;
|
||||||
|
register_set(&(SPI1->CR2), SPI_CR2_RXNEIE, 0xF7U); |
||||||
|
|
||||||
|
NVIC_EnableIRQ(DMA2_Stream2_IRQn); |
||||||
|
NVIC_EnableIRQ(DMA2_Stream3_IRQn); |
||||||
|
//NVIC_EnableIRQ(SPI1_IRQn);
|
||||||
|
|
||||||
|
// reset handshake back to pull up
|
||||||
|
set_gpio_mode(GPIOB, 0, MODE_INPUT); |
||||||
|
set_gpio_pullup(GPIOB, 0, PULL_UP); |
||||||
|
|
||||||
|
// setup interrupt on falling edge of SPI enable (on PA4)
|
||||||
|
register_set(&(SYSCFG->EXTICR[2]), SYSCFG_EXTICR2_EXTI4_PA, 0xFFFFU); |
||||||
|
register_set_bits(&(EXTI->IMR), (1U << 4)); |
||||||
|
register_set_bits(&(EXTI->FTSR), (1U << 4)); |
||||||
|
NVIC_EnableIRQ(EXTI4_IRQn); |
||||||
|
} |
@ -0,0 +1,7 @@ |
|||||||
|
void timer_init(TIM_TypeDef *TIM, int psc) { |
||||||
|
register_set(&(TIM->PSC), (psc-1), 0xFFFFU); |
||||||
|
register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU); |
||||||
|
register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU); |
||||||
|
TIM->SR = 0; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,440 @@ |
|||||||
|
// IRQs: USART1, USART2, USART3, UART5
|
||||||
|
|
||||||
|
// ***************************** Definitions *****************************
|
||||||
|
#define FIFO_SIZE_INT 0x400U |
||||||
|
#define FIFO_SIZE_DMA 0x1000U |
||||||
|
|
||||||
|
typedef struct uart_ring { |
||||||
|
volatile uint16_t w_ptr_tx; |
||||||
|
volatile uint16_t r_ptr_tx; |
||||||
|
uint8_t *elems_tx; |
||||||
|
uint32_t tx_fifo_size; |
||||||
|
volatile uint16_t w_ptr_rx; |
||||||
|
volatile uint16_t r_ptr_rx; |
||||||
|
uint8_t *elems_rx; |
||||||
|
uint32_t rx_fifo_size; |
||||||
|
USART_TypeDef *uart; |
||||||
|
void (*callback)(struct uart_ring*); |
||||||
|
bool dma_rx; |
||||||
|
} uart_ring; |
||||||
|
|
||||||
|
#define UART_BUFFER(x, size_rx, size_tx, uart_ptr, callback_ptr, rx_dma) \ |
||||||
|
uint8_t elems_rx_##x[size_rx]; \
|
||||||
|
uint8_t elems_tx_##x[size_tx]; \
|
||||||
|
uart_ring uart_ring_##x = { \
|
||||||
|
.w_ptr_tx = 0, \
|
||||||
|
.r_ptr_tx = 0, \
|
||||||
|
.elems_tx = ((uint8_t *)&elems_tx_##x), \
|
||||||
|
.tx_fifo_size = size_tx, \
|
||||||
|
.w_ptr_rx = 0, \
|
||||||
|
.r_ptr_rx = 0, \
|
||||||
|
.elems_rx = ((uint8_t *)&elems_rx_##x), \
|
||||||
|
.rx_fifo_size = size_rx, \
|
||||||
|
.uart = uart_ptr, \
|
||||||
|
.callback = callback_ptr, \
|
||||||
|
.dma_rx = rx_dma \
|
||||||
|
}; |
||||||
|
|
||||||
|
|
||||||
|
// ***************************** Function prototypes *****************************
|
||||||
|
void uart_init(uart_ring *q, int baud); |
||||||
|
|
||||||
|
bool getc(uart_ring *q, char *elem); |
||||||
|
bool putc(uart_ring *q, char elem); |
||||||
|
|
||||||
|
void puts(const char *a); |
||||||
|
void puth(unsigned int i); |
||||||
|
void hexdump(const void *a, int l); |
||||||
|
|
||||||
|
void debug_ring_callback(uart_ring *ring); |
||||||
|
|
||||||
|
// ******************************** UART buffers ********************************
|
||||||
|
|
||||||
|
// esp_gps = USART1
|
||||||
|
UART_BUFFER(esp_gps, FIFO_SIZE_DMA, FIFO_SIZE_INT, USART1, NULL, true) |
||||||
|
|
||||||
|
// lin1, K-LINE = UART5
|
||||||
|
// lin2, L-LINE = USART3
|
||||||
|
UART_BUFFER(lin1, FIFO_SIZE_INT, FIFO_SIZE_INT, UART5, NULL, false) |
||||||
|
UART_BUFFER(lin2, FIFO_SIZE_INT, FIFO_SIZE_INT, USART3, NULL, false) |
||||||
|
|
||||||
|
// debug = USART2
|
||||||
|
UART_BUFFER(debug, FIFO_SIZE_INT, FIFO_SIZE_INT, USART2, debug_ring_callback, false) |
||||||
|
|
||||||
|
uart_ring *get_ring_by_number(int a) { |
||||||
|
uart_ring *ring = NULL; |
||||||
|
switch(a) { |
||||||
|
case 0: |
||||||
|
ring = &uart_ring_debug; |
||||||
|
break; |
||||||
|
case 1: |
||||||
|
ring = &uart_ring_esp_gps; |
||||||
|
break; |
||||||
|
case 2: |
||||||
|
ring = &uart_ring_lin1; |
||||||
|
break; |
||||||
|
case 3: |
||||||
|
ring = &uart_ring_lin2; |
||||||
|
break; |
||||||
|
default: |
||||||
|
ring = NULL; |
||||||
|
break; |
||||||
|
} |
||||||
|
return ring; |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** Interrupt handlers *****************************
|
||||||
|
|
||||||
|
void uart_tx_ring(uart_ring *q){ |
||||||
|
ENTER_CRITICAL(); |
||||||
|
// Send out next byte of TX buffer
|
||||||
|
if (q->w_ptr_tx != q->r_ptr_tx) { |
||||||
|
// Only send if transmit register is empty (aka last byte has been sent)
|
||||||
|
if ((q->uart->SR & USART_SR_TXE) != 0) { |
||||||
|
q->uart->DR = q->elems_tx[q->r_ptr_tx]; // This clears TXE
|
||||||
|
q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; |
||||||
|
} |
||||||
|
|
||||||
|
// Enable TXE interrupt if there is still data to be sent
|
||||||
|
if(q->r_ptr_tx != q->w_ptr_tx){ |
||||||
|
q->uart->CR1 |= USART_CR1_TXEIE; |
||||||
|
} else { |
||||||
|
q->uart->CR1 &= ~USART_CR1_TXEIE; |
||||||
|
} |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void uart_rx_ring(uart_ring *q){ |
||||||
|
// Do not read out directly if DMA enabled
|
||||||
|
if (q->dma_rx == false) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
|
||||||
|
// Read out RX buffer
|
||||||
|
uint8_t c = q->uart->DR; // This read after reading SR clears a bunch of interrupts
|
||||||
|
|
||||||
|
uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; |
||||||
|
// Do not overwrite buffer data
|
||||||
|
if (next_w_ptr != q->r_ptr_rx) { |
||||||
|
q->elems_rx[q->w_ptr_rx] = c; |
||||||
|
q->w_ptr_rx = next_w_ptr; |
||||||
|
if (q->callback != NULL) { |
||||||
|
q->callback(q); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// This function should be called on:
|
||||||
|
// * Half-transfer DMA interrupt
|
||||||
|
// * Full-transfer DMA interrupt
|
||||||
|
// * UART IDLE detection
|
||||||
|
uint32_t prev_w_index = 0; |
||||||
|
void dma_pointer_handler(uart_ring *q, uint32_t dma_ndtr) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
uint32_t w_index = (q->rx_fifo_size - dma_ndtr); |
||||||
|
|
||||||
|
// Check for new data
|
||||||
|
if (w_index != prev_w_index){ |
||||||
|
// Check for overflow
|
||||||
|
if ( |
||||||
|
((prev_w_index < q->r_ptr_rx) && (q->r_ptr_rx <= w_index)) || // No rollover
|
||||||
|
((w_index < prev_w_index) && ((q->r_ptr_rx <= w_index) || (prev_w_index < q->r_ptr_rx))) // Rollover
|
||||||
|
){
|
||||||
|
// We lost data. Set the new read pointer to the oldest byte still available
|
||||||
|
q->r_ptr_rx = (w_index + 1U) % q->rx_fifo_size; |
||||||
|
} |
||||||
|
|
||||||
|
// Set write pointer
|
||||||
|
q->w_ptr_rx = w_index; |
||||||
|
} |
||||||
|
|
||||||
|
prev_w_index = w_index; |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
// This read after reading SR clears all error interrupts. We don't want compiler warnings, nor optimizations
|
||||||
|
#define UART_READ_DR(uart) volatile uint8_t t = (uart)->DR; UNUSED(t); |
||||||
|
|
||||||
|
void uart_interrupt_handler(uart_ring *q) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
|
||||||
|
// Read UART status. This is also the first step necessary in clearing most interrupts
|
||||||
|
uint32_t status = q->uart->SR; |
||||||
|
|
||||||
|
// If RXNE is set, perform a read. This clears RXNE, ORE, IDLE, NF and FE
|
||||||
|
if((status & USART_SR_RXNE) != 0U){ |
||||||
|
uart_rx_ring(q); |
||||||
|
} |
||||||
|
|
||||||
|
// Detect errors and clear them
|
||||||
|
uint32_t err = (status & USART_SR_ORE) | (status & USART_SR_NE) | (status & USART_SR_FE) | (status & USART_SR_PE); |
||||||
|
if(err != 0U){ |
||||||
|
#ifdef DEBUG_UART |
||||||
|
puts("Encountered UART error: "); puth(err); puts("\n"); |
||||||
|
#endif |
||||||
|
UART_READ_DR(q->uart) |
||||||
|
} |
||||||
|
// Send if necessary
|
||||||
|
uart_tx_ring(q); |
||||||
|
|
||||||
|
// Run DMA pointer handler if the line is idle
|
||||||
|
if(q->dma_rx && (status & USART_SR_IDLE)){ |
||||||
|
// Reset IDLE flag
|
||||||
|
UART_READ_DR(q->uart) |
||||||
|
|
||||||
|
if(q == &uart_ring_esp_gps){ |
||||||
|
dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); |
||||||
|
} else { |
||||||
|
#ifdef DEBUG_UART |
||||||
|
puts("No IDLE dma_pointer_handler implemented for this UART."); |
||||||
|
#endif |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
void USART1_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_esp_gps); } |
||||||
|
void USART2_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_debug); } |
||||||
|
void USART3_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin2); } |
||||||
|
void UART5_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin1); } |
||||||
|
|
||||||
|
void DMA2_Stream5_IRQ_Handler(void) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
|
||||||
|
// Handle errors
|
||||||
|
if((DMA2->HISR & DMA_HISR_TEIF5) || (DMA2->HISR & DMA_HISR_DMEIF5) || (DMA2->HISR & DMA_HISR_FEIF5)){ |
||||||
|
#ifdef DEBUG_UART |
||||||
|
puts("Encountered UART DMA error. Clearing and restarting DMA...\n"); |
||||||
|
#endif |
||||||
|
|
||||||
|
// Clear flags
|
||||||
|
DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; |
||||||
|
|
||||||
|
// Re-enable the DMA if necessary
|
||||||
|
DMA2_Stream5->CR |= DMA_SxCR_EN; |
||||||
|
} |
||||||
|
|
||||||
|
// Re-calculate write pointer and reset flags
|
||||||
|
dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); |
||||||
|
DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; |
||||||
|
|
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** Hardware setup *****************************
|
||||||
|
|
||||||
|
void dma_rx_init(uart_ring *q) { |
||||||
|
// Initialization is UART-dependent
|
||||||
|
if(q == &uart_ring_esp_gps){ |
||||||
|
// DMA2, stream 5, channel 4
|
||||||
|
|
||||||
|
// Disable FIFO mode (enable direct)
|
||||||
|
DMA2_Stream5->FCR &= ~DMA_SxFCR_DMDIS; |
||||||
|
|
||||||
|
// Setup addresses
|
||||||
|
DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); // Source
|
||||||
|
DMA2_Stream5->M0AR = (uint32_t)q->elems_rx; // Destination
|
||||||
|
DMA2_Stream5->NDTR = q->rx_fifo_size; // Number of bytes to copy
|
||||||
|
|
||||||
|
// Circular, Increment memory, byte size, periph -> memory, enable
|
||||||
|
// Transfer complete, half transfer, transfer error and direct mode error interrupt enable
|
||||||
|
DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_DMEIE | DMA_SxCR_EN; |
||||||
|
|
||||||
|
// Enable DMA receiver in UART
|
||||||
|
q->uart->CR3 |= USART_CR3_DMAR; |
||||||
|
|
||||||
|
// Enable UART IDLE interrupt
|
||||||
|
q->uart->CR1 |= USART_CR1_IDLEIE; |
||||||
|
|
||||||
|
// Enable interrupt
|
||||||
|
NVIC_EnableIRQ(DMA2_Stream5_IRQn); |
||||||
|
} else { |
||||||
|
puts("Tried to initialize RX DMA for an unsupported UART\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) |
||||||
|
#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) |
||||||
|
#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) |
||||||
|
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) |
||||||
|
|
||||||
|
void uart_set_baud(USART_TypeDef *u, unsigned int baud) { |
||||||
|
if (u == USART1) { |
||||||
|
// USART1 is on APB2
|
||||||
|
u->BRR = __USART_BRR(48000000U, baud); |
||||||
|
} else { |
||||||
|
u->BRR = __USART_BRR(24000000U, baud); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uart_init(uart_ring *q, int baud) { |
||||||
|
// Register interrupts (max data rate: 115200 baud)
|
||||||
|
REGISTER_INTERRUPT(USART1_IRQn, USART1_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_1) |
||||||
|
REGISTER_INTERRUPT(USART2_IRQn, USART2_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_2) |
||||||
|
REGISTER_INTERRUPT(USART3_IRQn, USART3_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_3) |
||||||
|
REGISTER_INTERRUPT(UART5_IRQn, UART5_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_5) |
||||||
|
REGISTER_INTERRUPT(DMA2_Stream5_IRQn, DMA2_Stream5_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_UART_DMA) // Called twice per buffer
|
||||||
|
|
||||||
|
// Set baud and enable peripheral with TX and RX mode
|
||||||
|
uart_set_baud(q->uart, baud); |
||||||
|
q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; |
||||||
|
|
||||||
|
// Enable UART interrupts
|
||||||
|
if(q->uart == USART1){ |
||||||
|
NVIC_EnableIRQ(USART1_IRQn); |
||||||
|
} else if (q->uart == USART2){ |
||||||
|
NVIC_EnableIRQ(USART2_IRQn); |
||||||
|
} else if (q->uart == USART3){ |
||||||
|
NVIC_EnableIRQ(USART3_IRQn); |
||||||
|
} else if (q->uart == UART5){ |
||||||
|
NVIC_EnableIRQ(UART5_IRQn); |
||||||
|
} else { |
||||||
|
// UART not used. Skip enabling interrupts
|
||||||
|
} |
||||||
|
|
||||||
|
// Initialise RX DMA if used
|
||||||
|
if(q->dma_rx){ |
||||||
|
dma_rx_init(q); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// ************************* Low-level buffer functions *************************
|
||||||
|
|
||||||
|
bool getc(uart_ring *q, char *elem) { |
||||||
|
bool ret = false; |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
if (q->w_ptr_rx != q->r_ptr_rx) { |
||||||
|
if (elem != NULL) *elem = q->elems_rx[q->r_ptr_rx]; |
||||||
|
q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; |
||||||
|
ret = true; |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool injectc(uart_ring *q, char elem) { |
||||||
|
int ret = false; |
||||||
|
uint16_t next_w_ptr; |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
next_w_ptr = (q->w_ptr_rx + 1U) % q->tx_fifo_size; |
||||||
|
if (next_w_ptr != q->r_ptr_rx) { |
||||||
|
q->elems_rx[q->w_ptr_rx] = elem; |
||||||
|
q->w_ptr_rx = next_w_ptr; |
||||||
|
ret = true; |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
bool putc(uart_ring *q, char elem) { |
||||||
|
bool ret = false; |
||||||
|
uint16_t next_w_ptr; |
||||||
|
|
||||||
|
ENTER_CRITICAL(); |
||||||
|
next_w_ptr = (q->w_ptr_tx + 1U) % q->tx_fifo_size; |
||||||
|
if (next_w_ptr != q->r_ptr_tx) { |
||||||
|
q->elems_tx[q->w_ptr_tx] = elem; |
||||||
|
q->w_ptr_tx = next_w_ptr; |
||||||
|
ret = true; |
||||||
|
} |
||||||
|
EXIT_CRITICAL(); |
||||||
|
|
||||||
|
uart_tx_ring(q); |
||||||
|
|
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
// Seems dangerous to use (might lock CPU if called with interrupts disabled f.e.)
|
||||||
|
// TODO: Remove? Not used anyways
|
||||||
|
void uart_flush(uart_ring *q) { |
||||||
|
while (q->w_ptr_tx != q->r_ptr_tx) { |
||||||
|
__WFI(); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uart_flush_sync(uart_ring *q) { |
||||||
|
// empty the TX buffer
|
||||||
|
while (q->w_ptr_tx != q->r_ptr_tx) { |
||||||
|
uart_tx_ring(q); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void uart_send_break(uart_ring *u) { |
||||||
|
while ((u->uart->CR1 & USART_CR1_SBK) != 0); |
||||||
|
u->uart->CR1 |= USART_CR1_SBK; |
||||||
|
} |
||||||
|
|
||||||
|
void clear_uart_buff(uart_ring *q) { |
||||||
|
ENTER_CRITICAL(); |
||||||
|
q->w_ptr_tx = 0; |
||||||
|
q->r_ptr_tx = 0; |
||||||
|
q->w_ptr_rx = 0; |
||||||
|
q->r_ptr_rx = 0; |
||||||
|
EXIT_CRITICAL(); |
||||||
|
} |
||||||
|
|
||||||
|
// ************************ High-level debug functions **********************
|
||||||
|
void putch(const char a) { |
||||||
|
if (has_external_debug_serial) { |
||||||
|
// assuming debugging is important if there's external serial connected
|
||||||
|
while (!putc(&uart_ring_debug, a)); |
||||||
|
|
||||||
|
} else { |
||||||
|
// misra-c2012-17.7: serial debug function, ok to ignore output
|
||||||
|
(void)injectc(&uart_ring_debug, a); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void puts(const char *a) { |
||||||
|
for (const char *in = a; *in; in++) { |
||||||
|
if (*in == '\n') putch('\r'); |
||||||
|
putch(*in); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void putui(uint32_t i) { |
||||||
|
uint32_t i_copy = i; |
||||||
|
char str[11]; |
||||||
|
uint8_t idx = 10; |
||||||
|
str[idx] = '\0'; |
||||||
|
idx--; |
||||||
|
do { |
||||||
|
str[idx] = (i_copy % 10U) + 0x30U; |
||||||
|
idx--; |
||||||
|
i_copy /= 10; |
||||||
|
} while (i_copy != 0U); |
||||||
|
puts(&str[idx + 1U]); |
||||||
|
} |
||||||
|
|
||||||
|
void puth(unsigned int i) { |
||||||
|
char c[] = "0123456789abcdef"; |
||||||
|
for (int pos = 28; pos != -4; pos -= 4) { |
||||||
|
putch(c[(i >> (unsigned int)(pos)) & 0xFU]); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void puth2(unsigned int i) { |
||||||
|
char c[] = "0123456789abcdef"; |
||||||
|
for (int pos = 4; pos != -4; pos -= 4) { |
||||||
|
putch(c[(i >> (unsigned int)(pos)) & 0xFU]); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void hexdump(const void *a, int l) { |
||||||
|
if (a != NULL) { |
||||||
|
for (int i=0; i < l; i++) { |
||||||
|
if ((i != 0) && ((i & 0xf) == 0)) puts("\n"); |
||||||
|
puth2(((const unsigned char*)a)[i]); |
||||||
|
puts(" "); |
||||||
|
} |
||||||
|
} |
||||||
|
puts("\n"); |
||||||
|
} |
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,49 @@ |
|||||||
|
#define FAULT_STATUS_NONE 0U |
||||||
|
#define FAULT_STATUS_TEMPORARY 1U |
||||||
|
#define FAULT_STATUS_PERMANENT 2U |
||||||
|
|
||||||
|
// Fault types
|
||||||
|
#define FAULT_RELAY_MALFUNCTION (1U << 0) |
||||||
|
#define FAULT_UNUSED_INTERRUPT_HANDLED (1U << 1) |
||||||
|
#define FAULT_INTERRUPT_RATE_CAN_1 (1U << 2) |
||||||
|
#define FAULT_INTERRUPT_RATE_CAN_2 (1U << 3) |
||||||
|
#define FAULT_INTERRUPT_RATE_CAN_3 (1U << 4) |
||||||
|
#define FAULT_INTERRUPT_RATE_TACH (1U << 5) |
||||||
|
#define FAULT_INTERRUPT_RATE_GMLAN (1U << 6) |
||||||
|
#define FAULT_INTERRUPT_RATE_INTERRUPTS (1U << 7) |
||||||
|
#define FAULT_INTERRUPT_RATE_SPI_DMA (1U << 8) |
||||||
|
#define FAULT_INTERRUPT_RATE_SPI_CS (1U << 9) |
||||||
|
#define FAULT_INTERRUPT_RATE_UART_1 (1U << 10) |
||||||
|
#define FAULT_INTERRUPT_RATE_UART_2 (1U << 11) |
||||||
|
#define FAULT_INTERRUPT_RATE_UART_3 (1U << 12) |
||||||
|
#define FAULT_INTERRUPT_RATE_UART_5 (1U << 13) |
||||||
|
#define FAULT_INTERRUPT_RATE_UART_DMA (1U << 14) |
||||||
|
#define FAULT_INTERRUPT_RATE_USB (1U << 15) |
||||||
|
#define FAULT_INTERRUPT_RATE_TIM1 (1U << 16) |
||||||
|
#define FAULT_INTERRUPT_RATE_TIM3 (1U << 17) |
||||||
|
#define FAULT_REGISTER_DIVERGENT (1U << 18) |
||||||
|
|
||||||
|
// Permanent faults
|
||||||
|
#define PERMANENT_FAULTS 0U |
||||||
|
|
||||||
|
uint8_t fault_status = FAULT_STATUS_NONE; |
||||||
|
uint32_t faults = 0U; |
||||||
|
|
||||||
|
void fault_occurred(uint32_t fault) { |
||||||
|
faults |= fault; |
||||||
|
if((PERMANENT_FAULTS & fault) != 0U){ |
||||||
|
puts("Permanent fault occurred: 0x"); puth(fault); puts("\n"); |
||||||
|
fault_status = FAULT_STATUS_PERMANENT; |
||||||
|
} else { |
||||||
|
puts("Temporary fault occurred: 0x"); puth(fault); puts("\n"); |
||||||
|
fault_status = FAULT_STATUS_TEMPORARY; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void fault_recovered(uint32_t fault) { |
||||||
|
if((PERMANENT_FAULTS & fault) == 0U){ |
||||||
|
faults &= ~fault; |
||||||
|
} else { |
||||||
|
puts("Cannot recover from a permanent fault!\n"); |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,3 @@ |
|||||||
|
#!/bin/bash |
||||||
|
sudo apt-get install gcc-arm-none-eabi python-pip |
||||||
|
sudo pip install libusb1 pycrypto requests |
@ -0,0 +1,5 @@ |
|||||||
|
#!/bin/bash |
||||||
|
# Need formula for gcc |
||||||
|
brew tap ArmMbed/homebrew-formulae |
||||||
|
brew install python dfu-util arm-none-eabi-gcc |
||||||
|
pip install --user libusb1 pycrypto requests |
@ -0,0 +1,76 @@ |
|||||||
|
// Early bringup
|
||||||
|
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef |
||||||
|
#define ENTER_SOFTLOADER_MAGIC 0xdeadc0de |
||||||
|
#define BOOT_NORMAL 0xdeadb111 |
||||||
|
|
||||||
|
extern void *g_pfnVectors; |
||||||
|
extern uint32_t enter_bootloader_mode; |
||||||
|
|
||||||
|
void jump_to_bootloader(void) { |
||||||
|
// do enter bootloader
|
||||||
|
enter_bootloader_mode = 0; |
||||||
|
void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004)); |
||||||
|
|
||||||
|
// jump to bootloader
|
||||||
|
bootloader(); |
||||||
|
|
||||||
|
// reset on exit
|
||||||
|
enter_bootloader_mode = BOOT_NORMAL; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
|
||||||
|
void early(void) { |
||||||
|
// Reset global critical depth
|
||||||
|
global_critical_depth = 0; |
||||||
|
|
||||||
|
// Init register and interrupt tables
|
||||||
|
init_registers(); |
||||||
|
|
||||||
|
// neccesary for DFU flashing on a non-power cycled white panda
|
||||||
|
enable_interrupts(); |
||||||
|
|
||||||
|
// after it's been in the bootloader, things are initted differently, so we reset
|
||||||
|
if ((enter_bootloader_mode != BOOT_NORMAL) && |
||||||
|
(enter_bootloader_mode != ENTER_BOOTLOADER_MAGIC) && |
||||||
|
(enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC)) { |
||||||
|
enter_bootloader_mode = BOOT_NORMAL; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
|
||||||
|
// if wrong chip, reboot
|
||||||
|
volatile unsigned int id = DBGMCU->IDCODE; |
||||||
|
#ifdef STM32F4 |
||||||
|
if ((id & 0xFFFU) != 0x463U) { |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
} |
||||||
|
#else |
||||||
|
if ((id & 0xFFFU) != 0x411U) { |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
// setup interrupt table
|
||||||
|
SCB->VTOR = (uint32_t)&g_pfnVectors; |
||||||
|
|
||||||
|
// early GPIOs float everything
|
||||||
|
RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; |
||||||
|
|
||||||
|
GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0; |
||||||
|
GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; |
||||||
|
GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; |
||||||
|
|
||||||
|
detect_configuration(); |
||||||
|
detect_board_type(); |
||||||
|
|
||||||
|
if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { |
||||||
|
#ifdef PANDA |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_DISABLED); |
||||||
|
#endif |
||||||
|
current_board->set_led(LED_GREEN, 1); |
||||||
|
jump_to_bootloader(); |
||||||
|
} |
||||||
|
|
||||||
|
if (is_entering_bootmode) { |
||||||
|
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,284 @@ |
|||||||
|
/**************************************************************************//**
|
||||||
|
* @file cmsis_compiler.h |
||||||
|
* @brief CMSIS compiler generic header file |
||||||
|
* @version V5.1.0 |
||||||
|
* @date 09. October 2018 |
||||||
|
******************************************************************************/ |
||||||
|
/*
|
||||||
|
* Copyright (c) 2009-2018 Arm Limited. All rights reserved. |
||||||
|
* |
||||||
|
* SPDX-License-Identifier: Apache-2.0 |
||||||
|
* |
||||||
|
* Licensed under the Apache License, Version 2.0 (the License); you may |
||||||
|
* not use this file except in compliance with the License. |
||||||
|
* You may obtain a copy of the License at |
||||||
|
* |
||||||
|
* www.apache.org/licenses/LICENSE-2.0 |
||||||
|
* |
||||||
|
* Unless required by applicable law or agreed to in writing, software |
||||||
|
* distributed under the License is distributed on an AS IS BASIS, WITHOUT |
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
||||||
|
* See the License for the specific language governing permissions and |
||||||
|
* limitations under the License. |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifndef __CMSIS_COMPILER_H |
||||||
|
#define __CMSIS_COMPILER_H |
||||||
|
|
||||||
|
#include <stdint.h> |
||||||
|
|
||||||
|
/*
|
||||||
|
* Arm Compiler 4/5 |
||||||
|
*/ |
||||||
|
#if defined ( __CC_ARM ) |
||||||
|
#include "cmsis_armcc.h" |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Arm Compiler 6.6 LTM (armclang) |
||||||
|
*/ |
||||||
|
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) |
||||||
|
#include "cmsis_armclang_ltm.h" |
||||||
|
|
||||||
|
/*
|
||||||
|
* Arm Compiler above 6.10.1 (armclang) |
||||||
|
*/ |
||||||
|
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) |
||||||
|
#include "cmsis_armclang.h" |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* GNU Compiler |
||||||
|
*/ |
||||||
|
#elif defined ( __GNUC__ ) |
||||||
|
#include "cmsis_gcc.h" |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* IAR Compiler |
||||||
|
*/ |
||||||
|
#elif defined ( __ICCARM__ ) |
||||||
|
#include <cmsis_iccarm.h> |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* TI Arm Compiler |
||||||
|
*/ |
||||||
|
#elif defined ( __TI_ARM__ ) |
||||||
|
#include <cmsis_ccs.h> |
||||||
|
|
||||||
|
#ifndef __ASM |
||||||
|
#define __ASM __asm |
||||||
|
#endif |
||||||
|
#ifndef __INLINE |
||||||
|
#define __INLINE inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_INLINE |
||||||
|
#define __STATIC_INLINE static inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_FORCEINLINE |
||||||
|
#define __STATIC_FORCEINLINE __STATIC_INLINE |
||||||
|
#endif |
||||||
|
#ifndef __NO_RETURN |
||||||
|
#define __NO_RETURN __attribute__((noreturn)) |
||||||
|
#endif |
||||||
|
#ifndef __USED |
||||||
|
#define __USED __attribute__((used)) |
||||||
|
#endif |
||||||
|
#ifndef __WEAK |
||||||
|
#define __WEAK __attribute__((weak)) |
||||||
|
#endif |
||||||
|
#ifndef __PACKED |
||||||
|
#define __PACKED __attribute__((packed)) |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_STRUCT |
||||||
|
#define __PACKED_STRUCT struct __attribute__((packed)) |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_UNION |
||||||
|
#define __PACKED_UNION union __attribute__((packed)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32 /* deprecated */ |
||||||
|
struct __attribute__((packed)) T_UINT32 { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_WRITE |
||||||
|
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_READ |
||||||
|
__PACKED_STRUCT T_UINT16_READ { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_WRITE |
||||||
|
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_READ |
||||||
|
__PACKED_STRUCT T_UINT32_READ { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __ALIGNED |
||||||
|
#define __ALIGNED(x) __attribute__((aligned(x))) |
||||||
|
#endif |
||||||
|
#ifndef __RESTRICT |
||||||
|
#define __RESTRICT __restrict |
||||||
|
#endif |
||||||
|
#ifndef __COMPILER_BARRIER |
||||||
|
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. |
||||||
|
#define __COMPILER_BARRIER() (void)0 |
||||||
|
#endif |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* TASKING Compiler |
||||||
|
*/ |
||||||
|
#elif defined ( __TASKING__ ) |
||||||
|
/*
|
||||||
|
* 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. |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifndef __ASM |
||||||
|
#define __ASM __asm |
||||||
|
#endif |
||||||
|
#ifndef __INLINE |
||||||
|
#define __INLINE inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_INLINE |
||||||
|
#define __STATIC_INLINE static inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_FORCEINLINE |
||||||
|
#define __STATIC_FORCEINLINE __STATIC_INLINE |
||||||
|
#endif |
||||||
|
#ifndef __NO_RETURN |
||||||
|
#define __NO_RETURN __attribute__((noreturn)) |
||||||
|
#endif |
||||||
|
#ifndef __USED |
||||||
|
#define __USED __attribute__((used)) |
||||||
|
#endif |
||||||
|
#ifndef __WEAK |
||||||
|
#define __WEAK __attribute__((weak)) |
||||||
|
#endif |
||||||
|
#ifndef __PACKED |
||||||
|
#define __PACKED __packed__ |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_STRUCT |
||||||
|
#define __PACKED_STRUCT struct __packed__ |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_UNION |
||||||
|
#define __PACKED_UNION union __packed__ |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32 /* deprecated */ |
||||||
|
struct __packed__ T_UINT32 { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_WRITE |
||||||
|
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_READ |
||||||
|
__PACKED_STRUCT T_UINT16_READ { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_WRITE |
||||||
|
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_READ |
||||||
|
__PACKED_STRUCT T_UINT32_READ { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __ALIGNED |
||||||
|
#define __ALIGNED(x) __align(x) |
||||||
|
#endif |
||||||
|
#ifndef __RESTRICT |
||||||
|
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. |
||||||
|
#define __RESTRICT |
||||||
|
#endif |
||||||
|
#ifndef __COMPILER_BARRIER |
||||||
|
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. |
||||||
|
#define __COMPILER_BARRIER() (void)0 |
||||||
|
#endif |
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* COSMIC Compiler |
||||||
|
*/ |
||||||
|
#elif defined ( __CSMC__ ) |
||||||
|
#include <cmsis_csm.h> |
||||||
|
|
||||||
|
#ifndef __ASM |
||||||
|
#define __ASM _asm |
||||||
|
#endif |
||||||
|
#ifndef __INLINE |
||||||
|
#define __INLINE inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_INLINE |
||||||
|
#define __STATIC_INLINE static inline |
||||||
|
#endif |
||||||
|
#ifndef __STATIC_FORCEINLINE |
||||||
|
#define __STATIC_FORCEINLINE __STATIC_INLINE |
||||||
|
#endif |
||||||
|
#ifndef __NO_RETURN |
||||||
|
// NO RETURN is automatically detected hence no warning here
|
||||||
|
#define __NO_RETURN |
||||||
|
#endif |
||||||
|
#ifndef __USED |
||||||
|
#warning No compiler specific solution for __USED. __USED is ignored. |
||||||
|
#define __USED |
||||||
|
#endif |
||||||
|
#ifndef __WEAK |
||||||
|
#define __WEAK __weak |
||||||
|
#endif |
||||||
|
#ifndef __PACKED |
||||||
|
#define __PACKED @packed |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_STRUCT |
||||||
|
#define __PACKED_STRUCT @packed struct |
||||||
|
#endif |
||||||
|
#ifndef __PACKED_UNION |
||||||
|
#define __PACKED_UNION @packed union |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32 /* deprecated */ |
||||||
|
@packed struct T_UINT32 { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_WRITE |
||||||
|
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT16_READ |
||||||
|
__PACKED_STRUCT T_UINT16_READ { uint16_t v; }; |
||||||
|
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_WRITE |
||||||
|
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) |
||||||
|
#endif |
||||||
|
#ifndef __UNALIGNED_UINT32_READ |
||||||
|
__PACKED_STRUCT T_UINT32_READ { uint32_t v; }; |
||||||
|
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) |
||||||
|
#endif |
||||||
|
#ifndef __ALIGNED |
||||||
|
#warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. |
||||||
|
#define __ALIGNED(x) |
||||||
|
#endif |
||||||
|
#ifndef __RESTRICT |
||||||
|
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. |
||||||
|
#define __RESTRICT |
||||||
|
#endif |
||||||
|
#ifndef __COMPILER_BARRIER |
||||||
|
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. |
||||||
|
#define __COMPILER_BARRIER() (void)0 |
||||||
|
#endif |
||||||
|
|
||||||
|
|
||||||
|
#else |
||||||
|
#error Unknown compiler. |
||||||
|
#endif |
||||||
|
|
||||||
|
|
||||||
|
#endif /* __CMSIS_COMPILER_H */ |
||||||
|
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,40 @@ |
|||||||
|
/**************************************************************************//**
|
||||||
|
* @file cmsis_version.h |
||||||
|
* @brief CMSIS Core(M) Version definitions |
||||||
|
* @version V5.0.3 |
||||||
|
* @date 24. June 2019 |
||||||
|
******************************************************************************/ |
||||||
|
/*
|
||||||
|
* Copyright (c) 2009-2019 ARM Limited. All rights reserved. |
||||||
|
* |
||||||
|
* SPDX-License-Identifier: Apache-2.0 |
||||||
|
* |
||||||
|
* Licensed under the Apache License, Version 2.0 (the License); you may |
||||||
|
* not use this file except in compliance with the License. |
||||||
|
* You may obtain a copy of the License at |
||||||
|
* |
||||||
|
* www.apache.org/licenses/LICENSE-2.0 |
||||||
|
* |
||||||
|
* Unless required by applicable law or agreed to in writing, software |
||||||
|
* distributed under the License is distributed on an AS IS BASIS, WITHOUT |
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
||||||
|
* See the License for the specific language governing permissions and |
||||||
|
* limitations under the License. |
||||||
|
*/ |
||||||
|
|
||||||
|
#if defined ( __ICCARM__ ) |
||||||
|
#pragma system_include /* treat file as system include file for MISRA check */ |
||||||
|
#elif defined (__clang__) |
||||||
|
#pragma clang system_header /* treat file as system include file */ |
||||||
|
#endif |
||||||
|
|
||||||
|
#ifndef __CMSIS_VERSION_H |
||||||
|
#define __CMSIS_VERSION_H |
||||||
|
|
||||||
|
/* CMSIS Version definitions */ |
||||||
|
#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ |
||||||
|
#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */ |
||||||
|
#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ |
||||||
|
__CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ |
||||||
|
#endif |
||||||
|
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,273 @@ |
|||||||
|
/******************************************************************************
|
||||||
|
* @file mpu_armv7.h |
||||||
|
* @brief CMSIS MPU API for Armv7-M MPU |
||||||
|
* @version V5.1.0 |
||||||
|
* @date 08. March 2019 |
||||||
|
******************************************************************************/ |
||||||
|
/*
|
||||||
|
* Copyright (c) 2017-2019 Arm Limited. All rights reserved. |
||||||
|
* |
||||||
|
* SPDX-License-Identifier: Apache-2.0 |
||||||
|
* |
||||||
|
* Licensed under the Apache License, Version 2.0 (the License); you may |
||||||
|
* not use this file except in compliance with the License. |
||||||
|
* You may obtain a copy of the License at |
||||||
|
* |
||||||
|
* www.apache.org/licenses/LICENSE-2.0 |
||||||
|
* |
||||||
|
* Unless required by applicable law or agreed to in writing, software |
||||||
|
* distributed under the License is distributed on an AS IS BASIS, WITHOUT |
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
||||||
|
* See the License for the specific language governing permissions and |
||||||
|
* limitations under the License. |
||||||
|
*/ |
||||||
|
|
||||||
|
#if defined ( __ICCARM__ ) |
||||||
|
#pragma system_include /* treat file as system include file for MISRA check */ |
||||||
|
#elif defined (__clang__) |
||||||
|
#pragma clang system_header /* treat file as system include file */ |
||||||
|
#endif |
||||||
|
|
||||||
|
#ifndef ARM_MPU_ARMV7_H |
||||||
|
#define ARM_MPU_ARMV7_H |
||||||
|
|
||||||
|
#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte
|
||||||
|
#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte
|
||||||
|
#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte
|
||||||
|
#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes
|
||||||
|
#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes
|
||||||
|
|
||||||
|
#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access
|
||||||
|
#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only
|
||||||
|
#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only
|
||||||
|
#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access
|
||||||
|
#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only
|
||||||
|
#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access
|
||||||
|
|
||||||
|
/** MPU Region Base Address Register Value
|
||||||
|
* |
||||||
|
* \param Region The region to be configured, number 0 to 15. |
||||||
|
* \param BaseAddress The base address for the region. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_RBAR(Region, BaseAddress) \ |
||||||
|
(((BaseAddress) & MPU_RBAR_ADDR_Msk) | \
|
||||||
|
((Region) & MPU_RBAR_REGION_Msk) | \
|
||||||
|
(MPU_RBAR_VALID_Msk)) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attributes |
||||||
|
*
|
||||||
|
* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. |
||||||
|
* \param IsShareable Region is shareable between multiple bus masters. |
||||||
|
* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. |
||||||
|
* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. |
||||||
|
*/
|
||||||
|
#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ |
||||||
|
((((TypeExtField) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \
|
||||||
|
(((IsShareable) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \
|
||||||
|
(((IsCacheable) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \
|
||||||
|
(((IsBufferable) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Region Attribute and Size Register Value |
||||||
|
*
|
||||||
|
* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. |
||||||
|
* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. |
||||||
|
* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. |
||||||
|
* \param SubRegionDisable Sub-region disable field. |
||||||
|
* \param Size Region size of the region to be configured, for example 4K, 8K. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ |
||||||
|
((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \
|
||||||
|
(((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \
|
||||||
|
(((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) | \
|
||||||
|
(((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \
|
||||||
|
(((Size) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \
|
||||||
|
(((MPU_RASR_ENABLE_Msk)))) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Region Attribute and Size Register Value |
||||||
|
*
|
||||||
|
* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. |
||||||
|
* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. |
||||||
|
* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. |
||||||
|
* \param IsShareable Region is shareable between multiple bus masters. |
||||||
|
* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. |
||||||
|
* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. |
||||||
|
* \param SubRegionDisable Sub-region disable field. |
||||||
|
* \param Size Region size of the region to be configured, for example 4K, 8K. |
||||||
|
*/
|
||||||
|
#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ |
||||||
|
ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute for strongly ordered memory. |
||||||
|
* - TEX: 000b |
||||||
|
* - Shareable |
||||||
|
* - Non-cacheable |
||||||
|
* - Non-bufferable |
||||||
|
*/
|
||||||
|
#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute for device memory. |
||||||
|
* - TEX: 000b (if shareable) or 010b (if non-shareable) |
||||||
|
* - Shareable or non-shareable |
||||||
|
* - Non-cacheable |
||||||
|
* - Bufferable (if shareable) or non-bufferable (if non-shareable) |
||||||
|
* |
||||||
|
* \param IsShareable Configures the device memory as shareable or non-shareable. |
||||||
|
*/
|
||||||
|
#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute for normal memory. |
||||||
|
* - TEX: 1BBb (reflecting outer cacheability rules) |
||||||
|
* - Shareable or non-shareable |
||||||
|
* - Cacheable or non-cacheable (reflecting inner cacheability rules) |
||||||
|
* - Bufferable or non-bufferable (reflecting inner cacheability rules) |
||||||
|
* |
||||||
|
* \param OuterCp Configures the outer cache policy. |
||||||
|
* \param InnerCp Configures the inner cache policy. |
||||||
|
* \param IsShareable Configures the memory as shareable or non-shareable. |
||||||
|
*/
|
||||||
|
#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute non-cacheable policy. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_CACHEP_NOCACHE 0U |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute write-back, write and read allocate policy. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_CACHEP_WB_WRA 1U |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute write-through, no write allocate policy. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_CACHEP_WT_NWA 2U |
||||||
|
|
||||||
|
/**
|
||||||
|
* MPU Memory Access Attribute write-back, no write allocate policy. |
||||||
|
*/ |
||||||
|
#define ARM_MPU_CACHEP_WB_NWA 3U |
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Struct for a single MPU Region |
||||||
|
*/ |
||||||
|
typedef struct { |
||||||
|
uint32_t RBAR; //!< The region base address register value (RBAR)
|
||||||
|
uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR
|
||||||
|
} ARM_MPU_Region_t; |
||||||
|
|
||||||
|
/** Enable the MPU.
|
||||||
|
* \param MPU_Control Default access permissions for unconfigured regions. |
||||||
|
*/ |
||||||
|
__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) |
||||||
|
{ |
||||||
|
MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; |
||||||
|
#ifdef SCB_SHCSR_MEMFAULTENA_Msk |
||||||
|
SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; |
||||||
|
#endif |
||||||
|
__DSB(); |
||||||
|
__ISB(); |
||||||
|
} |
||||||
|
|
||||||
|
/** Disable the MPU.
|
||||||
|
*/ |
||||||
|
__STATIC_INLINE void ARM_MPU_Disable(void) |
||||||
|
{ |
||||||
|
__DMB(); |
||||||
|
#ifdef SCB_SHCSR_MEMFAULTENA_Msk |
||||||
|
SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; |
||||||
|
#endif |
||||||
|
MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; |
||||||
|
} |
||||||
|
|
||||||
|
/** Clear and disable the given MPU region.
|
||||||
|
* \param rnr Region number to be cleared. |
||||||
|
*/ |
||||||
|
__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) |
||||||
|
{ |
||||||
|
MPU->RNR = rnr; |
||||||
|
MPU->RASR = 0U; |
||||||
|
} |
||||||
|
|
||||||
|
/** Configure an MPU region.
|
||||||
|
* \param rbar Value for RBAR register. |
||||||
|
* \param rsar Value for RSAR register. |
||||||
|
*/
|
||||||
|
__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) |
||||||
|
{ |
||||||
|
MPU->RBAR = rbar; |
||||||
|
MPU->RASR = rasr; |
||||||
|
} |
||||||
|
|
||||||
|
/** Configure the given MPU region.
|
||||||
|
* \param rnr Region number to be configured. |
||||||
|
* \param rbar Value for RBAR register. |
||||||
|
* \param rsar Value for RSAR register. |
||||||
|
*/
|
||||||
|
__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) |
||||||
|
{ |
||||||
|
MPU->RNR = rnr; |
||||||
|
MPU->RBAR = rbar; |
||||||
|
MPU->RASR = rasr; |
||||||
|
} |
||||||
|
|
||||||
|
/** Memcopy with strictly ordered memory access, e.g. for register targets.
|
||||||
|
* \param dst Destination data is copied to. |
||||||
|
* \param src Source data is copied from. |
||||||
|
* \param len Amount of data words to be copied. |
||||||
|
*/ |
||||||
|
__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) |
||||||
|
{ |
||||||
|
uint32_t i; |
||||||
|
for (i = 0U; i < len; ++i)
|
||||||
|
{ |
||||||
|
dst[i] = src[i]; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
/** Load the given number of MPU regions from a table.
|
||||||
|
* \param table Pointer to the MPU configuration table. |
||||||
|
* \param cnt Amount of regions to be configured. |
||||||
|
*/ |
||||||
|
__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt)
|
||||||
|
{ |
||||||
|
const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; |
||||||
|
while (cnt > MPU_TYPE_RALIASES) { |
||||||
|
ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); |
||||||
|
table += MPU_TYPE_RALIASES; |
||||||
|
cnt -= MPU_TYPE_RALIASES; |
||||||
|
} |
||||||
|
ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); |
||||||
|
} |
||||||
|
|
||||||
|
#endif |
||||||
|
|
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,209 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file stm32f2xx.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V2.1.2 |
||||||
|
* @date 29-June-2016 |
||||||
|
* @brief CMSIS STM32F2xx 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 STM32F2xx 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) 2016 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 stm32f2xx
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifndef __STM32F2xx_H |
||||||
|
#define __STM32F2xx_H |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif /* __cplusplus */ |
||||||
|
|
||||||
|
/** @addtogroup Library_configuration_section
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief STM32 Family |
||||||
|
*/ |
||||||
|
#if !defined (STM32F2) |
||||||
|
#define STM32F2 |
||||||
|
#endif /* STM32F2 */ |
||||||
|
|
||||||
|
/* Uncomment the line below according to the target STM32 device used in your
|
||||||
|
application |
||||||
|
*/ |
||||||
|
#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) |
||||||
|
|
||||||
|
/* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF,
|
||||||
|
STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC, |
||||||
|
STM32F205RB and STM32F205VB Devices */ |
||||||
|
/* #define STM32F215xx */ /*!< STM32F215RG, STM32F215VG, STM32F215ZG, STM32F215RE, STM32F215VE and STM32F215ZE Devices */ |
||||||
|
/* #define STM32F207xx */ /*!< STM32F207VG, STM32F207ZG, STM32F207IG, STM32F207VF, STM32F207ZF, STM32F207IF,
|
||||||
|
STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */ |
||||||
|
/* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE 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.1.2 |
||||||
|
*/ |
||||||
|
#define __STM32F2xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ |
||||||
|
#define __STM32F2xx_CMSIS_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */ |
||||||
|
#define __STM32F2xx_CMSIS_VERSION_SUB2 (0x02U) /*!< [15:8] sub2 version */ |
||||||
|
#define __STM32F2xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ |
||||||
|
#define __STM32F2xx_CMSIS_VERSION ((__STM32F2xx_CMSIS_VERSION_MAIN << 24)\ |
||||||
|
|(__STM32F2xx_CMSIS_VERSION_SUB1 << 16)\
|
||||||
|
|(__STM32F2xx_CMSIS_VERSION_SUB2 << 8 )\
|
||||||
|
|(__STM32F2xx_CMSIS_VERSION)) |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup Device_Included
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
#if defined(STM32F205xx) |
||||||
|
#include "stm32f205xx.h" |
||||||
|
#elif defined(STM32F215xx) |
||||||
|
#include "stm32f215xx.h" |
||||||
|
#elif defined(STM32F207xx) |
||||||
|
#include "stm32f207xx.h" |
||||||
|
#elif defined(STM32F217xx) |
||||||
|
#include "stm32f217xx.h" |
||||||
|
#else |
||||||
|
#error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.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 "stm32f2xx_hal.h" |
||||||
|
#endif /* USE_HAL_DRIVER */ |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif /* __cplusplus */ |
||||||
|
|
||||||
|
#endif /* __STM32F2xx_H */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,181 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file stm32f2xx_hal_def.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V1.1.3 |
||||||
|
* @date 29-June-2016 |
||||||
|
* @brief This file contains HAL common defines, enumeration, macros and |
||||||
|
* structures definitions. |
||||||
|
****************************************************************************** |
||||||
|
* @attention |
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 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. |
||||||
|
* |
||||||
|
****************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/ |
||||||
|
#ifndef __STM32F2xx_HAL_DEF |
||||||
|
#define __STM32F2xx_HAL_DEF |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/ |
||||||
|
#include "stm32f2xx.h" |
||||||
|
//#include "Legacy/stm32_hal_legacy.h"
|
||||||
|
//#include <stdio.h>
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief HAL Status structures definition |
||||||
|
*/ |
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
HAL_OK = 0x00U, |
||||||
|
HAL_ERROR = 0x01U, |
||||||
|
HAL_BUSY = 0x02U, |
||||||
|
HAL_TIMEOUT = 0x03U |
||||||
|
} HAL_StatusTypeDef; |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief HAL Lock structures definition |
||||||
|
*/ |
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
HAL_UNLOCKED = 0x00U, |
||||||
|
HAL_LOCKED = 0x01U |
||||||
|
} HAL_LockTypeDef; |
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/ |
||||||
|
#define HAL_MAX_DELAY 0xFFFFFFFFU |
||||||
|
|
||||||
|
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) |
||||||
|
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) |
||||||
|
|
||||||
|
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD_, __DMA_HANDLE_) \ |
||||||
|
do{ \
|
||||||
|
(__HANDLE__)->__PPP_DMA_FIELD_ = &(__DMA_HANDLE_); \
|
||||||
|
(__DMA_HANDLE_).Parent = (__HANDLE__); \
|
||||||
|
} while(0) |
||||||
|
|
||||||
|
#define UNUSED(x) ((void)(x)) |
||||||
|
|
||||||
|
/** @brief Reset the Handle's State field.
|
||||||
|
* @param __HANDLE__: specifies the Peripheral Handle. |
||||||
|
* @note This macro can be used for the following purpose: |
||||||
|
* - When the Handle is declared as local variable; before passing it as parameter |
||||||
|
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro |
||||||
|
* to set to 0 the Handle's "State" field. |
||||||
|
* Otherwise, "State" field may have any random value and the first time the function |
||||||
|
* HAL_PPP_Init() is called, the low level hardware initialization will be missed |
||||||
|
* (i.e. HAL_PPP_MspInit() will not be executed). |
||||||
|
* - When there is a need to reconfigure the low level hardware: instead of calling |
||||||
|
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). |
||||||
|
* In this later function, when the Handle's "State" field is set to 0, it will execute the function |
||||||
|
* HAL_PPP_MspInit() which will reconfigure the low level hardware. |
||||||
|
* @retval None |
||||||
|
*/ |
||||||
|
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) |
||||||
|
|
||||||
|
#if (USE_RTOS == 1) |
||||||
|
/* Reserved for future use */ |
||||||
|
#error " USE_RTOS should be 0 in the current HAL release " |
||||||
|
#else |
||||||
|
#define __HAL_LOCK(__HANDLE__) \ |
||||||
|
do{ \
|
||||||
|
if((__HANDLE__)->Lock == HAL_LOCKED) \
|
||||||
|
{ \
|
||||||
|
return HAL_BUSY; \
|
||||||
|
} \
|
||||||
|
else \
|
||||||
|
{ \
|
||||||
|
(__HANDLE__)->Lock = HAL_LOCKED; \
|
||||||
|
} \
|
||||||
|
}while (0) |
||||||
|
|
||||||
|
#define __HAL_UNLOCK(__HANDLE__) \ |
||||||
|
do{ \
|
||||||
|
(__HANDLE__)->Lock = HAL_UNLOCKED; \
|
||||||
|
}while (0) |
||||||
|
#endif /* USE_RTOS */ |
||||||
|
|
||||||
|
#if defined ( __GNUC__ ) |
||||||
|
#ifndef __weak |
||||||
|
#define __weak __attribute__((weak)) |
||||||
|
#endif /* __weak */ |
||||||
|
#ifndef __packed |
||||||
|
#define __packed __attribute__((__packed__)) |
||||||
|
#endif /* __packed */ |
||||||
|
#endif /* __GNUC__ */ |
||||||
|
|
||||||
|
|
||||||
|
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ |
||||||
|
#if defined (__GNUC__) /* GNU Compiler */ |
||||||
|
#ifndef __ALIGN_END |
||||||
|
#define __ALIGN_END __attribute__ ((aligned (4))) |
||||||
|
#endif /* __ALIGN_END */ |
||||||
|
#ifndef __ALIGN_BEGIN |
||||||
|
#define __ALIGN_BEGIN |
||||||
|
#endif /* __ALIGN_BEGIN */ |
||||||
|
#else |
||||||
|
#ifndef __ALIGN_END |
||||||
|
#define __ALIGN_END |
||||||
|
#endif /* __ALIGN_END */ |
||||||
|
#ifndef __ALIGN_BEGIN |
||||||
|
#if defined (__CC_ARM) /* ARM Compiler */ |
||||||
|
#define __ALIGN_BEGIN __align(4) |
||||||
|
#elif defined (__ICCARM__) /* IAR Compiler */ |
||||||
|
#define __ALIGN_BEGIN |
||||||
|
#endif /* __CC_ARM */ |
||||||
|
#endif /* __ALIGN_BEGIN */ |
||||||
|
#endif /* __GNUC__ */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief __NOINLINE definition |
||||||
|
*/ |
||||||
|
#if defined ( __CC_ARM ) || defined ( __GNUC__ ) |
||||||
|
/* ARM & GNUCompiler
|
||||||
|
---------------- |
||||||
|
*/ |
||||||
|
#define __NOINLINE __attribute__ ( (noinline) ) |
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) |
||||||
|
/* ICCARM Compiler
|
||||||
|
--------------- |
||||||
|
*/ |
||||||
|
#define __NOINLINE _Pragma("optimize = no_inline") |
||||||
|
|
||||||
|
#endif |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#endif /* ___STM32F2xx_HAL_DEF */ |
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,299 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file stm32f2xx_hal_gpio_ex.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V1.1.3 |
||||||
|
* @date 29-June-2016 |
||||||
|
* @brief Header file of GPIO HAL Extension module. |
||||||
|
****************************************************************************** |
||||||
|
* @attention |
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 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. |
||||||
|
* |
||||||
|
****************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/ |
||||||
|
#ifndef __STM32F2xx_HAL_GPIO_EX_H |
||||||
|
#define __STM32F2xx_HAL_GPIO_EX_H |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/ |
||||||
|
#include "stm32f2xx_hal_def.h" |
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_HAL_Driver
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @defgroup GPIOEx GPIOEx
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/ |
||||||
|
/* Exported constants --------------------------------------------------------*/ |
||||||
|
/* Exported constants --------------------------------------------------------*/ |
||||||
|
|
||||||
|
/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 0 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ |
||||||
|
#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ |
||||||
|
#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ |
||||||
|
#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ |
||||||
|
#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 1 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ |
||||||
|
#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 2 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ |
||||||
|
#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ |
||||||
|
#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 3 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ |
||||||
|
#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ |
||||||
|
#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ |
||||||
|
#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 4 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ |
||||||
|
#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ |
||||||
|
#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 5 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ |
||||||
|
#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ |
||||||
|
/**
|
||||||
|
* @brief AF 6 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 7 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ |
||||||
|
#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ |
||||||
|
#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 8 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ |
||||||
|
#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ |
||||||
|
#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 9 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ |
||||||
|
#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ |
||||||
|
#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ |
||||||
|
#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ |
||||||
|
#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 10 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF10_OTG_FS ((uint8_t)0xAU) /* OTG_FS Alternate Function mapping */ |
||||||
|
#define GPIO_AF10_OTG_HS ((uint8_t)0xAU) /* OTG_HS Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 11 selection |
||||||
|
*/ |
||||||
|
#if defined(STM32F207xx) || defined(STM32F217xx) |
||||||
|
#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ |
||||||
|
#endif /* STM32F207xx || STM32F217xx */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 12 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF12_FSMC ((uint8_t)0xCU) /* FSMC Alternate Function mapping */ |
||||||
|
#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xCU) /* OTG HS configured in FS, Alternate Function mapping */ |
||||||
|
#define GPIO_AF12_SDIO ((uint8_t)0xCU) /* SDIO Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 13 selection |
||||||
|
*/ |
||||||
|
#if defined(STM32F207xx) || defined(STM32F217xx) |
||||||
|
#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ |
||||||
|
#endif /* STM32F207xx || STM32F217xx */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief AF 15 selection |
||||||
|
*/ |
||||||
|
#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/ |
||||||
|
/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Exported functions --------------------------------------------------------*/ |
||||||
|
/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Private types -------------------------------------------------------------*/ |
||||||
|
/* Private variables ---------------------------------------------------------*/ |
||||||
|
/* Private constants ---------------------------------------------------------*/ |
||||||
|
/** @defgroup GPIOEx_Private_Constants GPIO Private Constants
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Private macros ------------------------------------------------------------*/ |
||||||
|
/** @defgroup GPIOEx_Private_Macros GPIO Private Macros
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ |
||||||
|
((__GPIOx__) == (GPIOB))? 1U :\
|
||||||
|
((__GPIOx__) == (GPIOC))? 2U :\
|
||||||
|
((__GPIOx__) == (GPIOD))? 3U :\
|
||||||
|
((__GPIOx__) == (GPIOE))? 4U :\
|
||||||
|
((__GPIOx__) == (GPIOF))? 5U :\
|
||||||
|
((__GPIOx__) == (GPIOG))? 6U :\
|
||||||
|
((__GPIOx__) == (GPIOH))? 7U :\
|
||||||
|
((__GPIOx__) == (GPIOI))? 8U : 9U) |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
#if defined(STM32F207xx) || defined(STM32F217xx) |
||||||
|
|
||||||
|
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ |
||||||
|
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \
|
||||||
|
((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \
|
||||||
|
((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \
|
||||||
|
((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \
|
||||||
|
((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \
|
||||||
|
((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \
|
||||||
|
((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \
|
||||||
|
((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \
|
||||||
|
((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \
|
||||||
|
((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \
|
||||||
|
((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \
|
||||||
|
((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \
|
||||||
|
((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \
|
||||||
|
((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \
|
||||||
|
((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \
|
||||||
|
((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \
|
||||||
|
((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) |
||||||
|
#else /* STM32F207xx || STM32F217xx */ |
||||||
|
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ |
||||||
|
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \
|
||||||
|
((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \
|
||||||
|
((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \
|
||||||
|
((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \
|
||||||
|
((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \
|
||||||
|
((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \
|
||||||
|
((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \
|
||||||
|
((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \
|
||||||
|
((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \
|
||||||
|
((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \
|
||||||
|
((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \
|
||||||
|
((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \
|
||||||
|
((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \
|
||||||
|
((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \
|
||||||
|
((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \
|
||||||
|
((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) |
||||||
|
#endif /* STM32F207xx || STM32F217xx */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Private functions ---------------------------------------------------------*/ |
||||||
|
/** @defgroup GPIOEx_Private_Functions GPIO Private Functions
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#endif /* __STM32F2xx_HAL_GPIO_EX_H */ |
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,271 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file stm32f4xx.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V2.6.0 |
||||||
|
* @date 04-November-2016 |
||||||
|
* @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) 2016 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 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 (STM32F410Tx) && !defined (STM32F410Cx) && \
|
||||||
|
!defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \
|
||||||
|
!defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \
|
||||||
|
!defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx) |
||||||
|
/* #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 STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */ |
||||||
|
/* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */ |
||||||
|
/* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */ |
||||||
|
/* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ |
||||||
|
/* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC,
|
||||||
|
and STM32F446ZE Devices */ |
||||||
|
/* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG,
|
||||||
|
STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */ |
||||||
|
/* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG
|
||||||
|
and STM32F479NG Devices */ |
||||||
|
/* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */ |
||||||
|
/* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */ |
||||||
|
/* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */ |
||||||
|
/* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */ |
||||||
|
/* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG,
|
||||||
|
STM32F413RG, STM32F413VG and STM32F413ZG Devices */ |
||||||
|
/* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH 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 version number V2.6.0 |
||||||
|
*/ |
||||||
|
#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ |
||||||
|
#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */ |
||||||
|
#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x00U) /*!< [15:8] sub2 version */ |
||||||
|
#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ |
||||||
|
#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\ |
||||||
|
|(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\
|
||||||
|
|(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\
|
||||||
|
|(__STM32F4xx_CMSIS_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(STM32F410Tx) |
||||||
|
#include "stm32f410tx.h" |
||||||
|
#elif defined(STM32F410Cx) |
||||||
|
#include "stm32f410cx.h" |
||||||
|
#elif defined(STM32F410Rx) |
||||||
|
#include "stm32f410rx.h" |
||||||
|
#elif defined(STM32F411xE) |
||||||
|
#include "stm32f411xe.h" |
||||||
|
#elif defined(STM32F446xx) |
||||||
|
#include "stm32f446xx.h" |
||||||
|
#elif defined(STM32F469xx) |
||||||
|
#include "stm32f469xx.h" |
||||||
|
#elif defined(STM32F479xx) |
||||||
|
#include "stm32f479xx.h" |
||||||
|
#elif defined(STM32F412Cx) |
||||||
|
#include "stm32f412cx.h" |
||||||
|
#elif defined(STM32F412Zx) |
||||||
|
#include "stm32f412zx.h" |
||||||
|
#elif defined(STM32F412Rx) |
||||||
|
#include "stm32f412rx.h" |
||||||
|
#elif defined(STM32F412Vx) |
||||||
|
#include "stm32f412vx.h" |
||||||
|
#elif defined(STM32F413xx) |
||||||
|
#include "stm32f413xx.h" |
||||||
|
#elif defined(STM32F423xx) |
||||||
|
#include "stm32f423xx.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 = 0U, |
||||||
|
SET = !RESET |
||||||
|
} FlagStatus, ITStatus; |
||||||
|
|
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
DISABLE = 0U, |
||||||
|
ENABLE = !DISABLE |
||||||
|
} FunctionalState; |
||||||
|
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) |
||||||
|
|
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
ERROR = 0U, |
||||||
|
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****/ |
@ -0,0 +1,214 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file stm32f4xx_hal_def.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V1.6.0 |
||||||
|
* @date 04-November-2016 |
||||||
|
* @brief This file contains HAL common defines, enumeration, macros and |
||||||
|
* structures definitions. |
||||||
|
****************************************************************************** |
||||||
|
* @attention |
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 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. |
||||||
|
* |
||||||
|
****************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/ |
||||||
|
#ifndef __STM32F4xx_HAL_DEF |
||||||
|
#define __STM32F4xx_HAL_DEF |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/ |
||||||
|
#include "stm32f4xx.h" |
||||||
|
//#include "Legacy/stm32_hal_legacy.h"
|
||||||
|
//#include <stdio.h>
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief HAL Status structures definition |
||||||
|
*/ |
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
HAL_OK = 0x00U, |
||||||
|
HAL_ERROR = 0x01U, |
||||||
|
HAL_BUSY = 0x02U, |
||||||
|
HAL_TIMEOUT = 0x03U |
||||||
|
} HAL_StatusTypeDef; |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief HAL Lock structures definition |
||||||
|
*/ |
||||||
|
typedef enum |
||||||
|
{ |
||||||
|
HAL_UNLOCKED = 0x00U, |
||||||
|
HAL_LOCKED = 0x01U |
||||||
|
} HAL_LockTypeDef; |
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/ |
||||||
|
#define HAL_MAX_DELAY 0xFFFFFFFFU |
||||||
|
|
||||||
|
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) |
||||||
|
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) |
||||||
|
|
||||||
|
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ |
||||||
|
do{ \
|
||||||
|
(__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
|
||||||
|
(__DMA_HANDLE__).Parent = (__HANDLE__); \
|
||||||
|
} while(0) |
||||||
|
|
||||||
|
#define UNUSED(x) ((void)(x)) |
||||||
|
|
||||||
|
/** @brief Reset the Handle's State field.
|
||||||
|
* @param __HANDLE__: specifies the Peripheral Handle. |
||||||
|
* @note This macro can be used for the following purpose: |
||||||
|
* - When the Handle is declared as local variable; before passing it as parameter |
||||||
|
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro |
||||||
|
* to set to 0 the Handle's "State" field. |
||||||
|
* Otherwise, "State" field may have any random value and the first time the function |
||||||
|
* HAL_PPP_Init() is called, the low level hardware initialization will be missed |
||||||
|
* (i.e. HAL_PPP_MspInit() will not be executed). |
||||||
|
* - When there is a need to reconfigure the low level hardware: instead of calling |
||||||
|
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). |
||||||
|
* In this later function, when the Handle's "State" field is set to 0, it will execute the function |
||||||
|
* HAL_PPP_MspInit() which will reconfigure the low level hardware. |
||||||
|
* @retval None |
||||||
|
*/ |
||||||
|
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) |
||||||
|
|
||||||
|
#if (USE_RTOS == 1) |
||||||
|
/* Reserved for future use */ |
||||||
|
#error "USE_RTOS should be 0 in the current HAL release" |
||||||
|
#else |
||||||
|
#define __HAL_LOCK(__HANDLE__) \ |
||||||
|
do{ \
|
||||||
|
if((__HANDLE__)->Lock == HAL_LOCKED) \
|
||||||
|
{ \
|
||||||
|
return HAL_BUSY; \
|
||||||
|
} \
|
||||||
|
else \
|
||||||
|
{ \
|
||||||
|
(__HANDLE__)->Lock = HAL_LOCKED; \
|
||||||
|
} \
|
||||||
|
}while (0) |
||||||
|
|
||||||
|
#define __HAL_UNLOCK(__HANDLE__) \ |
||||||
|
do{ \
|
||||||
|
(__HANDLE__)->Lock = HAL_UNLOCKED; \
|
||||||
|
}while (0) |
||||||
|
#endif /* USE_RTOS */ |
||||||
|
|
||||||
|
#if defined ( __GNUC__ ) |
||||||
|
#ifndef __weak |
||||||
|
#define __weak __attribute__((weak)) |
||||||
|
#endif /* __weak */ |
||||||
|
#ifndef __packed |
||||||
|
#define __packed __attribute__((__packed__)) |
||||||
|
#endif /* __packed */ |
||||||
|
#endif /* __GNUC__ */ |
||||||
|
|
||||||
|
|
||||||
|
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ |
||||||
|
#if defined (__GNUC__) /* GNU Compiler */ |
||||||
|
#ifndef __ALIGN_END |
||||||
|
#define __ALIGN_END __attribute__ ((aligned (4))) |
||||||
|
#endif /* __ALIGN_END */ |
||||||
|
#ifndef __ALIGN_BEGIN |
||||||
|
#define __ALIGN_BEGIN |
||||||
|
#endif /* __ALIGN_BEGIN */ |
||||||
|
#else |
||||||
|
#ifndef __ALIGN_END |
||||||
|
#define __ALIGN_END |
||||||
|
#endif /* __ALIGN_END */ |
||||||
|
#ifndef __ALIGN_BEGIN |
||||||
|
#if defined (__CC_ARM) /* ARM Compiler */ |
||||||
|
#define __ALIGN_BEGIN __align(4) |
||||||
|
#elif defined (__ICCARM__) /* IAR Compiler */ |
||||||
|
#define __ALIGN_BEGIN |
||||||
|
#endif /* __CC_ARM */ |
||||||
|
#endif /* __ALIGN_BEGIN */ |
||||||
|
#endif /* __GNUC__ */ |
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief __RAM_FUNC definition |
||||||
|
*/ |
||||||
|
#if defined ( __CC_ARM ) |
||||||
|
/* ARM Compiler
|
||||||
|
------------ |
||||||
|
RAM functions are defined using the toolchain options. |
||||||
|
Functions that are executed in RAM should reside in a separate source module. |
||||||
|
Using the 'Options for File' dialog you can simply change the 'Code / Const' |
||||||
|
area of a module to a memory space in physical RAM. |
||||||
|
Available memory areas are declared in the 'Target' tab of the 'Options for Target' |
||||||
|
dialog. |
||||||
|
*/ |
||||||
|
#define __RAM_FUNC HAL_StatusTypeDef |
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) |
||||||
|
/* ICCARM Compiler
|
||||||
|
--------------- |
||||||
|
RAM functions are defined using a specific toolchain keyword "__ramfunc". |
||||||
|
*/ |
||||||
|
#define __RAM_FUNC __ramfunc HAL_StatusTypeDef |
||||||
|
|
||||||
|
#elif defined ( __GNUC__ ) |
||||||
|
/* GNU Compiler
|
||||||
|
------------ |
||||||
|
RAM functions are defined using a specific toolchain attribute |
||||||
|
"__attribute__((section(".RamFunc")))". |
||||||
|
*/ |
||||||
|
#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc"))) |
||||||
|
|
||||||
|
#endif |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief __NOINLINE definition |
||||||
|
*/ |
||||||
|
#if defined ( __CC_ARM ) || defined ( __GNUC__ ) |
||||||
|
/* ARM & GNUCompiler
|
||||||
|
---------------- |
||||||
|
*/ |
||||||
|
#define __NOINLINE __attribute__ ( (noinline) ) |
||||||
|
|
||||||
|
#elif defined ( __ICCARM__ ) |
||||||
|
/* ICCARM Compiler
|
||||||
|
--------------- |
||||||
|
*/ |
||||||
|
#define __NOINLINE _Pragma("optimize = no_inline") |
||||||
|
|
||||||
|
#endif |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#endif /* ___STM32F4xx_HAL_DEF */ |
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,122 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file system_stm32f2xx.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V2.1.2 |
||||||
|
* @date 29-June-2016 |
||||||
|
* @brief CMSIS Cortex-M3 Device System Source File for STM32F2xx devices. |
||||||
|
****************************************************************************** |
||||||
|
* @attention |
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 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 stm32f2xx_system
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Define to prevent recursive inclusion |
||||||
|
*/ |
||||||
|
#ifndef __SYSTEM_STM32F2XX_H |
||||||
|
#define __SYSTEM_STM32F2XX_H |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_System_Includes
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_System_Exported_types
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/* This variable is updated in three ways:
|
||||||
|
1) by calling CMSIS function SystemCoreClockUpdate() |
||||||
|
2) by calling HAL API function HAL_RCC_GetSysClockFreq() |
||||||
|
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency |
||||||
|
Note: If you use this function to configure the system clock; then there |
||||||
|
is no need to call the 2 first functions listed above, since SystemCoreClock |
||||||
|
variable is updated automatically. |
||||||
|
*/ |
||||||
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ |
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_System_Exported_Constants
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_System_Exported_Macros
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F2xx_System_Exported_Functions
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
extern void SystemInit(void); |
||||||
|
extern void SystemCoreClockUpdate(void); |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#endif /*__SYSTEM_STM32F2XX_H */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,124 @@ |
|||||||
|
/**
|
||||||
|
****************************************************************************** |
||||||
|
* @file system_stm32f4xx.h |
||||||
|
* @author MCD Application Team |
||||||
|
* @version V2.6.0 |
||||||
|
* @date 04-November-2016 |
||||||
|
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. |
||||||
|
****************************************************************************** |
||||||
|
* @attention |
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 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_system
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Define to prevent recursive inclusion |
||||||
|
*/ |
||||||
|
#ifndef __SYSTEM_STM32F4XX_H |
||||||
|
#define __SYSTEM_STM32F4XX_H |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
extern "C" { |
||||||
|
#endif |
||||||
|
|
||||||
|
/** @addtogroup STM32F4xx_System_Includes
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
|
||||||
|
/** @addtogroup STM32F4xx_System_Exported_types
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
/* This variable is updated in three ways:
|
||||||
|
1) by calling CMSIS function SystemCoreClockUpdate() |
||||||
|
2) by calling HAL API function HAL_RCC_GetSysClockFreq() |
||||||
|
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency |
||||||
|
Note: If you use this function to configure the system clock; then there |
||||||
|
is no need to call the 2 first functions listed above, since SystemCoreClock |
||||||
|
variable is updated automatically. |
||||||
|
*/ |
||||||
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ |
||||||
|
|
||||||
|
extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ |
||||||
|
extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F4xx_System_Exported_Constants
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F4xx_System_Exported_Macros
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/** @addtogroup STM32F4xx_System_Exported_Functions
|
||||||
|
* @{ |
||||||
|
*/ |
||||||
|
|
||||||
|
extern void SystemInit(void); |
||||||
|
extern void SystemCoreClockUpdate(void); |
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
#ifdef __cplusplus |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#endif /*__SYSTEM_STM32F4XX_H */ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
|
||||||
|
/**
|
||||||
|
* @} |
||||||
|
*/ |
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,42 @@ |
|||||||
|
// **** libc ****
|
||||||
|
|
||||||
|
void delay(int a) { |
||||||
|
volatile int i; |
||||||
|
for (i = 0; i < a; i++); |
||||||
|
} |
||||||
|
|
||||||
|
void *memset(void *str, int c, unsigned int n) { |
||||||
|
uint8_t *s = str; |
||||||
|
for (unsigned int i = 0; i < n; i++) { |
||||||
|
*s = c; |
||||||
|
s++; |
||||||
|
} |
||||||
|
return str; |
||||||
|
} |
||||||
|
|
||||||
|
void *memcpy(void *dest, const void *src, unsigned int n) { |
||||||
|
uint8_t *d = dest; |
||||||
|
const uint8_t *s = src; |
||||||
|
for (unsigned int i = 0; i < n; i++) { |
||||||
|
*d = *s; |
||||||
|
d++; |
||||||
|
s++; |
||||||
|
} |
||||||
|
return dest; |
||||||
|
} |
||||||
|
|
||||||
|
int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { |
||||||
|
int ret = 0; |
||||||
|
const uint8_t *p1 = ptr1; |
||||||
|
const uint8_t *p2 = ptr2; |
||||||
|
for (unsigned int i = 0; i < num; i++) { |
||||||
|
if (*p1 != *p2) { |
||||||
|
ret = -1; |
||||||
|
break; |
||||||
|
} |
||||||
|
p1++; |
||||||
|
p2++; |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
@ -0,0 +1,871 @@ |
|||||||
|
//#define EON
|
||||||
|
//#define PANDA
|
||||||
|
|
||||||
|
// ********************* Includes *********************
|
||||||
|
#include "config.h" |
||||||
|
#include "obj/gitversion.h" |
||||||
|
|
||||||
|
#include "main_declarations.h" |
||||||
|
#include "critical.h" |
||||||
|
|
||||||
|
#include "libc.h" |
||||||
|
#include "provision.h" |
||||||
|
#include "faults.h" |
||||||
|
|
||||||
|
#include "drivers/registers.h" |
||||||
|
#include "drivers/interrupts.h" |
||||||
|
|
||||||
|
#include "drivers/llcan.h" |
||||||
|
#include "drivers/llgpio.h" |
||||||
|
#include "drivers/adc.h" |
||||||
|
#include "drivers/pwm.h" |
||||||
|
|
||||||
|
#include "board.h" |
||||||
|
|
||||||
|
#include "drivers/uart.h" |
||||||
|
#include "drivers/usb.h" |
||||||
|
#include "drivers/gmlan_alt.h" |
||||||
|
#include "drivers/timer.h" |
||||||
|
#include "drivers/clock.h" |
||||||
|
|
||||||
|
#include "gpio.h" |
||||||
|
|
||||||
|
#ifndef EON |
||||||
|
#include "drivers/spi.h" |
||||||
|
#endif |
||||||
|
|
||||||
|
#include "power_saving.h" |
||||||
|
#include "safety.h" |
||||||
|
|
||||||
|
#include "drivers/can.h" |
||||||
|
|
||||||
|
extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used
|
||||||
|
|
||||||
|
struct __attribute__((packed)) health_t { |
||||||
|
uint32_t uptime_pkt; |
||||||
|
uint32_t voltage_pkt; |
||||||
|
uint32_t current_pkt; |
||||||
|
uint32_t can_rx_errs_pkt; |
||||||
|
uint32_t can_send_errs_pkt; |
||||||
|
uint32_t can_fwd_errs_pkt; |
||||||
|
uint32_t gmlan_send_errs_pkt; |
||||||
|
uint32_t faults_pkt; |
||||||
|
uint8_t ignition_line_pkt; |
||||||
|
uint8_t ignition_can_pkt; |
||||||
|
uint8_t controls_allowed_pkt; |
||||||
|
uint8_t gas_interceptor_detected_pkt; |
||||||
|
uint8_t car_harness_status_pkt; |
||||||
|
uint8_t usb_power_mode_pkt; |
||||||
|
uint8_t safety_mode_pkt; |
||||||
|
uint8_t fault_status_pkt; |
||||||
|
uint8_t power_save_enabled_pkt; |
||||||
|
}; |
||||||
|
|
||||||
|
|
||||||
|
// ********************* Serial debugging *********************
|
||||||
|
|
||||||
|
bool check_started(void) { |
||||||
|
return current_board->check_ignition() || ignition_can; |
||||||
|
} |
||||||
|
|
||||||
|
void debug_ring_callback(uart_ring *ring) { |
||||||
|
char rcv; |
||||||
|
while (getc(ring, &rcv)) { |
||||||
|
(void)putc(ring, rcv); // misra-c2012-17.7: cast to void is ok: debug function
|
||||||
|
|
||||||
|
// only allow bootloader entry on debug builds
|
||||||
|
#ifdef ALLOW_DEBUG |
||||||
|
// jump to DFU flash
|
||||||
|
if (rcv == 'z') { |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
// normal reset
|
||||||
|
if (rcv == 'x') { |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
|
||||||
|
// enable CDP mode
|
||||||
|
if (rcv == 'C') { |
||||||
|
puts("switching USB to CDP mode\n"); |
||||||
|
current_board->set_usb_power_mode(USB_POWER_CDP); |
||||||
|
} |
||||||
|
if (rcv == 'c') { |
||||||
|
puts("switching USB to client mode\n"); |
||||||
|
current_board->set_usb_power_mode(USB_POWER_CLIENT); |
||||||
|
} |
||||||
|
if (rcv == 'D') { |
||||||
|
puts("switching USB to DCP mode\n"); |
||||||
|
current_board->set_usb_power_mode(USB_POWER_DCP); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// ****************************** safety mode ******************************
|
||||||
|
|
||||||
|
// this is the only way to leave silent mode
|
||||||
|
void set_safety_mode(uint16_t mode, int16_t param) { |
||||||
|
uint16_t mode_copy = mode; |
||||||
|
int err = set_safety_hooks(mode_copy, param); |
||||||
|
if (err == -1) { |
||||||
|
puts("Error: safety set mode failed. Falling back to SILENT\n"); |
||||||
|
mode_copy = SAFETY_SILENT; |
||||||
|
err = set_safety_hooks(mode_copy, 0); |
||||||
|
if (err == -1) { |
||||||
|
puts("Error: Failed setting SILENT mode. Hanging\n"); |
||||||
|
while (true) { |
||||||
|
// TERMINAL ERROR: we can't continue if SILENT safety mode isn't succesfully set
|
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
switch (mode_copy) { |
||||||
|
case SAFETY_SILENT: |
||||||
|
set_intercept_relay(false); |
||||||
|
if (board_has_obd()) { |
||||||
|
current_board->set_can_mode(CAN_MODE_NORMAL); |
||||||
|
} |
||||||
|
can_silent = ALL_CAN_SILENT; |
||||||
|
break; |
||||||
|
case SAFETY_NOOUTPUT: |
||||||
|
set_intercept_relay(false); |
||||||
|
if (board_has_obd()) { |
||||||
|
current_board->set_can_mode(CAN_MODE_NORMAL); |
||||||
|
} |
||||||
|
can_silent = ALL_CAN_LIVE; |
||||||
|
break; |
||||||
|
case SAFETY_ELM327: |
||||||
|
set_intercept_relay(false); |
||||||
|
heartbeat_counter = 0U; |
||||||
|
if (board_has_obd()) { |
||||||
|
current_board->set_can_mode(CAN_MODE_OBD_CAN2); |
||||||
|
} |
||||||
|
can_silent = ALL_CAN_LIVE; |
||||||
|
break; |
||||||
|
default: |
||||||
|
set_intercept_relay(true); |
||||||
|
heartbeat_counter = 0U; |
||||||
|
if (board_has_obd()) { |
||||||
|
current_board->set_can_mode(CAN_MODE_NORMAL); |
||||||
|
} |
||||||
|
can_silent = ALL_CAN_LIVE; |
||||||
|
break; |
||||||
|
} |
||||||
|
can_init_all(); |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** USB port *****************************
|
||||||
|
|
||||||
|
int get_health_pkt(void *dat) { |
||||||
|
COMPILE_TIME_ASSERT(sizeof(struct health_t) <= MAX_RESP_LEN); |
||||||
|
struct health_t * health = (struct health_t*)dat; |
||||||
|
|
||||||
|
health->uptime_pkt = uptime_cnt; |
||||||
|
health->voltage_pkt = adc_get_voltage(); |
||||||
|
health->current_pkt = current_board->read_current(); |
||||||
|
|
||||||
|
//Use the GPIO pin to determine ignition or use a CAN based logic
|
||||||
|
health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); |
||||||
|
health->ignition_can_pkt = (uint8_t)(ignition_can); |
||||||
|
|
||||||
|
health->controls_allowed_pkt = controls_allowed; |
||||||
|
health->gas_interceptor_detected_pkt = gas_interceptor_detected; |
||||||
|
health->can_rx_errs_pkt = can_rx_errs; |
||||||
|
health->can_send_errs_pkt = can_send_errs; |
||||||
|
health->can_fwd_errs_pkt = can_fwd_errs; |
||||||
|
health->gmlan_send_errs_pkt = gmlan_send_errs; |
||||||
|
health->car_harness_status_pkt = car_harness_status; |
||||||
|
health->usb_power_mode_pkt = usb_power_mode; |
||||||
|
health->safety_mode_pkt = (uint8_t)(current_safety_mode); |
||||||
|
health->power_save_enabled_pkt = (uint8_t)(power_save_status == POWER_SAVE_STATUS_ENABLED); |
||||||
|
|
||||||
|
health->fault_status_pkt = fault_status; |
||||||
|
health->faults_pkt = faults; |
||||||
|
|
||||||
|
return sizeof(*health); |
||||||
|
} |
||||||
|
|
||||||
|
int get_rtc_pkt(void *dat) { |
||||||
|
timestamp_t t = rtc_get_time(); |
||||||
|
(void)memcpy(dat, &t, sizeof(t)); |
||||||
|
return sizeof(t); |
||||||
|
} |
||||||
|
|
||||||
|
int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(hardwired); |
||||||
|
CAN_FIFOMailBox_TypeDef *reply = (CAN_FIFOMailBox_TypeDef *)usbdata; |
||||||
|
int ilen = 0; |
||||||
|
while (ilen < MIN(len/0x10, 4) && can_pop(&can_rx_q, &reply[ilen])) { |
||||||
|
ilen++; |
||||||
|
} |
||||||
|
return ilen*0x10; |
||||||
|
} |
||||||
|
|
||||||
|
// send on serial, first byte to select the ring
|
||||||
|
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(hardwired); |
||||||
|
uint8_t *usbdata8 = (uint8_t *)usbdata; |
||||||
|
uart_ring *ur = get_ring_by_number(usbdata8[0]); |
||||||
|
if ((len != 0) && (ur != NULL)) { |
||||||
|
if ((usbdata8[0] < 2U) || safety_tx_lin_hook(usbdata8[0] - 2U, &usbdata8[1], len - 1)) { |
||||||
|
for (int i = 1; i < len; i++) { |
||||||
|
while (!putc(ur, usbdata8[i])) { |
||||||
|
// wait
|
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// send on CAN
|
||||||
|
void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(hardwired); |
||||||
|
int dpkt = 0; |
||||||
|
uint32_t *d32 = (uint32_t *)usbdata; |
||||||
|
for (dpkt = 0; dpkt < (len / 4); dpkt += 4) { |
||||||
|
CAN_FIFOMailBox_TypeDef to_push; |
||||||
|
to_push.RDHR = d32[dpkt + 3]; |
||||||
|
to_push.RDLR = d32[dpkt + 2]; |
||||||
|
to_push.RDTR = d32[dpkt + 1]; |
||||||
|
to_push.RIR = d32[dpkt]; |
||||||
|
|
||||||
|
uint8_t bus_number = (to_push.RDTR >> 4) & CAN_BUS_NUM_MASK; |
||||||
|
can_send(&to_push, bus_number, false); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void usb_cb_enumeration_complete() { |
||||||
|
puts("USB enumeration complete\n"); |
||||||
|
is_enumerated = 1; |
||||||
|
} |
||||||
|
|
||||||
|
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { |
||||||
|
unsigned int resp_len = 0; |
||||||
|
uart_ring *ur = NULL; |
||||||
|
int i; |
||||||
|
timestamp_t t; |
||||||
|
switch (setup->b.bRequest) { |
||||||
|
// **** 0xa0: get rtc time
|
||||||
|
case 0xa0: |
||||||
|
resp_len = get_rtc_pkt(resp); |
||||||
|
break; |
||||||
|
// **** 0xa1: set rtc year
|
||||||
|
case 0xa1: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.year = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa2: set rtc month
|
||||||
|
case 0xa2: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.month = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa3: set rtc day
|
||||||
|
case 0xa3: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.day = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa4: set rtc weekday
|
||||||
|
case 0xa4: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.weekday = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa5: set rtc hour
|
||||||
|
case 0xa5: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.hour = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa6: set rtc minute
|
||||||
|
case 0xa6: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.minute = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xa7: set rtc second
|
||||||
|
case 0xa7: |
||||||
|
t = rtc_get_time(); |
||||||
|
t.second = setup->b.wValue.w; |
||||||
|
rtc_set_time(t); |
||||||
|
break; |
||||||
|
// **** 0xb0: set IR power
|
||||||
|
case 0xb0: |
||||||
|
if(power_save_status == POWER_SAVE_STATUS_DISABLED){ |
||||||
|
current_board->set_ir_power(setup->b.wValue.w); |
||||||
|
} else { |
||||||
|
puts("Setting IR power not allowed in power saving mode\n"); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xb1: set fan power
|
||||||
|
case 0xb1: |
||||||
|
if(power_save_status == POWER_SAVE_STATUS_DISABLED){ |
||||||
|
current_board->set_fan_power(setup->b.wValue.w); |
||||||
|
} else { |
||||||
|
puts("Setting fan power not allowed in power saving mode\n"); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xb2: get fan rpm
|
||||||
|
case 0xb2: |
||||||
|
resp[0] = (fan_rpm & 0x00FFU); |
||||||
|
resp[1] = ((fan_rpm & 0xFF00U) >> 8U); |
||||||
|
resp_len = 2; |
||||||
|
break; |
||||||
|
// **** 0xb3: set phone power
|
||||||
|
case 0xb3: |
||||||
|
current_board->set_phone_power(setup->b.wValue.w > 0U); |
||||||
|
break; |
||||||
|
// **** 0xc0: get CAN debug info
|
||||||
|
case 0xc0: |
||||||
|
puts("can tx: "); puth(can_tx_cnt); |
||||||
|
puts(" txd: "); puth(can_txd_cnt); |
||||||
|
puts(" rx: "); puth(can_rx_cnt); |
||||||
|
puts(" err: "); puth(can_err_cnt); |
||||||
|
puts("\n"); |
||||||
|
break; |
||||||
|
// **** 0xc1: get hardware type
|
||||||
|
case 0xc1: |
||||||
|
resp[0] = hw_type; |
||||||
|
resp_len = 1; |
||||||
|
break; |
||||||
|
// **** 0xd0: fetch serial number
|
||||||
|
case 0xd0: |
||||||
|
// addresses are OTP
|
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
(void)memcpy(resp, (uint8_t *)0x1fff79c0, 0x10); |
||||||
|
resp_len = 0x10; |
||||||
|
} else { |
||||||
|
get_provision_chunk(resp); |
||||||
|
resp_len = PROVISION_CHUNK_LEN; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd1: enter bootloader mode
|
||||||
|
case 0xd1: |
||||||
|
// this allows reflashing of the bootstub
|
||||||
|
// so it's blocked over wifi
|
||||||
|
switch (setup->b.wValue.w) { |
||||||
|
case 0: |
||||||
|
// only allow bootloader entry on debug builds
|
||||||
|
#ifdef ALLOW_DEBUG |
||||||
|
if (hardwired) { |
||||||
|
puts("-> entering bootloader\n"); |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
#endif |
||||||
|
break; |
||||||
|
case 1: |
||||||
|
puts("-> entering softloader\n"); |
||||||
|
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("Bootloader mode invalid\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd2: get health packet
|
||||||
|
case 0xd2: |
||||||
|
resp_len = get_health_pkt(resp); |
||||||
|
break; |
||||||
|
// **** 0xd3: get first 64 bytes of signature
|
||||||
|
case 0xd3: |
||||||
|
{ |
||||||
|
resp_len = 64; |
||||||
|
char * code = (char*)_app_start; |
||||||
|
int code_len = _app_start[0]; |
||||||
|
(void)memcpy(resp, &code[code_len], resp_len); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd4: get second 64 bytes of signature
|
||||||
|
case 0xd4: |
||||||
|
{ |
||||||
|
resp_len = 64; |
||||||
|
char * code = (char*)_app_start; |
||||||
|
int code_len = _app_start[0]; |
||||||
|
(void)memcpy(resp, &code[code_len + 64], resp_len); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd6: get version
|
||||||
|
case 0xd6: |
||||||
|
COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN); |
||||||
|
(void)memcpy(resp, gitversion, sizeof(gitversion)); |
||||||
|
resp_len = sizeof(gitversion) - 1U; |
||||||
|
break; |
||||||
|
// **** 0xd8: reset ST
|
||||||
|
case 0xd8: |
||||||
|
NVIC_SystemReset(); |
||||||
|
break; |
||||||
|
// **** 0xd9: set ESP power
|
||||||
|
case 0xd9: |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
} else if (setup->b.wValue.w == 2U) { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_BOOTMODE); |
||||||
|
} else { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_DISABLED); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xda: reset ESP, with optional boot mode
|
||||||
|
case 0xda: |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_DISABLED); |
||||||
|
delay(1000000); |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_BOOTMODE); |
||||||
|
} else { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
} |
||||||
|
delay(1000000); |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
break; |
||||||
|
// **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode
|
||||||
|
case 0xdb: |
||||||
|
if(board_has_obd()){ |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
// Enable OBD CAN
|
||||||
|
current_board->set_can_mode(CAN_MODE_OBD_CAN2); |
||||||
|
} else { |
||||||
|
// Disable OBD CAN
|
||||||
|
current_board->set_can_mode(CAN_MODE_NORMAL); |
||||||
|
} |
||||||
|
} else { |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
// GMLAN ON
|
||||||
|
if (setup->b.wIndex.w == 1U) { |
||||||
|
can_set_gmlan(1); |
||||||
|
} else if (setup->b.wIndex.w == 2U) { |
||||||
|
can_set_gmlan(2); |
||||||
|
} else { |
||||||
|
puts("Invalid bus num for GMLAN CAN set\n"); |
||||||
|
} |
||||||
|
} else { |
||||||
|
can_set_gmlan(-1); |
||||||
|
} |
||||||
|
} |
||||||
|
break; |
||||||
|
|
||||||
|
// **** 0xdc: set safety mode
|
||||||
|
case 0xdc: |
||||||
|
// Blocked over WiFi.
|
||||||
|
// Allow SILENT, NOOUTPUT and ELM security mode to be set over wifi.
|
||||||
|
if (hardwired || (setup->b.wValue.w == SAFETY_SILENT) || |
||||||
|
(setup->b.wValue.w == SAFETY_NOOUTPUT) || |
||||||
|
(setup->b.wValue.w == SAFETY_ELM327)) { |
||||||
|
set_safety_mode(setup->b.wValue.w, (uint16_t) setup->b.wIndex.w); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xdd: enable can forwarding
|
||||||
|
case 0xdd: |
||||||
|
// wValue = Can Bus Num to forward from
|
||||||
|
// wIndex = Can Bus Num to forward to
|
||||||
|
if ((setup->b.wValue.w < BUS_MAX) && (setup->b.wIndex.w < BUS_MAX) && |
||||||
|
(setup->b.wValue.w != setup->b.wIndex.w)) { // set forwarding
|
||||||
|
can_set_forwarding(setup->b.wValue.w, setup->b.wIndex.w & CAN_BUS_NUM_MASK); |
||||||
|
} else if((setup->b.wValue.w < BUS_MAX) && (setup->b.wIndex.w == 0xFFU)){ //Clear Forwarding
|
||||||
|
can_set_forwarding(setup->b.wValue.w, -1); |
||||||
|
} else { |
||||||
|
puts("Invalid CAN bus forwarding\n"); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xde: set can bitrate
|
||||||
|
case 0xde: |
||||||
|
if (setup->b.wValue.w < BUS_MAX) { |
||||||
|
can_speed[setup->b.wValue.w] = setup->b.wIndex.w; |
||||||
|
can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xe0: uart read
|
||||||
|
case 0xe0: |
||||||
|
ur = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (!ur) { |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: Remove this again and fix boardd code to hande the message bursts instead of single chars
|
||||||
|
if (ur == &uart_ring_esp_gps) { |
||||||
|
dma_pointer_handler(ur, DMA2_Stream5->NDTR); |
||||||
|
} |
||||||
|
|
||||||
|
// read
|
||||||
|
while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && |
||||||
|
getc(ur, (char*)&resp[resp_len])) { |
||||||
|
++resp_len; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xe1: uart set baud rate
|
||||||
|
case 0xe1: |
||||||
|
ur = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (!ur) { |
||||||
|
break; |
||||||
|
} |
||||||
|
uart_set_baud(ur->uart, setup->b.wIndex.w); |
||||||
|
break; |
||||||
|
// **** 0xe2: uart set parity
|
||||||
|
case 0xe2: |
||||||
|
ur = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (!ur) { |
||||||
|
break; |
||||||
|
} |
||||||
|
switch (setup->b.wIndex.w) { |
||||||
|
case 0: |
||||||
|
// disable parity, 8-bit
|
||||||
|
ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M); |
||||||
|
break; |
||||||
|
case 1: |
||||||
|
// even parity, 9-bit
|
||||||
|
ur->uart->CR1 &= ~USART_CR1_PS; |
||||||
|
ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; |
||||||
|
break; |
||||||
|
case 2: |
||||||
|
// odd parity, 9-bit
|
||||||
|
ur->uart->CR1 |= USART_CR1_PS; |
||||||
|
ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xe4: uart set baud rate extended
|
||||||
|
case 0xe4: |
||||||
|
ur = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (!ur) { |
||||||
|
break; |
||||||
|
} |
||||||
|
uart_set_baud(ur->uart, (int)setup->b.wIndex.w*300); |
||||||
|
break; |
||||||
|
// **** 0xe5: set CAN loopback (for testing)
|
||||||
|
case 0xe5: |
||||||
|
can_loopback = (setup->b.wValue.w > 0U); |
||||||
|
can_init_all(); |
||||||
|
break; |
||||||
|
// **** 0xe6: set USB power
|
||||||
|
case 0xe6: |
||||||
|
current_board->set_usb_power_mode(setup->b.wValue.w); |
||||||
|
break; |
||||||
|
// **** 0xe7: set power save state
|
||||||
|
case 0xe7: |
||||||
|
set_power_save_state(setup->b.wValue.w); |
||||||
|
break; |
||||||
|
// **** 0xf0: do k-line wValue pulse on uart2 for Acura
|
||||||
|
case 0xf0: |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
GPIOC->ODR &= ~(1U << 10); |
||||||
|
GPIOC->MODER &= ~GPIO_MODER_MODER10_1; |
||||||
|
GPIOC->MODER |= GPIO_MODER_MODER10_0; |
||||||
|
} else { |
||||||
|
GPIOC->ODR &= ~(1U << 12); |
||||||
|
GPIOC->MODER &= ~GPIO_MODER_MODER12_1; |
||||||
|
GPIOC->MODER |= GPIO_MODER_MODER12_0; |
||||||
|
} |
||||||
|
|
||||||
|
for (i = 0; i < 80; i++) { |
||||||
|
delay(8000); |
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
GPIOC->ODR |= (1U << 10); |
||||||
|
GPIOC->ODR &= ~(1U << 10); |
||||||
|
} else { |
||||||
|
GPIOC->ODR |= (1U << 12); |
||||||
|
GPIOC->ODR &= ~(1U << 12); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (setup->b.wValue.w == 1U) { |
||||||
|
GPIOC->MODER &= ~GPIO_MODER_MODER10_0; |
||||||
|
GPIOC->MODER |= GPIO_MODER_MODER10_1; |
||||||
|
} else { |
||||||
|
GPIOC->MODER &= ~GPIO_MODER_MODER12_0; |
||||||
|
GPIOC->MODER |= GPIO_MODER_MODER12_1; |
||||||
|
} |
||||||
|
|
||||||
|
delay(140 * 9000); |
||||||
|
break; |
||||||
|
// **** 0xf1: Clear CAN ring buffer.
|
||||||
|
case 0xf1: |
||||||
|
if (setup->b.wValue.w == 0xFFFFU) { |
||||||
|
puts("Clearing CAN Rx queue\n"); |
||||||
|
can_clear(&can_rx_q); |
||||||
|
} else if (setup->b.wValue.w < BUS_MAX) { |
||||||
|
puts("Clearing CAN Tx queue\n"); |
||||||
|
can_clear(can_queues[setup->b.wValue.w]); |
||||||
|
} else { |
||||||
|
puts("Clearing CAN CAN ring buffer failed: wrong bus number\n"); |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xf2: Clear UART ring buffer.
|
||||||
|
case 0xf2: |
||||||
|
{ |
||||||
|
uart_ring * rb = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (rb != NULL) { |
||||||
|
puts("Clearing UART queue.\n"); |
||||||
|
clear_uart_buff(rb); |
||||||
|
} |
||||||
|
break; |
||||||
|
} |
||||||
|
// **** 0xf3: Heartbeat. Resets heartbeat counter.
|
||||||
|
case 0xf3: |
||||||
|
{ |
||||||
|
heartbeat_counter = 0U; |
||||||
|
break; |
||||||
|
} |
||||||
|
default: |
||||||
|
puts("NO HANDLER "); |
||||||
|
puth(setup->b.bRequest); |
||||||
|
puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
return resp_len; |
||||||
|
} |
||||||
|
|
||||||
|
#ifndef EON |
||||||
|
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { |
||||||
|
// data[0] = endpoint
|
||||||
|
// data[2] = length
|
||||||
|
// data[4:] = data
|
||||||
|
UNUSED(len); |
||||||
|
int resp_len = 0; |
||||||
|
switch (data[0]) { |
||||||
|
case 0: |
||||||
|
// control transfer
|
||||||
|
resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); |
||||||
|
break; |
||||||
|
case 1: |
||||||
|
// ep 1, read
|
||||||
|
resp_len = usb_cb_ep1_in(data_out, 0x40, 0); |
||||||
|
break; |
||||||
|
case 2: |
||||||
|
// ep 2, send serial
|
||||||
|
usb_cb_ep2_out(data+4, data[2], 0); |
||||||
|
break; |
||||||
|
case 3: |
||||||
|
// ep 3, send CAN
|
||||||
|
usb_cb_ep3_out(data+4, data[2], 0); |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("SPI data invalid"); |
||||||
|
break; |
||||||
|
} |
||||||
|
return resp_len; |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
// ***************************** main code *****************************
|
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
|
||||||
|
void __initialize_hardware_early(void) { |
||||||
|
early(); |
||||||
|
} |
||||||
|
|
||||||
|
void __attribute__ ((noinline)) enable_fpu(void) { |
||||||
|
// enable the FPU
|
||||||
|
SCB->CPACR |= ((3UL << (10U * 2U)) | (3UL << (11U * 2U))); |
||||||
|
} |
||||||
|
|
||||||
|
// go into SILENT when the EON does not send a heartbeat for this amount of seconds.
|
||||||
|
#define EON_HEARTBEAT_IGNITION_CNT_ON 5U |
||||||
|
#define EON_HEARTBEAT_IGNITION_CNT_OFF 2U |
||||||
|
|
||||||
|
// called at 1Hz
|
||||||
|
void TIM1_BRK_TIM9_IRQ_Handler(void) { |
||||||
|
if (TIM9->SR != 0) { |
||||||
|
can_live = pending_can_live; |
||||||
|
|
||||||
|
current_board->usb_power_mode_tick(uptime_cnt); |
||||||
|
|
||||||
|
//puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n");
|
||||||
|
|
||||||
|
// reset this every 16th pass
|
||||||
|
if ((uptime_cnt & 0xFU) == 0U) { |
||||||
|
pending_can_live = 0; |
||||||
|
} |
||||||
|
#ifdef DEBUG |
||||||
|
puts("** blink "); |
||||||
|
puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); |
||||||
|
puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); |
||||||
|
puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); |
||||||
|
#endif |
||||||
|
|
||||||
|
// Tick fan driver
|
||||||
|
fan_tick(); |
||||||
|
//puts("Fan speed: "); puth((unsigned int) fan_rpm); puts("rpm\n");
|
||||||
|
|
||||||
|
// set green LED to be controls allowed
|
||||||
|
current_board->set_led(LED_GREEN, controls_allowed); |
||||||
|
|
||||||
|
// turn off the blue LED, turned on by CAN
|
||||||
|
// unless we are in power saving mode
|
||||||
|
current_board->set_led(LED_BLUE, (uptime_cnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED)); |
||||||
|
|
||||||
|
// increase heartbeat counter and cap it at the uint32 limit
|
||||||
|
if (heartbeat_counter < __UINT32_MAX__) { |
||||||
|
heartbeat_counter += 1U; |
||||||
|
} |
||||||
|
|
||||||
|
#ifdef EON |
||||||
|
// check heartbeat counter if we are running EON code.
|
||||||
|
// if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save
|
||||||
|
if (heartbeat_counter >= (check_started() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { |
||||||
|
puts("EON hasn't sent a heartbeat for 0x"); |
||||||
|
puth(heartbeat_counter); |
||||||
|
puts(" seconds. Safety is set to SILENT mode.\n"); |
||||||
|
if (current_safety_mode != SAFETY_SILENT) { |
||||||
|
set_safety_mode(SAFETY_SILENT, 0U); |
||||||
|
} |
||||||
|
if (power_save_status != POWER_SAVE_STATUS_ENABLED) { |
||||||
|
set_power_save_state(POWER_SAVE_STATUS_ENABLED); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// enter CDP mode when car starts to ensure we are charging a turned off EON
|
||||||
|
if (check_started() && (usb_power_mode != USB_POWER_CDP)) { |
||||||
|
current_board->set_usb_power_mode(USB_POWER_CDP); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
// check registers
|
||||||
|
check_registers(); |
||||||
|
|
||||||
|
// set ignition_can to false after 2s of no CAN seen
|
||||||
|
if (ignition_can_cnt > 2U) { |
||||||
|
ignition_can = false; |
||||||
|
}; |
||||||
|
|
||||||
|
// on to the next one
|
||||||
|
uptime_cnt += 1U; |
||||||
|
safety_mode_cnt += 1U; |
||||||
|
ignition_can_cnt += 1U; |
||||||
|
|
||||||
|
// synchronous safety check
|
||||||
|
safety_tick(current_hooks); |
||||||
|
} |
||||||
|
TIM9->SR = 0; |
||||||
|
} |
||||||
|
|
||||||
|
int main(void) { |
||||||
|
// Init interrupt table
|
||||||
|
init_interrupts(true); |
||||||
|
|
||||||
|
// 1s timer
|
||||||
|
REGISTER_INTERRUPT(TIM1_BRK_TIM9_IRQn, TIM1_BRK_TIM9_IRQ_Handler, 2U, FAULT_INTERRUPT_RATE_TIM1) |
||||||
|
|
||||||
|
// shouldn't have interrupts here, but just in case
|
||||||
|
disable_interrupts(); |
||||||
|
|
||||||
|
// init early devices
|
||||||
|
clock_init(); |
||||||
|
peripherals_init(); |
||||||
|
detect_configuration(); |
||||||
|
detect_board_type(); |
||||||
|
adc_init(); |
||||||
|
|
||||||
|
// print hello
|
||||||
|
puts("\n\n\n************************ MAIN START ************************\n"); |
||||||
|
|
||||||
|
// check for non-supported board types
|
||||||
|
if(hw_type == HW_TYPE_UNKNOWN){ |
||||||
|
puts("Unsupported board type\n"); |
||||||
|
while (1) { /* hang */ } |
||||||
|
} |
||||||
|
|
||||||
|
puts("Config:\n"); |
||||||
|
puts(" Board type: "); puts(current_board->board_type); puts("\n"); |
||||||
|
puts(has_external_debug_serial ? " Real serial\n" : " USB serial\n"); |
||||||
|
puts(is_entering_bootmode ? " ESP wants bootmode\n" : " No bootmode\n"); |
||||||
|
|
||||||
|
// init board
|
||||||
|
current_board->init(); |
||||||
|
|
||||||
|
// panda has an FPU, let's use it!
|
||||||
|
enable_fpu(); |
||||||
|
|
||||||
|
// enable main uart if it's connected
|
||||||
|
if (has_external_debug_serial) { |
||||||
|
// WEIRDNESS: without this gate around the UART, it would "crash", but only if the ESP is enabled
|
||||||
|
// assuming it's because the lines were left floating and spurious noise was on them
|
||||||
|
uart_init(&uart_ring_debug, 115200); |
||||||
|
} |
||||||
|
|
||||||
|
if (board_has_gps()) { |
||||||
|
uart_init(&uart_ring_esp_gps, 9600); |
||||||
|
} else { |
||||||
|
// enable ESP uart
|
||||||
|
uart_init(&uart_ring_esp_gps, 115200); |
||||||
|
} |
||||||
|
|
||||||
|
if(board_has_lin()){ |
||||||
|
// enable LIN
|
||||||
|
uart_init(&uart_ring_lin1, 10400); |
||||||
|
UART5->CR2 |= USART_CR2_LINEN; |
||||||
|
uart_init(&uart_ring_lin2, 10400); |
||||||
|
USART3->CR2 |= USART_CR2_LINEN; |
||||||
|
} |
||||||
|
|
||||||
|
// init microsecond system timer
|
||||||
|
// increments 1000000 times per second
|
||||||
|
// generate an update to set the prescaler
|
||||||
|
TIM2->PSC = 48-1; |
||||||
|
TIM2->CR1 = TIM_CR1_CEN; |
||||||
|
TIM2->EGR = TIM_EGR_UG; |
||||||
|
// use TIM2->CNT to read
|
||||||
|
|
||||||
|
// init to SILENT and can silent
|
||||||
|
set_safety_mode(SAFETY_SILENT, 0); |
||||||
|
|
||||||
|
// enable CAN TXs
|
||||||
|
current_board->enable_can_transcievers(true); |
||||||
|
|
||||||
|
#ifndef EON |
||||||
|
spi_init(); |
||||||
|
#endif |
||||||
|
|
||||||
|
// 1hz
|
||||||
|
timer_init(TIM9, 1464); |
||||||
|
NVIC_EnableIRQ(TIM1_BRK_TIM9_IRQn); |
||||||
|
|
||||||
|
#ifdef DEBUG |
||||||
|
puts("DEBUG ENABLED\n"); |
||||||
|
#endif |
||||||
|
// enable USB (right before interrupts or enum can fail!)
|
||||||
|
usb_init(); |
||||||
|
|
||||||
|
puts("**** INTERRUPTS ON ****\n"); |
||||||
|
enable_interrupts(); |
||||||
|
|
||||||
|
// LED should keep on blinking all the time
|
||||||
|
uint64_t cnt = 0; |
||||||
|
|
||||||
|
for (cnt=0;;cnt++) { |
||||||
|
if (power_save_status == POWER_SAVE_STATUS_DISABLED) { |
||||||
|
#ifdef DEBUG_FAULTS |
||||||
|
if(fault_status == FAULT_STATUS_NONE){ |
||||||
|
#endif |
||||||
|
int div_mode = ((usb_power_mode == USB_POWER_DCP) ? 4 : 1); |
||||||
|
|
||||||
|
// useful for debugging, fade breaks = panda is overloaded
|
||||||
|
for (int div_mode_loop = 0; div_mode_loop < div_mode; div_mode_loop++) { |
||||||
|
for (int fade = 0; fade < 1024; fade += 8) { |
||||||
|
for (int i = 0; i < (128/div_mode); i++) { |
||||||
|
current_board->set_led(LED_RED, 1); |
||||||
|
if (fade < 512) { delay(fade); } else { delay(1024-fade); } |
||||||
|
current_board->set_led(LED_RED, 0); |
||||||
|
if (fade < 512) { delay(512-fade); } else { delay(fade-512); } |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
#ifdef DEBUG_FAULTS |
||||||
|
} else { |
||||||
|
current_board->set_led(LED_RED, 1); |
||||||
|
delay(512000U); |
||||||
|
current_board->set_led(LED_RED, 0); |
||||||
|
delay(512000U); |
||||||
|
} |
||||||
|
#endif |
||||||
|
} else { |
||||||
|
__WFI(); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
return 0; |
||||||
|
} |
@ -0,0 +1,15 @@ |
|||||||
|
// ******************** Prototypes ********************
|
||||||
|
void puts(const char *a); |
||||||
|
void puth(unsigned int i); |
||||||
|
void puth2(unsigned int i); |
||||||
|
typedef struct board board; |
||||||
|
typedef struct harness_configuration harness_configuration; |
||||||
|
void can_flip_buses(uint8_t bus1, uint8_t bus2); |
||||||
|
void can_set_obd(uint8_t harness_orientation, bool obd); |
||||||
|
|
||||||
|
// ********************* Globals **********************
|
||||||
|
uint8_t hw_type = 0; |
||||||
|
const board *current_board; |
||||||
|
bool is_enumerated = 0; |
||||||
|
uint32_t heartbeat_counter = 0; |
||||||
|
uint32_t uptime_cnt = 0; |
@ -0,0 +1 @@ |
|||||||
|
obj/* |
@ -0,0 +1,67 @@ |
|||||||
|
# :set noet
|
||||||
|
PROJ_NAME = comma
|
||||||
|
|
||||||
|
CFLAGS = -O2 -Wall -Wextra -Wstrict-prototypes -Werror -std=gnu11 -DPEDAL
|
||||||
|
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
|
||||||
|
CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx
|
||||||
|
CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib -fno-builtin
|
||||||
|
CFLAGS += -T../stm32_flash.ld
|
||||||
|
|
||||||
|
STARTUP_FILE = startup_stm32f205xx
|
||||||
|
|
||||||
|
CC = arm-none-eabi-gcc
|
||||||
|
OBJCOPY = arm-none-eabi-objcopy
|
||||||
|
OBJDUMP = arm-none-eabi-objdump
|
||||||
|
DFU_UTIL = "dfu-util"
|
||||||
|
|
||||||
|
# pedal only uses the debug cert
|
||||||
|
CERT = ../../certs/debug
|
||||||
|
CFLAGS += "-DALLOW_DEBUG"
|
||||||
|
|
||||||
|
canflash: obj/$(PROJ_NAME).bin |
||||||
|
../../tests/pedal/enter_canloader.py $<
|
||||||
|
|
||||||
|
usbflash: obj/$(PROJ_NAME).bin |
||||||
|
../../tests/pedal/enter_canloader.py; sleep 0.5
|
||||||
|
PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)"
|
||||||
|
|
||||||
|
recover: obj/bootstub.bin obj/$(PROJ_NAME).bin |
||||||
|
../../tests/pedal/enter_canloader.py --recover; sleep 0.5
|
||||||
|
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||||
|
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin
|
||||||
|
|
||||||
|
include ../../common/version.mk |
||||||
|
|
||||||
|
obj/cert.h: ../../crypto/getcertheader.py |
||||||
|
../../crypto/getcertheader.py ../../certs/debug.pub ../../certs/release.pub > $@
|
||||||
|
|
||||||
|
obj/main.o: main.c ../*.h |
||||||
|
mkdir -p obj
|
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/bootstub.o: ../bootstub.c ../*.h obj/gitversion.h obj/cert.h |
||||||
|
mkdir -p obj
|
||||||
|
mkdir -p ../obj
|
||||||
|
cp obj/gitversion.h ../obj/gitversion.h
|
||||||
|
cp obj/cert.h ../obj/cert.h
|
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s |
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/%.o: ../../crypto/%.c |
||||||
|
$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.o |
||||||
|
# hack
|
||||||
|
$(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
|
||||||
|
$(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin
|
||||||
|
SETLEN=1 ../../crypto/sign.py obj/code.bin $@ $(CERT)
|
||||||
|
|
||||||
|
obj/bootstub.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o |
||||||
|
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
|
||||||
|
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
|
||||||
|
|
||||||
|
clean: |
||||||
|
rm -f obj/*
|
||||||
|
|
@ -0,0 +1,28 @@ |
|||||||
|
This is the firmware for the comma pedal. It borrows a lot from panda. |
||||||
|
|
||||||
|
The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal. |
||||||
|
|
||||||
|
This is the open source software. Note that it is not ready to use yet. |
||||||
|
|
||||||
|
== Test Plan == |
||||||
|
|
||||||
|
* Startup |
||||||
|
** Confirm STATE_FAULT_STARTUP |
||||||
|
* Timeout |
||||||
|
** Send value |
||||||
|
** Confirm value is output |
||||||
|
** Stop sending messages |
||||||
|
** Confirm value is passthru after 100ms |
||||||
|
** Confirm STATE_FAULT_TIMEOUT |
||||||
|
* Random values |
||||||
|
** Send random 6 byte messages |
||||||
|
** Confirm random values cause passthru |
||||||
|
** Confirm STATE_FAULT_BAD_CHECKSUM |
||||||
|
* Same message lockout |
||||||
|
** Send same message repeated |
||||||
|
** Confirm timeout behavior |
||||||
|
* Don't set enable |
||||||
|
** Confirm no output |
||||||
|
* Set enable and values |
||||||
|
** Confirm output |
||||||
|
|
@ -0,0 +1,352 @@ |
|||||||
|
// ********************* Includes *********************
|
||||||
|
#include "../config.h" |
||||||
|
#include "libc.h" |
||||||
|
|
||||||
|
#include "main_declarations.h" |
||||||
|
#include "critical.h" |
||||||
|
#include "faults.h" |
||||||
|
|
||||||
|
#include "drivers/registers.h" |
||||||
|
#include "drivers/interrupts.h" |
||||||
|
#include "drivers/llcan.h" |
||||||
|
#include "drivers/llgpio.h" |
||||||
|
#include "drivers/adc.h" |
||||||
|
|
||||||
|
#include "board.h" |
||||||
|
|
||||||
|
#include "drivers/clock.h" |
||||||
|
#include "drivers/dac.h" |
||||||
|
#include "drivers/timer.h" |
||||||
|
|
||||||
|
#include "gpio.h" |
||||||
|
|
||||||
|
#define CAN CAN1 |
||||||
|
|
||||||
|
//#define PEDAL_USB
|
||||||
|
|
||||||
|
#ifdef PEDAL_USB |
||||||
|
#include "drivers/uart.h" |
||||||
|
#include "drivers/usb.h" |
||||||
|
#else |
||||||
|
// no serial either
|
||||||
|
void puts(const char *a) { |
||||||
|
UNUSED(a); |
||||||
|
} |
||||||
|
void puth(unsigned int i) { |
||||||
|
UNUSED(i); |
||||||
|
} |
||||||
|
void puth2(unsigned int i) { |
||||||
|
UNUSED(i); |
||||||
|
} |
||||||
|
#endif |
||||||
|
|
||||||
|
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef |
||||||
|
uint32_t enter_bootloader_mode; |
||||||
|
|
||||||
|
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
|
||||||
|
void __initialize_hardware_early(void) { |
||||||
|
early(); |
||||||
|
} |
||||||
|
|
||||||
|
// ********************* serial debugging *********************
|
||||||
|
|
||||||
|
#ifdef PEDAL_USB |
||||||
|
|
||||||
|
void debug_ring_callback(uart_ring *ring) { |
||||||
|
char rcv; |
||||||
|
while (getc(ring, &rcv) != 0) { |
||||||
|
(void)putc(ring, rcv); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(usbdata); |
||||||
|
UNUSED(len); |
||||||
|
UNUSED(hardwired); |
||||||
|
return 0; |
||||||
|
} |
||||||
|
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(usbdata); |
||||||
|
UNUSED(len); |
||||||
|
UNUSED(hardwired); |
||||||
|
} |
||||||
|
void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(usbdata); |
||||||
|
UNUSED(len); |
||||||
|
UNUSED(hardwired); |
||||||
|
} |
||||||
|
void usb_cb_enumeration_complete(void) {} |
||||||
|
|
||||||
|
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { |
||||||
|
UNUSED(hardwired); |
||||||
|
unsigned int resp_len = 0; |
||||||
|
uart_ring *ur = NULL; |
||||||
|
switch (setup->b.bRequest) { |
||||||
|
// **** 0xe0: uart read
|
||||||
|
case 0xe0: |
||||||
|
ur = get_ring_by_number(setup->b.wValue.w); |
||||||
|
if (!ur) { |
||||||
|
break; |
||||||
|
} |
||||||
|
// read
|
||||||
|
while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && |
||||||
|
getc(ur, (char*)&resp[resp_len])) { |
||||||
|
++resp_len; |
||||||
|
} |
||||||
|
break; |
||||||
|
default: |
||||||
|
puts("NO HANDLER "); |
||||||
|
puth(setup->b.bRequest); |
||||||
|
puts("\n"); |
||||||
|
break; |
||||||
|
} |
||||||
|
return resp_len; |
||||||
|
} |
||||||
|
|
||||||
|
#endif |
||||||
|
|
||||||
|
// ***************************** pedal can checksum *****************************
|
||||||
|
|
||||||
|
uint8_t pedal_checksum(uint8_t *dat, int len) { |
||||||
|
uint8_t crc = 0xFF; |
||||||
|
uint8_t poly = 0xD5; // standard crc8
|
||||||
|
int i, j; |
||||||
|
for (i = len - 1; i >= 0; i--) { |
||||||
|
crc ^= dat[i]; |
||||||
|
for (j = 0; j < 8; j++) { |
||||||
|
if ((crc & 0x80U) != 0U) { |
||||||
|
crc = (uint8_t)((crc << 1) ^ poly); |
||||||
|
} |
||||||
|
else { |
||||||
|
crc <<= 1; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return crc; |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** can port *****************************
|
||||||
|
|
||||||
|
// addresses to be used on CAN
|
||||||
|
#define CAN_GAS_INPUT 0x200 |
||||||
|
#define CAN_GAS_OUTPUT 0x201U |
||||||
|
#define CAN_GAS_SIZE 6 |
||||||
|
#define COUNTER_CYCLE 0xFU |
||||||
|
|
||||||
|
void CAN1_TX_IRQ_Handler(void) { |
||||||
|
// clear interrupt
|
||||||
|
CAN->TSR |= CAN_TSR_RQCP0; |
||||||
|
} |
||||||
|
|
||||||
|
// two independent values
|
||||||
|
uint16_t gas_set_0 = 0; |
||||||
|
uint16_t gas_set_1 = 0; |
||||||
|
|
||||||
|
#define MAX_TIMEOUT 10U |
||||||
|
uint32_t timeout = 0; |
||||||
|
uint32_t current_index = 0; |
||||||
|
|
||||||
|
#define NO_FAULT 0U |
||||||
|
#define FAULT_BAD_CHECKSUM 1U |
||||||
|
#define FAULT_SEND 2U |
||||||
|
#define FAULT_SCE 3U |
||||||
|
#define FAULT_STARTUP 4U |
||||||
|
#define FAULT_TIMEOUT 5U |
||||||
|
#define FAULT_INVALID 6U |
||||||
|
uint8_t state = FAULT_STARTUP; |
||||||
|
|
||||||
|
void CAN1_RX0_IRQ_Handler(void) { |
||||||
|
while ((CAN->RF0R & CAN_RF0R_FMP0) != 0) { |
||||||
|
#ifdef DEBUG |
||||||
|
puts("CAN RX\n"); |
||||||
|
#endif |
||||||
|
int address = CAN->sFIFOMailBox[0].RIR >> 21; |
||||||
|
if (address == CAN_GAS_INPUT) { |
||||||
|
// softloader entry
|
||||||
|
if (GET_BYTES_04(&CAN->sFIFOMailBox[0]) == 0xdeadface) { |
||||||
|
if (GET_BYTES_48(&CAN->sFIFOMailBox[0]) == 0x0ab00b1e) { |
||||||
|
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} else if (GET_BYTES_48(&CAN->sFIFOMailBox[0]) == 0x02b00b1e) { |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} else { |
||||||
|
puts("Failed entering Softloader or Bootloader\n"); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// normal packet
|
||||||
|
uint8_t dat[8]; |
||||||
|
for (int i=0; i<8; i++) { |
||||||
|
dat[i] = GET_BYTE(&CAN->sFIFOMailBox[0], i); |
||||||
|
} |
||||||
|
uint16_t value_0 = (dat[0] << 8) | dat[1]; |
||||||
|
uint16_t value_1 = (dat[2] << 8) | dat[3]; |
||||||
|
bool enable = ((dat[4] >> 7) & 1U) != 0U; |
||||||
|
uint8_t index = dat[4] & COUNTER_CYCLE; |
||||||
|
if (pedal_checksum(dat, CAN_GAS_SIZE - 1) == dat[5]) { |
||||||
|
if (((current_index + 1U) & COUNTER_CYCLE) == index) { |
||||||
|
#ifdef DEBUG |
||||||
|
puts("setting gas "); |
||||||
|
puth(value_0); |
||||||
|
puts("\n"); |
||||||
|
#endif |
||||||
|
if (enable) { |
||||||
|
gas_set_0 = value_0; |
||||||
|
gas_set_1 = value_1; |
||||||
|
} else { |
||||||
|
// clear the fault state if values are 0
|
||||||
|
if ((value_0 == 0U) && (value_1 == 0U)) { |
||||||
|
state = NO_FAULT; |
||||||
|
} else { |
||||||
|
state = FAULT_INVALID; |
||||||
|
} |
||||||
|
gas_set_0 = 0; |
||||||
|
gas_set_1 = 0; |
||||||
|
} |
||||||
|
// clear the timeout
|
||||||
|
timeout = 0; |
||||||
|
} |
||||||
|
current_index = index; |
||||||
|
} else { |
||||||
|
// wrong checksum = fault
|
||||||
|
state = FAULT_BAD_CHECKSUM; |
||||||
|
} |
||||||
|
} |
||||||
|
// next
|
||||||
|
CAN->RF0R |= CAN_RF0R_RFOM0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void CAN1_SCE_IRQ_Handler(void) { |
||||||
|
state = FAULT_SCE; |
||||||
|
llcan_clear_send(CAN); |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t pdl0 = 0; |
||||||
|
uint32_t pdl1 = 0; |
||||||
|
unsigned int pkt_idx = 0; |
||||||
|
|
||||||
|
int led_value = 0; |
||||||
|
|
||||||
|
void TIM3_IRQ_Handler(void) { |
||||||
|
#ifdef DEBUG |
||||||
|
puth(TIM3->CNT); |
||||||
|
puts(" "); |
||||||
|
puth(pdl0); |
||||||
|
puts(" "); |
||||||
|
puth(pdl1); |
||||||
|
puts("\n"); |
||||||
|
#endif |
||||||
|
|
||||||
|
// check timer for sending the user pedal and clearing the CAN
|
||||||
|
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { |
||||||
|
uint8_t dat[8]; |
||||||
|
dat[0] = (pdl0 >> 8) & 0xFFU; |
||||||
|
dat[1] = (pdl0 >> 0) & 0xFFU; |
||||||
|
dat[2] = (pdl1 >> 8) & 0xFFU; |
||||||
|
dat[3] = (pdl1 >> 0) & 0xFFU; |
||||||
|
dat[4] = ((state & 0xFU) << 4) | pkt_idx; |
||||||
|
dat[5] = pedal_checksum(dat, CAN_GAS_SIZE - 1); |
||||||
|
CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1] << 8) | (dat[2] << 16) | (dat[3] << 24); |
||||||
|
CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5] << 8); |
||||||
|
CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5
|
||||||
|
CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1U; |
||||||
|
++pkt_idx; |
||||||
|
pkt_idx &= COUNTER_CYCLE; |
||||||
|
} else { |
||||||
|
// old can packet hasn't sent!
|
||||||
|
state = FAULT_SEND; |
||||||
|
#ifdef DEBUG |
||||||
|
puts("CAN MISS\n"); |
||||||
|
#endif |
||||||
|
} |
||||||
|
|
||||||
|
// blink the LED
|
||||||
|
current_board->set_led(LED_GREEN, led_value); |
||||||
|
led_value = !led_value; |
||||||
|
|
||||||
|
TIM3->SR = 0; |
||||||
|
|
||||||
|
// up timeout for gas set
|
||||||
|
if (timeout == MAX_TIMEOUT) { |
||||||
|
state = FAULT_TIMEOUT; |
||||||
|
} else { |
||||||
|
timeout += 1U; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// ***************************** main code *****************************
|
||||||
|
|
||||||
|
void pedal(void) { |
||||||
|
// read/write
|
||||||
|
pdl0 = adc_get(ADCCHAN_ACCEL0); |
||||||
|
pdl1 = adc_get(ADCCHAN_ACCEL1); |
||||||
|
|
||||||
|
// write the pedal to the DAC
|
||||||
|
if (state == NO_FAULT) { |
||||||
|
dac_set(0, MAX(gas_set_0, pdl0)); |
||||||
|
dac_set(1, MAX(gas_set_1, pdl1)); |
||||||
|
} else { |
||||||
|
dac_set(0, pdl0); |
||||||
|
dac_set(1, pdl1); |
||||||
|
} |
||||||
|
|
||||||
|
watchdog_feed(); |
||||||
|
} |
||||||
|
|
||||||
|
int main(void) { |
||||||
|
// Init interrupt table
|
||||||
|
init_interrupts(true); |
||||||
|
|
||||||
|
REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
|
||||||
|
// Should run at around 732Hz (see init below)
|
||||||
|
REGISTER_INTERRUPT(TIM3_IRQn, TIM3_IRQ_Handler, 1000U, FAULT_INTERRUPT_RATE_TIM3) |
||||||
|
|
||||||
|
disable_interrupts(); |
||||||
|
|
||||||
|
// init devices
|
||||||
|
clock_init(); |
||||||
|
peripherals_init(); |
||||||
|
detect_configuration(); |
||||||
|
detect_board_type(); |
||||||
|
|
||||||
|
// init board
|
||||||
|
current_board->init(); |
||||||
|
|
||||||
|
#ifdef PEDAL_USB |
||||||
|
// enable USB
|
||||||
|
usb_init(); |
||||||
|
#endif |
||||||
|
|
||||||
|
// pedal stuff
|
||||||
|
dac_init(); |
||||||
|
adc_init(); |
||||||
|
|
||||||
|
// init can
|
||||||
|
bool llcan_speed_set = llcan_set_speed(CAN1, 5000, false, false); |
||||||
|
if (!llcan_speed_set) { |
||||||
|
puts("Failed to set llcan speed"); |
||||||
|
} |
||||||
|
|
||||||
|
llcan_init(CAN1); |
||||||
|
|
||||||
|
// 48mhz / 65536 ~= 732
|
||||||
|
timer_init(TIM3, 15); |
||||||
|
NVIC_EnableIRQ(TIM3_IRQn); |
||||||
|
|
||||||
|
watchdog_init(); |
||||||
|
|
||||||
|
puts("**** INTERRUPTS ON ****\n"); |
||||||
|
enable_interrupts(); |
||||||
|
|
||||||
|
// main pedal loop
|
||||||
|
while (1) { |
||||||
|
pedal(); |
||||||
|
} |
||||||
|
|
||||||
|
return 0; |
||||||
|
} |
@ -0,0 +1,11 @@ |
|||||||
|
// ******************** Prototypes ********************
|
||||||
|
void puts(const char *a); |
||||||
|
void puth(unsigned int i); |
||||||
|
void puth2(unsigned int i); |
||||||
|
typedef struct board board; |
||||||
|
typedef struct harness_configuration harness_configuration; |
||||||
|
|
||||||
|
// ********************* Globals **********************
|
||||||
|
uint8_t hw_type = 0; |
||||||
|
const board *current_board; |
||||||
|
bool is_enumerated = 0; |
@ -0,0 +1,60 @@ |
|||||||
|
// WARNING: To stay in compliance with the SIL2 rules laid out in STM UM1840, we should never implement any of the available hardware low power modes.
|
||||||
|
// See rule: CoU_3
|
||||||
|
|
||||||
|
#define POWER_SAVE_STATUS_DISABLED 0 |
||||||
|
#define POWER_SAVE_STATUS_ENABLED 1 |
||||||
|
|
||||||
|
int power_save_status = POWER_SAVE_STATUS_DISABLED; |
||||||
|
|
||||||
|
void set_power_save_state(int state) { |
||||||
|
|
||||||
|
bool is_valid_state = (state == POWER_SAVE_STATUS_ENABLED) || (state == POWER_SAVE_STATUS_DISABLED); |
||||||
|
if (is_valid_state && (state != power_save_status)) { |
||||||
|
bool enable = false; |
||||||
|
if (state == POWER_SAVE_STATUS_ENABLED) { |
||||||
|
puts("enable power savings\n"); |
||||||
|
if (board_has_gps()) { |
||||||
|
char UBLOX_SLEEP_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x08\x00\x17\x78"; |
||||||
|
uart_ring *ur = get_ring_by_number(1); |
||||||
|
for (unsigned int i = 0; i < sizeof(UBLOX_SLEEP_MSG) - 1U; i++) while (!putc(ur, UBLOX_SLEEP_MSG[i])); |
||||||
|
} |
||||||
|
} else { |
||||||
|
puts("disable power savings\n"); |
||||||
|
if (board_has_gps()) { |
||||||
|
char UBLOX_WAKE_MSG[] = "\xb5\x62\x06\x04\x04\x00\x01\x00\x09\x00\x18\x7a"; |
||||||
|
uart_ring *ur = get_ring_by_number(1); |
||||||
|
for (unsigned int i = 0; i < sizeof(UBLOX_WAKE_MSG) - 1U; i++) while (!putc(ur, UBLOX_WAKE_MSG[i])); |
||||||
|
} |
||||||
|
enable = true; |
||||||
|
} |
||||||
|
|
||||||
|
current_board->enable_can_transcievers(enable); |
||||||
|
|
||||||
|
// Switch EPS/GPS
|
||||||
|
if (enable) { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_ENABLED); |
||||||
|
} else { |
||||||
|
current_board->set_esp_gps_mode(ESP_GPS_DISABLED); |
||||||
|
} |
||||||
|
|
||||||
|
if(board_has_gmlan()){ |
||||||
|
// turn on GMLAN
|
||||||
|
set_gpio_output(GPIOB, 14, enable); |
||||||
|
set_gpio_output(GPIOB, 15, enable); |
||||||
|
} |
||||||
|
|
||||||
|
if(board_has_lin()){ |
||||||
|
// turn on LIN
|
||||||
|
set_gpio_output(GPIOB, 7, enable); |
||||||
|
set_gpio_output(GPIOA, 14, enable); |
||||||
|
} |
||||||
|
|
||||||
|
// Switch off IR and fan when in power saving
|
||||||
|
if(!enable){ |
||||||
|
current_board->set_ir_power(0U); |
||||||
|
current_board->set_fan_power(0U); |
||||||
|
}
|
||||||
|
|
||||||
|
power_save_status = state; |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,19 @@ |
|||||||
|
#define PROVISION_CHUNK_LEN 0x20 |
||||||
|
|
||||||
|
// WiFi SSID = 0x0 - 0x10
|
||||||
|
// WiFi password = 0x10 - 0x1C
|
||||||
|
// SHA1 checksum = 0x1C - 0x20
|
||||||
|
|
||||||
|
void get_provision_chunk(uint8_t *resp) { |
||||||
|
(void)memcpy(resp, (uint8_t *)0x1fff79e0, PROVISION_CHUNK_LEN); |
||||||
|
if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { |
||||||
|
(void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t chunk[PROVISION_CHUNK_LEN]; |
||||||
|
bool is_provisioned(void) { |
||||||
|
(void)memcpy(chunk, (uint8_t *)0x1fff79e0, PROVISION_CHUNK_LEN); |
||||||
|
return (memcmp(chunk, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) != 0); |
||||||
|
} |
||||||
|
|
@ -0,0 +1,330 @@ |
|||||||
|
// include first, needed by safety policies
|
||||||
|
#include "safety_declarations.h" |
||||||
|
// Include the actual safety policies.
|
||||||
|
#include "safety/safety_defaults.h" |
||||||
|
#include "safety/safety_honda.h" |
||||||
|
#include "safety/safety_toyota.h" |
||||||
|
#include "safety/safety_toyota_ipas.h" |
||||||
|
#include "safety/safety_tesla.h" |
||||||
|
#include "safety/safety_gm_ascm.h" |
||||||
|
#include "safety/safety_gm.h" |
||||||
|
#include "safety/safety_ford.h" |
||||||
|
#include "safety/safety_cadillac.h" |
||||||
|
#include "safety/safety_hyundai.h" |
||||||
|
#include "safety/safety_chrysler.h" |
||||||
|
#include "safety/safety_subaru.h" |
||||||
|
#include "safety/safety_mazda.h" |
||||||
|
#include "safety/safety_volkswagen.h" |
||||||
|
#include "safety/safety_elm327.h" |
||||||
|
|
||||||
|
// from cereal.car.CarParams.SafetyModel
|
||||||
|
#define SAFETY_SILENT 0U |
||||||
|
#define SAFETY_HONDA_NIDEC 1U |
||||||
|
#define SAFETY_TOYOTA 2U |
||||||
|
#define SAFETY_ELM327 3U |
||||||
|
#define SAFETY_GM 4U |
||||||
|
#define SAFETY_HONDA_BOSCH_GIRAFFE 5U |
||||||
|
#define SAFETY_FORD 6U |
||||||
|
#define SAFETY_CADILLAC 7U |
||||||
|
#define SAFETY_HYUNDAI 8U |
||||||
|
#define SAFETY_CHRYSLER 9U |
||||||
|
#define SAFETY_TESLA 10U |
||||||
|
#define SAFETY_SUBARU 11U |
||||||
|
#define SAFETY_MAZDA 13U |
||||||
|
#define SAFETY_VOLKSWAGEN 15U |
||||||
|
#define SAFETY_TOYOTA_IPAS 16U |
||||||
|
#define SAFETY_ALLOUTPUT 17U |
||||||
|
#define SAFETY_GM_ASCM 18U |
||||||
|
#define SAFETY_NOOUTPUT 19U |
||||||
|
#define SAFETY_HONDA_BOSCH_HARNESS 20U |
||||||
|
|
||||||
|
uint16_t current_safety_mode = SAFETY_SILENT; |
||||||
|
const safety_hooks *current_hooks = &nooutput_hooks; |
||||||
|
|
||||||
|
int safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push){ |
||||||
|
return current_hooks->rx(to_push); |
||||||
|
} |
||||||
|
|
||||||
|
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
return current_hooks->tx(to_send); |
||||||
|
} |
||||||
|
|
||||||
|
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){ |
||||||
|
return current_hooks->tx_lin(lin_num, data, len); |
||||||
|
} |
||||||
|
|
||||||
|
int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
return current_hooks->fwd(bus_num, to_fwd); |
||||||
|
} |
||||||
|
|
||||||
|
bool msg_allowed(int addr, int bus, const AddrBus addr_list[], int len) { |
||||||
|
bool allowed = false; |
||||||
|
for (int i = 0; i < len; i++) { |
||||||
|
if ((addr == addr_list[i].addr) && (bus == addr_list[i].bus)) { |
||||||
|
allowed = true; |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
return allowed; |
||||||
|
} |
||||||
|
|
||||||
|
// compute the time elapsed (in microseconds) from 2 counter samples
|
||||||
|
// case where ts < ts_last is ok: overflow is properly re-casted into uint32_t
|
||||||
|
uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { |
||||||
|
return ts - ts_last; |
||||||
|
} |
||||||
|
|
||||||
|
int get_addr_check_index(CAN_FIFOMailBox_TypeDef *to_push, AddrCheckStruct addr_list[], const int len) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
int index = -1; |
||||||
|
for (int i = 0; i < len; i++) { |
||||||
|
for (uint8_t j = 0U; addr_list[i].addr[j] != 0; j++) { |
||||||
|
if ((addr == addr_list[i].addr[j]) && (bus == addr_list[i].bus)) { |
||||||
|
index = i; |
||||||
|
goto Return; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
Return: |
||||||
|
return index; |
||||||
|
} |
||||||
|
|
||||||
|
// 1Hz safety function called by main. Now just a check for lagging safety messages
|
||||||
|
void safety_tick(const safety_hooks *hooks) { |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
if (hooks->addr_check != NULL) { |
||||||
|
for (int i=0; i < hooks->addr_check_len; i++) { |
||||||
|
uint32_t elapsed_time = get_ts_elapsed(ts, hooks->addr_check[i].last_timestamp); |
||||||
|
// lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep.
|
||||||
|
// Quite conservative to not risk false triggers.
|
||||||
|
// 2s of lag is worse case, since the function is called at 1Hz
|
||||||
|
bool lagging = elapsed_time > MAX(hooks->addr_check[i].expected_timestep * MAX_MISSED_MSGS, 1e6); |
||||||
|
hooks->addr_check[i].lagging = lagging; |
||||||
|
if (lagging) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void update_counter(AddrCheckStruct addr_list[], int index, uint8_t counter) { |
||||||
|
if (index != -1) { |
||||||
|
uint8_t expected_counter = (addr_list[index].last_counter + 1U) % (addr_list[index].max_counter + 1U); |
||||||
|
addr_list[index].wrong_counters += (expected_counter == counter) ? -1 : 1; |
||||||
|
addr_list[index].wrong_counters = MAX(MIN(addr_list[index].wrong_counters, MAX_WRONG_COUNTERS), 0); |
||||||
|
addr_list[index].last_counter = counter; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool is_msg_valid(AddrCheckStruct addr_list[], int index) { |
||||||
|
bool valid = true; |
||||||
|
if (index != -1) { |
||||||
|
if ((!addr_list[index].valid_checksum) || (addr_list[index].wrong_counters >= MAX_WRONG_COUNTERS)) { |
||||||
|
valid = false; |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
return valid; |
||||||
|
} |
||||||
|
|
||||||
|
void update_addr_timestamp(AddrCheckStruct addr_list[], int index) { |
||||||
|
if (index != -1) { |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
addr_list[index].last_timestamp = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool addr_safety_check(CAN_FIFOMailBox_TypeDef *to_push, |
||||||
|
AddrCheckStruct *rx_checks, |
||||||
|
const int rx_checks_len, |
||||||
|
uint8_t (*get_checksum)(CAN_FIFOMailBox_TypeDef *to_push), |
||||||
|
uint8_t (*compute_checksum)(CAN_FIFOMailBox_TypeDef *to_push), |
||||||
|
uint8_t (*get_counter)(CAN_FIFOMailBox_TypeDef *to_push)) { |
||||||
|
|
||||||
|
int index = get_addr_check_index(to_push, rx_checks, rx_checks_len); |
||||||
|
update_addr_timestamp(rx_checks, index); |
||||||
|
|
||||||
|
if (index != -1) { |
||||||
|
// checksum check
|
||||||
|
if ((get_checksum != NULL) && (compute_checksum != NULL)) { |
||||||
|
if (rx_checks[index].check_checksum) { |
||||||
|
uint8_t checksum = get_checksum(to_push); |
||||||
|
uint8_t checksum_comp = compute_checksum(to_push); |
||||||
|
rx_checks[index].valid_checksum = checksum_comp == checksum; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// counter check
|
||||||
|
if (get_counter != NULL) { |
||||||
|
if (rx_checks[index].max_counter > 0U) { |
||||||
|
uint8_t counter = get_counter(to_push); |
||||||
|
update_counter(rx_checks, index, counter); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return is_msg_valid(rx_checks, index); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
typedef struct { |
||||||
|
uint16_t id; |
||||||
|
const safety_hooks *hooks; |
||||||
|
} safety_hook_config; |
||||||
|
|
||||||
|
const safety_hook_config safety_hook_registry[] = { |
||||||
|
{SAFETY_SILENT, &nooutput_hooks}, |
||||||
|
{SAFETY_HONDA_NIDEC, &honda_nidec_hooks}, |
||||||
|
{SAFETY_TOYOTA, &toyota_hooks}, |
||||||
|
{SAFETY_ELM327, &elm327_hooks}, |
||||||
|
{SAFETY_GM, &gm_hooks}, |
||||||
|
{SAFETY_HONDA_BOSCH_GIRAFFE, &honda_bosch_giraffe_hooks}, |
||||||
|
{SAFETY_HONDA_BOSCH_HARNESS, &honda_bosch_harness_hooks}, |
||||||
|
{SAFETY_HYUNDAI, &hyundai_hooks}, |
||||||
|
{SAFETY_CHRYSLER, &chrysler_hooks}, |
||||||
|
{SAFETY_SUBARU, &subaru_hooks}, |
||||||
|
{SAFETY_MAZDA, &mazda_hooks}, |
||||||
|
{SAFETY_VOLKSWAGEN, &volkswagen_hooks}, |
||||||
|
{SAFETY_NOOUTPUT, &nooutput_hooks}, |
||||||
|
#ifdef ALLOW_DEBUG |
||||||
|
{SAFETY_CADILLAC, &cadillac_hooks}, |
||||||
|
{SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, |
||||||
|
{SAFETY_TESLA, &tesla_hooks}, |
||||||
|
{SAFETY_ALLOUTPUT, &alloutput_hooks}, |
||||||
|
{SAFETY_GM_ASCM, &gm_ascm_hooks}, |
||||||
|
{SAFETY_FORD, &ford_hooks}, |
||||||
|
#endif |
||||||
|
}; |
||||||
|
|
||||||
|
int set_safety_hooks(uint16_t mode, int16_t param) { |
||||||
|
safety_mode_cnt = 0U; // reset safety mode timer
|
||||||
|
int set_status = -1; // not set
|
||||||
|
int hook_config_count = sizeof(safety_hook_registry) / sizeof(safety_hook_config); |
||||||
|
for (int i = 0; i < hook_config_count; i++) { |
||||||
|
if (safety_hook_registry[i].id == mode) { |
||||||
|
current_hooks = safety_hook_registry[i].hooks; |
||||||
|
current_safety_mode = safety_hook_registry[i].id; |
||||||
|
set_status = 0; // set
|
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
if ((set_status == 0) && (current_hooks->init != NULL)) { |
||||||
|
current_hooks->init(param); |
||||||
|
} |
||||||
|
return set_status; |
||||||
|
} |
||||||
|
|
||||||
|
// convert a trimmed integer to signed 32 bit int
|
||||||
|
int to_signed(int d, int bits) { |
||||||
|
int d_signed = d; |
||||||
|
if (d >= (1 << MAX((bits - 1), 0))) { |
||||||
|
d_signed = d - (1 << MAX(bits, 0)); |
||||||
|
} |
||||||
|
return d_signed; |
||||||
|
} |
||||||
|
|
||||||
|
// given a new sample, update the smaple_t struct
|
||||||
|
void update_sample(struct sample_t *sample, int sample_new) { |
||||||
|
int sample_size = sizeof(sample->values) / sizeof(sample->values[0]); |
||||||
|
for (int i = sample_size - 1; i > 0; i--) { |
||||||
|
sample->values[i] = sample->values[i-1]; |
||||||
|
} |
||||||
|
sample->values[0] = sample_new; |
||||||
|
|
||||||
|
// get the minimum and maximum measured samples
|
||||||
|
sample->min = sample->values[0]; |
||||||
|
sample->max = sample->values[0]; |
||||||
|
for (int i = 1; i < sample_size; i++) { |
||||||
|
if (sample->values[i] < sample->min) { |
||||||
|
sample->min = sample->values[i]; |
||||||
|
} |
||||||
|
if (sample->values[i] > sample->max) { |
||||||
|
sample->max = sample->values[i]; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { |
||||||
|
return (val > MAX_VAL) || (val < MIN_VAL); |
||||||
|
} |
||||||
|
|
||||||
|
// check that commanded value isn't too far from measured
|
||||||
|
bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, |
||||||
|
const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) { |
||||||
|
|
||||||
|
// *** val rate limit check ***
|
||||||
|
int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; |
||||||
|
int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; |
||||||
|
|
||||||
|
// if we've exceeded the meas val, we must start moving toward 0
|
||||||
|
int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, MAX(val_meas->max, 0) + MAX_ERROR)); |
||||||
|
int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, MIN(val_meas->min, 0) - MAX_ERROR)); |
||||||
|
|
||||||
|
// check for violation
|
||||||
|
return (val < lowest_allowed) || (val > highest_allowed); |
||||||
|
} |
||||||
|
|
||||||
|
// check that commanded value isn't fighting against driver
|
||||||
|
bool driver_limit_check(int val, int val_last, struct sample_t *val_driver, |
||||||
|
const int MAX_VAL, const int MAX_RATE_UP, const int MAX_RATE_DOWN, |
||||||
|
const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { |
||||||
|
|
||||||
|
int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; |
||||||
|
int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; |
||||||
|
|
||||||
|
int driver_max_limit = MAX_VAL + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR; |
||||||
|
int driver_min_limit = -MAX_VAL + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR; |
||||||
|
|
||||||
|
// if we've exceeded the applied torque, we must start moving toward 0
|
||||||
|
int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, |
||||||
|
MAX(driver_max_limit, 0))); |
||||||
|
int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, |
||||||
|
MIN(driver_min_limit, 0))); |
||||||
|
|
||||||
|
// check for violation
|
||||||
|
return (val < lowest_allowed) || (val > highest_allowed); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
// real time check, mainly used for steer torque rate limiter
|
||||||
|
bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
int highest_val = MAX(val_last, 0) + MAX_RT_DELTA; |
||||||
|
int lowest_val = MIN(val_last, 0) - MAX_RT_DELTA; |
||||||
|
|
||||||
|
// check for violation
|
||||||
|
return (val < lowest_val) || (val > highest_val); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
// interp function that holds extreme values
|
||||||
|
float interpolate(struct lookup_t xy, float x) { |
||||||
|
|
||||||
|
int size = sizeof(xy.x) / sizeof(xy.x[0]); |
||||||
|
float ret = xy.y[size - 1]; // default output is last point
|
||||||
|
|
||||||
|
// x is lower than the first point in the x array. Return the first point
|
||||||
|
if (x <= xy.x[0]) { |
||||||
|
ret = xy.y[0]; |
||||||
|
|
||||||
|
} else { |
||||||
|
// find the index such that (xy.x[i] <= x < xy.x[i+1]) and linearly interp
|
||||||
|
for (int i=0; i < (size - 1); i++) { |
||||||
|
if (x < xy.x[i+1]) { |
||||||
|
float x0 = xy.x[i]; |
||||||
|
float y0 = xy.y[i]; |
||||||
|
float dx = xy.x[i+1] - x0; |
||||||
|
float dy = xy.y[i+1] - y0; |
||||||
|
// dx should not be zero as xy.x is supposed to be monotonic
|
||||||
|
if (dx <= 0.) { |
||||||
|
dx = 0.0001; |
||||||
|
} |
||||||
|
ret = (dy * (x - x0) / dx) + y0; |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return ret; |
||||||
|
} |
@ -0,0 +1,125 @@ |
|||||||
|
#define CADILLAC_TORQUE_MSG_N 4 // 4 torque messages: 0x151, 0x152, 0x153, 0x154
|
||||||
|
|
||||||
|
const AddrBus CADILLAC_TX_MSGS[] = {{0x151, 2}, {0x152, 0}, {0x153, 2}, {0x154, 0}}; |
||||||
|
const int CADILLAC_MAX_STEER = 150; // 1s
|
||||||
|
// real time torque limit to prevent controls spamming
|
||||||
|
// the real time limit is 1500/sec
|
||||||
|
const int CADILLAC_MAX_RT_DELTA = 75; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t CADILLAC_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int CADILLAC_MAX_RATE_UP = 2; |
||||||
|
const int CADILLAC_MAX_RATE_DOWN = 5; |
||||||
|
const int CADILLAC_DRIVER_TORQUE_ALLOWANCE = 50; |
||||||
|
const int CADILLAC_DRIVER_TORQUE_FACTOR = 4; |
||||||
|
|
||||||
|
int cadillac_cruise_engaged_last = 0; |
||||||
|
int cadillac_rt_torque_last = 0; |
||||||
|
const int cadillac_torque_msgs_n = 4; |
||||||
|
int cadillac_desired_torque_last[CADILLAC_TORQUE_MSG_N] = {0}; |
||||||
|
uint32_t cadillac_ts_last = 0; |
||||||
|
bool cadillac_supercruise_on = 0; |
||||||
|
struct sample_t cadillac_torque_driver; // last few driver torques measured
|
||||||
|
|
||||||
|
int cadillac_get_torque_idx(int addr, int array_size) { |
||||||
|
return MIN(MAX(addr - 0x151, 0), array_size); // 0x151 is id 0, 0x152 is id 1 and so on...
|
||||||
|
} |
||||||
|
|
||||||
|
static int cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (addr == 356) { |
||||||
|
int torque_driver_new = ((GET_BYTE(to_push, 0) & 0x7U) << 8) | (GET_BYTE(to_push, 1)); |
||||||
|
|
||||||
|
torque_driver_new = to_signed(torque_driver_new, 11); |
||||||
|
// update array of samples
|
||||||
|
update_sample(&cadillac_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if ((addr == 0x370) && (bus == 0)) { |
||||||
|
int cruise_engaged = GET_BYTE(to_push, 2) & 0x80; // bit 23
|
||||||
|
if (cruise_engaged && !cadillac_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
if (!cruise_engaged) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
cadillac_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// know supercruise mode and block openpilot msgs if on
|
||||||
|
if ((addr == 0x152) || (addr == 0x154)) { |
||||||
|
cadillac_supercruise_on = (GET_BYTE(to_push, 4) & 0x10) != 0; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, CADILLAC_TX_MSGS, sizeof(CADILLAC_TX_MSGS) / sizeof(CADILLAC_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// steer cmd checks
|
||||||
|
if ((addr == 0x151) || (addr == 0x152) || (addr == 0x153) || (addr == 0x154)) { |
||||||
|
int desired_torque = ((GET_BYTE(to_send, 0) & 0x3f) << 8) | GET_BYTE(to_send, 1); |
||||||
|
int violation = 0; |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
int idx = cadillac_get_torque_idx(addr, CADILLAC_TORQUE_MSG_N); |
||||||
|
desired_torque = to_signed(desired_torque, 14); |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, CADILLAC_MAX_STEER, -CADILLAC_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
int desired_torque_last = cadillac_desired_torque_last[idx]; |
||||||
|
violation |= driver_limit_check(desired_torque, desired_torque_last, &cadillac_torque_driver, |
||||||
|
CADILLAC_MAX_STEER, CADILLAC_MAX_RATE_UP, CADILLAC_MAX_RATE_DOWN, |
||||||
|
CADILLAC_DRIVER_TORQUE_ALLOWANCE, CADILLAC_DRIVER_TORQUE_FACTOR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
cadillac_desired_torque_last[idx] = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, cadillac_rt_torque_last, CADILLAC_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, cadillac_ts_last); |
||||||
|
if (ts_elapsed > CADILLAC_RT_INTERVAL) { |
||||||
|
cadillac_rt_torque_last = desired_torque; |
||||||
|
cadillac_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
cadillac_desired_torque_last[idx] = 0; |
||||||
|
cadillac_rt_torque_last = 0; |
||||||
|
cadillac_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation || cadillac_supercruise_on) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks cadillac_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = cadillac_rx_hook, |
||||||
|
.tx = cadillac_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,152 @@ |
|||||||
|
const int CHRYSLER_MAX_STEER = 261; |
||||||
|
const int CHRYSLER_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t CHRYSLER_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int CHRYSLER_MAX_RATE_UP = 3; |
||||||
|
const int CHRYSLER_MAX_RATE_DOWN = 3; |
||||||
|
const int CHRYSLER_MAX_TORQUE_ERROR = 80; // max torque cmd in excess of torque motor
|
||||||
|
const AddrBus CHRYSLER_TX_MSGS[] = {{571, 0}, {658, 0}, {678, 0}}; |
||||||
|
|
||||||
|
// TODO: do checksum and counter checks
|
||||||
|
AddrCheckStruct chrysler_rx_checks[] = { |
||||||
|
{.addr = {544}, .bus = 0, .expected_timestep = 10000U}, |
||||||
|
{.addr = {500}, .bus = 0, .expected_timestep = 20000U}, |
||||||
|
}; |
||||||
|
const int CHRYSLER_RX_CHECK_LEN = sizeof(chrysler_rx_checks) / sizeof(chrysler_rx_checks[0]); |
||||||
|
|
||||||
|
int chrysler_rt_torque_last = 0; |
||||||
|
int chrysler_desired_torque_last = 0; |
||||||
|
int chrysler_cruise_engaged_last = 0; |
||||||
|
uint32_t chrysler_ts_last = 0; |
||||||
|
struct sample_t chrysler_torque_meas; // last few torques measured
|
||||||
|
|
||||||
|
static int chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
// Measured eps torque
|
||||||
|
if (addr == 544) { |
||||||
|
int torque_meas_new = ((GET_BYTE(to_push, 4) & 0x7U) << 8) + GET_BYTE(to_push, 5) - 1024U; |
||||||
|
|
||||||
|
// update array of samples
|
||||||
|
update_sample(&chrysler_torque_meas, torque_meas_new); |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if (addr == 0x1F4) { |
||||||
|
int cruise_engaged = ((GET_BYTE(to_push, 2) & 0x38) >> 3) == 7; |
||||||
|
if (cruise_engaged && !chrysler_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
if (!cruise_engaged) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
chrysler_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: add gas pressed check
|
||||||
|
|
||||||
|
// check if stock camera ECU is on bus 0
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && (addr == 0x292)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, CHRYSLER_TX_MSGS, sizeof(CHRYSLER_TX_MSGS) / sizeof(CHRYSLER_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// LKA STEER
|
||||||
|
if (addr == 0x292) { |
||||||
|
int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1) - 1024U; |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
bool violation = 0; |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, CHRYSLER_MAX_STEER, -CHRYSLER_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
violation |= dist_to_meas_check(desired_torque, chrysler_desired_torque_last, |
||||||
|
&chrysler_torque_meas, CHRYSLER_MAX_RATE_UP, CHRYSLER_MAX_RATE_DOWN, CHRYSLER_MAX_TORQUE_ERROR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
chrysler_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, chrysler_rt_torque_last, CHRYSLER_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, chrysler_ts_last); |
||||||
|
if (ts_elapsed > CHRYSLER_RT_INTERVAL) { |
||||||
|
chrysler_rt_torque_last = desired_torque; |
||||||
|
chrysler_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
chrysler_desired_torque_last = 0; |
||||||
|
chrysler_rt_torque_last = 0; |
||||||
|
chrysler_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// FORCE CANCEL: only the cancel button press is allowed
|
||||||
|
if (addr == 571) { |
||||||
|
if (GET_BYTE(to_send, 0) != 1) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int chrysler_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
|
||||||
|
int bus_fwd = -1; |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
|
||||||
|
if (!relay_malfunction) { |
||||||
|
// forward CAN 0 -> 2 so stock LKAS camera sees messages
|
||||||
|
if (bus_num == 0) { |
||||||
|
bus_fwd = 2; |
||||||
|
} |
||||||
|
// forward all messages from camera except LKAS_COMMAND and LKAS_HUD
|
||||||
|
if ((bus_num == 2) && (addr != 658) && (addr != 678)) { |
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
const safety_hooks chrysler_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = chrysler_rx_hook, |
||||||
|
.tx = chrysler_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = chrysler_fwd_hook, |
||||||
|
.addr_check = chrysler_rx_checks, |
||||||
|
.addr_check_len = sizeof(chrysler_rx_checks) / sizeof(chrysler_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,66 @@ |
|||||||
|
int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
UNUSED(to_push); |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
// *** no output safety mode ***
|
||||||
|
|
||||||
|
static void nooutput_init(int16_t param) { |
||||||
|
UNUSED(param); |
||||||
|
controls_allowed = false; |
||||||
|
relay_malfunction = false; |
||||||
|
} |
||||||
|
|
||||||
|
static int nooutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
UNUSED(to_send); |
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { |
||||||
|
UNUSED(lin_num); |
||||||
|
UNUSED(data); |
||||||
|
UNUSED(len); |
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
static int default_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
UNUSED(bus_num); |
||||||
|
UNUSED(to_fwd); |
||||||
|
return -1; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks nooutput_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = default_rx_hook, |
||||||
|
.tx = nooutput_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
}; |
||||||
|
|
||||||
|
// *** all output safety mode ***
|
||||||
|
|
||||||
|
static void alloutput_init(int16_t param) { |
||||||
|
UNUSED(param); |
||||||
|
controls_allowed = true; |
||||||
|
relay_malfunction = false; |
||||||
|
} |
||||||
|
|
||||||
|
static int alloutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
UNUSED(to_send); |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { |
||||||
|
UNUSED(lin_num); |
||||||
|
UNUSED(data); |
||||||
|
UNUSED(len); |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks alloutput_hooks = { |
||||||
|
.init = alloutput_init, |
||||||
|
.rx = default_rx_hook, |
||||||
|
.tx = alloutput_tx_hook, |
||||||
|
.tx_lin = alloutput_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,42 @@ |
|||||||
|
static int elm327_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int len = GET_LEN(to_send); |
||||||
|
|
||||||
|
//All ISO 15765-4 messages must be 8 bytes long
|
||||||
|
if (len != 8) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
//Check valid 29 bit send addresses for ISO 15765-4
|
||||||
|
//Check valid 11 bit send addresses for ISO 15765-4
|
||||||
|
if ((addr != 0x18DB33F1) && ((addr & 0x1FFF00FF) != 0x18DA00F1) && |
||||||
|
((addr & 0x1FFFFF00) != 0x700)) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { |
||||||
|
int tx = 1; |
||||||
|
if (lin_num != 0) { |
||||||
|
tx = 0; //Only operate on LIN 0, aka serial 2
|
||||||
|
} |
||||||
|
if ((len < 5) || (len > 11)) { |
||||||
|
tx = 0; //Valid KWP size
|
||||||
|
} |
||||||
|
if (!(((data[0] & 0xF8U) == 0xC0U) && ((data[0] & 0x07U) != 0U) && |
||||||
|
(data[1] == 0x33U) && (data[2] == 0xF1U))) { |
||||||
|
tx = 0; //Bad msg
|
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks elm327_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = default_rx_hook, |
||||||
|
.tx = elm327_tx_hook, |
||||||
|
.tx_lin = elm327_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,114 @@ |
|||||||
|
// board enforces
|
||||||
|
// in-state
|
||||||
|
// accel set/resume
|
||||||
|
// out-state
|
||||||
|
// cancel button
|
||||||
|
// accel rising edge
|
||||||
|
// brake rising edge
|
||||||
|
// brake > 0mph
|
||||||
|
|
||||||
|
int ford_brake_prev = 0; |
||||||
|
int ford_gas_prev = 0; |
||||||
|
bool ford_moving = false; |
||||||
|
|
||||||
|
static int ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
|
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
|
||||||
|
if (addr == 0x217) { |
||||||
|
// wheel speeds are 14 bits every 16
|
||||||
|
ford_moving = false; |
||||||
|
for (int i = 0; i < 8; i += 2) { |
||||||
|
ford_moving |= GET_BYTE(to_push, i) | (GET_BYTE(to_push, (int)(i + 1)) & 0xFCU); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// state machine to enter and exit controls
|
||||||
|
if (addr == 0x83) { |
||||||
|
bool cancel = GET_BYTE(to_push, 1) & 0x1; |
||||||
|
bool set_or_resume = GET_BYTE(to_push, 3) & 0x30; |
||||||
|
if (cancel) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
if (set_or_resume) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of brake press or on brake press when
|
||||||
|
// speed > 0
|
||||||
|
if (addr == 0x165) { |
||||||
|
int brake = GET_BYTE(to_push, 0) & 0x20; |
||||||
|
if (brake && (!(ford_brake_prev) || ford_moving)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
ford_brake_prev = brake; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press
|
||||||
|
if (addr == 0x204) { |
||||||
|
int gas = (GET_BYTE(to_push, 0) & 0x03) | GET_BYTE(to_push, 1); |
||||||
|
if (gas && !(ford_gas_prev)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
ford_gas_prev = gas; |
||||||
|
} |
||||||
|
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && (addr == 0x3CA)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
// all commands: just steering
|
||||||
|
// if controls_allowed and no pedals pressed
|
||||||
|
// allow all commands up to limit
|
||||||
|
// else
|
||||||
|
// block all commands that produce actuation
|
||||||
|
|
||||||
|
static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
|
||||||
|
// disallow actuator commands if gas or brake (with vehicle moving) are pressed
|
||||||
|
// and the the latching controls_allowed flag is True
|
||||||
|
int pedal_pressed = ford_gas_prev || (ford_brake_prev && ford_moving); |
||||||
|
bool current_controls_allowed = controls_allowed && !(pedal_pressed); |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// STEER: safety check
|
||||||
|
if (addr == 0x3CA) { |
||||||
|
if (!current_controls_allowed) { |
||||||
|
// bits 7-4 need to be 0xF to disallow lkas commands
|
||||||
|
if ((GET_BYTE(to_send, 0) & 0xF0) != 0xF0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// FORCE CANCEL: safety check only relevant when spamming the cancel button
|
||||||
|
// ensuring that set and resume aren't sent
|
||||||
|
if (addr == 0x83) { |
||||||
|
if ((GET_BYTE(to_send, 3) & 0x30) != 0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// 1 allows the message through
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: keep camera on bus 2 and make a fwd_hook
|
||||||
|
|
||||||
|
const safety_hooks ford_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = ford_rx_hook, |
||||||
|
.tx = ford_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,235 @@ |
|||||||
|
// board enforces
|
||||||
|
// in-state
|
||||||
|
// accel set/resume
|
||||||
|
// out-state
|
||||||
|
// cancel button
|
||||||
|
// regen paddle
|
||||||
|
// accel rising edge
|
||||||
|
// brake rising edge
|
||||||
|
// brake > 0mph
|
||||||
|
|
||||||
|
const int GM_MAX_STEER = 300; |
||||||
|
const int GM_MAX_RT_DELTA = 128; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t GM_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int GM_MAX_RATE_UP = 7; |
||||||
|
const int GM_MAX_RATE_DOWN = 17; |
||||||
|
const int GM_DRIVER_TORQUE_ALLOWANCE = 50; |
||||||
|
const int GM_DRIVER_TORQUE_FACTOR = 4; |
||||||
|
const int GM_MAX_GAS = 3072; |
||||||
|
const int GM_MAX_REGEN = 1404; |
||||||
|
const int GM_MAX_BRAKE = 350; |
||||||
|
const AddrBus GM_TX_MSGS[] = {{384, 0}, {1033, 0}, {1034, 0}, {715, 0}, {880, 0}, // pt bus
|
||||||
|
{161, 1}, {774, 1}, {776, 1}, {784, 1}, // obs bus
|
||||||
|
{789, 2}, // ch bus
|
||||||
|
{0x104c006c, 3}, {0x10400060, 3}}; // gmlan
|
||||||
|
|
||||||
|
// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now.
|
||||||
|
AddrCheckStruct gm_rx_checks[] = { |
||||||
|
{.addr = {388}, .bus = 0, .expected_timestep = 100000U}, |
||||||
|
{.addr = {842}, .bus = 0, .expected_timestep = 100000U}, |
||||||
|
{.addr = {481}, .bus = 0, .expected_timestep = 100000U}, |
||||||
|
{.addr = {241}, .bus = 0, .expected_timestep = 100000U}, |
||||||
|
{.addr = {417}, .bus = 0, .expected_timestep = 100000U}, |
||||||
|
}; |
||||||
|
const int GM_RX_CHECK_LEN = sizeof(gm_rx_checks) / sizeof(gm_rx_checks[0]); |
||||||
|
|
||||||
|
int gm_brake_prev = 0; |
||||||
|
int gm_gas_prev = 0; |
||||||
|
bool gm_moving = false; |
||||||
|
int gm_rt_torque_last = 0; |
||||||
|
int gm_desired_torque_last = 0; |
||||||
|
uint32_t gm_ts_last = 0; |
||||||
|
struct sample_t gm_torque_driver; // last few driver torques measured
|
||||||
|
|
||||||
|
static int gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (addr == 388) { |
||||||
|
int torque_driver_new = ((GET_BYTE(to_push, 6) & 0x7) << 8) | GET_BYTE(to_push, 7); |
||||||
|
torque_driver_new = to_signed(torque_driver_new, 11); |
||||||
|
// update array of samples
|
||||||
|
update_sample(&gm_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// sample speed, really only care if car is moving or not
|
||||||
|
// rear left wheel speed
|
||||||
|
if (addr == 842) { |
||||||
|
gm_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1); |
||||||
|
} |
||||||
|
|
||||||
|
// ACC steering wheel buttons
|
||||||
|
if (addr == 481) { |
||||||
|
int button = (GET_BYTE(to_push, 5) & 0x70) >> 4; |
||||||
|
switch (button) { |
||||||
|
case 2: // resume
|
||||||
|
case 3: // set
|
||||||
|
controls_allowed = 1; |
||||||
|
break; |
||||||
|
case 6: // cancel
|
||||||
|
controls_allowed = 0; |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; // any other button is irrelevant
|
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of brake press or on brake press when
|
||||||
|
// speed > 0
|
||||||
|
if (addr == 241) { |
||||||
|
int brake = GET_BYTE(to_push, 1); |
||||||
|
// Brake pedal's potentiometer returns near-zero reading
|
||||||
|
// even when pedal is not pressed
|
||||||
|
if (brake < 10) { |
||||||
|
brake = 0; |
||||||
|
} |
||||||
|
if (brake && (!gm_brake_prev || gm_moving)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
gm_brake_prev = brake; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press
|
||||||
|
if (addr == 417) { |
||||||
|
int gas = GET_BYTE(to_push, 6); |
||||||
|
if (gas && !gm_gas_prev) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
gm_gas_prev = gas; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on regen paddle
|
||||||
|
if (addr == 189) { |
||||||
|
bool regen = GET_BYTE(to_push, 0) & 0x20; |
||||||
|
if (regen) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// Check if ASCM or LKA camera are online
|
||||||
|
// on powertrain bus.
|
||||||
|
// 384 = ASCMLKASteeringCmd
|
||||||
|
// 715 = ASCMGasRegenCmd
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && ((addr == 384) || (addr == 715))) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
// all commands: gas/regen, friction brake and steering
|
||||||
|
// if controls_allowed and no pedals pressed
|
||||||
|
// allow all commands up to limit
|
||||||
|
// else
|
||||||
|
// block all commands that produce actuation
|
||||||
|
|
||||||
|
static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, GM_TX_MSGS, sizeof(GM_TX_MSGS)/sizeof(GM_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// disallow actuator commands if gas or brake (with vehicle moving) are pressed
|
||||||
|
// and the the latching controls_allowed flag is True
|
||||||
|
int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_moving); |
||||||
|
bool current_controls_allowed = controls_allowed && !pedal_pressed; |
||||||
|
|
||||||
|
// BRAKE: safety check
|
||||||
|
if (addr == 789) { |
||||||
|
int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1); |
||||||
|
brake = (0x1000 - brake) & 0xFFF; |
||||||
|
if (!current_controls_allowed) { |
||||||
|
if (brake != 0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
if (brake > GM_MAX_BRAKE) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// LKA STEER: safety check
|
||||||
|
if (addr == 384) { |
||||||
|
int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1); |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
bool violation = 0; |
||||||
|
desired_torque = to_signed(desired_torque, 11); |
||||||
|
|
||||||
|
if (current_controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, GM_MAX_STEER, -GM_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
violation |= driver_limit_check(desired_torque, gm_desired_torque_last, &gm_torque_driver, |
||||||
|
GM_MAX_STEER, GM_MAX_RATE_UP, GM_MAX_RATE_DOWN, |
||||||
|
GM_DRIVER_TORQUE_ALLOWANCE, GM_DRIVER_TORQUE_FACTOR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
gm_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, gm_rt_torque_last, GM_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, gm_ts_last); |
||||||
|
if (ts_elapsed > GM_RT_INTERVAL) { |
||||||
|
gm_rt_torque_last = desired_torque; |
||||||
|
gm_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!current_controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !current_controls_allowed) { |
||||||
|
gm_desired_torque_last = 0; |
||||||
|
gm_rt_torque_last = 0; |
||||||
|
gm_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// GAS/REGEN: safety check
|
||||||
|
if (addr == 715) { |
||||||
|
int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3); |
||||||
|
// Disabled message is !engaged with gas
|
||||||
|
// value that corresponds to max regen.
|
||||||
|
if (!current_controls_allowed) { |
||||||
|
bool apply = GET_BYTE(to_send, 0) & 1U; |
||||||
|
if (apply || (gas_regen != GM_MAX_REGEN)) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
if (gas_regen > GM_MAX_GAS) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// 1 allows the message through
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
const safety_hooks gm_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = gm_rx_hook, |
||||||
|
.tx = gm_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = default_fwd_hook, |
||||||
|
.addr_check = gm_rx_checks, |
||||||
|
.addr_check_len = sizeof(gm_rx_checks) / sizeof(gm_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,43 @@ |
|||||||
|
// BUS 0 is on the LKAS module (ASCM) side
|
||||||
|
// BUS 2 is on the actuator (EPS) side
|
||||||
|
|
||||||
|
static int gm_ascm_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
|
||||||
|
int bus_fwd = -1; |
||||||
|
|
||||||
|
if (bus_num == 0) { |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
bus_fwd = 2; |
||||||
|
// do not propagate lkas messages from ascm to actuators, unless supercruise is on
|
||||||
|
// block 0x152 and 0x154, which are the lkas command from ASCM1 and ASCM2
|
||||||
|
// block 0x315 and 0x2cb, which are the brake and accel commands from ASCM1
|
||||||
|
//if ((addr == 0x152) || (addr == 0x154) || (addr == 0x315) || (addr == 0x2cb)) {
|
||||||
|
if ((addr == 0x152) || (addr == 0x154)) { |
||||||
|
bool supercruise_on = (GET_BYTE(to_fwd, 4) & 0x10) != 0; // bit 36
|
||||||
|
if (!supercruise_on) { |
||||||
|
bus_fwd = -1; |
||||||
|
} |
||||||
|
} |
||||||
|
if ((addr == 0x151) || (addr == 0x153) || (addr == 0x314)) { |
||||||
|
// on the chassis bus, the OBDII port is on the module side, so we need to read
|
||||||
|
// the lkas messages sent by openpilot (put on unused 0x151 ane 0x153 addrs) and send it to
|
||||||
|
// the actuator as 0x152 and 0x154
|
||||||
|
uint32_t fwd_addr = addr + 1; |
||||||
|
to_fwd->RIR = (fwd_addr << 21) | (to_fwd->RIR & 0x1fffff); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (bus_num == 2) { |
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
|
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks gm_ascm_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = default_rx_hook, |
||||||
|
.tx = alloutput_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = gm_ascm_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,347 @@ |
|||||||
|
// board enforces
|
||||||
|
// in-state
|
||||||
|
// accel set/resume
|
||||||
|
// out-state
|
||||||
|
// cancel button
|
||||||
|
// accel rising edge
|
||||||
|
// brake rising edge
|
||||||
|
// brake > 0mph
|
||||||
|
const AddrBus HONDA_N_TX_MSGS[] = {{0xE4, 0}, {0x194, 0}, {0x1FA, 0}, {0x200, 0}, {0x30C, 0}, {0x33D, 0}}; |
||||||
|
const AddrBus HONDA_BG_TX_MSGS[] = {{0xE4, 2}, {0x296, 0}, {0x33D, 2}}; // Bosch Giraffe
|
||||||
|
const AddrBus HONDA_BH_TX_MSGS[] = {{0xE4, 0}, {0x296, 1}, {0x33D, 0}}; // Bosch Harness
|
||||||
|
const int HONDA_GAS_INTERCEPTOR_THRESHOLD = 328; // ratio between offset and gain from dbc file
|
||||||
|
|
||||||
|
// Nidec and Bosch giraffe have pt on bus 0
|
||||||
|
AddrCheckStruct honda_rx_checks[] = { |
||||||
|
{.addr = {0x1A6, 0x296}, .bus = 0, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, |
||||||
|
{.addr = { 0x158}, .bus = 0, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, |
||||||
|
{.addr = { 0x17C}, .bus = 0, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, |
||||||
|
}; |
||||||
|
const int HONDA_RX_CHECKS_LEN = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]); |
||||||
|
|
||||||
|
// Bosch harness has pt on bus 1
|
||||||
|
AddrCheckStruct honda_bh_rx_checks[] = { |
||||||
|
{.addr = {0x296}, .bus = 1, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, |
||||||
|
{.addr = {0x158}, .bus = 1, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, |
||||||
|
{.addr = {0x17C}, .bus = 1, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, |
||||||
|
}; |
||||||
|
const int HONDA_BH_RX_CHECKS_LEN = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]); |
||||||
|
|
||||||
|
int honda_brake = 0; |
||||||
|
int honda_gas_prev = 0; |
||||||
|
bool honda_brake_pressed_prev = false; |
||||||
|
bool honda_moving = false; |
||||||
|
bool honda_alt_brake_msg = false; |
||||||
|
bool honda_fwd_brake = false; |
||||||
|
enum {HONDA_N_HW, HONDA_BG_HW, HONDA_BH_HW} honda_hw = HONDA_N_HW; |
||||||
|
|
||||||
|
|
||||||
|
static uint8_t honda_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int checksum_byte = GET_LEN(to_push) - 1; |
||||||
|
return (uint8_t)(GET_BYTE(to_push, checksum_byte)) & 0xFU; |
||||||
|
} |
||||||
|
|
||||||
|
static uint8_t honda_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int len = GET_LEN(to_push); |
||||||
|
uint8_t checksum = 0U; |
||||||
|
unsigned int addr = GET_ADDR(to_push); |
||||||
|
while (addr > 0U) { |
||||||
|
checksum += (addr & 0xFU); addr >>= 4; |
||||||
|
} |
||||||
|
for (int j = 0; (j < len); j++) { |
||||||
|
uint8_t byte = GET_BYTE(to_push, j); |
||||||
|
checksum += (byte & 0xFU) + (byte >> 4U); |
||||||
|
if (j == (len - 1)) { |
||||||
|
checksum -= (byte & 0xFU); // remove checksum in message
|
||||||
|
} |
||||||
|
} |
||||||
|
return (8U - checksum) & 0xFU; |
||||||
|
} |
||||||
|
|
||||||
|
static uint8_t honda_get_counter(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int counter_byte = GET_LEN(to_push) - 1; |
||||||
|
return ((uint8_t)(GET_BYTE(to_push, counter_byte)) >> 4U) & 0x3U; |
||||||
|
} |
||||||
|
|
||||||
|
static int honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
|
||||||
|
bool valid; |
||||||
|
if (honda_hw == HONDA_BH_HW) { |
||||||
|
valid = addr_safety_check(to_push, honda_bh_rx_checks, HONDA_BH_RX_CHECKS_LEN, |
||||||
|
honda_get_checksum, honda_compute_checksum, honda_get_counter); |
||||||
|
} else { |
||||||
|
valid = addr_safety_check(to_push, honda_rx_checks, HONDA_RX_CHECKS_LEN, |
||||||
|
honda_get_checksum, honda_compute_checksum, honda_get_counter); |
||||||
|
} |
||||||
|
|
||||||
|
if (valid) { |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
int len = GET_LEN(to_push); |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
|
||||||
|
// sample speed
|
||||||
|
if (addr == 0x158) { |
||||||
|
// first 2 bytes
|
||||||
|
honda_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1); |
||||||
|
} |
||||||
|
|
||||||
|
// state machine to enter and exit controls
|
||||||
|
// 0x1A6 for the ILX, 0x296 for the Civic Touring
|
||||||
|
if ((addr == 0x1A6) || (addr == 0x296)) { |
||||||
|
int button = (GET_BYTE(to_push, 0) & 0xE0) >> 5; |
||||||
|
switch (button) { |
||||||
|
case 2: // cancel
|
||||||
|
controls_allowed = 0; |
||||||
|
break; |
||||||
|
case 3: // set
|
||||||
|
case 4: // resume
|
||||||
|
controls_allowed = 1; |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; // any other button is irrelevant
|
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// user brake signal on 0x17C reports applied brake from computer brake on accord
|
||||||
|
// and crv, which prevents the usual brake safety from working correctly. these
|
||||||
|
// cars have a signal on 0x1BE which only detects user's brake being applied so
|
||||||
|
// in these cases, this is used instead.
|
||||||
|
// most hondas: 0x17C bit 53
|
||||||
|
// accord, crv: 0x1BE bit 4
|
||||||
|
// exit controls on rising edge of brake press or on brake press when speed > 0
|
||||||
|
bool is_user_brake_msg = honda_alt_brake_msg ? ((addr) == 0x1BE) : ((addr) == 0x17C); |
||||||
|
if (is_user_brake_msg) { |
||||||
|
bool brake_pressed = honda_alt_brake_msg ? (GET_BYTE((to_push), 0) & 0x10) : (GET_BYTE((to_push), 6) & 0x20); |
||||||
|
if (brake_pressed && (!(honda_brake_pressed_prev) || honda_moving)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
honda_brake_pressed_prev = brake_pressed; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press if interceptor (0x201 w/ len = 6)
|
||||||
|
// length check because bosch hardware also uses this id (0x201 w/ len = 8)
|
||||||
|
if ((addr == 0x201) && (len == 6)) { |
||||||
|
gas_interceptor_detected = 1; |
||||||
|
int gas_interceptor = GET_INTERCEPTOR(to_push); |
||||||
|
if ((gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD) && |
||||||
|
(gas_interceptor_prev <= HONDA_GAS_INTERCEPTOR_THRESHOLD)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
gas_interceptor_prev = gas_interceptor; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press if no interceptor
|
||||||
|
if (!gas_interceptor_detected) { |
||||||
|
if (addr == 0x17C) { |
||||||
|
int gas = GET_BYTE(to_push, 0); |
||||||
|
if (gas && !honda_gas_prev) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
honda_gas_prev = gas; |
||||||
|
} |
||||||
|
} |
||||||
|
if ((bus == 2) && (addr == 0x1FA)) { |
||||||
|
bool honda_stock_aeb = GET_BYTE(to_push, 3) & 0x20; |
||||||
|
int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) + ((GET_BYTE(to_push, 1) >> 6) & 0x3); |
||||||
|
|
||||||
|
// Forward AEB when stock braking is higher than openpilot braking
|
||||||
|
// only stop forwarding when AEB event is over
|
||||||
|
if (!honda_stock_aeb) { |
||||||
|
honda_fwd_brake = false; |
||||||
|
} else if (honda_stock_brake >= honda_brake) { |
||||||
|
honda_fwd_brake = true; |
||||||
|
} else { |
||||||
|
// Leave Honda forward brake as is
|
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// if steering controls messages are received on the destination bus, it's an indication
|
||||||
|
// that the relay might be malfunctioning
|
||||||
|
int bus_rdr_car = (honda_hw == HONDA_BH_HW) ? 0 : 2; // radar bus, car side
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && ((addr == 0xE4) || (addr == 0x194))) { |
||||||
|
if (((honda_hw != HONDA_N_HW) && (bus == bus_rdr_car)) || |
||||||
|
((honda_hw == HONDA_N_HW) && (bus == 0))) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return valid; |
||||||
|
} |
||||||
|
|
||||||
|
// all commands: gas, brake and steering
|
||||||
|
// if controls_allowed and no pedals pressed
|
||||||
|
// allow all commands up to limit
|
||||||
|
// else
|
||||||
|
// block all commands that produce actuation
|
||||||
|
|
||||||
|
static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (honda_hw == HONDA_BG_HW) { |
||||||
|
tx = msg_allowed(addr, bus, HONDA_BG_TX_MSGS, sizeof(HONDA_BG_TX_MSGS)/sizeof(HONDA_BG_TX_MSGS[0])); |
||||||
|
} else if (honda_hw == HONDA_BH_HW) { |
||||||
|
tx = msg_allowed(addr, bus, HONDA_BH_TX_MSGS, sizeof(HONDA_BH_TX_MSGS)/sizeof(HONDA_BH_TX_MSGS[0])); |
||||||
|
} else { |
||||||
|
tx = msg_allowed(addr, bus, HONDA_N_TX_MSGS, sizeof(HONDA_N_TX_MSGS)/sizeof(HONDA_N_TX_MSGS[0])); |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// disallow actuator commands if gas or brake (with vehicle moving) are pressed
|
||||||
|
// and the the latching controls_allowed flag is True
|
||||||
|
int pedal_pressed = honda_gas_prev || (gas_interceptor_prev > HONDA_GAS_INTERCEPTOR_THRESHOLD) || |
||||||
|
(honda_brake_pressed_prev && honda_moving); |
||||||
|
bool current_controls_allowed = controls_allowed && !(pedal_pressed); |
||||||
|
|
||||||
|
// BRAKE: safety check
|
||||||
|
if ((addr == 0x1FA) && (bus == 0)) { |
||||||
|
honda_brake = (GET_BYTE(to_send, 0) << 2) + ((GET_BYTE(to_send, 1) >> 6) & 0x3); |
||||||
|
if (!current_controls_allowed) { |
||||||
|
if (honda_brake != 0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
if (honda_brake > 255) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
if (honda_fwd_brake) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// STEER: safety check
|
||||||
|
if ((addr == 0xE4) || (addr == 0x194)) { |
||||||
|
if (!current_controls_allowed) { |
||||||
|
bool steer_applied = GET_BYTE(to_send, 0) | GET_BYTE(to_send, 1); |
||||||
|
if (steer_applied) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// GAS: safety check
|
||||||
|
if (addr == 0x200) { |
||||||
|
if (!current_controls_allowed) { |
||||||
|
if (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW
|
||||||
|
// ensuring that only the cancel button press is sent (VAL 2) when controls are off.
|
||||||
|
// This avoids unintended engagements while still allowing resume spam
|
||||||
|
int bus_pt = (honda_hw == HONDA_BH_HW)? 1 : 0; |
||||||
|
if ((addr == 0x296) && !current_controls_allowed && (bus == bus_pt)) { |
||||||
|
if (((GET_BYTE(to_send, 0) >> 5) & 0x7) != 2) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// 1 allows the message through
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static void honda_nidec_init(int16_t param) { |
||||||
|
UNUSED(param); |
||||||
|
controls_allowed = false; |
||||||
|
relay_malfunction = false; |
||||||
|
honda_hw = HONDA_N_HW; |
||||||
|
honda_alt_brake_msg = false; |
||||||
|
} |
||||||
|
|
||||||
|
static void honda_bosch_giraffe_init(int16_t param) { |
||||||
|
controls_allowed = false; |
||||||
|
relay_malfunction = false; |
||||||
|
honda_hw = HONDA_BG_HW; |
||||||
|
// Checking for alternate brake override from safety parameter
|
||||||
|
honda_alt_brake_msg = (param == 1) ? true : false; |
||||||
|
} |
||||||
|
|
||||||
|
static void honda_bosch_harness_init(int16_t param) { |
||||||
|
controls_allowed = false; |
||||||
|
relay_malfunction = false; |
||||||
|
honda_hw = HONDA_BH_HW; |
||||||
|
// Checking for alternate brake override from safety parameter
|
||||||
|
honda_alt_brake_msg = (param == 1) ? true : false; |
||||||
|
} |
||||||
|
|
||||||
|
static int honda_nidec_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
// fwd from car to camera. also fwd certain msgs from camera to car
|
||||||
|
// 0xE4 is steering on all cars except CRV and RDX, 0x194 for CRV and RDX,
|
||||||
|
// 0x1FA is brake control, 0x30C is acc hud, 0x33D is lkas hud,
|
||||||
|
int bus_fwd = -1; |
||||||
|
|
||||||
|
if (!relay_malfunction) { |
||||||
|
if (bus_num == 0) { |
||||||
|
bus_fwd = 2; |
||||||
|
} |
||||||
|
if (bus_num == 2) { |
||||||
|
// block stock lkas messages and stock acc messages (if OP is doing ACC)
|
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
bool is_lkas_msg = (addr == 0xE4) || (addr == 0x194) || (addr == 0x33D); |
||||||
|
bool is_acc_hud_msg = addr == 0x30C; |
||||||
|
bool is_brake_msg = addr == 0x1FA; |
||||||
|
bool block_fwd = is_lkas_msg || is_acc_hud_msg || (is_brake_msg && !honda_fwd_brake); |
||||||
|
if (!block_fwd) { |
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
int bus_fwd = -1; |
||||||
|
int bus_rdr_cam = (honda_hw == HONDA_BH_HW) ? 2 : 1; // radar bus, camera side
|
||||||
|
int bus_rdr_car = (honda_hw == HONDA_BH_HW) ? 0 : 2; // radar bus, car side
|
||||||
|
|
||||||
|
if (!relay_malfunction) { |
||||||
|
if (bus_num == bus_rdr_car) { |
||||||
|
bus_fwd = bus_rdr_cam; |
||||||
|
} |
||||||
|
if (bus_num == bus_rdr_cam) { |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
int is_lkas_msg = (addr == 0xE4) || (addr == 0x33D); |
||||||
|
if (!is_lkas_msg) { |
||||||
|
bus_fwd = bus_rdr_car; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks honda_nidec_hooks = { |
||||||
|
.init = honda_nidec_init, |
||||||
|
.rx = honda_rx_hook, |
||||||
|
.tx = honda_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = honda_nidec_fwd_hook, |
||||||
|
.addr_check = honda_rx_checks, |
||||||
|
.addr_check_len = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]), |
||||||
|
}; |
||||||
|
|
||||||
|
const safety_hooks honda_bosch_giraffe_hooks = { |
||||||
|
.init = honda_bosch_giraffe_init, |
||||||
|
.rx = honda_rx_hook, |
||||||
|
.tx = honda_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = honda_bosch_fwd_hook, |
||||||
|
.addr_check = honda_rx_checks, |
||||||
|
.addr_check_len = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]), |
||||||
|
}; |
||||||
|
|
||||||
|
const safety_hooks honda_bosch_harness_hooks = { |
||||||
|
.init = honda_bosch_harness_init, |
||||||
|
.rx = honda_rx_hook, |
||||||
|
.tx = honda_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = honda_bosch_fwd_hook, |
||||||
|
.addr_check = honda_bh_rx_checks, |
||||||
|
.addr_check_len = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,154 @@ |
|||||||
|
const int HYUNDAI_MAX_STEER = 255; // like stock
|
||||||
|
const int HYUNDAI_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t HYUNDAI_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int HYUNDAI_MAX_RATE_UP = 3; |
||||||
|
const int HYUNDAI_MAX_RATE_DOWN = 7; |
||||||
|
const int HYUNDAI_DRIVER_TORQUE_ALLOWANCE = 50; |
||||||
|
const int HYUNDAI_DRIVER_TORQUE_FACTOR = 2; |
||||||
|
const AddrBus HYUNDAI_TX_MSGS[] = {{832, 0}, {1265, 0}}; |
||||||
|
|
||||||
|
// TODO: do checksum and counter checks
|
||||||
|
AddrCheckStruct hyundai_rx_checks[] = { |
||||||
|
{.addr = {897}, .bus = 0, .expected_timestep = 10000U}, |
||||||
|
{.addr = {1057}, .bus = 0, .expected_timestep = 20000U}, |
||||||
|
}; |
||||||
|
const int HYUNDAI_RX_CHECK_LEN = sizeof(hyundai_rx_checks) / sizeof(hyundai_rx_checks[0]); |
||||||
|
|
||||||
|
int hyundai_rt_torque_last = 0; |
||||||
|
int hyundai_desired_torque_last = 0; |
||||||
|
int hyundai_cruise_engaged_last = 0; |
||||||
|
uint32_t hyundai_ts_last = 0; |
||||||
|
struct sample_t hyundai_torque_driver; // last few driver torques measured
|
||||||
|
|
||||||
|
static int hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (addr == 897) { |
||||||
|
int torque_driver_new = ((GET_BYTES_04(to_push) >> 11) & 0xfff) - 2048; |
||||||
|
// update array of samples
|
||||||
|
update_sample(&hyundai_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if (addr == 1057) { |
||||||
|
// 2 bits: 13-14
|
||||||
|
int cruise_engaged = (GET_BYTES_04(to_push) >> 13) & 0x3; |
||||||
|
if (cruise_engaged && !hyundai_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
if (!cruise_engaged) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
hyundai_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: check gas pressed
|
||||||
|
|
||||||
|
// check if stock camera ECU is on bus 0
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && (addr == 832)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, HYUNDAI_TX_MSGS, sizeof(HYUNDAI_TX_MSGS)/sizeof(HYUNDAI_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// LKA STEER: safety check
|
||||||
|
if (addr == 832) { |
||||||
|
int desired_torque = ((GET_BYTES_04(to_send) >> 16) & 0x7ff) - 1024; |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
bool violation = 0; |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, HYUNDAI_MAX_STEER, -HYUNDAI_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
violation |= driver_limit_check(desired_torque, hyundai_desired_torque_last, &hyundai_torque_driver, |
||||||
|
HYUNDAI_MAX_STEER, HYUNDAI_MAX_RATE_UP, HYUNDAI_MAX_RATE_DOWN, |
||||||
|
HYUNDAI_DRIVER_TORQUE_ALLOWANCE, HYUNDAI_DRIVER_TORQUE_FACTOR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
hyundai_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, hyundai_rt_torque_last, HYUNDAI_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, hyundai_ts_last); |
||||||
|
if (ts_elapsed > HYUNDAI_RT_INTERVAL) { |
||||||
|
hyundai_rt_torque_last = desired_torque; |
||||||
|
hyundai_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
hyundai_desired_torque_last = 0; |
||||||
|
hyundai_rt_torque_last = 0; |
||||||
|
hyundai_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// FORCE CANCEL: safety check only relevant when spamming the cancel button.
|
||||||
|
// ensuring that only the cancel button press is sent (VAL 4) when controls are off.
|
||||||
|
// This avoids unintended engagements while still allowing resume spam
|
||||||
|
if ((addr == 1265) && !controls_allowed) { |
||||||
|
if ((GET_BYTES_04(to_send) & 0x7) != 4) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// 1 allows the message through
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int hyundai_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
|
||||||
|
int bus_fwd = -1; |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
// forward cam to ccan and viceversa, except lkas cmd
|
||||||
|
if (!relay_malfunction) { |
||||||
|
if (bus_num == 0) { |
||||||
|
bus_fwd = 2; |
||||||
|
} |
||||||
|
if ((bus_num == 2) && (addr != 832)) { |
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
const safety_hooks hyundai_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = hyundai_rx_hook, |
||||||
|
.tx = hyundai_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = hyundai_fwd_hook, |
||||||
|
.addr_check = hyundai_rx_checks, |
||||||
|
.addr_check_len = sizeof(hyundai_rx_checks) / sizeof(hyundai_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,150 @@ |
|||||||
|
|
||||||
|
// CAN msgs we care about
|
||||||
|
#define MAZDA_LKAS 0x243 |
||||||
|
#define MAZDA_LANEINFO 0x440 |
||||||
|
#define MAZDA_CRZ_CTRL 0x21c |
||||||
|
#define MAZDA_WHEEL_SPEED 0x215 |
||||||
|
#define MAZDA_STEER_TORQUE 0x240 |
||||||
|
|
||||||
|
// CAN bus numbers
|
||||||
|
#define MAZDA_MAIN 0 |
||||||
|
#define MAZDA_AUX 1 |
||||||
|
#define MAZDA_CAM 2 |
||||||
|
|
||||||
|
#define MAZDA_MAX_STEER 2048 |
||||||
|
|
||||||
|
// max delta torque allowed for real time checks
|
||||||
|
#define MAZDA_MAX_RT_DELTA 940 |
||||||
|
// 250ms between real time checks
|
||||||
|
#define MAZDA_RT_INTERVAL 250000 |
||||||
|
#define MAZDA_MAX_RATE_UP 10 |
||||||
|
#define MAZDA_MAX_RATE_DOWN 25 |
||||||
|
#define MAZDA_DRIVER_TORQUE_ALLOWANCE 15 |
||||||
|
#define MAZDA_DRIVER_TORQUE_FACTOR 1 |
||||||
|
|
||||||
|
int mazda_cruise_engaged_last = 0; |
||||||
|
int mazda_rt_torque_last = 0; |
||||||
|
int mazda_desired_torque_last = 0; |
||||||
|
uint32_t mazda_ts_last = 0; |
||||||
|
struct sample_t mazda_torque_driver; // last few driver torques measured
|
||||||
|
|
||||||
|
// track msgs coming from OP so that we know what CAM msgs to drop and what to forward
|
||||||
|
static int mazda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if ((addr == MAZDA_STEER_TORQUE) && (bus == MAZDA_MAIN)) { |
||||||
|
int torque_driver_new = GET_BYTE(to_push, 0) - 127; |
||||||
|
// update array of samples
|
||||||
|
update_sample(&mazda_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if ((addr == MAZDA_CRZ_CTRL) && (bus == MAZDA_MAIN)) { |
||||||
|
int cruise_engaged = GET_BYTE(to_push, 0) & 8; |
||||||
|
if (cruise_engaged != 0) { |
||||||
|
if (!mazda_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
} |
||||||
|
else { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
mazda_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// if we see wheel speed msgs on MAZDA_CAM bus then relay is closed
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == MAZDA_CAM) && (addr == MAZDA_WHEEL_SPEED)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int mazda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// Check if msg is sent on the main BUS
|
||||||
|
if (bus == MAZDA_MAIN) { |
||||||
|
// steer cmd checks
|
||||||
|
if (addr == MAZDA_LKAS) { |
||||||
|
int desired_torque = (((GET_BYTE(to_send, 0) & 0x0f) << 8) | GET_BYTE(to_send, 1)) - MAZDA_MAX_STEER; |
||||||
|
bool violation = 0; |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, MAZDA_MAX_STEER, -MAZDA_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
int desired_torque_last = mazda_desired_torque_last; |
||||||
|
violation |= driver_limit_check(desired_torque, desired_torque_last, &mazda_torque_driver, |
||||||
|
MAZDA_MAX_STEER, MAZDA_MAX_RATE_UP, MAZDA_MAX_RATE_DOWN, |
||||||
|
MAZDA_DRIVER_TORQUE_ALLOWANCE, MAZDA_DRIVER_TORQUE_FACTOR); |
||||||
|
// used next time
|
||||||
|
mazda_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, mazda_rt_torque_last, MAZDA_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, mazda_ts_last); |
||||||
|
if (ts_elapsed > ((uint32_t) MAZDA_RT_INTERVAL)) { |
||||||
|
mazda_rt_torque_last = desired_torque; |
||||||
|
mazda_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
mazda_desired_torque_last = 0; |
||||||
|
mazda_rt_torque_last = 0; |
||||||
|
mazda_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int mazda_fwd_hook(int bus, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
int bus_fwd = -1; |
||||||
|
if (!relay_malfunction) { |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
if (bus == MAZDA_MAIN) { |
||||||
|
bus_fwd = MAZDA_CAM; |
||||||
|
} |
||||||
|
else if (bus == MAZDA_CAM) { |
||||||
|
if (!(addr == MAZDA_LKAS)) { |
||||||
|
bus_fwd = MAZDA_MAIN; |
||||||
|
} |
||||||
|
} |
||||||
|
else { |
||||||
|
bus_fwd = -1; |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks mazda_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = mazda_rx_hook, |
||||||
|
.tx = mazda_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = mazda_fwd_hook, |
||||||
|
// TODO: add addr safety checks
|
||||||
|
}; |
@ -0,0 +1,156 @@ |
|||||||
|
const int SUBARU_MAX_STEER = 2047; // 1s
|
||||||
|
// real time torque limit to prevent controls spamming
|
||||||
|
// the real time limit is 1500/sec
|
||||||
|
const int SUBARU_MAX_RT_DELTA = 940; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t SUBARU_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int SUBARU_MAX_RATE_UP = 50; |
||||||
|
const int SUBARU_MAX_RATE_DOWN = 70; |
||||||
|
const int SUBARU_DRIVER_TORQUE_ALLOWANCE = 60; |
||||||
|
const int SUBARU_DRIVER_TORQUE_FACTOR = 10; |
||||||
|
|
||||||
|
const AddrBus SUBARU_TX_MSGS[] = {{0x122, 0}, {0x164, 0}, {0x221, 0}, {0x322, 0}}; |
||||||
|
|
||||||
|
// TODO: do checksum and counter checks after adding the signals to the outback dbc file
|
||||||
|
AddrCheckStruct subaru_rx_checks[] = { |
||||||
|
{.addr = {0x119, 0x371}, .bus = 0, .expected_timestep = 20000U}, |
||||||
|
{.addr = {0x240, 0x144}, .bus = 0, .expected_timestep = 50000U}, |
||||||
|
}; |
||||||
|
const int SUBARU_RX_CHECK_LEN = sizeof(subaru_rx_checks) / sizeof(subaru_rx_checks[0]); |
||||||
|
|
||||||
|
int subaru_cruise_engaged_last = 0; |
||||||
|
int subaru_rt_torque_last = 0; |
||||||
|
int subaru_desired_torque_last = 0; |
||||||
|
uint32_t subaru_ts_last = 0; |
||||||
|
struct sample_t subaru_torque_driver; // last few driver torques measured
|
||||||
|
|
||||||
|
static int subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (((addr == 0x119) || (addr == 0x371)) && (bus == 0)){ |
||||||
|
int bit_shift = (addr == 0x119) ? 16 : 29; |
||||||
|
int torque_driver_new = ((GET_BYTES_04(to_push) >> bit_shift) & 0x7FF); |
||||||
|
torque_driver_new = to_signed(torque_driver_new, 11); |
||||||
|
// update array of samples
|
||||||
|
update_sample(&subaru_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if (((addr == 0x240) || (addr == 0x144)) && (bus == 0)) { |
||||||
|
int bit_shift = (addr == 0x240) ? 9 : 17; |
||||||
|
int cruise_engaged = ((GET_BYTES_48(to_push) >> bit_shift) & 1); |
||||||
|
if (cruise_engaged && !subaru_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
if (!cruise_engaged) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
subaru_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// TODO: enforce cancellation on gas pressed
|
||||||
|
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && ((addr == 0x122) || (addr == 0x164))) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int subaru_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, SUBARU_TX_MSGS, sizeof(SUBARU_TX_MSGS) / sizeof(SUBARU_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// steer cmd checks
|
||||||
|
if ((addr == 0x122) || (addr == 0x164)) { |
||||||
|
int bit_shift = (addr == 0x122) ? 16 : 8; |
||||||
|
int desired_torque = ((GET_BYTES_04(to_send) >> bit_shift) & 0x1FFF); |
||||||
|
bool violation = 0; |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
desired_torque = to_signed(desired_torque, 13); |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, SUBARU_MAX_STEER, -SUBARU_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
int desired_torque_last = subaru_desired_torque_last; |
||||||
|
violation |= driver_limit_check(desired_torque, desired_torque_last, &subaru_torque_driver, |
||||||
|
SUBARU_MAX_STEER, SUBARU_MAX_RATE_UP, SUBARU_MAX_RATE_DOWN, |
||||||
|
SUBARU_DRIVER_TORQUE_ALLOWANCE, SUBARU_DRIVER_TORQUE_FACTOR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
subaru_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, subaru_rt_torque_last, SUBARU_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, subaru_ts_last); |
||||||
|
if (ts_elapsed > SUBARU_RT_INTERVAL) { |
||||||
|
subaru_rt_torque_last = desired_torque; |
||||||
|
subaru_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
subaru_desired_torque_last = 0; |
||||||
|
subaru_rt_torque_last = 0; |
||||||
|
subaru_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int subaru_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
int bus_fwd = -1; |
||||||
|
|
||||||
|
if (!relay_malfunction) { |
||||||
|
if (bus_num == 0) { |
||||||
|
bus_fwd = 2; // Camera CAN
|
||||||
|
} |
||||||
|
if (bus_num == 2) { |
||||||
|
// 290 is LKAS for Global Platform
|
||||||
|
// 356 is LKAS for outback 2015
|
||||||
|
// 545 is ES_Distance
|
||||||
|
// 802 is ES_LKAS
|
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
int block_msg = (addr == 290) || (addr == 356) || (addr == 545) || (addr == 802); |
||||||
|
if (!block_msg) { |
||||||
|
bus_fwd = 0; // Main CAN
|
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
// fallback to do not forward
|
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks subaru_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = subaru_rx_hook, |
||||||
|
.tx = subaru_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = subaru_fwd_hook, |
||||||
|
.addr_check = subaru_rx_checks, |
||||||
|
.addr_check_len = sizeof(subaru_rx_checks) / sizeof(subaru_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,214 @@ |
|||||||
|
// board enforces
|
||||||
|
// in-state
|
||||||
|
// accel set/resume
|
||||||
|
// out-state
|
||||||
|
// cancel button
|
||||||
|
// regen paddle
|
||||||
|
// accel rising edge
|
||||||
|
// brake rising edge
|
||||||
|
// brake > 0mph
|
||||||
|
//
|
||||||
|
bool fmax_limit_check(float val, const float MAX_VAL, const float MIN_VAL) { |
||||||
|
return (val > MAX_VAL) || (val < MIN_VAL); |
||||||
|
} |
||||||
|
|
||||||
|
// 2m/s are added to be less restrictive
|
||||||
|
const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_UP = { |
||||||
|
{2., 7., 17.}, |
||||||
|
{5., .8, .25}}; |
||||||
|
|
||||||
|
const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_DOWN = { |
||||||
|
{2., 7., 17.}, |
||||||
|
{5., 3.5, .8}}; |
||||||
|
|
||||||
|
const struct lookup_t TESLA_LOOKUP_MAX_ANGLE = { |
||||||
|
{2., 29., 38.}, |
||||||
|
{410., 92., 36.}}; |
||||||
|
|
||||||
|
const uint32_t TESLA_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
|
||||||
|
// state of angle limits
|
||||||
|
float tesla_desired_angle_last = 0; // last desired steer angle
|
||||||
|
float tesla_rt_angle_last = 0.; // last real time angle
|
||||||
|
float tesla_ts_angle_last = 0; |
||||||
|
|
||||||
|
int tesla_controls_allowed_last = 0; |
||||||
|
|
||||||
|
int tesla_brake_prev = 0; |
||||||
|
int tesla_gas_prev = 0; |
||||||
|
int tesla_speed = 0; |
||||||
|
int eac_status = 0; |
||||||
|
|
||||||
|
void set_gmlan_digital_output(int to_set); |
||||||
|
void reset_gmlan_switch_timeout(void); |
||||||
|
void gmlan_switch_init(int timeout_enable); |
||||||
|
|
||||||
|
|
||||||
|
static int tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
set_gmlan_digital_output(0); // #define GMLAN_HIGH 0
|
||||||
|
reset_gmlan_switch_timeout(); //we're still in tesla safety mode, reset the timeout counter and make sure our output is enabled
|
||||||
|
|
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (addr == 0x45) { |
||||||
|
// 6 bits starting at position 0
|
||||||
|
int lever_position = GET_BYTE(to_push, 0) & 0x3F; |
||||||
|
if (lever_position == 2) { // pull forward
|
||||||
|
// activate openpilot
|
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
if (lever_position == 1) { // push towards the back
|
||||||
|
// deactivate openpilot
|
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on brake press
|
||||||
|
// DI_torque2::DI_brakePedal 0x118
|
||||||
|
if (addr == 0x118) { |
||||||
|
// 1 bit at position 16
|
||||||
|
if ((GET_BYTE(to_push, 1) & 0x80) != 0) { |
||||||
|
// disable break cancel by commenting line below
|
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
//get vehicle speed in m/s. Tesla gives MPH
|
||||||
|
tesla_speed = (((((GET_BYTE(to_push, 3) & 0xF) << 8) + GET_BYTE(to_push, 2)) * 0.05) - 25) * 1.609 / 3.6; |
||||||
|
if (tesla_speed < 0) { |
||||||
|
tesla_speed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on EPAS error
|
||||||
|
// EPAS_sysStatus::EPAS_eacStatus 0x370
|
||||||
|
if (addr == 0x370) { |
||||||
|
// if EPAS_eacStatus is not 1 or 2, disable control
|
||||||
|
eac_status = (GET_BYTE(to_push, 6) >> 5) & 0x7; |
||||||
|
// For human steering override we must not disable controls when eac_status == 0
|
||||||
|
// Additional safety: we could only allow eac_status == 0 when we have human steering allowed
|
||||||
|
if (controls_allowed && (eac_status != 0) && (eac_status != 1) && (eac_status != 2)) { |
||||||
|
controls_allowed = 0; |
||||||
|
//puts("EPAS error! \n");
|
||||||
|
} |
||||||
|
} |
||||||
|
//get latest steering wheel angle
|
||||||
|
if (addr == 0x00E) { |
||||||
|
float angle_meas_now = (int)(((((GET_BYTE(to_push, 0) & 0x3F) << 8) + GET_BYTE(to_push, 1)) * 0.1) - 819.2); |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, tesla_ts_angle_last); |
||||||
|
|
||||||
|
// *** angle real time check
|
||||||
|
// add 1 to not false trigger the violation and multiply by 25 since the check is done every 250 ms and steer angle is updated at 100Hz
|
||||||
|
float rt_delta_angle_up = (interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) * 25.) + 1.; |
||||||
|
float rt_delta_angle_down = (interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) * 25.) + 1.; |
||||||
|
float highest_rt_angle = tesla_rt_angle_last + ((tesla_rt_angle_last > 0.) ? rt_delta_angle_up : rt_delta_angle_down); |
||||||
|
float lowest_rt_angle = tesla_rt_angle_last - ((tesla_rt_angle_last > 0.) ? rt_delta_angle_down : rt_delta_angle_up); |
||||||
|
|
||||||
|
if ((ts_elapsed > TESLA_RT_INTERVAL) || (controls_allowed && !tesla_controls_allowed_last)) { |
||||||
|
tesla_rt_angle_last = angle_meas_now; |
||||||
|
tesla_ts_angle_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
// check for violation;
|
||||||
|
if (fmax_limit_check(angle_meas_now, highest_rt_angle, lowest_rt_angle)) { |
||||||
|
// We should not be able to STEER under these conditions
|
||||||
|
// Other sending is fine (to allow human override)
|
||||||
|
controls_allowed = 0; |
||||||
|
//puts("WARN: RT Angle - No steer allowed! \n");
|
||||||
|
} else { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
|
||||||
|
tesla_controls_allowed_last = controls_allowed; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
// all commands: gas/regen, friction brake and steering
|
||||||
|
// if controls_allowed and no pedals pressed
|
||||||
|
// allow all commands up to limit
|
||||||
|
// else
|
||||||
|
// block all commands that produce actuation
|
||||||
|
|
||||||
|
static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
|
||||||
|
// do not transmit CAN message if steering angle too high
|
||||||
|
// DAS_steeringControl::DAS_steeringAngleRequest
|
||||||
|
if (addr == 0x488) { |
||||||
|
float angle_raw = ((GET_BYTE(to_send, 0) & 0x7F) << 8) + GET_BYTE(to_send, 1); |
||||||
|
float desired_angle = (angle_raw * 0.1) - 1638.35; |
||||||
|
bool violation = 0; |
||||||
|
int st_enabled = GET_BYTE(to_send, 2) & 0x40; |
||||||
|
|
||||||
|
if (st_enabled == 0) { |
||||||
|
//steering is not enabled, do not check angles and do send
|
||||||
|
tesla_desired_angle_last = desired_angle; |
||||||
|
} else if (controls_allowed) { |
||||||
|
// add 1 to not false trigger the violation
|
||||||
|
float delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) + 1.; |
||||||
|
float delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) + 1.; |
||||||
|
float highest_desired_angle = tesla_desired_angle_last + ((tesla_desired_angle_last > 0.) ? delta_angle_up : delta_angle_down); |
||||||
|
float lowest_desired_angle = tesla_desired_angle_last - ((tesla_desired_angle_last > 0.) ? delta_angle_down : delta_angle_up); |
||||||
|
float TESLA_MAX_ANGLE = interpolate(TESLA_LOOKUP_MAX_ANGLE, tesla_speed) + 1.; |
||||||
|
|
||||||
|
//check for max angles
|
||||||
|
violation |= fmax_limit_check(desired_angle, TESLA_MAX_ANGLE, -TESLA_MAX_ANGLE); |
||||||
|
|
||||||
|
//check for angle delta changes
|
||||||
|
violation |= fmax_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
controls_allowed = 0; |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
tesla_desired_angle_last = desired_angle; |
||||||
|
} else { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static void tesla_init(int16_t param) { |
||||||
|
UNUSED(param); |
||||||
|
controls_allowed = 0; |
||||||
|
gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled
|
||||||
|
} |
||||||
|
|
||||||
|
static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
|
||||||
|
int bus_fwd = -1; |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
|
||||||
|
if (bus_num == 0) { |
||||||
|
// change inhibit of GTW_epasControl
|
||||||
|
|
||||||
|
if (addr != 0x214) { |
||||||
|
// remove EPB_epasControl
|
||||||
|
bus_fwd = 2; // Custom EPAS bus
|
||||||
|
} |
||||||
|
if (addr == 0x101) { |
||||||
|
to_fwd->RDLR = GET_BYTES_04(to_fwd) | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque)
|
||||||
|
uint32_t checksum = (GET_BYTE(to_fwd, 1) + GET_BYTE(to_fwd, 0) + 2) & 0xFF; |
||||||
|
to_fwd->RDLR = GET_BYTES_04(to_fwd) & 0xFFFF; |
||||||
|
to_fwd->RDLR = GET_BYTES_04(to_fwd) + (checksum << 16); |
||||||
|
} |
||||||
|
} |
||||||
|
if (bus_num == 2) { |
||||||
|
// remove GTW_epasControl in forwards
|
||||||
|
if (addr != 0x101) { |
||||||
|
bus_fwd = 0; // Chassis CAN
|
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks tesla_hooks = { |
||||||
|
.init = tesla_init, |
||||||
|
.rx = tesla_rx_hook, |
||||||
|
.tx = tesla_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = tesla_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,254 @@ |
|||||||
|
// global torque limit
|
||||||
|
const int TOYOTA_MAX_TORQUE = 1500; // max torque cmd allowed ever
|
||||||
|
|
||||||
|
// rate based torque limit + stay within actually applied
|
||||||
|
// packet is sent at 100hz, so this limit is 1000/sec
|
||||||
|
const int TOYOTA_MAX_RATE_UP = 10; // ramp up slow
|
||||||
|
const int TOYOTA_MAX_RATE_DOWN = 25; // ramp down fast
|
||||||
|
const int TOYOTA_MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor
|
||||||
|
|
||||||
|
// real time torque limit to prevent controls spamming
|
||||||
|
// the real time limit is 1500/sec
|
||||||
|
const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real time checks
|
||||||
|
const uint32_t TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
|
||||||
|
// longitudinal limits
|
||||||
|
const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2
|
||||||
|
const int TOYOTA_MIN_ACCEL = -3000; // 3.0 m/s2
|
||||||
|
|
||||||
|
const int TOYOTA_GAS_INTERCEPTOR_THRESHOLD = 475; // ratio between offset and gain from dbc file
|
||||||
|
|
||||||
|
const AddrBus TOYOTA_TX_MSGS[] = {{0x283, 0}, {0x2E6, 0}, {0x2E7, 0}, {0x33E, 0}, {0x344, 0}, {0x365, 0}, {0x366, 0}, {0x4CB, 0}, // DSU bus 0
|
||||||
|
{0x128, 1}, {0x141, 1}, {0x160, 1}, {0x161, 1}, {0x470, 1}, // DSU bus 1
|
||||||
|
{0x2E4, 0}, {0x411, 0}, {0x412, 0}, {0x343, 0}, {0x1D2, 0}, // LKAS + ACC
|
||||||
|
{0x200, 0}}; // interceptor
|
||||||
|
|
||||||
|
AddrCheckStruct toyota_rx_checks[] = { |
||||||
|
{.addr = {0x260}, .bus = 0, .check_checksum = true, .max_counter = 0U, .expected_timestep = 20000U}, |
||||||
|
{.addr = {0x1D2}, .bus = 0, .check_checksum = true, .max_counter = 0U, .expected_timestep = 30000U}, |
||||||
|
}; |
||||||
|
const int TOYOTA_RX_CHECKS_LEN = sizeof(toyota_rx_checks) / sizeof(toyota_rx_checks[0]); |
||||||
|
|
||||||
|
// global actuation limit states
|
||||||
|
int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
|
||||||
|
|
||||||
|
// states
|
||||||
|
int toyota_desired_torque_last = 0; // last desired steer torque
|
||||||
|
int toyota_rt_torque_last = 0; // last desired torque for real time check
|
||||||
|
uint32_t toyota_ts_last = 0; |
||||||
|
int toyota_cruise_engaged_last = 0; // cruise state
|
||||||
|
int toyota_gas_prev = 0; |
||||||
|
struct sample_t toyota_torque_meas; // last 3 motor torques produced by the eps
|
||||||
|
|
||||||
|
|
||||||
|
static uint8_t toyota_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
int len = GET_LEN(to_push); |
||||||
|
uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U) + (uint8_t)(len); |
||||||
|
for (int i = 0; i < (len - 1); i++) { |
||||||
|
checksum += (uint8_t)GET_BYTE(to_push, i); |
||||||
|
} |
||||||
|
return checksum; |
||||||
|
} |
||||||
|
|
||||||
|
static uint8_t toyota_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int checksum_byte = GET_LEN(to_push) - 1; |
||||||
|
return (uint8_t)(GET_BYTE(to_push, checksum_byte)); |
||||||
|
} |
||||||
|
|
||||||
|
static int toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
|
||||||
|
bool valid = addr_safety_check(to_push, toyota_rx_checks, TOYOTA_RX_CHECKS_LEN, |
||||||
|
toyota_get_checksum, toyota_compute_checksum, NULL); |
||||||
|
if (valid) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
// get eps motor torque (0.66 factor in dbc)
|
||||||
|
if (addr == 0x260) { |
||||||
|
int torque_meas_new = (GET_BYTE(to_push, 5) << 8) | GET_BYTE(to_push, 6); |
||||||
|
torque_meas_new = to_signed(torque_meas_new, 16); |
||||||
|
|
||||||
|
// scale by dbc_factor
|
||||||
|
torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100; |
||||||
|
|
||||||
|
// update array of sample
|
||||||
|
update_sample(&toyota_torque_meas, torque_meas_new); |
||||||
|
|
||||||
|
// increase torque_meas by 1 to be conservative on rounding
|
||||||
|
toyota_torque_meas.min--; |
||||||
|
toyota_torque_meas.max++; |
||||||
|
} |
||||||
|
|
||||||
|
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||||
|
if (addr == 0x1D2) { |
||||||
|
// 5th bit is CRUISE_ACTIVE
|
||||||
|
int cruise_engaged = GET_BYTE(to_push, 0) & 0x20; |
||||||
|
if (!cruise_engaged) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
if (cruise_engaged && !toyota_cruise_engaged_last) { |
||||||
|
controls_allowed = 1; |
||||||
|
} |
||||||
|
toyota_cruise_engaged_last = cruise_engaged; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of interceptor gas press
|
||||||
|
if (addr == 0x201) { |
||||||
|
gas_interceptor_detected = 1; |
||||||
|
int gas_interceptor = GET_INTERCEPTOR(to_push); |
||||||
|
if ((gas_interceptor > TOYOTA_GAS_INTERCEPTOR_THRESHOLD) && |
||||||
|
(gas_interceptor_prev <= TOYOTA_GAS_INTERCEPTOR_THRESHOLD)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
gas_interceptor_prev = gas_interceptor; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press
|
||||||
|
if (addr == 0x2C1) { |
||||||
|
int gas = GET_BYTE(to_push, 6) & 0xFF; |
||||||
|
if ((gas > 0) && (toyota_gas_prev == 0) && !gas_interceptor_detected) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
toyota_gas_prev = gas; |
||||||
|
} |
||||||
|
|
||||||
|
// 0x2E4 is lkas cmd. If it is on bus 0, then relay is unexpectedly closed
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (addr == 0x2E4) && (bus == 0)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
} |
||||||
|
return valid; |
||||||
|
} |
||||||
|
|
||||||
|
static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, TOYOTA_TX_MSGS, sizeof(TOYOTA_TX_MSGS)/sizeof(TOYOTA_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// Check if msg is sent on BUS 0
|
||||||
|
if (bus == 0) { |
||||||
|
|
||||||
|
// GAS PEDAL: safety check
|
||||||
|
if (addr == 0x200) { |
||||||
|
if (!controls_allowed) { |
||||||
|
if (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// ACCEL: safety check on byte 1-2
|
||||||
|
if (addr == 0x343) { |
||||||
|
int desired_accel = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1); |
||||||
|
desired_accel = to_signed(desired_accel, 16); |
||||||
|
if (!controls_allowed) { |
||||||
|
if (desired_accel != 0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
bool violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL); |
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// STEER: safety check on bytes 2-3
|
||||||
|
if (addr == 0x2E4) { |
||||||
|
int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); |
||||||
|
desired_torque = to_signed(desired_torque, 16); |
||||||
|
bool violation = 0; |
||||||
|
|
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, TOYOTA_MAX_TORQUE, -TOYOTA_MAX_TORQUE); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
violation |= dist_to_meas_check(desired_torque, toyota_desired_torque_last, |
||||||
|
&toyota_torque_meas, TOYOTA_MAX_RATE_UP, TOYOTA_MAX_RATE_DOWN, TOYOTA_MAX_TORQUE_ERROR); |
||||||
|
|
||||||
|
// used next time
|
||||||
|
toyota_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, toyota_rt_torque_last, TOYOTA_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, toyota_ts_last); |
||||||
|
if (ts_elapsed > TOYOTA_RT_INTERVAL) { |
||||||
|
toyota_rt_torque_last = desired_torque; |
||||||
|
toyota_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
toyota_desired_torque_last = 0; |
||||||
|
toyota_rt_torque_last = 0; |
||||||
|
toyota_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static void toyota_init(int16_t param) { |
||||||
|
controls_allowed = 0; |
||||||
|
relay_malfunction = 0; |
||||||
|
toyota_dbc_eps_torque_factor = param; |
||||||
|
} |
||||||
|
|
||||||
|
static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
|
||||||
|
int bus_fwd = -1; |
||||||
|
if (!relay_malfunction) { |
||||||
|
if (bus_num == 0) { |
||||||
|
bus_fwd = 2; |
||||||
|
} |
||||||
|
if (bus_num == 2) { |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
// block stock lkas messages and stock acc messages (if OP is doing ACC)
|
||||||
|
// in TSS2, 0x191 is LTA which we need to block to avoid controls collision
|
||||||
|
int is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191)); |
||||||
|
// in TSS2 the camera does ACC as well, so filter 0x343
|
||||||
|
int is_acc_msg = (addr == 0x343); |
||||||
|
int block_msg = is_lkas_msg || is_acc_msg; |
||||||
|
if (!block_msg) { |
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks toyota_hooks = { |
||||||
|
.init = toyota_init, |
||||||
|
.rx = toyota_rx_hook, |
||||||
|
.tx = toyota_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = toyota_fwd_hook, |
||||||
|
.addr_check = toyota_rx_checks, |
||||||
|
.addr_check_len = sizeof(toyota_rx_checks)/sizeof(toyota_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,169 @@ |
|||||||
|
// uses tons from safety_toyota
|
||||||
|
// TODO: refactor to repeat less code
|
||||||
|
|
||||||
|
// IPAS override
|
||||||
|
const int32_t TOYOTA_IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value
|
||||||
|
|
||||||
|
// 2m/s are added to be less restrictive
|
||||||
|
const struct lookup_t LOOKUP_ANGLE_RATE_UP = { |
||||||
|
{2., 7., 17.}, |
||||||
|
{5., .8, .15}}; |
||||||
|
|
||||||
|
const struct lookup_t LOOKUP_ANGLE_RATE_DOWN = { |
||||||
|
{2., 7., 17.}, |
||||||
|
{5., 3.5, .4}}; |
||||||
|
|
||||||
|
const float RT_ANGLE_FUDGE = 1.5; // for RT checks allow 50% more angle change
|
||||||
|
const float CAN_TO_DEG = 2. / 3.; // convert angles from CAN unit to degrees
|
||||||
|
|
||||||
|
int ipas_state = 1; // 1 disabled, 3 executing angle control, 5 override
|
||||||
|
int angle_control = 0; // 1 if direct angle control packets are seen
|
||||||
|
float speed = 0.; |
||||||
|
|
||||||
|
struct sample_t angle_meas; // last 3 steer angles
|
||||||
|
struct sample_t torque_driver; // last 3 driver steering torque
|
||||||
|
|
||||||
|
// state of angle limits
|
||||||
|
int16_t desired_angle_last = 0; // last desired steer angle
|
||||||
|
int16_t rt_angle_last = 0; // last desired torque for real time check
|
||||||
|
uint32_t ts_angle_last = 0; |
||||||
|
|
||||||
|
int controls_allowed_last = 0; |
||||||
|
|
||||||
|
|
||||||
|
static int toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
// check standard toyota stuff as well
|
||||||
|
bool valid = toyota_rx_hook(to_push); |
||||||
|
|
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
if (addr == 0x260) { |
||||||
|
// get driver steering torque
|
||||||
|
int16_t torque_driver_new = (GET_BYTE(to_push, 1) << 8) | GET_BYTE(to_push, 2); |
||||||
|
|
||||||
|
// update array of samples
|
||||||
|
update_sample(&torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// get steer angle
|
||||||
|
if (addr == 0x25) { |
||||||
|
int angle_meas_new = ((GET_BYTE(to_push, 0) & 0xF) << 8) | GET_BYTE(to_push, 1); |
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
|
||||||
|
angle_meas_new = to_signed(angle_meas_new, 12); |
||||||
|
|
||||||
|
// update array of samples
|
||||||
|
update_sample(&angle_meas, angle_meas_new); |
||||||
|
|
||||||
|
// *** angle real time check
|
||||||
|
// add 1 to not false trigger the violation and multiply by 20 since the check is done every 250ms and steer angle is updated at 80Hz
|
||||||
|
int rt_delta_angle_up = ((int)(RT_ANGLE_FUDGE * ((interpolate(LOOKUP_ANGLE_RATE_UP, speed) * 20. * CAN_TO_DEG) + 1.))); |
||||||
|
int rt_delta_angle_down = ((int)(RT_ANGLE_FUDGE * ((interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * 20. * CAN_TO_DEG) + 1.))); |
||||||
|
int highest_rt_angle = rt_angle_last + ((rt_angle_last > 0) ? rt_delta_angle_up : rt_delta_angle_down); |
||||||
|
int lowest_rt_angle = rt_angle_last - ((rt_angle_last > 0) ? rt_delta_angle_down : rt_delta_angle_up); |
||||||
|
|
||||||
|
// every RT_INTERVAL or when controls are turned on, set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_last); |
||||||
|
if ((ts_elapsed > TOYOTA_RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) { |
||||||
|
rt_angle_last = angle_meas_new; |
||||||
|
ts_angle_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
// check for violation
|
||||||
|
if (angle_control && |
||||||
|
((angle_meas_new < lowest_rt_angle) || |
||||||
|
(angle_meas_new > highest_rt_angle))) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
|
||||||
|
controls_allowed_last = controls_allowed; |
||||||
|
} |
||||||
|
|
||||||
|
// get speed
|
||||||
|
if (addr == 0xb4) { |
||||||
|
speed = ((float)((GET_BYTE(to_push, 5) << 8) | GET_BYTE(to_push, 6))) * 0.01 / 3.6; |
||||||
|
} |
||||||
|
|
||||||
|
// get ipas state
|
||||||
|
if (addr == 0x262) { |
||||||
|
ipas_state = GET_BYTE(to_push, 0) & 0xf; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on high steering override
|
||||||
|
if (angle_control && ((torque_driver.min > TOYOTA_IPAS_OVERRIDE_THRESHOLD) || |
||||||
|
(torque_driver.max < -TOYOTA_IPAS_OVERRIDE_THRESHOLD) || |
||||||
|
(ipas_state==5))) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
return valid; |
||||||
|
} |
||||||
|
|
||||||
|
static int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
|
||||||
|
int tx = 1; |
||||||
|
int bypass_standard_tx_hook = 0; |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
|
||||||
|
// Check if msg is sent on BUS 0
|
||||||
|
if (bus == 0) { |
||||||
|
|
||||||
|
// STEER ANGLE
|
||||||
|
if ((addr == 0x266) || (addr == 0x167)) { |
||||||
|
|
||||||
|
angle_control = 1; // we are in angle control mode
|
||||||
|
int desired_angle = ((GET_BYTE(to_send, 0) & 0xF) << 8) | GET_BYTE(to_send, 1); |
||||||
|
int ipas_state_cmd = GET_BYTE(to_send, 0) >> 4; |
||||||
|
bool violation = 0; |
||||||
|
|
||||||
|
desired_angle = to_signed(desired_angle, 12); |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
// add 1 to not false trigger the violation
|
||||||
|
float delta_angle_float; |
||||||
|
delta_angle_float = (interpolate(LOOKUP_ANGLE_RATE_UP, speed) * CAN_TO_DEG) + 1.; |
||||||
|
int delta_angle_up = (int) (delta_angle_float); |
||||||
|
delta_angle_float = (interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * CAN_TO_DEG) + 1.; |
||||||
|
int delta_angle_down = (int) (delta_angle_float); |
||||||
|
|
||||||
|
int highest_desired_angle = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up : delta_angle_down); |
||||||
|
int lowest_desired_angle = desired_angle_last - ((desired_angle_last > 0) ? delta_angle_down : delta_angle_up); |
||||||
|
if ((desired_angle > highest_desired_angle) || |
||||||
|
(desired_angle < lowest_desired_angle)){ |
||||||
|
violation = 1; |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// desired steer angle should be the same as steer angle measured when controls are off
|
||||||
|
if ((!controls_allowed) && |
||||||
|
((desired_angle < (angle_meas.min - 1)) || |
||||||
|
(desired_angle > (angle_meas.max + 1)) || |
||||||
|
(ipas_state_cmd != 1))) { |
||||||
|
violation = 1; |
||||||
|
} |
||||||
|
|
||||||
|
desired_angle_last = desired_angle; |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
bypass_standard_tx_hook = 1; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// check standard toyota stuff as well if addr isn't IPAS related
|
||||||
|
if (!bypass_standard_tx_hook) { |
||||||
|
tx &= toyota_tx_hook(to_send); |
||||||
|
} |
||||||
|
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks toyota_ipas_hooks = { |
||||||
|
.init = toyota_init, |
||||||
|
.rx = toyota_ipas_rx_hook, |
||||||
|
.tx = toyota_ipas_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = toyota_fwd_hook, |
||||||
|
}; |
@ -0,0 +1,189 @@ |
|||||||
|
// Safety-relevant CAN messages for the Volkswagen MQB platform.
|
||||||
|
#define MSG_EPS_01 0x09F |
||||||
|
#define MSG_MOTOR_20 0x121 |
||||||
|
#define MSG_ACC_06 0x122 |
||||||
|
#define MSG_HCA_01 0x126 |
||||||
|
#define MSG_GRA_ACC_01 0x12B |
||||||
|
#define MSG_LDW_02 0x397 |
||||||
|
|
||||||
|
const int VOLKSWAGEN_MAX_STEER = 250; // 2.5 Nm (EPS side max of 3.0Nm with fault if violated)
|
||||||
|
const int VOLKSWAGEN_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75
|
||||||
|
const uint32_t VOLKSWAGEN_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||||
|
const int VOLKSWAGEN_MAX_RATE_UP = 4; // 2.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s)
|
||||||
|
const int VOLKSWAGEN_MAX_RATE_DOWN = 10; // 5.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s)
|
||||||
|
const int VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE = 80; |
||||||
|
const int VOLKSWAGEN_DRIVER_TORQUE_FACTOR = 3; |
||||||
|
|
||||||
|
// MSG_GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
|
||||||
|
const AddrBus VOLKSWAGEN_TX_MSGS[] = {{MSG_HCA_01, 0}, {MSG_GRA_ACC_01, 0}, {MSG_GRA_ACC_01, 2}, {MSG_LDW_02, 0}}; |
||||||
|
|
||||||
|
// TODO: do checksum and counter checks
|
||||||
|
AddrCheckStruct volkswagen_rx_checks[] = { |
||||||
|
{.addr = {MSG_EPS_01}, .bus = 0, .expected_timestep = 10000U}, |
||||||
|
{.addr = {MSG_ACC_06}, .bus = 0, .expected_timestep = 20000U}, |
||||||
|
{.addr = {MSG_MOTOR_20}, .bus = 0, .expected_timestep = 20000U}, |
||||||
|
}; |
||||||
|
|
||||||
|
const int VOLKSWAGEN_RX_CHECK_LEN = sizeof(volkswagen_rx_checks) / sizeof(volkswagen_rx_checks[0]); |
||||||
|
|
||||||
|
struct sample_t volkswagen_torque_driver; // last few driver torques measured
|
||||||
|
int volkswagen_rt_torque_last = 0; |
||||||
|
int volkswagen_desired_torque_last = 0; |
||||||
|
uint32_t volkswagen_ts_last = 0; |
||||||
|
int volkswagen_gas_prev = 0; |
||||||
|
|
||||||
|
static int volkswagen_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||||
|
int bus = GET_BUS(to_push); |
||||||
|
int addr = GET_ADDR(to_push); |
||||||
|
|
||||||
|
// Update driver input torque samples from EPS_01.Driver_Strain for absolute torque, and EPS_01.Driver_Strain_VZ
|
||||||
|
// for the direction.
|
||||||
|
if ((bus == 0) && (addr == MSG_EPS_01)) { |
||||||
|
int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1F) << 8); |
||||||
|
int sign = (GET_BYTE(to_push, 6) & 0x80) >> 7; |
||||||
|
if (sign == 1) { |
||||||
|
torque_driver_new *= -1; |
||||||
|
} |
||||||
|
|
||||||
|
update_sample(&volkswagen_torque_driver, torque_driver_new); |
||||||
|
} |
||||||
|
|
||||||
|
// Monitor ACC_06.ACC_Status_ACC for stock ACC status. Because the current MQB port is lateral-only, OP's control
|
||||||
|
// allowed state is directly driven by stock ACC engagement. Permit the ACC message to come from either bus, in
|
||||||
|
// order to accommodate future camera-side integrations if needed.
|
||||||
|
if (addr == MSG_ACC_06) { |
||||||
|
int acc_status = (GET_BYTE(to_push, 7) & 0x70) >> 4; |
||||||
|
controls_allowed = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0; |
||||||
|
} |
||||||
|
|
||||||
|
// exit controls on rising edge of gas press. Bits [12-20)
|
||||||
|
if (addr == MSG_MOTOR_20) { |
||||||
|
int gas = (GET_BYTES_04(to_push) >> 12) & 0xFF; |
||||||
|
if ((gas > 0) && (volkswagen_gas_prev == 0)) { |
||||||
|
controls_allowed = 0; |
||||||
|
} |
||||||
|
volkswagen_gas_prev = gas; |
||||||
|
} |
||||||
|
|
||||||
|
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && (bus == 0) && (addr == MSG_HCA_01)) { |
||||||
|
relay_malfunction = true; |
||||||
|
} |
||||||
|
return 1; |
||||||
|
} |
||||||
|
|
||||||
|
static int volkswagen_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||||
|
int addr = GET_ADDR(to_send); |
||||||
|
int bus = GET_BUS(to_send); |
||||||
|
int tx = 1; |
||||||
|
|
||||||
|
if (!msg_allowed(addr, bus, VOLKSWAGEN_TX_MSGS, sizeof(VOLKSWAGEN_TX_MSGS)/sizeof(VOLKSWAGEN_TX_MSGS[0]))) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
if (relay_malfunction) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
|
||||||
|
// Safety check for HCA_01 Heading Control Assist torque.
|
||||||
|
if (addr == MSG_HCA_01) { |
||||||
|
bool violation = false; |
||||||
|
|
||||||
|
int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x3F) << 8); |
||||||
|
int sign = (GET_BYTE(to_send, 3) & 0x80) >> 7; |
||||||
|
if (sign == 1) { |
||||||
|
desired_torque *= -1; |
||||||
|
} |
||||||
|
|
||||||
|
uint32_t ts = TIM2->CNT; |
||||||
|
|
||||||
|
if (controls_allowed) { |
||||||
|
|
||||||
|
// *** global torque limit check ***
|
||||||
|
violation |= max_limit_check(desired_torque, VOLKSWAGEN_MAX_STEER, -VOLKSWAGEN_MAX_STEER); |
||||||
|
|
||||||
|
// *** torque rate limit check ***
|
||||||
|
violation |= driver_limit_check(desired_torque, volkswagen_desired_torque_last, &volkswagen_torque_driver, |
||||||
|
VOLKSWAGEN_MAX_STEER, VOLKSWAGEN_MAX_RATE_UP, VOLKSWAGEN_MAX_RATE_DOWN, |
||||||
|
VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_DRIVER_TORQUE_FACTOR); |
||||||
|
volkswagen_desired_torque_last = desired_torque; |
||||||
|
|
||||||
|
// *** torque real time rate limit check ***
|
||||||
|
violation |= rt_rate_limit_check(desired_torque, volkswagen_rt_torque_last, VOLKSWAGEN_MAX_RT_DELTA); |
||||||
|
|
||||||
|
// every RT_INTERVAL set the new limits
|
||||||
|
uint32_t ts_elapsed = get_ts_elapsed(ts, volkswagen_ts_last); |
||||||
|
if (ts_elapsed > VOLKSWAGEN_RT_INTERVAL) { |
||||||
|
volkswagen_rt_torque_last = desired_torque; |
||||||
|
volkswagen_ts_last = ts; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// no torque if controls is not allowed
|
||||||
|
if (!controls_allowed && (desired_torque != 0)) { |
||||||
|
violation = true; |
||||||
|
} |
||||||
|
|
||||||
|
// reset to 0 if either controls is not allowed or there's a violation
|
||||||
|
if (violation || !controls_allowed) { |
||||||
|
volkswagen_desired_torque_last = 0; |
||||||
|
volkswagen_rt_torque_last = 0; |
||||||
|
volkswagen_ts_last = ts; |
||||||
|
} |
||||||
|
|
||||||
|
if (violation) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off.
|
||||||
|
// This avoids unintended engagements while still allowing resume spam
|
||||||
|
if ((addr == MSG_GRA_ACC_01) && !controls_allowed) { |
||||||
|
// disallow resume and set: bits 16 and 19
|
||||||
|
if ((GET_BYTE(to_send, 2) & 0x9) != 0) { |
||||||
|
tx = 0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// 1 allows the message through
|
||||||
|
return tx; |
||||||
|
} |
||||||
|
|
||||||
|
static int volkswagen_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||||
|
int addr = GET_ADDR(to_fwd); |
||||||
|
int bus_fwd = -1; |
||||||
|
|
||||||
|
// NOTE: Will need refactoring for other bus layouts, such as no-forwarding at camera or J533 running-gear CAN
|
||||||
|
|
||||||
|
if (!relay_malfunction) { |
||||||
|
switch (bus_num) { |
||||||
|
case 0: |
||||||
|
// Forward all traffic from J533 gateway to Extended CAN devices.
|
||||||
|
bus_fwd = 2; |
||||||
|
break; |
||||||
|
case 2: |
||||||
|
if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { |
||||||
|
// OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera.
|
||||||
|
bus_fwd = -1; |
||||||
|
} else { |
||||||
|
// Forward all remaining traffic from Extended CAN devices to J533 gateway.
|
||||||
|
bus_fwd = 0; |
||||||
|
} |
||||||
|
break; |
||||||
|
default: |
||||||
|
// No other buses should be in use; fallback to do-not-forward.
|
||||||
|
bus_fwd = -1; |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
return bus_fwd; |
||||||
|
} |
||||||
|
|
||||||
|
const safety_hooks volkswagen_hooks = { |
||||||
|
.init = nooutput_init, |
||||||
|
.rx = volkswagen_rx_hook, |
||||||
|
.tx = volkswagen_tx_hook, |
||||||
|
.tx_lin = nooutput_tx_lin_hook, |
||||||
|
.fwd = volkswagen_fwd_hook, |
||||||
|
.addr_check = volkswagen_rx_checks, |
||||||
|
.addr_check_len = sizeof(volkswagen_rx_checks) / sizeof(volkswagen_rx_checks[0]), |
||||||
|
}; |
@ -0,0 +1,94 @@ |
|||||||
|
const int MAX_WRONG_COUNTERS = 5; |
||||||
|
const uint8_t MAX_MISSED_MSGS = 10U; |
||||||
|
|
||||||
|
// sample struct that keeps 3 samples in memory
|
||||||
|
struct sample_t { |
||||||
|
int values[6]; |
||||||
|
int min; |
||||||
|
int max; |
||||||
|
} sample_t_default = {{0}, 0, 0}; |
||||||
|
|
||||||
|
// safety code requires floats
|
||||||
|
struct lookup_t { |
||||||
|
float x[3]; |
||||||
|
float y[3]; |
||||||
|
}; |
||||||
|
|
||||||
|
typedef struct { |
||||||
|
int addr; |
||||||
|
int bus; |
||||||
|
} AddrBus; |
||||||
|
|
||||||
|
// params and flags about checksum, counter and frequency checks for each monitored address
|
||||||
|
typedef struct { |
||||||
|
// const params
|
||||||
|
const int addr[3]; // check either messages (e.g. honda steer). Array MUST terminate with a zero to know its length.
|
||||||
|
const int bus; // bus where to expect the addr. Temp hack: -1 means skip the bus check
|
||||||
|
const bool check_checksum; // true is checksum check is performed
|
||||||
|
const uint8_t max_counter; // maximum value of the counter. 0 means that the counter check is skipped
|
||||||
|
const uint32_t expected_timestep; // expected time between message updates [us]
|
||||||
|
// dynamic flags
|
||||||
|
bool valid_checksum; // true if and only if checksum check is passed
|
||||||
|
int wrong_counters; // counter of wrong counters, saturated between 0 and MAX_WRONG_COUNTERS
|
||||||
|
uint8_t last_counter; // last counter value
|
||||||
|
uint32_t last_timestamp; // micro-s
|
||||||
|
bool lagging; // true if and only if the time between updates is excessive
|
||||||
|
} AddrCheckStruct; |
||||||
|
|
||||||
|
int safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); |
||||||
|
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); |
||||||
|
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); |
||||||
|
uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); |
||||||
|
int to_signed(int d, int bits); |
||||||
|
void update_sample(struct sample_t *sample, int sample_new); |
||||||
|
bool max_limit_check(int val, const int MAX, const int MIN); |
||||||
|
bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, |
||||||
|
const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); |
||||||
|
bool driver_limit_check(int val, int val_last, struct sample_t *val_driver, |
||||||
|
const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, |
||||||
|
const int MAX_ALLOWANCE, const int DRIVER_FACTOR); |
||||||
|
bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA); |
||||||
|
float interpolate(struct lookup_t xy, float x); |
||||||
|
bool msg_allowed(int addr, int bus, const AddrBus addr_list[], int len); |
||||||
|
int get_addr_check_index(CAN_FIFOMailBox_TypeDef *to_push, AddrCheckStruct addr_list[], const int len); |
||||||
|
void update_counter(AddrCheckStruct addr_list[], int index, uint8_t counter); |
||||||
|
void update_addr_timestamp(AddrCheckStruct addr_list[], int index); |
||||||
|
bool is_msg_valid(AddrCheckStruct addr_list[], int index); |
||||||
|
bool addr_safety_check(CAN_FIFOMailBox_TypeDef *to_push, |
||||||
|
AddrCheckStruct *addr_check, |
||||||
|
const int addr_check_len, |
||||||
|
uint8_t (*get_checksum)(CAN_FIFOMailBox_TypeDef *to_push), |
||||||
|
uint8_t (*compute_checksum)(CAN_FIFOMailBox_TypeDef *to_push), |
||||||
|
uint8_t (*get_counter)(CAN_FIFOMailBox_TypeDef *to_push)); |
||||||
|
|
||||||
|
typedef void (*safety_hook_init)(int16_t param); |
||||||
|
typedef int (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push); |
||||||
|
typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send); |
||||||
|
typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); |
||||||
|
typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd); |
||||||
|
|
||||||
|
typedef struct { |
||||||
|
safety_hook_init init; |
||||||
|
rx_hook rx; |
||||||
|
tx_hook tx; |
||||||
|
tx_lin_hook tx_lin; |
||||||
|
fwd_hook fwd; |
||||||
|
AddrCheckStruct *addr_check; |
||||||
|
const int addr_check_len; |
||||||
|
} safety_hooks; |
||||||
|
|
||||||
|
void safety_tick(const safety_hooks *hooks); |
||||||
|
|
||||||
|
// This can be set by the safety hooks
|
||||||
|
bool controls_allowed = false; |
||||||
|
bool relay_malfunction = false; |
||||||
|
bool gas_interceptor_detected = false; |
||||||
|
int gas_interceptor_prev = 0; |
||||||
|
|
||||||
|
// time since safety mode has been changed
|
||||||
|
uint32_t safety_mode_cnt = 0U; |
||||||
|
// allow 1s of transition timeout after relay changes state before assessing malfunctioning
|
||||||
|
const uint32_t RELAY_TRNS_TIMEOUT = 1U; |
||||||
|
|
||||||
|
// avg between 2 tracks
|
||||||
|
#define GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + ((GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2 ) / 2) |
@ -0,0 +1,342 @@ |
|||||||
|
// flasher state variables
|
||||||
|
uint32_t *prog_ptr = NULL; |
||||||
|
int unlocked = 0; |
||||||
|
|
||||||
|
#ifdef uart_ring |
||||||
|
void debug_ring_callback(uart_ring *ring) {} |
||||||
|
#endif |
||||||
|
|
||||||
|
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { |
||||||
|
int resp_len = 0; |
||||||
|
|
||||||
|
// flasher machine
|
||||||
|
memset(resp, 0, 4); |
||||||
|
memcpy(resp+4, "\xde\xad\xd0\x0d", 4); |
||||||
|
resp[0] = 0xff; |
||||||
|
resp[2] = setup->b.bRequest; |
||||||
|
resp[3] = ~setup->b.bRequest; |
||||||
|
*((uint32_t **)&resp[8]) = prog_ptr; |
||||||
|
resp_len = 0xc; |
||||||
|
|
||||||
|
int sec; |
||||||
|
switch (setup->b.bRequest) { |
||||||
|
// **** 0xb0: flasher echo
|
||||||
|
case 0xb0: |
||||||
|
resp[1] = 0xff; |
||||||
|
break; |
||||||
|
// **** 0xb1: unlock flash
|
||||||
|
case 0xb1: |
||||||
|
if (FLASH->CR & FLASH_CR_LOCK) { |
||||||
|
FLASH->KEYR = 0x45670123; |
||||||
|
FLASH->KEYR = 0xCDEF89AB; |
||||||
|
resp[1] = 0xff; |
||||||
|
} |
||||||
|
current_board->set_led(LED_GREEN, 1); |
||||||
|
unlocked = 1; |
||||||
|
prog_ptr = (uint32_t *)0x8004000; |
||||||
|
break; |
||||||
|
// **** 0xb2: erase sector
|
||||||
|
case 0xb2: |
||||||
|
sec = setup->b.wValue.w; |
||||||
|
// don't erase the bootloader
|
||||||
|
if (sec != 0 && sec < 12 && unlocked) { |
||||||
|
FLASH->CR = (sec << 3) | FLASH_CR_SER; |
||||||
|
FLASH->CR |= FLASH_CR_STRT; |
||||||
|
while (FLASH->SR & FLASH_SR_BSY); |
||||||
|
resp[1] = 0xff; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd0: fetch serial number
|
||||||
|
case 0xd0: |
||||||
|
#ifdef STM32F4 |
||||||
|
// addresses are OTP
|
||||||
|
if (setup->b.wValue.w == 1) { |
||||||
|
memcpy(resp, (void *)0x1fff79c0, 0x10); |
||||||
|
resp_len = 0x10; |
||||||
|
} else { |
||||||
|
get_provision_chunk(resp); |
||||||
|
resp_len = PROVISION_CHUNK_LEN; |
||||||
|
} |
||||||
|
#endif |
||||||
|
break; |
||||||
|
// **** 0xd1: enter bootloader mode
|
||||||
|
case 0xd1: |
||||||
|
// this allows reflashing of the bootstub
|
||||||
|
// so it's blocked over wifi
|
||||||
|
switch (setup->b.wValue.w) { |
||||||
|
case 0: |
||||||
|
// TODO: put this back when it's no longer a "devkit"
|
||||||
|
//#ifdef ALLOW_DEBUG
|
||||||
|
#if 1 |
||||||
|
if (hardwired) { |
||||||
|
#else |
||||||
|
// no more bootstub on UNO once OTP block is flashed
|
||||||
|
if (hardwired && ((hw_type != HW_TYPE_UNO) || (!is_provisioned()))) { |
||||||
|
#endif |
||||||
|
puts("-> entering bootloader\n"); |
||||||
|
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
} |
||||||
|
break; |
||||||
|
case 1: |
||||||
|
puts("-> entering softloader\n"); |
||||||
|
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; |
||||||
|
NVIC_SystemReset(); |
||||||
|
break; |
||||||
|
} |
||||||
|
break; |
||||||
|
// **** 0xd6: get version
|
||||||
|
case 0xd6: |
||||||
|
COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN); |
||||||
|
memcpy(resp, gitversion, sizeof(gitversion)); |
||||||
|
resp_len = sizeof(gitversion); |
||||||
|
break; |
||||||
|
// **** 0xd8: reset ST
|
||||||
|
case 0xd8: |
||||||
|
NVIC_SystemReset(); |
||||||
|
break; |
||||||
|
} |
||||||
|
return resp_len; |
||||||
|
} |
||||||
|
|
||||||
|
int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(usbdata); |
||||||
|
UNUSED(len); |
||||||
|
UNUSED(hardwired); |
||||||
|
return 0; |
||||||
|
} |
||||||
|
void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(usbdata); |
||||||
|
UNUSED(len); |
||||||
|
UNUSED(hardwired); |
||||||
|
} |
||||||
|
|
||||||
|
int is_enumerated = 0; |
||||||
|
void usb_cb_enumeration_complete(void) { |
||||||
|
puts("USB enumeration complete\n"); |
||||||
|
is_enumerated = 1; |
||||||
|
} |
||||||
|
|
||||||
|
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { |
||||||
|
UNUSED(hardwired); |
||||||
|
current_board->set_led(LED_RED, 0); |
||||||
|
for (int i = 0; i < len/4; i++) { |
||||||
|
// program byte 1
|
||||||
|
FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; |
||||||
|
|
||||||
|
*prog_ptr = *(uint32_t*)(usbdata+(i*4)); |
||||||
|
while (FLASH->SR & FLASH_SR_BSY); |
||||||
|
|
||||||
|
//*(uint64_t*)(&spi_tx_buf[0x30+(i*4)]) = *prog_ptr;
|
||||||
|
prog_ptr++; |
||||||
|
} |
||||||
|
current_board->set_led(LED_RED, 1); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { |
||||||
|
UNUSED(len); |
||||||
|
int resp_len = 0; |
||||||
|
switch (data[0]) { |
||||||
|
case 0: |
||||||
|
// control transfer
|
||||||
|
resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); |
||||||
|
break; |
||||||
|
case 2: |
||||||
|
// ep 2, flash!
|
||||||
|
usb_cb_ep2_out(data+4, data[2], 0); |
||||||
|
break; |
||||||
|
} |
||||||
|
return resp_len; |
||||||
|
} |
||||||
|
|
||||||
|
#ifdef PEDAL |
||||||
|
|
||||||
|
#include "drivers/llcan.h" |
||||||
|
#define CAN CAN1 |
||||||
|
|
||||||
|
#define CAN_BL_INPUT 0x1 |
||||||
|
#define CAN_BL_OUTPUT 0x2 |
||||||
|
|
||||||
|
void CAN1_TX_IRQ_Handler(void) { |
||||||
|
// clear interrupt
|
||||||
|
CAN->TSR |= CAN_TSR_RQCP0; |
||||||
|
} |
||||||
|
|
||||||
|
#define ISOTP_BUF_SIZE 0x110 |
||||||
|
|
||||||
|
uint8_t isotp_buf[ISOTP_BUF_SIZE]; |
||||||
|
uint8_t *isotp_buf_ptr = NULL; |
||||||
|
int isotp_buf_remain = 0; |
||||||
|
|
||||||
|
uint8_t isotp_buf_out[ISOTP_BUF_SIZE]; |
||||||
|
uint8_t *isotp_buf_out_ptr = NULL; |
||||||
|
int isotp_buf_out_remain = 0; |
||||||
|
int isotp_buf_out_idx = 0; |
||||||
|
|
||||||
|
void bl_can_send(uint8_t *odat) { |
||||||
|
// wait for send
|
||||||
|
while (!(CAN->TSR & CAN_TSR_TME0)); |
||||||
|
|
||||||
|
// send continue
|
||||||
|
CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; |
||||||
|
CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; |
||||||
|
CAN->sTxMailBox[0].TDTR = 8; |
||||||
|
CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; |
||||||
|
} |
||||||
|
|
||||||
|
void CAN1_RX0_IRQ_Handler(void) { |
||||||
|
while (CAN->RF0R & CAN_RF0R_FMP0) { |
||||||
|
if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { |
||||||
|
uint8_t dat[8]; |
||||||
|
for (int i = 0; i < 8; i++) { |
||||||
|
dat[i] = GET_BYTE(&CAN->sFIFOMailBox[0], i); |
||||||
|
} |
||||||
|
uint8_t odat[8]; |
||||||
|
uint8_t type = dat[0] & 0xF0; |
||||||
|
if (type == 0x30) { |
||||||
|
// continue
|
||||||
|
while (isotp_buf_out_remain > 0) { |
||||||
|
// wait for send
|
||||||
|
while (!(CAN->TSR & CAN_TSR_TME0)); |
||||||
|
|
||||||
|
odat[0] = 0x20 | isotp_buf_out_idx; |
||||||
|
memcpy(odat+1, isotp_buf_out_ptr, 7); |
||||||
|
isotp_buf_out_remain -= 7; |
||||||
|
isotp_buf_out_ptr += 7; |
||||||
|
isotp_buf_out_idx++; |
||||||
|
|
||||||
|
bl_can_send(odat); |
||||||
|
} |
||||||
|
} else if (type == 0x20) { |
||||||
|
if (isotp_buf_remain > 0) { |
||||||
|
memcpy(isotp_buf_ptr, dat+1, 7); |
||||||
|
isotp_buf_ptr += 7; |
||||||
|
isotp_buf_remain -= 7; |
||||||
|
} |
||||||
|
if (isotp_buf_remain <= 0) { |
||||||
|
int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain; |
||||||
|
|
||||||
|
// call the function
|
||||||
|
memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); |
||||||
|
isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out); |
||||||
|
isotp_buf_out_ptr = isotp_buf_out; |
||||||
|
isotp_buf_out_idx = 0; |
||||||
|
|
||||||
|
// send initial
|
||||||
|
if (isotp_buf_out_remain <= 7) { |
||||||
|
odat[0] = isotp_buf_out_remain; |
||||||
|
memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain); |
||||||
|
} else { |
||||||
|
odat[0] = 0x10 | (isotp_buf_out_remain>>8); |
||||||
|
odat[1] = isotp_buf_out_remain & 0xFF; |
||||||
|
memcpy(odat+2, isotp_buf_out_ptr, 6); |
||||||
|
isotp_buf_out_remain -= 6; |
||||||
|
isotp_buf_out_ptr += 6; |
||||||
|
isotp_buf_out_idx++; |
||||||
|
} |
||||||
|
|
||||||
|
bl_can_send(odat); |
||||||
|
} |
||||||
|
} else if (type == 0x10) { |
||||||
|
int len = ((dat[0]&0xF)<<8) | dat[1]; |
||||||
|
|
||||||
|
// setup buffer
|
||||||
|
isotp_buf_ptr = isotp_buf; |
||||||
|
memcpy(isotp_buf_ptr, dat+2, 6); |
||||||
|
|
||||||
|
if (len < (ISOTP_BUF_SIZE-0x10)) { |
||||||
|
isotp_buf_ptr += 6; |
||||||
|
isotp_buf_remain = len-6; |
||||||
|
} |
||||||
|
|
||||||
|
memset(odat, 0, 8); |
||||||
|
odat[0] = 0x30; |
||||||
|
bl_can_send(odat); |
||||||
|
} |
||||||
|
} |
||||||
|
// next
|
||||||
|
CAN->RF0R |= CAN_RF0R_RFOM0; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void CAN1_SCE_IRQ_Handler(void) { |
||||||
|
llcan_clear_send(CAN); |
||||||
|
} |
||||||
|
|
||||||
|
#endif |
||||||
|
|
||||||
|
void soft_flasher_start(void) { |
||||||
|
#ifdef PEDAL |
||||||
|
REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) |
||||||
|
#endif |
||||||
|
|
||||||
|
puts("\n\n\n************************ FLASHER START ************************\n"); |
||||||
|
|
||||||
|
enter_bootloader_mode = 0; |
||||||
|
|
||||||
|
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; |
||||||
|
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; |
||||||
|
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_USART2EN; |
||||||
|
|
||||||
|
// pedal has the canloader
|
||||||
|
#ifdef PEDAL |
||||||
|
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; |
||||||
|
|
||||||
|
// B8,B9: CAN 1
|
||||||
|
set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); |
||||||
|
set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); |
||||||
|
current_board->enable_can_transciever(1, true); |
||||||
|
|
||||||
|
// init can
|
||||||
|
llcan_set_speed(CAN1, 5000, false, false); |
||||||
|
llcan_init(CAN1); |
||||||
|
#endif |
||||||
|
|
||||||
|
// A4,A5,A6,A7: setup SPI
|
||||||
|
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); |
||||||
|
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); |
||||||
|
|
||||||
|
// A2,A3: USART 2 for debugging
|
||||||
|
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); |
||||||
|
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); |
||||||
|
|
||||||
|
// A11,A12: USB
|
||||||
|
set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); |
||||||
|
set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); |
||||||
|
GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; |
||||||
|
|
||||||
|
// flasher
|
||||||
|
spi_init(); |
||||||
|
|
||||||
|
// enable USB
|
||||||
|
usb_init(); |
||||||
|
|
||||||
|
// green LED on for flashing
|
||||||
|
current_board->set_led(LED_GREEN, 1); |
||||||
|
|
||||||
|
enable_interrupts(); |
||||||
|
|
||||||
|
uint64_t cnt = 0; |
||||||
|
|
||||||
|
for (cnt=0;;cnt++) { |
||||||
|
if (cnt == 35 && !is_enumerated && usb_power_mode == USB_POWER_CLIENT) { |
||||||
|
// if you are connected through a hub to the phone
|
||||||
|
// you need power to be able to see the device
|
||||||
|
puts("USBP: didn't enumerate, switching to CDP mode\n"); |
||||||
|
current_board->set_usb_power_mode(USB_POWER_CDP); |
||||||
|
current_board->set_led(LED_BLUE, 1); |
||||||
|
} |
||||||
|
// blink the green LED fast
|
||||||
|
current_board->set_led(LED_GREEN, 0); |
||||||
|
delay(500000); |
||||||
|
current_board->set_led(LED_GREEN, 1); |
||||||
|
delay(500000); |
||||||
|
} |
||||||
|
} |
||||||
|
|
@ -0,0 +1,511 @@ |
|||||||
|
/** |
||||||
|
****************************************************************************** |
||||||
|
* @file startup_stm32f205xx.s
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V2.1.2
|
||||||
|
* @date 29-June-2016
|
||||||
|
* @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain.
|
||||||
|
* This module performs: |
||||||
|
* - Set the initial SP |
||||||
|
* - Set the initial PC == Reset_Handler, |
||||||
|
* - Set the vector table entries with the exceptions ISR address |
||||||
|
* - Branches to main in the C library (which eventually |
||||||
|
* calls main()). |
||||||
|
* After Reset the Cortex-M3 processor is in Thread mode, |
||||||
|
* priority is Privileged, and the Stack is set to Main. |
||||||
|
****************************************************************************** |
||||||
|
* @attention
|
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT 2016 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. |
||||||
|
* |
||||||
|
****************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
.syntax unified
|
||||||
|
.cpu cortex-m3 |
||||||
|
.thumb |
||||||
|
|
||||||
|
.global g_pfnVectors
|
||||||
|
.global Default_Handler
|
||||||
|
|
||||||
|
/* start address for the initialization values of the .data section. |
||||||
|
defined in linker script */ |
||||||
|
.word _sidata
|
||||||
|
/* start address for the .data section. defined in linker script */ |
||||||
|
.word _sdata
|
||||||
|
/* end address for the .data section. defined in linker script */ |
||||||
|
.word _edata
|
||||||
|
/* start address for the .bss section. defined in linker script */ |
||||||
|
.word _sbss
|
||||||
|
/* end address for the .bss section. defined in linker script */ |
||||||
|
.word _ebss
|
||||||
|
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ |
||||||
|
|
||||||
|
/** |
||||||
|
* @brief This is the code that gets called when the processor first
|
||||||
|
* starts execution following a reset event. Only the absolutely |
||||||
|
* necessary set is performed, after which the application |
||||||
|
* supplied main() routine is called. |
||||||
|
* @param None
|
||||||
|
* @retval : None
|
||||||
|
*/ |
||||||
|
|
||||||
|
.section .text.Reset_Handler |
||||||
|
.weak Reset_Handler
|
||||||
|
.type Reset_Handler, %function |
||||||
|
Reset_Handler: |
||||||
|
ldr sp, =_estack /* set stack pointer */ |
||||||
|
bl __initialize_hardware_early |
||||||
|
|
||||||
|
/* Copy the data segment initializers from flash to SRAM */ |
||||||
|
movs r1, #0 |
||||||
|
b LoopCopyDataInit |
||||||
|
|
||||||
|
CopyDataInit: |
||||||
|
ldr r3, =_sidata |
||||||
|
ldr r3, [r3, r1] |
||||||
|
str r3, [r0, r1] |
||||||
|
adds r1, r1, #4 |
||||||
|
|
||||||
|
LoopCopyDataInit: |
||||||
|
ldr r0, =_sdata |
||||||
|
ldr r3, =_edata |
||||||
|
adds r2, r0, r1 |
||||||
|
cmp r2, r3 |
||||||
|
bcc CopyDataInit |
||||||
|
ldr r2, =_sbss |
||||||
|
b LoopFillZerobss |
||||||
|
/* Zero fill the bss segment. */ |
||||||
|
FillZerobss: |
||||||
|
movs r3, #0 |
||||||
|
str r3, [r2], #4 |
||||||
|
|
||||||
|
LoopFillZerobss: |
||||||
|
ldr r3, = _ebss |
||||||
|
cmp r2, r3 |
||||||
|
bcc FillZerobss |
||||||
|
|
||||||
|
/* Call the clock system initialization function.*/ |
||||||
|
/*bl SystemInit */ |
||||||
|
/* Call static constructors */ |
||||||
|
/*bl __libc_init_array*/ |
||||||
|
/* Call the application's entry point.*/ |
||||||
|
bl main |
||||||
|
bx lr |
||||||
|
.size Reset_Handler, .-Reset_Handler |
||||||
|
|
||||||
|
/** |
||||||
|
* @brief This is the code that gets called when the processor receives an
|
||||||
|
* unexpected interrupt. This simply enters an infinite loop, preserving |
||||||
|
* the system state for examination by a debugger. |
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/ |
||||||
|
.section .text.Default_Handler,"ax",%progbits |
||||||
|
Default_Handler: |
||||||
|
Infinite_Loop: |
||||||
|
b Infinite_Loop |
||||||
|
.size Default_Handler, .-Default_Handler |
||||||
|
/****************************************************************************** |
||||||
|
* |
||||||
|
* The minimal vector table for a Cortex M3. Note that the proper constructs |
||||||
|
* must be placed on this to ensure that it ends up at physical address |
||||||
|
* 0x0000.0000. |
||||||
|
* |
||||||
|
*******************************************************************************/ |
||||||
|
.section .isr_vector,"a",%progbits |
||||||
|
.type g_pfnVectors, %object |
||||||
|
.size g_pfnVectors, .-g_pfnVectors |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
g_pfnVectors: |
||||||
|
.word _estack
|
||||||
|
.word Reset_Handler
|
||||||
|
|
||||||
|
.word NMI_Handler
|
||||||
|
.word HardFault_Handler
|
||||||
|
.word MemManage_Handler
|
||||||
|
.word BusFault_Handler
|
||||||
|
.word UsageFault_Handler
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word SVC_Handler
|
||||||
|
.word DebugMon_Handler
|
||||||
|
.word 0
|
||||||
|
.word PendSV_Handler
|
||||||
|
.word SysTick_Handler
|
||||||
|
|
||||||
|
/* External Interrupts */ |
||||||
|
.word WWDG_IRQHandler /* Window WatchDog */ |
||||||
|
.word PVD_IRQHandler /* PVD through EXTI Line detection */ |
||||||
|
.word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ |
||||||
|
.word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ |
||||||
|
.word FLASH_IRQHandler /* FLASH */ |
||||||
|
.word RCC_IRQHandler /* RCC */ |
||||||
|
.word EXTI0_IRQHandler /* EXTI Line0 */ |
||||||
|
.word EXTI1_IRQHandler /* EXTI Line1 */ |
||||||
|
.word EXTI2_IRQHandler /* EXTI Line2 */ |
||||||
|
.word EXTI3_IRQHandler /* EXTI Line3 */ |
||||||
|
.word EXTI4_IRQHandler /* EXTI Line4 */ |
||||||
|
.word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ |
||||||
|
.word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ |
||||||
|
.word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ |
||||||
|
.word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ |
||||||
|
.word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ |
||||||
|
.word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ |
||||||
|
.word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ |
||||||
|
.word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ |
||||||
|
.word CAN1_TX_IRQHandler /* CAN1 TX */ |
||||||
|
.word CAN1_RX0_IRQHandler /* CAN1 RX0 */ |
||||||
|
.word CAN1_RX1_IRQHandler /* CAN1 RX1 */ |
||||||
|
.word CAN1_SCE_IRQHandler /* CAN1 SCE */ |
||||||
|
.word EXTI9_5_IRQHandler /* External Line[9:5]s */ |
||||||
|
.word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ |
||||||
|
.word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ |
||||||
|
.word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ |
||||||
|
.word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ |
||||||
|
.word TIM2_IRQHandler /* TIM2 */ |
||||||
|
.word TIM3_IRQHandler /* TIM3 */ |
||||||
|
.word TIM4_IRQHandler /* TIM4 */ |
||||||
|
.word I2C1_EV_IRQHandler /* I2C1 Event */ |
||||||
|
.word I2C1_ER_IRQHandler /* I2C1 Error */ |
||||||
|
.word I2C2_EV_IRQHandler /* I2C2 Event */ |
||||||
|
.word I2C2_ER_IRQHandler /* I2C2 Error */ |
||||||
|
.word SPI1_IRQHandler /* SPI1 */ |
||||||
|
.word SPI2_IRQHandler /* SPI2 */ |
||||||
|
.word USART1_IRQHandler /* USART1 */ |
||||||
|
.word USART2_IRQHandler /* USART2 */ |
||||||
|
.word USART3_IRQHandler /* USART3 */ |
||||||
|
.word EXTI15_10_IRQHandler /* External Line[15:10]s */ |
||||||
|
.word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ |
||||||
|
.word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ |
||||||
|
.word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ |
||||||
|
.word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ |
||||||
|
.word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ |
||||||
|
.word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ |
||||||
|
.word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ |
||||||
|
.word FSMC_IRQHandler /* FSMC */ |
||||||
|
.word SDIO_IRQHandler /* SDIO */ |
||||||
|
.word TIM5_IRQHandler /* TIM5 */ |
||||||
|
.word SPI3_IRQHandler /* SPI3 */ |
||||||
|
.word UART4_IRQHandler /* UART4 */ |
||||||
|
.word UART5_IRQHandler /* UART5 */ |
||||||
|
.word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ |
||||||
|
.word TIM7_IRQHandler /* TIM7 */ |
||||||
|
.word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ |
||||||
|
.word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ |
||||||
|
.word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ |
||||||
|
.word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ |
||||||
|
.word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word CAN2_TX_IRQHandler /* CAN2 TX */ |
||||||
|
.word CAN2_RX0_IRQHandler /* CAN2 RX0 */ |
||||||
|
.word CAN2_RX1_IRQHandler /* CAN2 RX1 */ |
||||||
|
.word CAN2_SCE_IRQHandler /* CAN2 SCE */ |
||||||
|
.word OTG_FS_IRQHandler /* USB OTG FS */ |
||||||
|
.word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ |
||||||
|
.word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ |
||||||
|
.word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ |
||||||
|
.word USART6_IRQHandler /* USART6 */ |
||||||
|
.word I2C3_EV_IRQHandler /* I2C3 event */ |
||||||
|
.word I2C3_ER_IRQHandler /* I2C3 error */ |
||||||
|
.word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ |
||||||
|
.word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ |
||||||
|
.word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ |
||||||
|
.word OTG_HS_IRQHandler /* USB OTG HS */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word HASH_RNG_IRQHandler /* Hash and Rng */ |
||||||
|
|
||||||
|
/******************************************************************************* |
||||||
|
* |
||||||
|
* Provide weak aliases for each Exception handler to the Default_Handler. |
||||||
|
* As they are weak aliases, any function with the same name will override |
||||||
|
* this definition. |
||||||
|
* |
||||||
|
*******************************************************************************/ |
||||||
|
.weak NMI_Handler
|
||||||
|
.thumb_set NMI_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak HardFault_Handler
|
||||||
|
.thumb_set HardFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak MemManage_Handler
|
||||||
|
.thumb_set MemManage_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak BusFault_Handler
|
||||||
|
.thumb_set BusFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak UsageFault_Handler
|
||||||
|
.thumb_set UsageFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak SVC_Handler
|
||||||
|
.thumb_set SVC_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak DebugMon_Handler
|
||||||
|
.thumb_set DebugMon_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak PendSV_Handler
|
||||||
|
.thumb_set PendSV_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak SysTick_Handler
|
||||||
|
.thumb_set SysTick_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak WWDG_IRQHandler
|
||||||
|
.thumb_set WWDG_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak PVD_IRQHandler
|
||||||
|
.thumb_set PVD_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TAMP_STAMP_IRQHandler
|
||||||
|
.thumb_set TAMP_STAMP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RTC_WKUP_IRQHandler
|
||||||
|
.thumb_set RTC_WKUP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FLASH_IRQHandler
|
||||||
|
.thumb_set FLASH_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RCC_IRQHandler
|
||||||
|
.thumb_set RCC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI0_IRQHandler
|
||||||
|
.thumb_set EXTI0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI1_IRQHandler
|
||||||
|
.thumb_set EXTI1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI2_IRQHandler
|
||||||
|
.thumb_set EXTI2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI3_IRQHandler
|
||||||
|
.thumb_set EXTI3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI4_IRQHandler
|
||||||
|
.thumb_set EXTI4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream0_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream1_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream2_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream3_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream4_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream5_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream6_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak ADC_IRQHandler
|
||||||
|
.thumb_set ADC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_TX_IRQHandler
|
||||||
|
.thumb_set CAN1_TX_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_RX0_IRQHandler
|
||||||
|
.thumb_set CAN1_RX0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_RX1_IRQHandler
|
||||||
|
.thumb_set CAN1_RX1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_SCE_IRQHandler
|
||||||
|
.thumb_set CAN1_SCE_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI9_5_IRQHandler
|
||||||
|
.thumb_set EXTI9_5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_BRK_TIM9_IRQHandler
|
||||||
|
.thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_UP_TIM10_IRQHandler
|
||||||
|
.thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_TRG_COM_TIM11_IRQHandler
|
||||||
|
.thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_CC_IRQHandler
|
||||||
|
.thumb_set TIM1_CC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM2_IRQHandler
|
||||||
|
.thumb_set TIM2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM3_IRQHandler
|
||||||
|
.thumb_set TIM3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM4_IRQHandler
|
||||||
|
.thumb_set TIM4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C1_EV_IRQHandler
|
||||||
|
.thumb_set I2C1_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C1_ER_IRQHandler
|
||||||
|
.thumb_set I2C1_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C2_EV_IRQHandler
|
||||||
|
.thumb_set I2C2_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C2_ER_IRQHandler
|
||||||
|
.thumb_set I2C2_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI1_IRQHandler
|
||||||
|
.thumb_set SPI1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI2_IRQHandler
|
||||||
|
.thumb_set SPI2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART1_IRQHandler
|
||||||
|
.thumb_set USART1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART2_IRQHandler
|
||||||
|
.thumb_set USART2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART3_IRQHandler
|
||||||
|
.thumb_set USART3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI15_10_IRQHandler
|
||||||
|
.thumb_set EXTI15_10_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RTC_Alarm_IRQHandler
|
||||||
|
.thumb_set RTC_Alarm_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_FS_WKUP_IRQHandler
|
||||||
|
.thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_BRK_TIM12_IRQHandler
|
||||||
|
.thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_UP_TIM13_IRQHandler
|
||||||
|
.thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_TRG_COM_TIM14_IRQHandler
|
||||||
|
.thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_CC_IRQHandler
|
||||||
|
.thumb_set TIM8_CC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream7_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FSMC_IRQHandler
|
||||||
|
.thumb_set FSMC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SDIO_IRQHandler
|
||||||
|
.thumb_set SDIO_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM5_IRQHandler
|
||||||
|
.thumb_set TIM5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI3_IRQHandler
|
||||||
|
.thumb_set SPI3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART4_IRQHandler
|
||||||
|
.thumb_set UART4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART5_IRQHandler
|
||||||
|
.thumb_set UART5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM6_DAC_IRQHandler
|
||||||
|
.thumb_set TIM6_DAC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM7_IRQHandler
|
||||||
|
.thumb_set TIM7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream0_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream1_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream2_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream3_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream4_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_TX_IRQHandler
|
||||||
|
.thumb_set CAN2_TX_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_RX0_IRQHandler
|
||||||
|
.thumb_set CAN2_RX0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_RX1_IRQHandler
|
||||||
|
.thumb_set CAN2_RX1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_SCE_IRQHandler
|
||||||
|
.thumb_set CAN2_SCE_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_FS_IRQHandler
|
||||||
|
.thumb_set OTG_FS_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream5_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream6_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream7_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART6_IRQHandler
|
||||||
|
.thumb_set USART6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C3_EV_IRQHandler
|
||||||
|
.thumb_set I2C3_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C3_ER_IRQHandler
|
||||||
|
.thumb_set I2C3_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_HS_EP1_OUT_IRQHandler
|
||||||
|
.thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_HS_EP1_IN_IRQHandler
|
||||||
|
.thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_HS_WKUP_IRQHandler
|
||||||
|
.thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_HS_IRQHandler
|
||||||
|
.thumb_set OTG_HS_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak HASH_RNG_IRQHandler
|
||||||
|
.thumb_set HASH_RNG_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,583 @@ |
|||||||
|
/** |
||||||
|
****************************************************************************** |
||||||
|
* @file startup_stm32f413xx.s
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V2.6.0
|
||||||
|
* @date 04-November-2016
|
||||||
|
* @brief STM32F413xx Devices vector table for GCC based toolchains.
|
||||||
|
* This module performs: |
||||||
|
* - Set the initial SP |
||||||
|
* - Set the initial PC == Reset_Handler, |
||||||
|
* - Set the vector table entries with the exceptions ISR address |
||||||
|
* - Branches to main in the C library (which eventually |
||||||
|
* calls main()). |
||||||
|
* After Reset the Cortex-M4 processor is in Thread mode, |
||||||
|
* priority is Privileged, and the Stack is set to Main. |
||||||
|
****************************************************************************** |
||||||
|
* @attention
|
||||||
|
* |
||||||
|
* <h2><center>© COPYRIGHT 2016 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. |
||||||
|
* |
||||||
|
****************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
.syntax unified
|
||||||
|
.cpu cortex-m4 |
||||||
|
.fpu softvfp
|
||||||
|
.thumb |
||||||
|
|
||||||
|
.global g_pfnVectors
|
||||||
|
.global Default_Handler
|
||||||
|
|
||||||
|
/* start address for the initialization values of the .data section. |
||||||
|
defined in linker script */ |
||||||
|
.word _sidata
|
||||||
|
/* start address for the .data section. defined in linker script */ |
||||||
|
.word _sdata
|
||||||
|
/* end address for the .data section. defined in linker script */ |
||||||
|
.word _edata
|
||||||
|
/* start address for the .bss section. defined in linker script */ |
||||||
|
.word _sbss
|
||||||
|
/* end address for the .bss section. defined in linker script */ |
||||||
|
.word _ebss
|
||||||
|
/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ |
||||||
|
|
||||||
|
/** |
||||||
|
* @brief This is the code that gets called when the processor first
|
||||||
|
* starts execution following a reset event. Only the absolutely |
||||||
|
* necessary set is performed, after which the application |
||||||
|
* supplied main() routine is called. |
||||||
|
* @param None
|
||||||
|
* @retval : None
|
||||||
|
*/ |
||||||
|
|
||||||
|
.section .text.Reset_Handler |
||||||
|
.weak Reset_Handler
|
||||||
|
.type Reset_Handler, %function |
||||||
|
Reset_Handler: |
||||||
|
ldr sp, =_estack /* set stack pointer */ |
||||||
|
bl __initialize_hardware_early |
||||||
|
|
||||||
|
/* Copy the data segment initializers from flash to SRAM */ |
||||||
|
movs r1, #0 |
||||||
|
b LoopCopyDataInit |
||||||
|
|
||||||
|
CopyDataInit: |
||||||
|
ldr r3, =_sidata |
||||||
|
ldr r3, [r3, r1] |
||||||
|
str r3, [r0, r1] |
||||||
|
adds r1, r1, #4 |
||||||
|
|
||||||
|
LoopCopyDataInit: |
||||||
|
ldr r0, =_sdata |
||||||
|
ldr r3, =_edata |
||||||
|
adds r2, r0, r1 |
||||||
|
cmp r2, r3 |
||||||
|
bcc CopyDataInit |
||||||
|
ldr r2, =_sbss |
||||||
|
b LoopFillZerobss |
||||||
|
/* Zero fill the bss segment. */ |
||||||
|
FillZerobss: |
||||||
|
movs r3, #0 |
||||||
|
str r3, [r2], #4 |
||||||
|
|
||||||
|
LoopFillZerobss: |
||||||
|
ldr r3, = _ebss |
||||||
|
cmp r2, r3 |
||||||
|
bcc FillZerobss |
||||||
|
|
||||||
|
/* Call the clock system intitialization function.*/ |
||||||
|
/* bl SystemInit */ |
||||||
|
/* Call static constructors */ |
||||||
|
/* bl __libc_init_array */ |
||||||
|
/* Call the application's entry point.*/ |
||||||
|
bl main |
||||||
|
bx lr |
||||||
|
.size Reset_Handler, .-Reset_Handler |
||||||
|
|
||||||
|
/** |
||||||
|
* @brief This is the code that gets called when the processor receives an
|
||||||
|
* unexpected interrupt. This simply enters an infinite loop, preserving |
||||||
|
* the system state for examination by a debugger. |
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/ |
||||||
|
.section .text.Default_Handler,"ax",%progbits |
||||||
|
Default_Handler: |
||||||
|
Infinite_Loop: |
||||||
|
b Infinite_Loop |
||||||
|
.size Default_Handler, .-Default_Handler |
||||||
|
/****************************************************************************** |
||||||
|
* |
||||||
|
* The minimal vector table for a Cortex M3. Note that the proper constructs |
||||||
|
* must be placed on this to ensure that it ends up at physical address |
||||||
|
* 0x0000.0000. |
||||||
|
* |
||||||
|
*******************************************************************************/ |
||||||
|
.section .isr_vector,"a",%progbits |
||||||
|
.type g_pfnVectors, %object |
||||||
|
.size g_pfnVectors, .-g_pfnVectors |
||||||
|
|
||||||
|
g_pfnVectors: |
||||||
|
.word _estack
|
||||||
|
.word Reset_Handler
|
||||||
|
.word NMI_Handler
|
||||||
|
.word HardFault_Handler
|
||||||
|
.word MemManage_Handler
|
||||||
|
.word BusFault_Handler
|
||||||
|
.word UsageFault_Handler
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word 0
|
||||||
|
.word SVC_Handler
|
||||||
|
.word DebugMon_Handler
|
||||||
|
.word 0
|
||||||
|
.word PendSV_Handler
|
||||||
|
.word SysTick_Handler
|
||||||
|
|
||||||
|
/* External Interrupts */ |
||||||
|
.word WWDG_IRQHandler /* Window WatchDog */ |
||||||
|
.word PVD_IRQHandler /* PVD through EXTI Line detection */ |
||||||
|
.word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ |
||||||
|
.word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ |
||||||
|
.word FLASH_IRQHandler /* FLASH */ |
||||||
|
.word RCC_IRQHandler /* RCC */ |
||||||
|
.word EXTI0_IRQHandler /* EXTI Line0 */ |
||||||
|
.word EXTI1_IRQHandler /* EXTI Line1 */ |
||||||
|
.word EXTI2_IRQHandler /* EXTI Line2 */ |
||||||
|
.word EXTI3_IRQHandler /* EXTI Line3 */ |
||||||
|
.word EXTI4_IRQHandler /* EXTI Line4 */ |
||||||
|
.word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ |
||||||
|
.word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ |
||||||
|
.word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ |
||||||
|
.word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ |
||||||
|
.word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ |
||||||
|
.word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ |
||||||
|
.word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ |
||||||
|
.word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ |
||||||
|
.word CAN1_TX_IRQHandler /* CAN1 TX */ |
||||||
|
.word CAN1_RX0_IRQHandler /* CAN1 RX0 */ |
||||||
|
.word CAN1_RX1_IRQHandler /* CAN1 RX1 */ |
||||||
|
.word CAN1_SCE_IRQHandler /* CAN1 SCE */ |
||||||
|
.word EXTI9_5_IRQHandler /* External Line[9:5]s */ |
||||||
|
.word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ |
||||||
|
.word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ |
||||||
|
.word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ |
||||||
|
.word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ |
||||||
|
.word TIM2_IRQHandler /* TIM2 */ |
||||||
|
.word TIM3_IRQHandler /* TIM3 */ |
||||||
|
.word TIM4_IRQHandler /* TIM4 */ |
||||||
|
.word I2C1_EV_IRQHandler /* I2C1 Event */ |
||||||
|
.word I2C1_ER_IRQHandler /* I2C1 Error */ |
||||||
|
.word I2C2_EV_IRQHandler /* I2C2 Event */ |
||||||
|
.word I2C2_ER_IRQHandler /* I2C2 Error */ |
||||||
|
.word SPI1_IRQHandler /* SPI1 */ |
||||||
|
.word SPI2_IRQHandler /* SPI2 */ |
||||||
|
.word USART1_IRQHandler /* USART1 */ |
||||||
|
.word USART2_IRQHandler /* USART2 */ |
||||||
|
.word USART3_IRQHandler /* USART3 */ |
||||||
|
.word EXTI15_10_IRQHandler /* External Line[15:10]s */ |
||||||
|
.word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ |
||||||
|
.word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ |
||||||
|
.word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ |
||||||
|
.word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ |
||||||
|
.word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ |
||||||
|
.word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ |
||||||
|
.word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ |
||||||
|
.word FSMC_IRQHandler /* FSMC */ |
||||||
|
.word SDIO_IRQHandler /* SDIO */ |
||||||
|
.word TIM5_IRQHandler /* TIM5 */ |
||||||
|
.word SPI3_IRQHandler /* SPI3 */ |
||||||
|
.word UART4_IRQHandler /* UART4 */ |
||||||
|
.word UART5_IRQHandler /* UART5 */ |
||||||
|
.word TIM6_DAC_IRQHandler /* TIM6, DAC1 and DAC2 */ |
||||||
|
.word TIM7_IRQHandler /* TIM7 */ |
||||||
|
.word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ |
||||||
|
.word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ |
||||||
|
.word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ |
||||||
|
.word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ |
||||||
|
.word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ |
||||||
|
.word DFSDM1_FLT0_IRQHandler /* DFSDM1 Filter0 */ |
||||||
|
.word DFSDM1_FLT1_IRQHandler /* DFSDM1 Filter1 */ |
||||||
|
.word CAN2_TX_IRQHandler /* CAN2 TX */ |
||||||
|
.word CAN2_RX0_IRQHandler /* CAN2 RX0 */ |
||||||
|
.word CAN2_RX1_IRQHandler /* CAN2 RX1 */ |
||||||
|
.word CAN2_SCE_IRQHandler /* CAN2 SCE */ |
||||||
|
.word OTG_FS_IRQHandler /* USB OTG FS */ |
||||||
|
.word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ |
||||||
|
.word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ |
||||||
|
.word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ |
||||||
|
.word USART6_IRQHandler /* USART6 */ |
||||||
|
.word I2C3_EV_IRQHandler /* I2C3 event */ |
||||||
|
.word I2C3_ER_IRQHandler /* I2C3 error */ |
||||||
|
.word CAN3_TX_IRQHandler /* CAN3 TX */ |
||||||
|
.word CAN3_RX0_IRQHandler /* CAN3 RX0 */ |
||||||
|
.word CAN3_RX1_IRQHandler /* CAN3 RX1 */ |
||||||
|
.word CAN3_SCE_IRQHandler /* CAN3 SCE */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word RNG_IRQHandler /* RNG */ |
||||||
|
.word FPU_IRQHandler /* FPU */ |
||||||
|
.word UART7_IRQHandler /* UART7 */ |
||||||
|
.word UART8_IRQHandler /* UART8 */ |
||||||
|
.word SPI4_IRQHandler /* SPI4 */ |
||||||
|
.word SPI5_IRQHandler /* SPI5 */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word SAI1_IRQHandler /* SAI1 */ |
||||||
|
.word UART9_IRQHandler /* UART9 */ |
||||||
|
.word UART10_IRQHandler /* UART10 */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word QUADSPI_IRQHandler /* QuadSPI */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word 0 /* Reserved */ |
||||||
|
.word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ |
||||||
|
.word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ |
||||||
|
.word LPTIM1_IRQHandler /* LPTIM1 */ |
||||||
|
.word DFSDM2_FLT0_IRQHandler /* DFSDM2 Filter0 */ |
||||||
|
.word DFSDM2_FLT1_IRQHandler /* DFSDM2 Filter1 */ |
||||||
|
.word DFSDM2_FLT2_IRQHandler /* DFSDM2 Filter2 */ |
||||||
|
.word DFSDM2_FLT3_IRQHandler /* DFSDM2 Filter3 */ |
||||||
|
|
||||||
|
/******************************************************************************* |
||||||
|
* |
||||||
|
* Provide weak aliases for each Exception handler to the Default_Handler. |
||||||
|
* As they are weak aliases, any function with the same name will override |
||||||
|
* this definition. |
||||||
|
* |
||||||
|
*******************************************************************************/ |
||||||
|
.weak NMI_Handler
|
||||||
|
.thumb_set NMI_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak HardFault_Handler
|
||||||
|
.thumb_set HardFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak MemManage_Handler
|
||||||
|
.thumb_set MemManage_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak BusFault_Handler
|
||||||
|
.thumb_set BusFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak UsageFault_Handler
|
||||||
|
.thumb_set UsageFault_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak SVC_Handler
|
||||||
|
.thumb_set SVC_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak DebugMon_Handler
|
||||||
|
.thumb_set DebugMon_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak PendSV_Handler
|
||||||
|
.thumb_set PendSV_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak SysTick_Handler
|
||||||
|
.thumb_set SysTick_Handler,Default_Handler |
||||||
|
|
||||||
|
.weak WWDG_IRQHandler
|
||||||
|
.thumb_set WWDG_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak PVD_IRQHandler
|
||||||
|
.thumb_set PVD_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TAMP_STAMP_IRQHandler
|
||||||
|
.thumb_set TAMP_STAMP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RTC_WKUP_IRQHandler
|
||||||
|
.thumb_set RTC_WKUP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FLASH_IRQHandler
|
||||||
|
.thumb_set FLASH_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RCC_IRQHandler
|
||||||
|
.thumb_set RCC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI0_IRQHandler
|
||||||
|
.thumb_set EXTI0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI1_IRQHandler
|
||||||
|
.thumb_set EXTI1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI2_IRQHandler
|
||||||
|
.thumb_set EXTI2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI3_IRQHandler
|
||||||
|
.thumb_set EXTI3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI4_IRQHandler
|
||||||
|
.thumb_set EXTI4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream0_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream1_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream2_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream3_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream4_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream5_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream6_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak ADC_IRQHandler
|
||||||
|
.thumb_set ADC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_TX_IRQHandler
|
||||||
|
.thumb_set CAN1_TX_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_RX0_IRQHandler
|
||||||
|
.thumb_set CAN1_RX0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_RX1_IRQHandler
|
||||||
|
.thumb_set CAN1_RX1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN1_SCE_IRQHandler
|
||||||
|
.thumb_set CAN1_SCE_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI9_5_IRQHandler
|
||||||
|
.thumb_set EXTI9_5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_BRK_TIM9_IRQHandler
|
||||||
|
.thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_UP_TIM10_IRQHandler
|
||||||
|
.thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_TRG_COM_TIM11_IRQHandler
|
||||||
|
.thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM1_CC_IRQHandler
|
||||||
|
.thumb_set TIM1_CC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM2_IRQHandler
|
||||||
|
.thumb_set TIM2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM3_IRQHandler
|
||||||
|
.thumb_set TIM3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM4_IRQHandler
|
||||||
|
.thumb_set TIM4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C1_EV_IRQHandler
|
||||||
|
.thumb_set I2C1_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C1_ER_IRQHandler
|
||||||
|
.thumb_set I2C1_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C2_EV_IRQHandler
|
||||||
|
.thumb_set I2C2_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C2_ER_IRQHandler
|
||||||
|
.thumb_set I2C2_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI1_IRQHandler
|
||||||
|
.thumb_set SPI1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI2_IRQHandler
|
||||||
|
.thumb_set SPI2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART1_IRQHandler
|
||||||
|
.thumb_set USART1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART2_IRQHandler
|
||||||
|
.thumb_set USART2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART3_IRQHandler
|
||||||
|
.thumb_set USART3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak EXTI15_10_IRQHandler
|
||||||
|
.thumb_set EXTI15_10_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RTC_Alarm_IRQHandler
|
||||||
|
.thumb_set RTC_Alarm_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_FS_WKUP_IRQHandler
|
||||||
|
.thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_BRK_TIM12_IRQHandler
|
||||||
|
.thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_UP_TIM13_IRQHandler
|
||||||
|
.thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_TRG_COM_TIM14_IRQHandler
|
||||||
|
.thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM8_CC_IRQHandler
|
||||||
|
.thumb_set TIM8_CC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA1_Stream7_IRQHandler
|
||||||
|
.thumb_set DMA1_Stream7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FSMC_IRQHandler
|
||||||
|
.thumb_set FSMC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SDIO_IRQHandler
|
||||||
|
.thumb_set SDIO_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM5_IRQHandler
|
||||||
|
.thumb_set TIM5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI3_IRQHandler
|
||||||
|
.thumb_set SPI3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART4_IRQHandler
|
||||||
|
.thumb_set UART4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART5_IRQHandler
|
||||||
|
.thumb_set UART5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM6_DAC_IRQHandler
|
||||||
|
.thumb_set TIM6_DAC_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak TIM7_IRQHandler
|
||||||
|
.thumb_set TIM7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream0_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream1_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream2_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream3_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream3_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream4_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM1_FLT0_IRQHandler
|
||||||
|
.thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM1_FLT1_IRQHandler
|
||||||
|
.thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_TX_IRQHandler
|
||||||
|
.thumb_set CAN2_TX_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_RX0_IRQHandler
|
||||||
|
.thumb_set CAN2_RX0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_RX1_IRQHandler
|
||||||
|
.thumb_set CAN2_RX1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN2_SCE_IRQHandler
|
||||||
|
.thumb_set CAN2_SCE_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak OTG_FS_IRQHandler
|
||||||
|
.thumb_set OTG_FS_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream5_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream6_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DMA2_Stream7_IRQHandler
|
||||||
|
.thumb_set DMA2_Stream7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak USART6_IRQHandler
|
||||||
|
.thumb_set USART6_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C3_EV_IRQHandler
|
||||||
|
.thumb_set I2C3_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak I2C3_ER_IRQHandler
|
||||||
|
.thumb_set I2C3_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN3_TX_IRQHandler
|
||||||
|
.thumb_set CAN3_TX_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN3_RX0_IRQHandler
|
||||||
|
.thumb_set CAN3_RX0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN3_RX1_IRQHandler
|
||||||
|
.thumb_set CAN3_RX1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak CAN3_SCE_IRQHandler
|
||||||
|
.thumb_set CAN3_SCE_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak RNG_IRQHandler
|
||||||
|
.thumb_set RNG_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FPU_IRQHandler
|
||||||
|
.thumb_set FPU_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART7_IRQHandler
|
||||||
|
.thumb_set UART7_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART8_IRQHandler
|
||||||
|
.thumb_set UART8_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI4_IRQHandler
|
||||||
|
.thumb_set SPI4_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SPI5_IRQHandler
|
||||||
|
.thumb_set SPI5_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak SAI1_IRQHandler
|
||||||
|
.thumb_set SAI1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART9_IRQHandler
|
||||||
|
.thumb_set UART9_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak UART10_IRQHandler
|
||||||
|
.thumb_set UART10_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak QUADSPI_IRQHandler
|
||||||
|
.thumb_set QUADSPI_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FMPI2C1_EV_IRQHandler
|
||||||
|
.thumb_set FMPI2C1_EV_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak FMPI2C1_ER_IRQHandler
|
||||||
|
.thumb_set FMPI2C1_ER_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak LPTIM1_IRQHandler
|
||||||
|
.thumb_set LPTIM1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM2_FLT0_IRQHandler
|
||||||
|
.thumb_set DFSDM2_FLT0_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM2_FLT1_IRQHandler
|
||||||
|
.thumb_set DFSDM2_FLT1_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM2_FLT2_IRQHandler
|
||||||
|
.thumb_set DFSDM2_FLT2_IRQHandler,Default_Handler |
||||||
|
|
||||||
|
.weak DFSDM2_FLT3_IRQHandler
|
||||||
|
.thumb_set DFSDM2_FLT3_IRQHandler,Default_Handler |
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -0,0 +1,165 @@ |
|||||||
|
/* |
||||||
|
***************************************************************************** |
||||||
|
** |
||||||
|
** File : stm32_flash.ld |
||||||
|
** |
||||||
|
** Abstract : Linker script for STM32F407VG Device with |
||||||
|
** 1024KByte FLASH, 192KByte RAM |
||||||
|
** |
||||||
|
** Set heap size, stack size and stack location according |
||||||
|
** to application requirements. |
||||||
|
** |
||||||
|
** Set memory bank area and size if external memory is used. |
||||||
|
** |
||||||
|
** Target : STMicroelectronics STM32 |
||||||
|
** |
||||||
|
** Environment : Atollic TrueSTUDIO(R) |
||||||
|
** |
||||||
|
** Distribution: The file is distributed “as is,” without any warranty |
||||||
|
** of any kind. |
||||||
|
** |
||||||
|
** (c)Copyright Atollic AB. |
||||||
|
** You may use this file as-is or modify it according to the needs of your |
||||||
|
** project. Distribution of this file (unmodified or modified) is not |
||||||
|
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the |
||||||
|
** rights to distribute the assembled, compiled & linked contents of this |
||||||
|
** file as part of an application binary file, provided that it is built |
||||||
|
** using the Atollic TrueSTUDIO(R) toolchain. |
||||||
|
** |
||||||
|
***************************************************************************** |
||||||
|
*/ |
||||||
|
|
||||||
|
/* Entry Point */ |
||||||
|
ENTRY(Reset_Handler) |
||||||
|
|
||||||
|
/* Highest address of the user mode stack */ |
||||||
|
enter_bootloader_mode = 0x2001FFFC; |
||||||
|
_estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ |
||||||
|
_app_start = 0x08004000; /* Reserve 16K for bootloader */ |
||||||
|
|
||||||
|
/* Generate a link error if heap and stack don't fit into RAM */ |
||||||
|
_Min_Heap_Size = 0; /* required amount of heap */ |
||||||
|
_Min_Stack_Size = 0x400; /* required amount of stack */ |
||||||
|
|
||||||
|
/* Specify the memory areas */ |
||||||
|
MEMORY |
||||||
|
{ |
||||||
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K |
||||||
|
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K |
||||||
|
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K |
||||||
|
} |
||||||
|
|
||||||
|
/* Define output sections */ |
||||||
|
SECTIONS |
||||||
|
{ |
||||||
|
/* The startup code goes first into FLASH */ |
||||||
|
.isr_vector : |
||||||
|
{ |
||||||
|
. = ALIGN(4); |
||||||
|
KEEP(*(.isr_vector)) /* Startup code */ |
||||||
|
. = ALIGN(4); |
||||||
|
} >FLASH |
||||||
|
|
||||||
|
/* The program code and other data goes into FLASH */ |
||||||
|
.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)) |
||||||
|
KEEP (*(.fini)) |
||||||
|
|
||||||
|
. = ALIGN(4); |
||||||
|
_etext = .; /* define a global symbols at end of code */ |
||||||
|
_exit = .; |
||||||
|
} >FLASH |
||||||
|
|
||||||
|
|
||||||
|
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH |
||||||
|
.ARM : { |
||||||
|
__exidx_start = .; |
||||||
|
*(.ARM.exidx*) |
||||||
|
__exidx_end = .; |
||||||
|
} >FLASH |
||||||
|
|
||||||
|
.preinit_array : |
||||||
|
{ |
||||||
|
PROVIDE_HIDDEN (__preinit_array_start = .); |
||||||
|
KEEP (*(.preinit_array*)) |
||||||
|
PROVIDE_HIDDEN (__preinit_array_end = .); |
||||||
|
} >FLASH |
||||||
|
.init_array : |
||||||
|
{ |
||||||
|
PROVIDE_HIDDEN (__init_array_start = .); |
||||||
|
KEEP (*(SORT(.init_array.*))) |
||||||
|
KEEP (*(.init_array*)) |
||||||
|
PROVIDE_HIDDEN (__init_array_end = .); |
||||||
|
} >FLASH |
||||||
|
.fini_array : |
||||||
|
{ |
||||||
|
PROVIDE_HIDDEN (__fini_array_start = .); |
||||||
|
KEEP (*(.fini_array*)) |
||||||
|
KEEP (*(SORT(.fini_array.*))) |
||||||
|
PROVIDE_HIDDEN (__fini_array_end = .); |
||||||
|
} >FLASH |
||||||
|
|
||||||
|
/* used by the startup to initialize data */ |
||||||
|
_sidata = .; |
||||||
|
|
||||||
|
/* Initialized data sections goes into RAM, load LMA copy after code */ |
||||||
|
.data : AT ( _sidata ) |
||||||
|
{ |
||||||
|
. = ALIGN(4); |
||||||
|
_sdata = .; /* create a global symbol at data start */ |
||||||
|
*(.data) /* .data sections */ |
||||||
|
*(.data*) /* .data* sections */ |
||||||
|
|
||||||
|
. = ALIGN(4); |
||||||
|
_edata = .; /* define a global symbol at data end */ |
||||||
|
} >RAM |
||||||
|
|
||||||
|
/* Uninitialized data section */ |
||||||
|
. = ALIGN(4); |
||||||
|
.bss : |
||||||
|
{ |
||||||
|
/* This is used by the startup in order to initialize the .bss secion */ |
||||||
|
_sbss = .; /* define a global symbol at bss start */ |
||||||
|
__bss_start__ = _sbss; |
||||||
|
*(.bss) |
||||||
|
*(.bss*) |
||||||
|
*(COMMON) |
||||||
|
|
||||||
|
. = ALIGN(4); |
||||||
|
_ebss = .; /* define a global symbol at bss end */ |
||||||
|
__bss_end__ = _ebss; |
||||||
|
} >RAM |
||||||
|
|
||||||
|
/* User_heap_stack section, used to check that there is enough RAM left */ |
||||||
|
._user_heap_stack : |
||||||
|
{ |
||||||
|
. = ALIGN(4); |
||||||
|
PROVIDE ( end = . ); |
||||||
|
PROVIDE ( _end = . ); |
||||||
|
. = . + _Min_Heap_Size; |
||||||
|
. = . + _Min_Stack_Size; |
||||||
|
. = ALIGN(4); |
||||||
|
} >RAM |
||||||
|
|
||||||
|
/* MEMORY_bank1 section, code must be located here explicitly */ |
||||||
|
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ |
||||||
|
.memory_b1_text : |
||||||
|
{ |
||||||
|
*(.mb1text) /* .mb1text sections (code) */ |
||||||
|
*(.mb1text*) /* .mb1text* sections (code) */ |
||||||
|
*(.mb1rodata) /* read-only data (constants) */ |
||||||
|
*(.mb1rodata*) |
||||||
|
} >MEMORY_B1 |
||||||
|
|
||||||
|
.ARM.attributes 0 : { *(.ARM.attributes) } |
||||||
|
} |
@ -0,0 +1,35 @@ |
|||||||
|
/*
|
||||||
|
gcc -DTEST_RSA test_rsa.c ../crypto/rsa.c ../crypto/sha.c && ./a.out |
||||||
|
*/ |
||||||
|
|
||||||
|
#include <stdio.h> |
||||||
|
#include <stdlib.h> |
||||||
|
|
||||||
|
#define MAX_LEN 0x40000 |
||||||
|
char buf[MAX_LEN]; |
||||||
|
|
||||||
|
#include "../crypto/sha.h" |
||||||
|
#include "../crypto/rsa.h" |
||||||
|
#include "../obj/cert.h" |
||||||
|
|
||||||
|
int main() { |
||||||
|
FILE *f = fopen("../obj/panda.bin", "rb"); |
||||||
|
int tlen = fread(buf, 1, MAX_LEN, f); |
||||||
|
fclose(f); |
||||||
|
printf("read %d\n", tlen); |
||||||
|
uint32_t *_app_start = (uint32_t *)buf; |
||||||
|
|
||||||
|
int len = _app_start[0]; |
||||||
|
char digest[SHA_DIGEST_SIZE]; |
||||||
|
SHA_hash(&_app_start[1], len-4, digest); |
||||||
|
printf("SHA hash done\n"); |
||||||
|
|
||||||
|
if (!RSA_verify(&rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { |
||||||
|
printf("RSA fail\n"); |
||||||
|
} else { |
||||||
|
printf("RSA match!!!\n"); |
||||||
|
} |
||||||
|
|
||||||
|
return 0; |
||||||
|
} |
||||||
|
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue