Merge panda subtree

pull/758/head
Vehicle Researcher 2019-07-22 19:15:27 +00:00
commit c8b4633cd1
78 changed files with 6702 additions and 5856 deletions

View File

@ -40,19 +40,6 @@ jobs:
path: /tmp/misra/misra_safety_output.txt
strict-compiler:
machine:
docker_layer_caching: true
steps:
- checkout
- run:
name: Build image
command: "docker build -t panda_strict_compiler -f tests/build_strict/Dockerfile ."
- run:
name: Build Panda with strict compiler rules
command: |
docker run panda_strict_compiler /bin/bash -c "cd /panda/tests/build_strict; ./test_build_strict.sh"
build:
machine:
docker_layer_caching: true
@ -99,12 +86,25 @@ jobs:
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"
workflows:
version: 2
main:
jobs:
- safety
- misra-c2012
- strict-compiler
- build
- safety_replay
- language_check

42
panda/Jenkinsfile vendored
View File

@ -20,34 +20,54 @@ pipeline {
}
}
}
stage('Test Dev Build') {
stage('Test Dev Build (no WIFI)') {
steps {
lock(resource: "Pandas", inversePrecedence: true, quantity:1){
lock(resource: "Pandas", inversePrecedence: true, quantity: 1){
timeout(time: 60, unit: 'MINUTES') {
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 '"
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){
lock(resource: "Pandas", inversePrecedence: true, quantity: 1){
timeout(time: 60, unit: 'MINUTES') {
sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_dev.xml"
sh "touch EON && docker cp EON ${env.DOCKER_NAME}:/EON"
sh "docker start -a ${env.DOCKER_NAME}"
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 {
always {
failure {
script {
sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_EON.xml"
sh "docker rm ${env.DOCKER_NAME}"
sh "docker rm ${env.DOCKER_NAME} || true"
}
}
always {
junit "test_results*.xml"
}
}
}
}

View File

@ -1 +1 @@
v1.4.0
v1.4.1

View File

@ -1,5 +1,5 @@
PROJ_NAME = panda
CFLAGS = -g -Wall
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

View File

@ -1,8 +0,0 @@
PROJ_NAME = panda
CFLAGS = -g -Wall -Wextra -Wstrict-prototypes
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

View File

@ -13,8 +13,13 @@
#endif
// default since there's no serial
void puts(const char *a) {}
void puth(unsigned int i) {}
void puts(const char *a) {
UNUSED(a);
}
void puth(unsigned int i) {
UNUSED(i);
}
#include "libc.h"
#include "provision.h"
@ -34,11 +39,11 @@ void puth(unsigned int i) {}
#include "spi_flasher.h"
void __initialize_hardware_early() {
void __initialize_hardware_early(void) {
early();
}
void fail() {
void fail(void) {
soft_flasher_start();
}
@ -48,7 +53,7 @@ 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() {
int main(void) {
__disable_irq();
clock_init();
detect();
@ -88,7 +93,7 @@ fail:
return 0;
good:
// jump to flash
((void(*)()) _app_start[1])();
((void(*)(void)) _app_start[1])();
return 0;
}

View File

@ -12,12 +12,12 @@
#include "stm32f2xx.h"
#endif
#define USB_VID 0xbbaa
#define USB_VID 0xbbaaU
#ifdef BOOTSTUB
#define USB_PID 0xddee
#define USB_PID 0xddeeU
#else
#define USB_PID 0xddcc
#define USB_PID 0xddccU
#endif
#include <stdbool.h>
@ -34,7 +34,7 @@
__typeof__ (b) _b = (b); \
(_a > _b) ? _a : _b; })
#define MAX_RESP_LEN 0x40
#define MAX_RESP_LEN 0x40U
#endif

View File

@ -19,7 +19,7 @@ void adc_init(void) {
ADC1->SMPR1 = ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13;
}
uint32_t adc_get(int channel) {
uint32_t adc_get(unsigned int channel) {
// includes length
//ADC1->SQR1 = 0;

View File

@ -9,11 +9,14 @@ typedef struct {
CAN_FIFOMailBox_TypeDef *elems;
} can_ring;
#define CAN_BUS_RET_FLAG 0x80
#define CAN_BUS_NUM_MASK 0x7F
#define CAN_BUS_RET_FLAG 0x80U
#define CAN_BUS_NUM_MASK 0x7FU
#define BUS_MAX 4
#define BUS_MAX 4U
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
@ -63,8 +66,11 @@ bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
enter_critical_section();
if (q->w_ptr != q->r_ptr) {
*elem = q->elems[q->r_ptr];
if ((q->r_ptr + 1) == q->fifo_size) q->r_ptr = 0;
else q->r_ptr += 1;
if ((q->r_ptr + 1U) == q->fifo_size) {
q->r_ptr = 0;
} else {
q->r_ptr += 1U;
}
ret = 1;
}
exit_critical_section();
@ -72,20 +78,23 @@ bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
return ret;
}
int can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
int ret = 0;
bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
bool ret = false;
uint32_t next_w_ptr;
enter_critical_section();
if ((q->w_ptr + 1) == q->fifo_size) next_w_ptr = 0;
else next_w_ptr = q->w_ptr + 1;
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 = 1;
ret = true;
}
exit_critical_section();
if (ret == 0) {
if (!ret) {
can_overflow_cnt++;
#ifdef DEBUG
puts("can_push failed!\n");
@ -130,7 +139,7 @@ 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, can_silent & (1 << 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");
@ -138,7 +147,7 @@ void can_set_speed(uint8_t can_number) {
}
void can_init(uint8_t can_number) {
if (can_number != 0xff) {
if (can_number != 0xffU) {
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number);
set_can_enable(CAN, 1);
can_set_speed(can_number);
@ -156,48 +165,45 @@ void can_init_all(void) {
}
}
void can_set_gmlan(int bus) {
if ((bus == -1) || (bus != can_num_lookup[3])) {
// GMLAN OFF
switch (can_num_lookup[3]) {
void can_set_gmlan(uint8_t bus) {
// first, disable GMLAN on prev bus
uint8_t prev_bus = can_num_lookup[3];
if (bus != prev_bus) {
switch (prev_bus) {
case 1:
puts("disable GMLAN on CAN2\n");
set_can_mode(1, 0);
bus_lookup[1] = 1;
can_num_lookup[1] = 1;
can_num_lookup[3] = -1;
can_init(1);
break;
case 2:
puts("disable GMLAN on CAN3\n");
set_can_mode(2, 0);
bus_lookup[2] = 2;
can_num_lookup[2] = 2;
puts("Disable GMLAN on CAN");
puth(prev_bus + 1U);
puts("\n");
set_can_mode(prev_bus, 0);
bus_lookup[prev_bus] = prev_bus;
can_num_lookup[prev_bus] = prev_bus;
can_num_lookup[3] = -1;
can_init(2);
can_init(prev_bus);
break;
default:
puts("GMLAN bus value invalid\n");
// GMLAN was not set on either BUS 1 or 2
break;
}
}
if (bus == 1) {
puts("GMLAN on CAN2\n");
// GMLAN on CAN2
set_can_mode(1, 1);
bus_lookup[1] = 3;
can_num_lookup[1] = -1;
can_num_lookup[3] = 1;
can_init(1);
} else if (bus == 2) {
puts("GMLAN on CAN3\n");
// GMLAN on CAN3
set_can_mode(2, 1);
bus_lookup[2] = 3;
can_num_lookup[2] = -1;
can_num_lookup[3] = 2;
can_init(2);
// now enable GMLAN on the new bus
switch (bus) {
case 1:
case 2:
puts("Enable GMLAN on CAN");
puth(bus + 1U);
puts("\n");
set_can_mode(bus, 1);
bus_lookup[bus] = 3;
can_num_lookup[bus] = -1;
can_num_lookup[3] = bus;
can_init(bus);
break;
default:
puts("GMLAN can only be set on CAN2 or CAN3");
break;
}
}
@ -232,7 +238,7 @@ void can_sce(CAN_TypeDef *CAN) {
// ***************************** CAN *****************************
void process_can(uint8_t can_number) {
if (can_number != 0xff) {
if (can_number != 0xffU) {
enter_critical_section();
@ -249,10 +255,10 @@ void process_can(uint8_t can_number) {
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 & 0xFFFF000F) | ((CAN_BUS_RET_FLAG | bus_number) << 4);
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_push(&can_rx_q, &to_push);
can_send_errs += !can_push(&can_rx_q, &to_push);
}
if ((CAN->TSR & CAN_TSR_TERR0) == CAN_TSR_TERR0) {
@ -321,7 +327,7 @@ void can_rx(uint8_t can_number) {
safety_rx_hook(&to_push);
set_led(LED_BLUE, 1);
can_push(&can_rx_q, &to_push);
can_send_errs += !can_push(&can_rx_q, &to_push);
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
@ -346,11 +352,11 @@ void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) {
// add CAN packet to send queue
// bus number isn't passed through
to_push->RDTR &= 0xF;
if ((bus_number == 3) && (can_num_lookup[3] == 0xFF)) {
if ((bus_number == 3U) && (can_num_lookup[3] == 0xFFU)) {
// TODO: why uint8 bro? only int8?
bitbang_gmlan(to_push);
gmlan_send_errs += !bitbang_gmlan(to_push);
} else {
can_push(can_queues[bus_number], to_push);
can_fwd_errs += !can_push(can_queues[bus_number], to_push);
process_can(CAN_NUM_FROM_BUS_NUM(bus_number));
}
}

View File

@ -3,7 +3,7 @@ void clock_init(void) {
RCC->CR |= RCC_CR_HSEON;
while ((RCC->CR & RCC_CR_HSERDY) == 0);
// divide shit
// divide things
RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4;
// 16mhz crystal

View File

@ -1,4 +1,7 @@
void dac_init() {
void puth(unsigned int i);
void puts(const char *a);
void dac_init(void) {
// no buffers required since we have an opamp
//DAC->CR = DAC_CR_EN1 | DAC_CR_BOFF1 | DAC_CR_EN2 | DAC_CR_BOFF2;
DAC->DHR12R1 = 0;
@ -11,6 +14,10 @@ void dac_set(int channel, uint32_t value) {
DAC->DHR12R1 = value;
} else if (channel == 1) {
DAC->DHR12R2 = value;
} else {
puts("Failed to set DAC: invalid channel value: ");
puth(value);
puts("\n");
}
}

View File

@ -41,35 +41,38 @@ int do_bitstuff(char *out, char *in, int in_len) {
}
int append_crc(char *in, int in_len) {
int crc = 0;
unsigned int crc = 0;
for (int i = 0; i < in_len; i++) {
crc <<= 1;
if ((in[i] ^ ((crc >> 15) & 1)) != 0) {
crc = crc ^ 0x4599;
if (((unsigned int)(in[i]) ^ ((crc >> 15) & 1U)) != 0U) {
crc = crc ^ 0x4599U;
}
crc &= 0x7fff;
crc &= 0x7fffU;
}
int in_len_copy = in_len;
for (int i = 14; i >= 0; i--) {
in[in_len] = (crc>>i)&1;
in_len++;
in[in_len_copy] = (crc >> (unsigned int)(i)) & 1U;
in_len_copy++;
}
return in_len;
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] = app[i];
in_len++;
in[in_len_copy] = app[i];
in_len_copy++;
}
return in_len;
return in_len_copy;
}
int append_int(char *in, int in_len, int val, int val_len) {
for (int i = val_len-1; i >= 0; i--) {
in[in_len] = (val&(1<<i)) != 0;
in_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;
return in_len_copy;
}
int get_bit_message(char *out, CAN_FIFOMailBox_TypeDef *to_bang) {
@ -92,7 +95,7 @@ int get_bit_message(char *out, CAN_FIFOMailBox_TypeDef *to_bang) {
// 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) & ((1<<18)-1), 18); // Identifier
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
@ -168,15 +171,16 @@ void reset_gmlan_switch_timeout(void) {
void set_bitbanged_gmlan(int val) {
if (val != 0) {
GPIOB->ODR |= (1 << 13);
GPIOB->ODR |= (1U << 13);
} else {
GPIOB->ODR &= ~(1 << 13);
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;
@ -193,7 +197,7 @@ void TIM4_IRQHandler(void) {
} else {
gmlan_silent_count++;
}
} else if (gmlan_silent_count == REQUIRED_SILENT_TIME) {
} else {
bool retry = 0;
// in send loop
if ((gmlan_sending > 0) && // not first bit
@ -206,6 +210,8 @@ void TIM4_IRQHandler(void) {
} 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)
@ -215,6 +221,7 @@ void TIM4_IRQHandler(void) {
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]);
@ -230,9 +237,7 @@ void TIM4_IRQHandler(void) {
}
}
TIM4->SR = 0;
} //bit bang mode
else if (gmlan_alt_mode == GPIO_SWITCH) {
} 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
@ -255,25 +260,27 @@ void TIM4_IRQHandler(void) {
}
}
TIM4->SR = 0;
} //gmlan switch mode
} else {
puts("invalid gmlan_alt_mode\n");
}
}
void bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) {
bool bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) {
gmlan_send_ok = true;
gmlan_alt_mode = BITBANG;
// TODO: make failure less silent
if (gmlan_sendmax == -1) {
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);
setup_timer4();
}
return gmlan_send_ok;
}

View File

@ -1,38 +1,48 @@
// this is needed for 1 mbps support
#define CAN_QUANTA 8
#define CAN_QUANTA 8U
#define CAN_SEQ1 6 // roundf(quanta * 0.875f) - 1;
#define CAN_SEQ2 1 // roundf(quanta * 0.125f);
#define CAN_PCLK 24000
#define CAN_PCLK 24000U
// 333 = 33.3 kbps
// 5000 = 500 kbps
#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10 / (x))
#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x))
bool llcan_set_speed(CAN_TypeDef *CAN, uint32_t speed, bool loopback, bool silent) {
#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
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
CAN_obj->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN_obj->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
// set time quanta from defines
CAN->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) |
CAN_obj->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) |
(CAN_BTR_TS2_0 * (CAN_SEQ2-1)) |
(can_speed_to_prescaler(speed) - 1);
(can_speed_to_prescaler(speed) - 1U);
// silent loopback mode for debugging
if (loopback) {
CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM;
CAN_obj->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM;
}
if (silent) {
CAN->BTR |= CAN_BTR_SILM;
CAN_obj->BTR |= CAN_BTR_SILM;
}
// reset
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM;
// cppcheck-suppress redundantAssignment ; it's a register
CAN_obj->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM;
#define CAN_TIMEOUT 1000000
int tmp = 0;
bool ret = false;
while(((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (tmp < CAN_TIMEOUT)) tmp++;
while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (tmp < CAN_TIMEOUT)) tmp++;
if (tmp < CAN_TIMEOUT) {
ret = true;
}
@ -40,42 +50,45 @@ bool llcan_set_speed(CAN_TypeDef *CAN, uint32_t speed, bool loopback, bool silen
return ret;
}
void llcan_init(CAN_TypeDef *CAN) {
void llcan_init(CAN_TypeDef *CAN_obj) {
// accept all filter
CAN->FMR |= CAN_FMR_FINIT;
CAN_obj->FMR |= CAN_FMR_FINIT;
// no mask
CAN->sFilterRegister[0].FR1 = 0;
CAN->sFilterRegister[0].FR2 = 0;
CAN->sFilterRegister[14].FR1 = 0;
CAN->sFilterRegister[14].FR2 = 0;
CAN->FA1R |= 1 | (1U << 14);
CAN_obj->sFilterRegister[0].FR1 = 0;
CAN_obj->sFilterRegister[0].FR2 = 0;
CAN_obj->sFilterRegister[14].FR1 = 0;
CAN_obj->sFilterRegister[14].FR2 = 0;
CAN_obj->FA1R |= 1U | (1U << 14);
CAN->FMR &= ~(CAN_FMR_FINIT);
CAN_obj->FMR &= ~(CAN_FMR_FINIT);
// enable certain CAN interrupts
CAN->IER |= CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_WKUIE;
CAN_obj->IER |= CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_WKUIE;
if (CAN == CAN1) {
if (CAN_obj == CAN1) {
NVIC_EnableIRQ(CAN1_TX_IRQn);
NVIC_EnableIRQ(CAN1_RX0_IRQn);
NVIC_EnableIRQ(CAN1_SCE_IRQn);
} else if (CAN == CAN2) {
} 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 == 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) {
CAN->TSR |= CAN_TSR_ABRQ0;
CAN->MSR &= ~(CAN_MSR_ERRI);
CAN->MSR = CAN->MSR;
void llcan_clear_send(CAN_TypeDef *CAN_obj) {
CAN_obj->TSR |= CAN_TSR_ABRQ0;
CAN_obj->MSR &= ~(CAN_MSR_ERRI);
// cppcheck-suppress selfAssignment ; needed to clear the register
CAN_obj->MSR = CAN_obj->MSR;
}

View File

@ -7,38 +7,38 @@
#define PULL_UP 1
#define PULL_DOWN 2
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode) {
void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
uint32_t tmp = GPIO->MODER;
tmp &= ~(3 << (pin*2));
tmp |= (mode << (pin*2));
tmp &= ~(3U << (pin * 2U));
tmp |= (mode << (pin * 2U));
GPIO->MODER = tmp;
}
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, bool enabled) {
void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) {
if (enabled) {
GPIO->ODR |= (1 << pin);
GPIO->ODR |= (1U << pin);
} else {
GPIO->ODR &= ~(1 << pin);
GPIO->ODR &= ~(1U << pin);
}
set_gpio_mode(GPIO, pin, MODE_OUTPUT);
}
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode) {
uint32_t tmp = GPIO->AFR[pin>>3];
tmp &= ~(0xF << ((pin&7)*4));
tmp |= mode << ((pin&7)*4);
GPIO->AFR[pin>>3] = tmp;
void set_gpio_alternate(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
uint32_t tmp = GPIO->AFR[pin >> 3U];
tmp &= ~(0xFU << ((pin & 7U) * 4U));
tmp |= mode << ((pin & 7U) * 4U);
GPIO->AFR[pin >> 3] = tmp;
set_gpio_mode(GPIO, pin, MODE_ALTERNATE);
}
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode) {
void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
uint32_t tmp = GPIO->PUPDR;
tmp &= ~(3 << (pin*2));
tmp |= (mode << (pin*2));
tmp &= ~(3U << (pin * 2U));
tmp |= (mode << (pin * 2U));
GPIO->PUPDR = tmp;
}
int get_gpio_input(GPIO_TypeDef *GPIO, int pin) {
int get_gpio_input(GPIO_TypeDef *GPIO, unsigned int pin) {
return (GPIO->IDR & (1U << pin)) == (1U << pin);
}

View File

@ -28,8 +28,8 @@ void spi_init(void) {
// setup interrupt on falling edge of SPI enable (on PA4)
SYSCFG->EXTICR[2] = SYSCFG_EXTICR2_EXTI4_PA;
EXTI->IMR |= (1 << 4);
EXTI->FTSR |= (1 << 4);
EXTI->IMR |= (1U << 4);
EXTI->FTSR |= (1U << 4);
NVIC_EnableIRQ(EXTI4_IRQn);
}
@ -85,7 +85,7 @@ uint8_t spi_tx_buf[0x44];
// SPI RX
void DMA2_Stream2_IRQHandler(void) {
int *resp_len = (int*)spi_tx_buf;
memset(spi_tx_buf, 0xaa, 0x44);
(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: ");
@ -113,12 +113,12 @@ void DMA2_Stream3_IRQHandler(void) {
}
void EXTI4_IRQHandler(void) {
volatile int pr = EXTI->PR & (1 << 4);
volatile unsigned int pr = EXTI->PR & (1U << 4);
#ifdef DEBUG_SPI
puts("exti4\n");
#endif
// SPI CS falling
if ((pr & (1 << 4)) != 0) {
if ((pr & (1U << 4)) != 0U) {
spi_total_count = 0;
spi_rx_dma(spi_buf, 0x14);
}

View File

@ -1,6 +1,6 @@
// IRQs: USART1, USART2, USART3, UART5
#define FIFO_SIZE 0x400
#define FIFO_SIZE 0x400U
typedef struct uart_ring {
volatile uint16_t w_ptr_tx;
volatile uint16_t r_ptr_tx;
@ -81,7 +81,7 @@ void uart_ring_process(uart_ring *q) {
if (q->w_ptr_tx != q->r_ptr_tx) {
if ((sr & USART_SR_TXE) != 0) {
q->uart->DR = q->elems_tx[q->r_ptr_tx];
q->r_ptr_tx = (q->r_ptr_tx + 1) % FIFO_SIZE;
q->r_ptr_tx = (q->r_ptr_tx + 1U) % FIFO_SIZE;
}
// there could be more to send
q->uart->CR1 |= USART_CR1_TXEIE;
@ -93,7 +93,7 @@ void uart_ring_process(uart_ring *q) {
if ((sr & USART_SR_RXNE) || (sr & USART_SR_ORE)) {
uint8_t c = q->uart->DR; // TODO: can drop packets
if (q != &esp_ring) {
uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE;
uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % FIFO_SIZE;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = c;
q->w_ptr_rx = next_w_ptr;
@ -124,7 +124,7 @@ bool getc(uart_ring *q, char *elem) {
enter_critical_section();
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 + 1) % FIFO_SIZE;
q->r_ptr_rx = (q->r_ptr_rx + 1U) % FIFO_SIZE;
ret = true;
}
exit_critical_section();
@ -137,7 +137,7 @@ bool injectc(uart_ring *q, char elem) {
uint16_t next_w_ptr;
enter_critical_section();
next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE;
next_w_ptr = (q->w_ptr_rx + 1U) % 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;
@ -153,7 +153,7 @@ bool putc(uart_ring *q, char elem) {
uint16_t next_w_ptr;
enter_critical_section();
next_w_ptr = (q->w_ptr_tx + 1) % FIFO_SIZE;
next_w_ptr = (q->w_ptr_tx + 1U) % 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;
@ -195,17 +195,17 @@ void clear_uart_buff(uart_ring *q) {
// ***************************** start UART code *****************************
#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25) / (4 * (_BAUD_)))
#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100)
#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16) + 50) / 100)
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F))
#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, int baud) {
void uart_set_baud(USART_TypeDef *u, unsigned int baud) {
if (u == USART1) {
// USART1 is on APB2
u->BRR = __USART_BRR(48000000, baud);
u->BRR = __USART_BRR(48000000U, baud);
} else {
u->BRR = __USART_BRR(24000000, baud);
u->BRR = __USART_BRR(24000000U, baud);
}
}
@ -226,7 +226,7 @@ void uart_dma_drain(void) {
unsigned int i;
for (i = 0; i < (USART1_DMA_LEN - DMA2_Stream5->NDTR); i++) {
char c = usart1_dma[i];
uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE;
uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % FIFO_SIZE;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = c;
q->w_ptr_rx = next_w_ptr;
@ -289,6 +289,8 @@ void uart_init(USART_TypeDef *u, int baud) {
NVIC_EnableIRQ(USART3_IRQn);
} else if (u == UART5) {
NVIC_EnableIRQ(UART5_IRQn);
} else {
// USART type undefined, skip
}
}
@ -302,49 +304,48 @@ void putch(const char a) {
//putc(&debug_ring, a);
} else {
injectc(&debug_ring, a);
// misra-c2012-17.7: serial debug function, ok to ignore output
(void)injectc(&debug_ring, a);
}
}
void puts(const char *a) {
for (;*a;a++) {
if (*a == '\n') putch('\r');
putch(*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 % 10) + 0x30;
str[idx] = (i_copy % 10U) + 0x30U;
idx--;
i /= 10;
} while (i != 0);
puts(str + idx + 1);
i_copy /= 10;
} while (i_copy != 0U);
puts(str + idx + 1U);
}
void puth(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 28; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
for (int pos = 28; pos != -4; pos -= 4) {
putch(c[(i >> (unsigned int)(pos)) & 0xFU]);
}
}
void puth2(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 4; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
for (int pos = 4; pos != -4; pos -= 4) {
putch(c[(i >> (unsigned int)(pos)) & 0xFU]);
}
}
void hexdump(const void *a, int l) {
int i;
for (i=0;i<l;i++) {
for (int i=0; i < l; i++) {
if ((i != 0) && ((i & 0xf) == 0)) puts("\n");
puth2(((const unsigned char*)a)[i]);
puts(" ");

View File

@ -25,9 +25,9 @@ USB_Setup_TypeDef;
void usb_init(void);
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired);
int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired);
void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired);
void usb_cb_ep3_out(uint8_t *usbdata, int len, bool hardwired);
int usb_cb_ep1_in(void *usbdata, int len, bool hardwired);
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired);
void usb_cb_ep3_out(void *usbdata, int len, bool hardwired);
void usb_cb_enumeration_complete(void);
// **** supporting defines ****
@ -96,7 +96,7 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS;
#define STS_SETUP_COMP 4
#define STS_SETUP_UPDT 6
#define USBD_FS_TRDT_VALUE 5
#define USBD_FS_TRDT_VALUE 5U
#define USB_OTG_SPEED_FULL 3
@ -125,7 +125,7 @@ uint8_t resp[MAX_RESP_LEN];
// Convert machine byte order to USB byte order
#define TOUSBORDER(num)\
((num) & 0xFF), (((num) >> 8) & 0xFF)
((num) & 0xFFU), (((num) >> 8) & 0xFFU)
// take in string length and return the first 2 bytes of a string descriptor
#define STRING_DESCRIPTOR_HEADER(size)\
@ -158,7 +158,7 @@ uint8_t device_qualifier[] = {
uint8_t configuration_desc[] = {
DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type,
TOUSBORDER(0x0045), // Total Len (uint16)
TOUSBORDER(0x0045U), // Total Len (uint16)
0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration
0xc0, 0x32, // Attributes, Max Power
// interface 0 ALT 0
@ -169,17 +169,17 @@ uint8_t configuration_desc[] = {
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval (NA)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
// interface 0 ALT 1
DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type
@ -189,17 +189,17 @@ uint8_t configuration_desc[] = {
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x05, // Polling Interval (5 frames)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
TOUSBORDER(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
};
@ -394,36 +394,36 @@ int current_int0_alt_setting = 0;
// packet read and write
void *USB_ReadPacket(void *dest, uint16_t len) {
uint32_t i=0;
uint32_t count32b = (len + 3) / 4;
uint32_t *dest_copy = (uint32_t *)dest;
uint32_t count32b = (len + 3U) / 4U;
for ( i = 0; i < count32b; i++) {
// packed?
*(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0);
dest += 4;
for (uint32_t i = 0; i < count32b; i++) {
*dest_copy = USBx_DFIFO(0);
dest_copy++;
}
return ((void *)dest);
return ((void *)dest_copy);
}
void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) {
void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) {
#ifdef DEBUG_USB
puts("writing ");
hexdump(src, len);
#endif
uint8_t numpacket = (len+(MAX_RESP_LEN-1))/MAX_RESP_LEN;
uint32_t count32b = 0, i = 0;
count32b = (len + 3) / 4;
uint8_t numpacket = (len + (MAX_RESP_LEN - 1U)) / MAX_RESP_LEN;
uint32_t count32b = 0;
count32b = (len + 3U) / 4U;
// bullshit
// TODO: revisit this
USBx_INEP(ep)->DIEPTSIZ = ((numpacket << 19) & USB_OTG_DIEPTSIZ_PKTCNT) |
(len & USB_OTG_DIEPTSIZ_XFRSIZ);
USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
// load the FIFO
for (i = 0; i < count32b; i++) {
USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src);
src += 4;
const uint32_t *src_copy = (const uint32_t *)src;
for (uint32_t i = 0; i < count32b; i++) {
USBx_DFIFO(ep) = *src_copy;
src_copy++;
}
}
@ -471,10 +471,10 @@ void usb_reset(void) {
USBx->GRXFSIZ = 0x40;
// 0x100 to offset past GRXFSIZ
USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40;
USBx->DIEPTXF0_HNPTXFSIZ = (0x40U << 16) | 0x40U;
// EP1, massive
USBx->DIEPTXF[0] = (0x40 << 16) | 0x80;
USBx->DIEPTXF[0] = (0x40U << 16) | 0x80U;
// flush TX fifo
USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4;
@ -487,7 +487,7 @@ void usb_reset(void) {
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK;
// ready to receive setup packets
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8);
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)) | (3U << 3);
}
char to_hex_char(int a) {
@ -506,17 +506,17 @@ void usb_setup(void) {
switch (setup.b.bRequest) {
case USB_REQ_SET_CONFIGURATION:
// enable other endpoints, has to be here?
USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) |
USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2U << 18) | (1U << 22) |
USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP;
USBx_INEP(1)->DIEPINT = 0xFF;
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USBx_OUTEP(2)->DOEPTSIZ = (1U << 19) | 0x40U;
USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(2)->DOEPINT = 0xFF;
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U;
USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(3)->DOEPINT = 0xFF;
@ -529,7 +529,7 @@ void usb_setup(void) {
break;
case USB_REQ_SET_ADDRESS:
// set now?
USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4);
USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7fU) << 4);
#ifdef DEBUG_USB
puts(" set address\n");
@ -575,16 +575,16 @@ void usb_setup(void) {
break;
case STRING_OFFSET_ISERIAL:
#ifdef UID_BASE
resp[0] = 0x02 + 12*4;
resp[0] = 0x02 + (12 * 4);
resp[1] = 0x03;
// 96 bits = 12 bytes
for (int i = 0; i < 12; i++){
uint8_t cc = ((uint8_t *)UID_BASE)[i];
resp[2 + i*4 + 0] = to_hex_char((cc>>4)&0xF);
resp[2 + i*4 + 1] = '\0';
resp[2 + i*4 + 2] = to_hex_char((cc>>0)&0xF);
resp[2 + i*4 + 3] = '\0';
resp[2 + (i * 4) + 0] = to_hex_char((cc >> 4) & 0xFU);
resp[2 + (i * 4) + 1] = '\0';
resp[2 + (i * 4) + 2] = to_hex_char((cc >> 0) & 0xFU);
resp[2 + (i * 4) + 3] = '\0';
}
USB_WritePacket(resp, MIN(resp[0], setup.b.wLength.w), 0);
@ -683,7 +683,7 @@ void usb_init(void) {
USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD;
// slowest timings
USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
// power up the PHY
#ifdef STM32F4
@ -732,7 +732,6 @@ void usb_init(void) {
USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT;
// DCTL startup value is 2 on new chip, 0 on old chip
// THIS IS FUCKING BULLSHIT
USBx_DEVICE->DCTL = 0;
// enable the IRQ
@ -793,21 +792,22 @@ void usb_irqhandler(void) {
if ((gintsts & USB_OTG_GINTSTS_RXFLVL) != 0) {
// 1. Read the Receive status pop register
volatile unsigned int rxst = USBx->GRXSTSP;
int status = (rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17;
#ifdef DEBUG_USB
puts(" RX FIFO:");
puth(rxst);
puts(" status: ");
puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17);
puth(status);
puts(" len: ");
puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4);
puts("\n");
#endif
if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) {
if (status == STS_DATA_UPDT) {
int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM);
int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4;
USB_ReadPacket(&usbdata, len);
(void)USB_ReadPacket(&usbdata, len);
#ifdef DEBUG_USB
puts(" data ");
puth(len);
@ -822,13 +822,15 @@ void usb_irqhandler(void) {
if (endpoint == 3) {
usb_cb_ep3_out(usbdata, len, 1);
}
} else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) {
USB_ReadPacket(&setup, 8);
} else if (status == STS_SETUP_UPDT) {
(void)USB_ReadPacket(&setup, 8);
#ifdef DEBUG_USB
puts(" setup ");
hexdump(&setup, 8);
puts("\n");
#endif
} else {
// status is neither STS_DATA_UPDT or STS_SETUP_UPDT, skip
}
}
@ -882,7 +884,7 @@ void usb_irqhandler(void) {
#ifdef DEBUG_USB
puts(" OUT2 PACKET XFRC\n");
#endif
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPTSIZ = (1U << 19) | 0x40U;
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
}
@ -890,24 +892,26 @@ void usb_irqhandler(void) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET XFRC\n");
#endif
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
} else if ((USBx_OUTEP(3)->DOEPINT & 0x2000) != 0) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET WTF\n");
#endif
// if NAK was set trigger this, unknown interrupt
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
} else if ((USBx_OUTEP(3)->DOEPINT) != 0) {
puts("OUTEP3 error ");
puth(USBx_OUTEP(3)->DOEPINT);
puts("\n");
} else {
// USBx_OUTEP(3)->DOEPINT is 0, ok to skip
}
if ((USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) != 0) {
// ready for next packet
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8);
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)) | (1U << 3);
}
// respond to setup packets
@ -978,12 +982,12 @@ void usb_irqhandler(void) {
puts(" IN PACKET QUEUE\n");
#endif
if ((ep0_txlen != 0) && ((USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40)) {
if ((ep0_txlen != 0U) && ((USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40U)) {
uint16_t len = MIN(ep0_txlen, 0x40);
USB_WritePacket(ep0_txdata, len, 0);
ep0_txdata += len;
ep0_txlen -= len;
if (ep0_txlen == 0) {
if (ep0_txlen == 0U) {
ep0_txdata = NULL;
USBx_DEVICE->DIEPEMPMSK &= ~1;
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;

View File

@ -99,9 +99,9 @@ void periph_init(void) {
// ********************* setters *********************
void set_can_enable(CAN_TypeDef *CAN, bool enabled) {
void set_can_enable(CAN_TypeDef *CAN_obj, bool enabled) {
// enable CAN busses
if (CAN == CAN1) {
if (CAN_obj == CAN1) {
#ifdef PANDA
// CAN1_EN
set_gpio_output(GPIOC, 1, !enabled);
@ -114,7 +114,7 @@ void set_can_enable(CAN_TypeDef *CAN, bool enabled) {
set_gpio_output(GPIOB, 3, enabled);
#endif
#endif
} else if (CAN == CAN2) {
} else if (CAN_obj == CAN2) {
#ifdef PANDA
// CAN2_EN
set_gpio_output(GPIOC, 13, !enabled);
@ -123,10 +123,12 @@ void set_can_enable(CAN_TypeDef *CAN, bool enabled) {
set_gpio_output(GPIOB, 4, enabled);
#endif
#ifdef CAN3
} else if (CAN == CAN3) {
} else if (CAN_obj == CAN3) {
// CAN3_EN
set_gpio_output(GPIOA, 0, !enabled);
#endif
} else {
puts("Invalid CAN: enabling failed\n");
}
}
@ -171,6 +173,8 @@ void set_can_mode(int can, bool use_gmlan) {
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3);
#endif
} else {
puts("Invalid CAN: mode setting failed\n");
}
} else {
if (can == 1) {
@ -190,6 +194,8 @@ void set_can_mode(int can, bool use_gmlan) {
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
#endif
} else {
puts("Invalid CAN: mode setting failed\n");
}
}
}
@ -404,9 +410,13 @@ void early(void) {
// if wrong chip, reboot
volatile unsigned int id = DBGMCU->IDCODE;
#ifdef STM32F4
if ((id&0xFFF) != 0x463) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
if ((id & 0xFFFU) != 0x463U) {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
}
#else
if ((id&0xFFF) != 0x411) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
if ((id & 0xFFFU) != 0x411U) {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
}
#endif
// setup interrupt table

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V2.1.2
* @date 29-June-2016
* @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File.
* This file contains :
* @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File.
* This file contains :
* - Data structures and the address mapping for all peripherals
* - Peripherals registers declarations and bits definition
* - Macros to access peripherals registers hardware
@ -47,21 +47,21 @@
/** @addtogroup stm32f205xx
* @{
*/
#ifndef __STM32F205xx_H
#define __STM32F205xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Configuration_section_for_CMSIS
* @{
*/
/**
* @brief Configuration of the Cortex-M3 Processor and Core Peripherals
* @brief Configuration of the Cortex-M3 Processor and Core Peripherals
*/
#define __CM3_REV 0x0200U /*!< Core revision r0p1 */
#define __MPU_PRESENT 1U /*!< STM32F2XX provides an MPU */
@ -71,14 +71,14 @@
/**
* @}
*/
/** @addtogroup Peripheral_interrupt_number_definition
* @{
*/
/**
* @brief STM32F2XX Interrupt Number Definition, according to the selected device
* in @ref Library_configuration_section
* @brief STM32F2XX Interrupt Number Definition, according to the selected device
* in @ref Library_configuration_section
*/
typedef enum
{
@ -126,7 +126,7 @@ typedef enum
I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */
I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */
I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */
I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */
I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */
SPI1_IRQn = 35, /*!< SPI1 global Interrupt */
SPI2_IRQn = 36, /*!< SPI2 global Interrupt */
USART1_IRQn = 37, /*!< USART1 global Interrupt */
@ -134,7 +134,7 @@ typedef enum
USART3_IRQn = 39, /*!< USART3 global Interrupt */
EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */
RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */
OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */
OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */
TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */
TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */
TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */
@ -181,16 +181,16 @@ typedef enum
/** @addtogroup Peripheral_registers_structures
* @{
*/
*/
/**
* @brief Analog to Digital Converter
/**
* @brief Analog to Digital Converter
*/
typedef struct
{
__IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */
__IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */
__IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */
__IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */
__IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */
__IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */
@ -220,8 +220,8 @@ typedef struct
} ADC_Common_TypeDef;
/**
* @brief Controller Area Network TxMailBox
/**
* @brief Controller Area Network TxMailBox
*/
typedef struct
@ -232,10 +232,10 @@ typedef struct
__IO uint32_t TDHR; /*!< CAN mailbox data high register */
} CAN_TxMailBox_TypeDef;
/**
* @brief Controller Area Network FIFOMailBox
/**
* @brief Controller Area Network FIFOMailBox
*/
typedef struct
{
__IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */
@ -244,20 +244,20 @@ typedef struct
__IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */
} CAN_FIFOMailBox_TypeDef;
/**
* @brief Controller Area Network FilterRegister
/**
* @brief Controller Area Network FilterRegister
*/
typedef struct
{
__IO uint32_t FR1; /*!< CAN Filter bank register 1 */
__IO uint32_t FR2; /*!< CAN Filter bank register 1 */
} CAN_FilterRegister_TypeDef;
/**
* @brief Controller Area Network
/**
* @brief Controller Area Network
*/
typedef struct
{
__IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */
@ -280,12 +280,12 @@ typedef struct
__IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */
uint32_t RESERVED4; /*!< Reserved, 0x218 */
__IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */
uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */
uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */
CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */
} CAN_TypeDef;
/**
* @brief CRC calculation unit
/**
* @brief CRC calculation unit
*/
typedef struct
@ -297,7 +297,7 @@ typedef struct
__IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */
} CRC_TypeDef;
/**
/**
* @brief Digital to Analog Converter
*/
@ -319,7 +319,7 @@ typedef struct
__IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */
} DAC_TypeDef;
/**
/**
* @brief Debug MCU
*/
@ -332,7 +332,7 @@ typedef struct
}DBGMCU_TypeDef;
/**
/**
* @brief DMA Controller
*/
@ -355,7 +355,7 @@ typedef struct
} DMA_TypeDef;
/**
/**
* @brief External Interrupt/Event Controller
*/
@ -369,7 +369,7 @@ typedef struct
__IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */
} EXTI_TypeDef;
/**
/**
* @brief FLASH Registers
*/
@ -384,28 +384,28 @@ typedef struct
} FLASH_TypeDef;
/**
/**
* @brief Flexible Static Memory Controller
*/
typedef struct
{
__IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */
} FSMC_Bank1_TypeDef;
__IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */
} FSMC_Bank1_TypeDef;
/**
/**
* @brief Flexible Static Memory Controller Bank1E
*/
typedef struct
{
__IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */
} FSMC_Bank1E_TypeDef;
/**
/**
* @brief Flexible Static Memory Controller Bank2
*/
typedef struct
{
__IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */
@ -424,10 +424,10 @@ typedef struct
__IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */
} FSMC_Bank2_3_TypeDef;
/**
/**
* @brief Flexible Static Memory Controller Bank4
*/
typedef struct
{
__IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */
@ -435,10 +435,10 @@ typedef struct
__IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */
__IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */
__IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */
} FSMC_Bank4_TypeDef;
} FSMC_Bank4_TypeDef;
/**
/**
* @brief General Purpose I/O
*/
@ -455,20 +455,20 @@ typedef struct
__IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */
} GPIO_TypeDef;
/**
/**
* @brief System configuration controller
*/
typedef struct
{
__IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */
__IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */
__IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */
uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */
uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */
__IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */
} SYSCFG_TypeDef;
/**
/**
* @brief Inter-integrated Circuit Interface
*/
@ -485,7 +485,7 @@ typedef struct
__IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */
} I2C_TypeDef;
/**
/**
* @brief Independent WATCHDOG
*/
@ -497,7 +497,7 @@ typedef struct
__IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */
} IWDG_TypeDef;
/**
/**
* @brief Power Control
*/
@ -507,7 +507,7 @@ typedef struct
__IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */
} PWR_TypeDef;
/**
/**
* @brief Reset and Clock Control
*/
@ -546,7 +546,7 @@ typedef struct
} RCC_TypeDef;
/**
/**
* @brief Real-Time Clock
*/
@ -595,7 +595,7 @@ typedef struct
} RTC_TypeDef;
/**
/**
* @brief SD host Interface
*/
@ -623,7 +623,7 @@ typedef struct
__IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */
} SDIO_TypeDef;
/**
/**
* @brief Serial Peripheral Interface
*/
@ -640,7 +640,7 @@ typedef struct
__IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */
} SPI_TypeDef;
/**
/**
* @brief TIM
*/
@ -669,10 +669,10 @@ typedef struct
__IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */
} TIM_TypeDef;
/**
/**
* @brief Universal Synchronous Asynchronous Receiver Transmitter
*/
typedef struct
{
__IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */
@ -684,7 +684,7 @@ typedef struct
__IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */
} USART_TypeDef;
/**
/**
* @brief Window WATCHDOG
*/
@ -696,11 +696,11 @@ typedef struct
} WWDG_TypeDef;
/**
/**
* @brief RNG
*/
typedef struct
typedef struct
{
__IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */
__IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */
@ -708,8 +708,8 @@ typedef struct
} RNG_TypeDef;
/**
/**
* @brief __USB_OTG_Core_register
*/
typedef struct
@ -737,10 +737,10 @@ USB_OTG_GlobalTypeDef;
/**
/**
* @brief __device_Registers
*/
typedef struct
typedef struct
{
__IO uint32_t DCFG; /*!< dev Configuration Register Address offset : 0x800 */
__IO uint32_t DCTL; /*!< dev Control Register Address offset : 0x804 */
@ -757,19 +757,19 @@ typedef struct
__IO uint32_t DTHRCTL; /*!< dev thr Address offset : 0x830 */
__IO uint32_t DIEPEMPMSK; /*!< dev empty msk Address offset : 0x834 */
__IO uint32_t DEACHINT; /*!< dedicated EP interrupt Address offset : 0x838 */
__IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset : 0x83C */
__IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset : 0x83C */
uint32_t Reserved40; /*!< dedicated EP mask Address offset : 0x840 */
__IO uint32_t DINEP1MSK; /*!< dedicated EP mask Address offset : 0x844 */
uint32_t Reserved44[15]; /*!< Reserved Address offset : 0x844-0x87C */
__IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset : 0x884 */
__IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset : 0x884 */
}
USB_OTG_DeviceTypeDef;
/**
/**
* @brief __IN_Endpoint-Specific_Register
*/
typedef struct
typedef struct
{
__IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */
uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h */
@ -783,10 +783,10 @@ typedef struct
USB_OTG_INEndpointTypeDef;
/**
/**
* @brief __OUT_Endpoint-Specific_Registers
*/
typedef struct
typedef struct
{
__IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/
uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/
@ -799,10 +799,10 @@ typedef struct
USB_OTG_OUTEndpointTypeDef;
/**
/**
* @brief __Host_Mode_Register_Structures
*/
typedef struct
typedef struct
{
__IO uint32_t HCFG; /* Host Configuration Register 400h*/
__IO uint32_t HFIR; /* Host Frame Interval Register 404h*/
@ -815,7 +815,7 @@ typedef struct
USB_OTG_HostTypeDef;
/**
/**
* @brief __Host_Channel_Specific_Registers
*/
typedef struct
@ -830,8 +830,8 @@ typedef struct
}
USB_OTG_HostChannelTypeDef;
/**
/**
* @brief Peripheral_memory_map
*/
#define FLASH_BASE 0x08000000U /*!< FLASH(up to 1 MB) base address in the alias region */
@ -965,10 +965,10 @@ USB_OTG_HostChannelTypeDef;
/**
* @}
*/
/** @addtogroup Peripheral_declaration
* @{
*/
*/
#define TIM2 ((TIM_TypeDef *) TIM2_BASE)
#define TIM3 ((TIM_TypeDef *) TIM3_BASE)
#define TIM4 ((TIM_TypeDef *) TIM4_BASE)
@ -1003,7 +1003,7 @@ USB_OTG_HostChannelTypeDef;
#define ADC2 ((ADC_TypeDef *) ADC2_BASE)
#define ADC3 ((ADC_TypeDef *) ADC3_BASE)
#define SDIO ((SDIO_TypeDef *) SDIO_BASE)
#define SPI1 ((SPI_TypeDef *) SPI1_BASE)
#define SPI1 ((SPI_TypeDef *) SPI1_BASE)
#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE)
#define EXTI ((EXTI_TypeDef *) EXTI_BASE)
#define TIM9 ((TIM_TypeDef *) TIM9_BASE)
@ -1038,7 +1038,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE)
#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE)
#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE)
#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE)
#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE)
#define RNG ((RNG_TypeDef *) RNG_BASE)
#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE)
#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE)
@ -1057,11 +1057,11 @@ USB_OTG_HostChannelTypeDef;
/** @addtogroup Exported_constants
* @{
*/
/** @addtogroup Peripheral_Registers_Bits_Definition
* @{
*/
/******************************************************************************/
/* Peripheral Registers_Bits_Definition */
/******************************************************************************/
@ -1104,7 +1104,7 @@ USB_OTG_HostChannelTypeDef;
#define ADC_CR1_RES_0 0x01000000U /*!<Bit 0 */
#define ADC_CR1_RES_1 0x02000000U /*!<Bit 1 */
#define ADC_CR1_OVRIE 0x04000000U /*!<overrun interrupt enable */
/******************* Bit definition for ADC_CR2 register ********************/
#define ADC_CR2_ADON 0x00000001U /*!<A/D Converter ON / OFF */
#define ADC_CR2_CONT 0x00000002U /*!<Continuous Conversion */
@ -1337,7 +1337,7 @@ USB_OTG_HostChannelTypeDef;
#define ADC_SQR3_SQ6_4 0x20000000U /*!<Bit 4 */
/******************* Bit definition for ADC_JSQR register *******************/
#define ADC_JSQR_JSQ1 0x0000001FU /*!<JSQ1[4:0] bits (1st conversion in injected sequence) */
#define ADC_JSQR_JSQ1 0x0000001FU /*!<JSQ1[4:0] bits (1st conversion in injected sequence) */
#define ADC_JSQR_JSQ1_0 0x00000001U /*!<Bit 0 */
#define ADC_JSQR_JSQ1_1 0x00000002U /*!<Bit 1 */
#define ADC_JSQR_JSQ1_2 0x00000004U /*!<Bit 2 */
@ -1407,22 +1407,22 @@ USB_OTG_HostChannelTypeDef;
#define ADC_CSR_DOVR3 ADC_CSR_OVR3
/******************* Bit definition for ADC_CCR register ********************/
#define ADC_CCR_MULTI 0x0000001FU /*!<MULTI[4:0] bits (Multi-ADC mode selection) */
#define ADC_CCR_MULTI 0x0000001FU /*!<MULTI[4:0] bits (Multi-ADC mode selection) */
#define ADC_CCR_MULTI_0 0x00000001U /*!<Bit 0 */
#define ADC_CCR_MULTI_1 0x00000002U /*!<Bit 1 */
#define ADC_CCR_MULTI_2 0x00000004U /*!<Bit 2 */
#define ADC_CCR_MULTI_3 0x00000008U /*!<Bit 3 */
#define ADC_CCR_MULTI_4 0x00000010U /*!<Bit 4 */
#define ADC_CCR_DELAY 0x00000F00U /*!<DELAY[3:0] bits (Delay between 2 sampling phases) */
#define ADC_CCR_DELAY 0x00000F00U /*!<DELAY[3:0] bits (Delay between 2 sampling phases) */
#define ADC_CCR_DELAY_0 0x00000100U /*!<Bit 0 */
#define ADC_CCR_DELAY_1 0x00000200U /*!<Bit 1 */
#define ADC_CCR_DELAY_2 0x00000400U /*!<Bit 2 */
#define ADC_CCR_DELAY_3 0x00000800U /*!<Bit 3 */
#define ADC_CCR_DDS 0x00002000U /*!<DMA disable selection (Multi-ADC mode) */
#define ADC_CCR_DMA 0x0000C000U /*!<DMA[1:0] bits (Direct Memory Access mode for multimode) */
#define ADC_CCR_DMA 0x0000C000U /*!<DMA[1:0] bits (Direct Memory Access mode for multimode) */
#define ADC_CCR_DMA_0 0x00004000U /*!<Bit 0 */
#define ADC_CCR_DMA_1 0x00008000U /*!<Bit 1 */
#define ADC_CCR_ADCPRE 0x00030000U /*!<ADCPRE[1:0] bits (ADC prescaler) */
#define ADC_CCR_ADCPRE 0x00030000U /*!<ADCPRE[1:0] bits (ADC prescaler) */
#define ADC_CCR_ADCPRE_0 0x00010000U /*!<Bit 0 */
#define ADC_CCR_ADCPRE_1 0x00020000U /*!<Bit 1 */
#define ADC_CCR_VBATE 0x00400000U /*!<VBAT Enable */
@ -1603,7 +1603,7 @@ USB_OTG_HostChannelTypeDef;
#define CAN_TI2R_EXID 0x001FFFF8U /*!<Extended identifier */
#define CAN_TI2R_STID 0xFFE00000U /*!<Standard Identifier or Extended Identifier */
/******************* Bit definition for CAN_TDT2R register ******************/
/******************* Bit definition for CAN_TDT2R register ******************/
#define CAN_TDT2R_DLC 0x0000000FU /*!<Data Length Code */
#define CAN_TDT2R_TGT 0x00000100U /*!<Transmit Global Time */
#define CAN_TDT2R_TIME 0xFFFF0000U /*!<Message Time Stamp */
@ -2925,7 +2925,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA_SxNDT_14 0x00004000U
#define DMA_SxNDT_15 0x00008000U
/******************** Bits definition for DMA_SxFCR register ****************/
/******************** Bits definition for DMA_SxFCR register ****************/
#define DMA_SxFCR_FEIE 0x00000080U
#define DMA_SxFCR_FS 0x00000038U
#define DMA_SxFCR_FS_0 0x00000008U
@ -2936,7 +2936,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA_SxFCR_FTH_0 0x00000001U
#define DMA_SxFCR_FTH_1 0x00000002U
/******************** Bits definition for DMA_LISR register *****************/
/******************** Bits definition for DMA_LISR register *****************/
#define DMA_LISR_TCIF3 0x08000000U
#define DMA_LISR_HTIF3 0x04000000U
#define DMA_LISR_TEIF3 0x02000000U
@ -2958,7 +2958,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA_LISR_DMEIF0 0x00000004U
#define DMA_LISR_FEIF0 0x00000001U
/******************** Bits definition for DMA_HISR register *****************/
/******************** Bits definition for DMA_HISR register *****************/
#define DMA_HISR_TCIF7 0x08000000U
#define DMA_HISR_HTIF7 0x04000000U
#define DMA_HISR_TEIF7 0x02000000U
@ -2980,7 +2980,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA_HISR_DMEIF4 0x00000004U
#define DMA_HISR_FEIF4 0x00000001U
/******************** Bits definition for DMA_LIFCR register ****************/
/******************** Bits definition for DMA_LIFCR register ****************/
#define DMA_LIFCR_CTCIF3 0x08000000U
#define DMA_LIFCR_CHTIF3 0x04000000U
#define DMA_LIFCR_CTEIF3 0x02000000U
@ -3002,7 +3002,7 @@ USB_OTG_HostChannelTypeDef;
#define DMA_LIFCR_CDMEIF0 0x00000004U
#define DMA_LIFCR_CFEIF0 0x00000001U
/******************** Bits definition for DMA_HIFCR register ****************/
/******************** Bits definition for DMA_HIFCR register ****************/
#define DMA_HIFCR_CTCIF7 0x08000000U
#define DMA_HIFCR_CHTIF7 0x04000000U
#define DMA_HIFCR_CTEIF7 0x02000000U
@ -5921,80 +5921,80 @@ USB_OTG_HostChannelTypeDef;
/****************** Bit definition for SPI_I2SPR register *******************/
#define SPI_I2SPR_I2SDIV 0x000000FFU /*!<I2S Linear prescaler */
#define SPI_I2SPR_ODD 0x00000100U /*!<Odd factor for the prescaler */
#define SPI_I2SPR_MCKOE 0x00000200U /*!<Master Clock Output Enable */
/******************************************************************************/
/* */
/* SYSCFG */
/* */
/******************************************************************************/
/****************** Bit definition for SYSCFG_MEMRMP register ***************/
#define SYSCFG_MEMRMP_MEM_MODE 0x00000003U /*!<SYSCFG_Memory Remap Config */
#define SYSCFG_MEMRMP_MEM_MODE_0 0x00000001U
#define SYSCFG_MEMRMP_MEM_MODE_1 0x00000002U
/***************** Bit definition for SYSCFG_EXTICR1 register ***************/
#define SYSCFG_EXTICR1_EXTI0 0x0000000FU /*!<EXTI 0 configuration */
#define SYSCFG_EXTICR1_EXTI1 0x000000F0U /*!<EXTI 1 configuration */
#define SYSCFG_EXTICR1_EXTI2 0x00000F00U /*!<EXTI 2 configuration */
#define SYSCFG_EXTICR1_EXTI3 0x0000F000U /*!<EXTI 3 configuration */
/**
* @brief EXTI0 configuration
*/
#define SYSCFG_EXTICR1_EXTI0_PA 0x00000000U /*!<PA[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PB 0x00000001U /*!<PB[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PC 0x00000002U /*!<PC[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PD 0x00000003U /*!<PD[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PE 0x00000004U /*!<PE[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PF 0x00000005U /*!<PF[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PG 0x00000006U /*!<PG[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PH 0x00000007U /*!<PH[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PI 0x00000008U /*!<PI[0] pin */
/**
* @brief EXTI1 configuration
*/
#define SYSCFG_EXTICR1_EXTI1_PA 0x00000000U /*!<PA[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PB 0x00000010U /*!<PB[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PC 0x00000020U /*!<PC[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PD 0x00000030U /*!<PD[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PE 0x00000040U /*!<PE[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PF 0x00000050) /*!<PF[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PG 0x00000060U /*!<PG[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PH 0x00000070U /*!<PH[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PI 0x00000080U /*!<PI[1] pin */
/**
* @brief EXTI2 configuration
*/
#define SYSCFG_EXTICR1_EXTI2_PA 0x00000000U /*!<PA[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PB 0x00000100U /*!<PB[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PC 0x00000200U /*!<PC[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PD 0x00000300U /*!<PD[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PE 0x00000400U /*!<PE[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PF 0x00000500) /*!<PF[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PG 0x00000600) /*!<PG[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PH 0x00000700U /*!<PH[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PI 0x00000800U /*!<PI[2] pin */
/**
* @brief EXTI3 configuration
*/
#define SYSCFG_EXTICR1_EXTI3_PA 0x00000000U /*!<PA[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PB 0x00001000U /*!<PB[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PC 0x00002000U /*!<PC[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PD 0x00003000U /*!<PD[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PE 0x00004000U /*!<PE[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PF 0x00005000) /*!<PF[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PG 0x00006000U /*!<PG[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PH 0x00007000U /*!<PH[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PI 0x00008000U /*!<PI[3] pin */
#define SPI_I2SPR_MCKOE 0x00000200U /*!<Master Clock Output Enable */
/******************************************************************************/
/* */
/* SYSCFG */
/* */
/******************************************************************************/
/****************** Bit definition for SYSCFG_MEMRMP register ***************/
#define SYSCFG_MEMRMP_MEM_MODE 0x00000003U /*!<SYSCFG_Memory Remap Config */
#define SYSCFG_MEMRMP_MEM_MODE_0 0x00000001U
#define SYSCFG_MEMRMP_MEM_MODE_1 0x00000002U
/***************** Bit definition for SYSCFG_EXTICR1 register ***************/
#define SYSCFG_EXTICR1_EXTI0 0x0000000FU /*!<EXTI 0 configuration */
#define SYSCFG_EXTICR1_EXTI1 0x000000F0U /*!<EXTI 1 configuration */
#define SYSCFG_EXTICR1_EXTI2 0x00000F00U /*!<EXTI 2 configuration */
#define SYSCFG_EXTICR1_EXTI3 0x0000F000U /*!<EXTI 3 configuration */
/**
* @brief EXTI0 configuration
*/
#define SYSCFG_EXTICR1_EXTI0_PA 0x00000000U /*!<PA[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PB 0x00000001U /*!<PB[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PC 0x00000002U /*!<PC[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PD 0x00000003U /*!<PD[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PE 0x00000004U /*!<PE[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PF 0x00000005U /*!<PF[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PG 0x00000006U /*!<PG[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PH 0x00000007U /*!<PH[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PI 0x00000008U /*!<PI[0] pin */
/**
* @brief EXTI1 configuration
*/
#define SYSCFG_EXTICR1_EXTI1_PA 0x00000000U /*!<PA[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PB 0x00000010U /*!<PB[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PC 0x00000020U /*!<PC[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PD 0x00000030U /*!<PD[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PE 0x00000040U /*!<PE[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PF 0x00000050) /*!<PF[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PG 0x00000060U /*!<PG[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PH 0x00000070U /*!<PH[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PI 0x00000080U /*!<PI[1] pin */
/**
* @brief EXTI2 configuration
*/
#define SYSCFG_EXTICR1_EXTI2_PA 0x00000000U /*!<PA[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PB 0x00000100U /*!<PB[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PC 0x00000200U /*!<PC[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PD 0x00000300U /*!<PD[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PE 0x00000400U /*!<PE[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PF 0x00000500) /*!<PF[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PG 0x00000600) /*!<PG[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PH 0x00000700U /*!<PH[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PI 0x00000800U /*!<PI[2] pin */
/**
* @brief EXTI3 configuration
*/
#define SYSCFG_EXTICR1_EXTI3_PA 0x00000000U /*!<PA[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PB 0x00001000U /*!<PB[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PC 0x00002000U /*!<PC[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PD 0x00003000U /*!<PD[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PE 0x00004000U /*!<PE[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PF 0x00005000) /*!<PF[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PG 0x00006000U /*!<PG[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PH 0x00007000U /*!<PH[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PI 0x00008000U /*!<PI[3] pin */
/***************** Bit definition for SYSCFG_EXTICR2 register ***************/
#define SYSCFG_EXTICR2_EXTI4 0x0000000FU /*!<EXTI 4 configuration */
#define SYSCFG_EXTICR2_EXTI5 0x000000F0U /*!<EXTI 5 configuration */
#define SYSCFG_EXTICR2_EXTI6 0x00000F00U /*!<EXTI 6 configuration */
#define SYSCFG_EXTICR2_EXTI7 0x0000F000U /*!<EXTI 7 configuration */
/**
* @brief EXTI4 configuration
*/
/**
* @brief EXTI4 configuration
*/
#define SYSCFG_EXTICR2_EXTI4_PA 0x00000000U /*!<PA[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PB 0x00000001U /*!<PB[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PC 0x00000002U /*!<PC[4] pin */
@ -6004,9 +6004,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR2_EXTI4_PG 0x00000006U /*!<PG[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PH 0x00000007U /*!<PH[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PI 0x00000008U /*!<PI[4] pin */
/**
* @brief EXTI5 configuration
*/
/**
* @brief EXTI5 configuration
*/
#define SYSCFG_EXTICR2_EXTI5_PA 0x00000000U /*!<PA[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PB 0x00000010U /*!<PB[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PC 0x00000020U /*!<PC[5] pin */
@ -6016,9 +6016,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR2_EXTI5_PG 0x00000060U /*!<PG[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PH 0x00000070U /*!<PH[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PI 0x00000080U /*!<PI[5] pin */
/**
* @brief EXTI6 configuration
*/
/**
* @brief EXTI6 configuration
*/
#define SYSCFG_EXTICR2_EXTI6_PA 0x00000000U /*!<PA[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PB 0x00000100U /*!<PB[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PC 0x00000200U /*!<PC[6] pin */
@ -6028,9 +6028,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR2_EXTI6_PG 0x00000600) /*!<PG[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PH 0x00000700U /*!<PH[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PI 0x00000800U /*!<PI[6] pin */
/**
* @brief EXTI7 configuration
*/
/**
* @brief EXTI7 configuration
*/
#define SYSCFG_EXTICR2_EXTI7_PA 0x00000000U /*!<PA[7] pin */
#define SYSCFG_EXTICR2_EXTI7_PB 0x00001000U /*!<PB[7] pin */
#define SYSCFG_EXTICR2_EXTI7_PC 0x00002000U /*!<PC[7] pin */
@ -6046,10 +6046,10 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR3_EXTI9 0x000000F0U /*!<EXTI 9 configuration */
#define SYSCFG_EXTICR3_EXTI10 0x00000F00U /*!<EXTI 10 configuration */
#define SYSCFG_EXTICR3_EXTI11 0x0000F000U /*!<EXTI 11 configuration */
/**
* @brief EXTI8 configuration
*/
/**
* @brief EXTI8 configuration
*/
#define SYSCFG_EXTICR3_EXTI8_PA 0x00000000U /*!<PA[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PB 0x00000001U /*!<PB[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PC 0x00000002U /*!<PC[8] pin */
@ -6059,9 +6059,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR3_EXTI8_PG 0x00000006U /*!<PG[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PH 0x00000007U /*!<PH[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PI 0x00000008U /*!<PI[8] pin */
/**
* @brief EXTI9 configuration
*/
/**
* @brief EXTI9 configuration
*/
#define SYSCFG_EXTICR3_EXTI9_PA 0x00000000U /*!<PA[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PB 0x00000010U /*!<PB[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PC 0x00000020U /*!<PC[9] pin */
@ -6071,9 +6071,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR3_EXTI9_PG 0x00000060U /*!<PG[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PH 0x00000070U /*!<PH[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PI 0x00000080U /*!<PI[9] pin */
/**
* @brief EXTI10 configuration
*/
/**
* @brief EXTI10 configuration
*/
#define SYSCFG_EXTICR3_EXTI10_PA 0x00000000U /*!<PA[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PB 0x00000100U /*!<PB[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PC 0x00000200U /*!<PC[10] pin */
@ -6083,9 +6083,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR3_EXTI10_PG 0x00000600) /*!<PG[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PH 0x00000700U /*!<PH[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PI 0x00000800U /*!<PI[10] pin */
/**
* @brief EXTI11 configuration
*/
/**
* @brief EXTI11 configuration
*/
#define SYSCFG_EXTICR3_EXTI11_PA 0x00000000U /*!<PA[11] pin */
#define SYSCFG_EXTICR3_EXTI11_PB 0x00001000U /*!<PB[11] pin */
#define SYSCFG_EXTICR3_EXTI11_PC 0x00002000U /*!<PC[11] pin */
@ -6101,9 +6101,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR4_EXTI13 0x000000F0U /*!<EXTI 13 configuration */
#define SYSCFG_EXTICR4_EXTI14 0x00000F00U /*!<EXTI 14 configuration */
#define SYSCFG_EXTICR4_EXTI15 0x0000F000U /*!<EXTI 15 configuration */
/**
* @brief EXTI12 configuration
*/
/**
* @brief EXTI12 configuration
*/
#define SYSCFG_EXTICR4_EXTI12_PA 0x00000000U /*!<PA[12] pin */
#define SYSCFG_EXTICR4_EXTI12_PB 0x00000001U /*!<PB[12] pin */
#define SYSCFG_EXTICR4_EXTI12_PC 0x00000002U /*!<PC[12] pin */
@ -6112,9 +6112,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR4_EXTI12_PF 0x00000005U /*!<PF[12] pin */
#define SYSCFG_EXTICR4_EXTI12_PG 0x00000006U /*!<PG[12] pin */
#define SYSCFG_EXTICR3_EXTI12_PH 0x00000007U /*!<PH[12] pin */
/**
* @brief EXTI13 configuration
*/
/**
* @brief EXTI13 configuration
*/
#define SYSCFG_EXTICR4_EXTI13_PA 0x00000000U /*!<PA[13] pin */
#define SYSCFG_EXTICR4_EXTI13_PB 0x00000010U /*!<PB[13] pin */
#define SYSCFG_EXTICR4_EXTI13_PC 0x00000020U /*!<PC[13] pin */
@ -6123,9 +6123,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR4_EXTI13_PF 0x00000050) /*!<PF[13] pin */
#define SYSCFG_EXTICR4_EXTI13_PG 0x00000060U /*!<PG[13] pin */
#define SYSCFG_EXTICR3_EXTI13_PH 0x00000070U /*!<PH[13] pin */
/**
* @brief EXTI14 configuration
*/
/**
* @brief EXTI14 configuration
*/
#define SYSCFG_EXTICR4_EXTI14_PA 0x00000000U /*!<PA[14] pin */
#define SYSCFG_EXTICR4_EXTI14_PB 0x00000100U /*!<PB[14] pin */
#define SYSCFG_EXTICR4_EXTI14_PC 0x00000200U /*!<PC[14] pin */
@ -6134,9 +6134,9 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR4_EXTI14_PF 0x00000500) /*!<PF[14] pin */
#define SYSCFG_EXTICR4_EXTI14_PG 0x00000600) /*!<PG[14] pin */
#define SYSCFG_EXTICR3_EXTI14_PH 0x00000700U /*!<PH[14] pin */
/**
* @brief EXTI15 configuration
*/
/**
* @brief EXTI15 configuration
*/
#define SYSCFG_EXTICR4_EXTI15_PA 0x00000000U /*!<PA[15] pin */
#define SYSCFG_EXTICR4_EXTI15_PB 0x00001000U /*!<PB[15] pin */
#define SYSCFG_EXTICR4_EXTI15_PC 0x00002000U /*!<PC[15] pin */
@ -6146,7 +6146,7 @@ USB_OTG_HostChannelTypeDef;
#define SYSCFG_EXTICR4_EXTI15_PG 0x00006000U /*!<PG[15] pin */
#define SYSCFG_EXTICR3_EXTI15_PH 0x00007000U /*!<PH[15] pin */
/****************** Bit definition for SYSCFG_CMPCR register ****************/
/****************** Bit definition for SYSCFG_CMPCR register ****************/
#define SYSCFG_CMPCR_CMP_PD 0x00000001U /*!<Compensation cell ready flag */
#define SYSCFG_CMPCR_READY 0x00000100U /*!<Compensation cell power-down */
@ -7294,7 +7294,7 @@ USB_OTG_HostChannelTypeDef;
/**
* @}
*/
*/
/**
* @}
@ -7303,7 +7303,7 @@ USB_OTG_HostChannelTypeDef;
/** @addtogroup Exported_macros
* @{
*/
/******************************* ADC Instances ********************************/
#define IS_ADC_ALL_INSTANCE(INSTANCE) (((INSTANCE) == ADC1) || \
((INSTANCE) == ADC2) || \
@ -7312,7 +7312,7 @@ USB_OTG_HostChannelTypeDef;
/******************************* CAN Instances ********************************/
#define IS_CAN_ALL_INSTANCE(INSTANCE) (((INSTANCE) == CAN1) || \
((INSTANCE) == CAN2))
/******************************* CRC Instances ********************************/
#define IS_CRC_ALL_INSTANCE(INSTANCE) ((INSTANCE) == CRC)
@ -7463,7 +7463,7 @@ USB_OTG_HostChannelTypeDef;
((INSTANCE) == TIM3) || \
((INSTANCE) == TIM4) || \
((INSTANCE) == TIM5) || \
((INSTANCE) == TIM8))
((INSTANCE) == TIM8))
/******************** TIM Instances : DMA burst feature ***********************/
#define IS_TIM_DMABURST_INSTANCE(INSTANCE) (((INSTANCE) == TIM1) || \
@ -7614,7 +7614,7 @@ USB_OTG_HostChannelTypeDef;
((INSTANCE) == USART3) || \
((INSTANCE) == UART4) || \
((INSTANCE) == UART5) || \
((INSTANCE) == USART6))
((INSTANCE) == USART6))
/*********************** PCD Instances ****************************************/
#define IS_PCD_ALL_INSTANCE(INSTANCE) (((INSTANCE) == USB_OTG_FS) || \
@ -7646,7 +7646,7 @@ USB_OTG_HostChannelTypeDef;
/**
* @}
*/
*/
/**
* @}

View File

@ -4,17 +4,17 @@
* @author MCD Application Team
* @version V2.1.2
* @date 29-June-2016
* @brief CMSIS STM32F2xx Device Peripheral Access Layer Header File.
* @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 peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* - To use or not the peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* "#define USE_HAL_DRIVER"
*
*
******************************************************************************
* @attention
*
@ -52,14 +52,14 @@
/** @addtogroup stm32f2xx
* @{
*/
#ifndef __STM32F2xx_H
#define __STM32F2xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Library_configuration_section
* @{
*/
@ -70,9 +70,9 @@
#if !defined (STM32F2)
#define STM32F2
#endif /* STM32F2 */
/* Uncomment the line below according to the target STM32 device used in your
application
application
*/
#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx)
@ -83,17 +83,17 @@
/* #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
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 */
@ -136,23 +136,23 @@
/** @addtogroup Exported_types
* @{
*/
typedef enum
*/
typedef enum
{
RESET = 0,
RESET = 0,
SET = !RESET
} FlagStatus, ITStatus;
typedef enum
typedef enum
{
DISABLE = 0,
DISABLE = 0,
ENABLE = !DISABLE
} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum
typedef enum
{
ERROR = 0,
ERROR = 0,
SUCCESS = !ERROR
} ErrorStatus;
@ -178,13 +178,13 @@ typedef enum
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
/**
* @}
*/
#if defined (USE_HAL_DRIVER)
#include "stm32f2xx_hal.h"
#endif /* USE_HAL_DRIVER */
@ -202,7 +202,7 @@ typedef enum
/**
* @}
*/

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V1.1.3
* @date 29-June-2016
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
@ -51,10 +51,10 @@
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00U,
HAL_ERROR = 0x01U,
@ -62,13 +62,13 @@ typedef enum
HAL_TIMEOUT = 0x03U
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
/**
* @brief HAL Lock structures definition
*/
typedef enum
typedef enum
{
HAL_UNLOCKED = 0x00U,
HAL_LOCKED = 0x01U
HAL_LOCKED = 0x01U
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
@ -84,14 +84,14 @@ typedef enum
} 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:
* @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 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
* 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
@ -133,34 +133,34 @@ typedef enum
#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
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __CC_ARM */
#endif /* __ALIGN_BEGIN */
#endif /* __GNUC__ */
/**
/**
* @brief __NOINLINE definition
*/
*/
#if defined ( __CC_ARM ) || defined ( __GNUC__ )
/* ARM & GNUCompiler
----------------
/* ARM & GNUCompiler
----------------
*/
#define __NOINLINE __attribute__ ( (noinline) )

View File

@ -33,7 +33,7 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F2xx_HAL_GPIO_EX_H
@ -52,7 +52,7 @@
/** @defgroup GPIOEx GPIOEx
* @{
*/
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
@ -60,117 +60,117 @@
/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants
* @{
*/
/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection
*/
/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection
* @{
*/
/**
* @brief AF 0 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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @brief AF 6 selection
*/
#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */
/**
* @brief AF 7 selection
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @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
*/
/**
* @brief AF 15 selection
*/
#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */
/**
* @}
*/
*/
/**
* @}
@ -184,7 +184,7 @@
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions
* @{
*/
@ -224,9 +224,9 @@
/** @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) || \
@ -264,10 +264,10 @@
((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \
((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT))
#endif /* STM32F207xx || STM32F217xx */
/**
* @}
*/
*/
/**
* @}
@ -284,12 +284,12 @@
/**
* @}
*/
*/
/**
* @}
*/
*/
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -5,16 +5,16 @@
* @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 peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* - To use or not the peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* "#define USE_HAL_DRIVER"
*
*
******************************************************************************
* @attention
*
@ -52,18 +52,18 @@
/** @addtogroup stm32f4xx
* @{
*/
#ifndef __STM32F4xx_H
#define __STM32F4xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Library_configuration_section
* @{
*/
/**
* @brief STM32 Family
*/
@ -72,7 +72,7 @@
#endif /* STM32F4 */
/* Uncomment the line below according to the target STM32 device used in your
application
application
*/
#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \
!defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \
@ -86,9 +86,9 @@
/* #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,
/* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG,
STM32F439NI, STM32F429IG and STM32F429II Devices */
/* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG,
/* #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 */
@ -96,11 +96,11 @@
/* #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,
/* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC,
and STM32F446ZE Devices */
/* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG,
/* #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
/* #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 */
@ -110,15 +110,15 @@
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
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 */
@ -199,23 +199,23 @@
/** @addtogroup Exported_types
* @{
*/
typedef enum
*/
typedef enum
{
RESET = 0U,
RESET = 0U,
SET = !RESET
} FlagStatus, ITStatus;
typedef enum
typedef enum
{
DISABLE = 0U,
DISABLE = 0U,
ENABLE = !DISABLE
} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum
typedef enum
{
ERROR = 0U,
ERROR = 0U,
SUCCESS = !ERROR
} ErrorStatus;
@ -241,7 +241,7 @@ typedef enum
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
/**
@ -264,7 +264,7 @@ typedef enum
/**
* @}
*/

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V1.6.0
* @date 04-November-2016
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
@ -51,10 +51,10 @@
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00U,
HAL_ERROR = 0x01U,
@ -62,13 +62,13 @@ typedef enum
HAL_TIMEOUT = 0x03U
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
/**
* @brief HAL Lock structures definition
*/
typedef enum
typedef enum
{
HAL_UNLOCKED = 0x00U,
HAL_LOCKED = 0x01U
HAL_LOCKED = 0x01U
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
@ -87,11 +87,11 @@ typedef enum
/** @brief Reset the Handle's State field.
* @param __HANDLE__: specifies the Peripheral Handle.
* @note This macro can be used for the following purpose:
* @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 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
* 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
@ -139,61 +139,61 @@ typedef enum
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#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.
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'
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.
dialog.
*/
#define __RAM_FUNC HAL_StatusTypeDef
#define __RAM_FUNC HAL_StatusTypeDef
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
RAM functions are defined using a specific toolchain keyword "__ramfunc".
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
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
----------------
/* ARM & GNUCompiler
----------------
*/
#define __NOINLINE __attribute__ ( (noinline) )

File diff suppressed because it is too large Load Diff

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V2.1.2
* @date 29-June-2016
* @brief CMSIS Cortex-M3 Device System Source File for STM32F2xx devices.
* @brief CMSIS Cortex-M3 Device System Source File for STM32F2xx devices.
******************************************************************************
* @attention
*
@ -32,8 +32,8 @@
* 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
* @{
@ -41,8 +41,8 @@
/** @addtogroup stm32f2xx_system
* @{
*/
*/
/**
* @brief Define to prevent recursive inclusion
*/
@ -51,7 +51,7 @@
#ifdef __cplusplus
extern "C" {
#endif
#endif
/** @addtogroup STM32F2xx_System_Includes
* @{
@ -68,7 +68,7 @@
/* 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
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.
@ -99,7 +99,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Cloc
/** @addtogroup STM32F2xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
@ -115,8 +115,8 @@ extern void SystemCoreClockUpdate(void);
/**
* @}
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V2.6.0
* @date 04-November-2016
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
@ -32,8 +32,8 @@
* 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
* @{
@ -41,8 +41,8 @@
/** @addtogroup stm32f4xx_system
* @{
*/
*/
/**
* @brief Define to prevent recursive inclusion
*/
@ -51,7 +51,7 @@
#ifdef __cplusplus
extern "C" {
#endif
#endif
/** @addtogroup STM32F4xx_System_Includes
* @{
@ -68,7 +68,7 @@
/* 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
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.
@ -101,7 +101,7 @@ extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
/** @addtogroup STM32F4xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
@ -117,8 +117,8 @@ extern void SystemCoreClockUpdate(void);
/**
* @}
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -6,32 +6,36 @@ void delay(int a) {
}
void *memset(void *str, int c, unsigned int n) {
unsigned int i;
for (i = 0; i < n; i++) {
*((uint8_t*)str) = c;
++str;
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) {
unsigned int i;
// TODO: make not slow
for (i = 0; i < n; i++) {
((uint8_t*)dest)[i] = *(uint8_t*)src;
++src;
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) {
unsigned int i;
int ret = 0;
for (i = 0; i < num; i++) {
if ( ((uint8_t*)ptr1)[i] != ((uint8_t*)ptr2)[i] ) {
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;
}

View File

@ -33,7 +33,7 @@
void debug_ring_callback(uart_ring *ring) {
char rcv;
while (getc(ring, &rcv)) {
putc(ring, rcv);
(void)putc(ring, rcv); // misra-c2012-17.7: cast to void is ok: debug function
// jump to DFU flash
if (rcv == 'z') {
@ -69,9 +69,10 @@ bool is_gpio_started(void) {
return (GPIOA->IDR & (1U << 1)) == 0;
}
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void EXTI1_IRQHandler(void) {
volatile int pr = EXTI->PR & (1U << 1);
if ((pr & (1U << 1)) != 0) {
volatile unsigned int pr = EXTI->PR & (1U << 1);
if ((pr & (1U << 1)) != 0U) {
#ifdef DEBUG
puts("got started interrupt\n");
#endif
@ -98,13 +99,14 @@ void started_interrupt_init(void) {
int get_health_pkt(void *dat) {
struct __attribute__((packed)) {
uint32_t voltage;
uint32_t current;
uint8_t started;
uint8_t controls_allowed;
uint8_t gas_interceptor_detected;
uint8_t started_signal_detected;
uint8_t started_alt;
uint32_t voltage_pkt;
uint32_t current_pkt;
uint8_t started_pkt;
uint8_t controls_allowed_pkt;
uint8_t gas_interceptor_detected_pkt;
uint32_t can_send_errs_pkt;
uint32_t can_fwd_errs_pkt;
uint32_t gmlan_send_errs_pkt;
} *health = dat;
//Voltage will be measured in mv. 5000 = 5V
@ -117,29 +119,28 @@ int get_health_pkt(void *dat) {
// s = 1000/((4095/3.3)*(1/11)) = 8.8623046875
// Avoid needing floating point math
health->voltage = (voltage * 8862) / 1000;
health->voltage_pkt = (voltage * 8862U) / 1000U;
health->current = adc_get(ADCCHAN_CURRENT);
health->current_pkt = adc_get(ADCCHAN_CURRENT);
int safety_ignition = safety_ignition_hook();
if (safety_ignition < 0) {
//Use the GPIO pin to determine ignition
health->started = is_gpio_started();
health->started_pkt = is_gpio_started();
} else {
//Current safety hooks want to determine ignition (ex: GM)
health->started = safety_ignition;
health->started_pkt = safety_ignition;
}
health->controls_allowed = controls_allowed;
health->gas_interceptor_detected = gas_interceptor_detected;
// DEPRECATED
health->started_alt = 0;
health->started_signal_detected = 0;
health->controls_allowed_pkt = controls_allowed;
health->gas_interceptor_detected_pkt = gas_interceptor_detected;
health->can_send_errs_pkt = can_send_errs;
health->can_fwd_errs_pkt = can_fwd_errs;
health->gmlan_send_errs_pkt = gmlan_send_errs;
return sizeof(*health);
}
int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired) {
int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) {
UNUSED(hardwired);
CAN_FIFOMailBox_TypeDef *reply = (CAN_FIFOMailBox_TypeDef *)usbdata;
int ilen = 0;
@ -150,13 +151,14 @@ int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired) {
}
// send on serial, first byte to select the ring
void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) {
UNUSED(hardwired);
uart_ring *ur = get_ring_by_number(usbdata[0]);
uint8_t *usbdata8 = (uint8_t *)usbdata;
uart_ring *ur = get_ring_by_number(usbdata8[0]);
if ((len != 0) && (ur != NULL)) {
if ((usbdata[0] < 2) || safety_tx_lin_hook(usbdata[0]-2, usbdata+1, len-1)) {
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, usbdata[i])) {
while (!putc(ur, usbdata8[i])) {
// wait
}
}
@ -165,18 +167,16 @@ void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {
}
// send on CAN
void usb_cb_ep3_out(uint8_t *usbdata, int len, bool hardwired) {
void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) {
UNUSED(hardwired);
int dpkt = 0;
for (dpkt = 0; dpkt < len; dpkt += 0x10) {
uint32_t *tf = (uint32_t*)(&usbdata[dpkt]);
// make a copy
uint32_t *d32 = (uint32_t *)usbdata;
for (dpkt = 0; dpkt < (len / 4); dpkt += 4) {
CAN_FIFOMailBox_TypeDef to_push;
to_push.RDHR = tf[3];
to_push.RDLR = tf[2];
to_push.RDTR = tf[1];
to_push.RIR = tf[0];
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);
@ -191,7 +191,7 @@ void usb_cb_enumeration_complete() {
}
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) {
int resp_len = 0;
unsigned int resp_len = 0;
uart_ring *ur = NULL;
int i;
switch (setup->b.bRequest) {
@ -211,8 +211,8 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
// **** 0xd0: fetch serial number
case 0xd0:
// addresses are OTP
if (setup->b.wValue.w == 1) {
memcpy(resp, (void *)0x1fff79c0, 0x10);
if (setup->b.wValue.w == 1U) {
(void)memcpy(resp, (uint8_t *)0x1fff79c0, 0x10);
resp_len = 0x10;
} else {
get_provision_chunk(resp);
@ -248,8 +248,8 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
// **** 0xd6: get version
case 0xd6:
COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN);
memcpy(resp, gitversion, sizeof(gitversion));
resp_len = sizeof(gitversion)-1;
(void)memcpy(resp, gitversion, sizeof(gitversion));
resp_len = sizeof(gitversion) - 1U;
break;
// **** 0xd8: reset ST
case 0xd8:
@ -257,9 +257,9 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
break;
// **** 0xd9: set ESP power
case 0xd9:
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
set_esp_mode(ESP_ENABLED);
} else if (setup->b.wValue.w == 2) {
} else if (setup->b.wValue.w == 2U) {
set_esp_mode(ESP_BOOTMODE);
} else {
set_esp_mode(ESP_DISABLED);
@ -269,7 +269,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
case 0xda:
set_esp_mode(ESP_DISABLED);
delay(1000000);
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
set_esp_mode(ESP_BOOTMODE);
} else {
set_esp_mode(ESP_ENABLED);
@ -279,12 +279,14 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
break;
// **** 0xdb: set GMLAN multiplexing mode
case 0xdb:
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
// GMLAN ON
if (setup->b.wIndex.w == 1) {
if (setup->b.wIndex.w == 1U) {
can_set_gmlan(1);
} else if (setup->b.wIndex.w == 2) {
} 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);
@ -296,27 +298,33 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
// and it's blocked over WiFi
// Allow ELM security mode to be set over wifi.
if (hardwired || (setup->b.wValue.w == SAFETY_NOOUTPUT) || (setup->b.wValue.w == SAFETY_ELM327)) {
safety_set_mode(setup->b.wValue.w, (int16_t)setup->b.wIndex.w);
if (safety_ignition_hook() != -1) {
// if the ignition hook depends on something other than the started GPIO
// we have to disable power savings (fix for GM and Tesla)
set_power_save_state(POWER_SAVE_STATUS_DISABLED);
}
#ifndef EON
// always LIVE on EON
switch (setup->b.wValue.w) {
case SAFETY_NOOUTPUT:
can_silent = ALL_CAN_SILENT;
break;
case SAFETY_ELM327:
can_silent = ALL_CAN_BUT_MAIN_SILENT;
break;
default:
can_silent = ALL_CAN_LIVE;
break;
int err = safety_set_mode(setup->b.wValue.w, (int16_t)setup->b.wIndex.w);
if (err == -1) {
puts("Error: safety set mode failed\n");
} else {
#ifndef EON
// always LIVE on EON
switch (setup->b.wValue.w) {
case SAFETY_NOOUTPUT:
can_silent = ALL_CAN_SILENT;
break;
case SAFETY_ELM327:
can_silent = ALL_CAN_BUT_MAIN_SILENT;
break;
default:
can_silent = ALL_CAN_LIVE;
break;
}
#endif
if (safety_ignition_hook() != -1) {
// if the ignition hook depends on something other than the started GPIO
// we have to disable power savings (fix for GM and Tesla)
set_power_save_state(POWER_SAVE_STATUS_DISABLED);
} else {
// power mode is already POWER_SAVE_STATUS_DISABLED and CAN TXs are active
}
#endif
can_init_all();
can_init_all();
}
}
break;
// **** 0xdd: enable can forwarding
@ -326,8 +334,10 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
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 == 0xFF)){ //Clear Forwarding
} 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
@ -340,7 +350,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
// **** 0xdf: set long controls allowed
case 0xdf:
if (hardwired) {
long_controls_allowed = setup->b.wValue.w & 1;
long_controls_allowed = setup->b.wValue.w & 1U;
}
break;
// **** 0xe0: uart read
@ -401,15 +411,15 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
break;
// **** 0xe5: set CAN loopback (for testing)
case 0xe5:
can_loopback = (setup->b.wValue.w > 0);
can_loopback = (setup->b.wValue.w > 0U);
can_init_all();
break;
// **** 0xe6: set USB power
case 0xe6:
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
puts("user setting CDP mode\n");
set_usb_power_mode(USB_POWER_CDP);
} else if (setup->b.wValue.w == 2) {
} else if (setup->b.wValue.w == 2U) {
puts("user setting DCP mode\n");
set_usb_power_mode(USB_POWER_DCP);
} else {
@ -419,7 +429,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
break;
// **** 0xf0: do k-line wValue pulse on uart2 for Acura
case 0xf0:
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
GPIOC->ODR &= ~(1U << 10);
GPIOC->MODER &= ~GPIO_MODER_MODER10_1;
GPIOC->MODER |= GPIO_MODER_MODER10_0;
@ -431,7 +441,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
for (i = 0; i < 80; i++) {
delay(8000);
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
GPIOC->ODR |= (1U << 10);
GPIOC->ODR &= ~(1U << 10);
} else {
@ -440,7 +450,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
}
}
if (setup->b.wValue.w == 1) {
if (setup->b.wValue.w == 1U) {
GPIOC->MODER &= ~GPIO_MODER_MODER10_0;
GPIOC->MODER |= GPIO_MODER_MODER10_1;
} else {
@ -452,12 +462,14 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
break;
// **** 0xf1: Clear CAN ring buffer.
case 0xf1:
if (setup->b.wValue.w == 0xFFFF) {
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.
@ -479,6 +491,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
return resp_len;
}
#ifndef EON
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
// data[0] = endpoint
// data[2] = length
@ -508,26 +521,28 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
}
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 * 2)) | (3UL << (11U * 2)));
SCB->CPACR |= ((3UL << (10U * 2U)) | (3UL << (11U * 2U)));
}
uint64_t tcnt = 0;
uint64_t marker = 0;
// called once per second
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void TIM3_IRQHandler(void) {
#define CURRENT_THRESHOLD 0xF00
#define CLICKS 5 // 5 seconds to switch modes
#define CURRENT_THRESHOLD 0xF00U
#define CLICKS 5U // 5 seconds to switch modes
if (TIM3->SR != 0) {
can_live = pending_can_live;
@ -538,7 +553,7 @@ void TIM3_IRQHandler(void) {
switch (usb_power_mode) {
case USB_POWER_CLIENT:
if ((tcnt-marker) >= CLICKS) {
if ((tcnt - marker) >= CLICKS) {
if (!is_enumerated) {
puts("USBP: didn't enumerate, switching to CDP mode\n");
// switch to CDP
@ -594,7 +609,7 @@ void TIM3_IRQHandler(void) {
puts("\n");*/
// reset this every 16th pass
if ((tcnt&0xF) == 0) {
if ((tcnt & 0xFU) == 0U) {
pending_can_live = 0;
}
#ifdef DEBUG
@ -609,10 +624,10 @@ void TIM3_IRQHandler(void) {
// turn off the blue LED, turned on by CAN
// unless we are in power saving mode
set_led(LED_BLUE, (tcnt & 1) && (power_save_status == POWER_SAVE_STATUS_ENABLED));
set_led(LED_BLUE, (tcnt & 1U) && (power_save_status == POWER_SAVE_STATUS_ENABLED));
// on to the next one
tcnt += 1;
tcnt += 1U;
}
TIM3->SR = 0;
}
@ -680,7 +695,13 @@ int main(void) {
// default to silent mode to prevent issues with Ford
// hardcode a specific safety mode if you want to force the panda to be in a specific mode
safety_set_mode(SAFETY_NOOUTPUT, 0);
int err = safety_set_mode(SAFETY_NOOUTPUT, 0);
if (err == -1) {
puts("Failed to set safety mode\n");
while (true) {
// if SAFETY_NOOUTPUT isn't succesfully set, we can't continue
}
}
#ifdef EON
// if we're on an EON, it's fine for CAN to be live for fingerprinting
can_silent = ALL_CAN_LIVE;

View File

@ -1,10 +1,10 @@
# :set noet
PROJ_NAME = comma
CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL
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
CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib -fno-builtin
CFLAGS += -T../stm32_flash.ld
STARTUP_FILE = startup_stm32f205xx

View File

@ -19,14 +19,19 @@
#include "drivers/usb.h"
#else
// no serial either
void puts(const char *a) {}
void puth(unsigned int i) {}
void puts(const char *a) {
UNUSED(a);
}
void puth(unsigned int i) {
UNUSED(i);
}
#endif
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
uint32_t enter_bootloader_mode;
void __initialize_hardware_early() {
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void __initialize_hardware_early(void) {
early();
}
@ -36,31 +41,54 @@ void __initialize_hardware_early() {
void debug_ring_callback(uart_ring *ring) {
char rcv;
while (getc(ring, &rcv)) {
putc(ring, rcv);
while (getc(ring, &rcv) != 0) {
(void)putc(ring, rcv);
}
}
int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired) { return 0; }
void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {}
void usb_cb_ep3_out(uint8_t *usbdata, int len, bool hardwired) {}
void usb_cb_enumeration_complete() {}
int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired) {
UNUSED(usbdata);
UNUSED(len);
UNUSED(hardwired);
return 0;
}
void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {
UNUSED(usbdata);
UNUSED(len);
UNUSED(hardwired);
}
void usb_cb_ep3_out(uint8_t *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) {
int resp_len = 0;
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;
if (ur == &esp_ring) uart_dma_drain();
if (!ur) {
break;
}
if (ur == &esp_ring) {
uart_dma_drain();
}
// 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;
}
@ -76,7 +104,7 @@ uint8_t pedal_checksum(uint8_t *dat, int len) {
for (i = len - 1; i >= 0; i--) {
crc ^= dat[i];
for (j = 0; j < 8; j++) {
if ((crc & 0x80) != 0) {
if ((crc & 0x80U) != 0U) {
crc = (uint8_t)((crc << 1) ^ poly);
}
else {
@ -91,11 +119,12 @@ uint8_t pedal_checksum(uint8_t *dat, int len) {
// addresses to be used on CAN
#define CAN_GAS_INPUT 0x200
#define CAN_GAS_OUTPUT 0x201
#define CAN_GAS_OUTPUT 0x201U
#define CAN_GAS_SIZE 6
#define COUNTER_CYCLE 0xF
#define COUNTER_CYCLE 0xFU
void CAN1_TX_IRQHandler() {
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void CAN1_TX_IRQHandler(void) {
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
@ -104,51 +133,51 @@ void CAN1_TX_IRQHandler() {
uint16_t gas_set_0 = 0;
uint16_t gas_set_1 = 0;
#define MAX_TIMEOUT 10
#define MAX_TIMEOUT 10U
uint32_t timeout = 0;
uint32_t current_index = 0;
#define NO_FAULT 0
#define FAULT_BAD_CHECKSUM 1
#define FAULT_SEND 2
#define FAULT_SCE 3
#define FAULT_STARTUP 4
#define FAULT_TIMEOUT 5
#define FAULT_INVALID 6
#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_IRQHandler() {
while (CAN->RF0R & CAN_RF0R_FMP0) {
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void CAN1_RX0_IRQHandler(void) {
while ((CAN->RF0R & CAN_RF0R_FMP0) != 0) {
#ifdef DEBUG
puts("CAN RX\n");
#endif
uint32_t address = CAN->sFIFOMailBox[0].RIR>>21;
int address = CAN->sFIFOMailBox[0].RIR >> 21;
if (address == CAN_GAS_INPUT) {
// softloader entry
if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) {
if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) {
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 (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) {
} 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];
uint8_t *rdlr = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
uint8_t *rdhr = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
for (int i=0; i<4; i++) {
dat[i] = rdlr[i];
dat[i+4] = rdhr[i];
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];
uint8_t enable = (dat[4] >> 7) & 1;
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 + 1) & COUNTER_CYCLE) == index) {
if (((current_index + 1U) & COUNTER_CYCLE) == index) {
#ifdef DEBUG
puts("setting gas ");
puth(value);
@ -159,12 +188,13 @@ void CAN1_RX0_IRQHandler() {
gas_set_1 = value_1;
} else {
// clear the fault state if values are 0
if (value_0 == 0 && value_1 == 0) {
if ((value_0 == 0U) && (value_1 == 0U)) {
state = NO_FAULT;
} else {
state = FAULT_INVALID;
}
gas_set_0 = gas_set_1 = 0;
gas_set_0 = 0;
gas_set_1 = 0;
}
// clear the timeout
timeout = 0;
@ -180,17 +210,20 @@ void CAN1_RX0_IRQHandler() {
}
}
void CAN1_SCE_IRQHandler() {
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void CAN1_SCE_IRQHandler(void) {
state = FAULT_SCE;
llcan_clear_send(CAN);
}
int pdl0 = 0, pdl1 = 0;
int pkt_idx = 0;
uint32_t pdl0 = 0;
uint32_t pdl1 = 0;
unsigned int pkt_idx = 0;
int led_value = 0;
void TIM3_IRQHandler() {
// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck
void TIM3_IRQHandler(void) {
#ifdef DEBUG
puth(TIM3->CNT);
puts(" ");
@ -203,16 +236,16 @@ void TIM3_IRQHandler() {
// 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) & 0xFF;
dat[1] = (pdl0>>0) & 0xFF;
dat[2] = (pdl1>>8) & 0xFF;
dat[3] = (pdl1>>0) & 0xFF;
dat[4] = (state & 0xF) << 4 | pkt_idx;
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].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) | 1;
CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1U;
++pkt_idx;
pkt_idx &= COUNTER_CYCLE;
} else {
@ -233,13 +266,13 @@ void TIM3_IRQHandler() {
if (timeout == MAX_TIMEOUT) {
state = FAULT_TIMEOUT;
} else {
timeout += 1;
timeout += 1U;
}
}
// ***************************** main code *****************************
void pedal() {
void pedal(void) {
// read/write
pdl0 = adc_get(ADCCHAN_ACCEL0);
pdl1 = adc_get(ADCCHAN_ACCEL1);
@ -256,7 +289,7 @@ void pedal() {
watchdog_feed();
}
int main() {
int main(void) {
__disable_irq();
// init devices
@ -274,7 +307,11 @@ int main() {
adc_init();
// init can
llcan_set_speed(CAN1, 5000, false, false);
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

View File

@ -13,14 +13,14 @@ void set_power_save_state(int state) {
if (is_grey_panda) {
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) - 1; i++) while (!putc(ur, UBLOX_SLEEP_MSG[i]));
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 (is_grey_panda) {
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) - 1; i++) while (!putc(ur, UBLOX_WAKE_MSG[i]));
for (unsigned int i = 0; i < sizeof(UBLOX_WAKE_MSG) - 1U; i++) while (!putc(ur, UBLOX_WAKE_MSG[i]));
}
enable = true;
}

View File

@ -5,9 +5,9 @@
// SHA1 checksum = 0x1C - 0x20
void get_provision_chunk(uint8_t *resp) {
memcpy(resp, (void *)0x1fff79e0, PROVISION_CHUNK_LEN);
(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) {
memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20);
(void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20);
}
}

View File

@ -44,21 +44,21 @@ typedef struct {
const safety_hooks *hooks;
} safety_hook_config;
#define SAFETY_NOOUTPUT 0
#define SAFETY_HONDA 1
#define SAFETY_TOYOTA 2
#define SAFETY_GM 3
#define SAFETY_HONDA_BOSCH 4
#define SAFETY_FORD 5
#define SAFETY_CADILLAC 6
#define SAFETY_HYUNDAI 7
#define SAFETY_TESLA 8
#define SAFETY_CHRYSLER 9
#define SAFETY_SUBARU 10
#define SAFETY_GM_ASCM 0x1334
#define SAFETY_TOYOTA_IPAS 0x1335
#define SAFETY_ALLOUTPUT 0x1337
#define SAFETY_ELM327 0xE327
#define SAFETY_NOOUTPUT 0U
#define SAFETY_HONDA 1U
#define SAFETY_TOYOTA 2U
#define SAFETY_GM 3U
#define SAFETY_HONDA_BOSCH 4U
#define SAFETY_FORD 5U
#define SAFETY_CADILLAC 6U
#define SAFETY_HYUNDAI 7U
#define SAFETY_TESLA 8U
#define SAFETY_CHRYSLER 9U
#define SAFETY_SUBARU 10U
#define SAFETY_GM_ASCM 0x1334U
#define SAFETY_TOYOTA_IPAS 0x1335U
#define SAFETY_ALLOUTPUT 0x1337U
#define SAFETY_ELM327 0xE327U
const safety_hook_config safety_hook_registry[] = {
{SAFETY_NOOUTPUT, &nooutput_hooks},

View File

@ -10,13 +10,13 @@ const int CADILLAC_MAX_RATE_DOWN = 5;
const int CADILLAC_DRIVER_TORQUE_ALLOWANCE = 50;
const int CADILLAC_DRIVER_TORQUE_FACTOR = 4;
int cadillac_ign = 0;
bool cadillac_ign = 0;
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;
int cadillac_supercruise_on = 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) {
@ -28,7 +28,8 @@ static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
int addr = GET_ADDR(to_push);
if (addr == 356) {
int torque_driver_new = ((to_push->RDLR & 0x7) << 8) | ((to_push->RDLR >> 8) & 0xFF);
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);
@ -36,12 +37,12 @@ static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// this message isn't all zeros when ignition is on
if ((addr == 0x160) && (bus == 0)) {
cadillac_ign = to_push->RDLR > 0;
cadillac_ign = GET_BYTES_04(to_push) != 0;
}
// enter controls on rising edge of ACC, exit controls on ACC off
if ((addr == 0x370) && (bus == 0)) {
int cruise_engaged = to_push->RDLR & 0x800000; // bit 23
int cruise_engaged = GET_BYTE(to_push, 2) & 0x80; // bit 23
if (cruise_engaged && !cadillac_cruise_engaged_last) {
controls_allowed = 1;
}
@ -53,7 +54,7 @@ static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// know supercruise mode and block openpilot msgs if on
if ((addr == 0x152) || (addr == 0x154)) {
cadillac_supercruise_on = (to_push->RDHR>>4) & 0x1;
cadillac_supercruise_on = (GET_BYTE(to_push, 4) & 0x10) != 0;
}
}
@ -63,7 +64,7 @@ static int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// steer cmd checks
if ((addr == 0x151) || (addr == 0x152) || (addr == 0x153) || (addr == 0x154)) {
int desired_torque = ((to_send->RDLR & 0x3f) << 8) + ((to_send->RDLR & 0xff00) >> 8);
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);

View File

@ -18,8 +18,7 @@ static void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// Measured eps torque
if (addr == 544) {
uint32_t rdhr = to_push->RDHR;
int torque_meas_new = ((rdhr & 0x7U) << 8) + ((rdhr & 0xFF00U) >> 8) - 1024U;
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);
@ -27,7 +26,7 @@ static void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// enter controls on rising edge of ACC, exit controls on ACC off
if (addr == 0x1F4) {
int cruise_engaged = ((to_push->RDLR & 0x380000) >> 19) == 7;
int cruise_engaged = ((GET_BYTE(to_push, 2) & 0x38) >> 3) == 7;
if (cruise_engaged && !chrysler_cruise_engaged_last) {
controls_allowed = 1;
}
@ -57,8 +56,7 @@ static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// LKA STEER
if (addr == 0x292) {
uint32_t rdlr = to_send->RDLR;
int desired_torque = ((rdlr & 0x7U) << 8) + ((rdlr & 0xFF00U) >> 8) - 1024U;
int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1) - 1024U;
uint32_t ts = TIM2->CNT;
bool violation = 0;

View File

@ -9,7 +9,7 @@
int ford_brake_prev = 0;
int ford_gas_prev = 0;
int ford_is_moving = 0;
bool ford_moving = false;
static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
@ -17,14 +17,16 @@ static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
if (addr == 0x217) {
// wheel speeds are 14 bits every 16
ford_is_moving = 0xFCFF & (to_push->RDLR | (to_push->RDLR >> 16) |
to_push->RDHR | (to_push->RDHR >> 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 = (to_push->RDLR >> 8) & 0x1;
bool set_or_resume = (to_push->RDLR >> 28) & 0x3;
bool cancel = GET_BYTE(to_push, 1) & 0x1;
bool set_or_resume = GET_BYTE(to_push, 3) & 0x30;
if (cancel) {
controls_allowed = 0;
}
@ -36,8 +38,8 @@ static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of brake press or on brake press when
// speed > 0
if (addr == 0x165) {
int brake = to_push->RDLR & 0x20;
if (brake && (!(ford_brake_prev) || ford_is_moving)) {
int brake = GET_BYTE(to_push, 0) & 0x20;
if (brake && (!(ford_brake_prev) || ford_moving)) {
controls_allowed = 0;
}
ford_brake_prev = brake;
@ -45,7 +47,7 @@ static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of gas press
if (addr == 0x204) {
int gas = to_push->RDLR & 0xFF03;
int gas = (GET_BYTE(to_push, 0) & 0x03) | GET_BYTE(to_push, 1);
if (gas && !(ford_gas_prev)) {
controls_allowed = 0;
}
@ -64,7 +66,7 @@ static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
int tx = 1;
// 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_is_moving);
int pedal_pressed = ford_gas_prev || (ford_brake_prev && ford_moving);
bool current_controls_allowed = controls_allowed && !(pedal_pressed);
int addr = GET_ADDR(to_send);
@ -72,7 +74,7 @@ static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
if (addr == 0x3CA) {
if (!current_controls_allowed) {
// bits 7-4 need to be 0xF to disallow lkas commands
if (((to_send->RDLR >> 4) & 0xF) != 0xF) {
if ((GET_BYTE(to_send, 0) & 0xF0) != 0xF0) {
tx = 0;
}
}
@ -81,7 +83,7 @@ static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// FORCE CANCEL: safety check only relevant when spamming the cancel button
// ensuring that set and resume aren't sent
if (addr == 0x83) {
if (((to_send->RDLR >> 28) & 0x3) != 0) {
if ((GET_BYTE(to_send, 3) & 0x30) != 0) {
tx = 0;
}
}

View File

@ -21,7 +21,7 @@ const int GM_MAX_BRAKE = 350;
int gm_brake_prev = 0;
int gm_gas_prev = 0;
int gm_speed = 0;
bool gm_moving = false;
// silence everything if stock car control ECUs are still online
bool gm_ascm_detected = 0;
bool gm_ignition_started = 0;
@ -35,7 +35,7 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
int addr = GET_ADDR(to_push);
if (addr == 388) {
int torque_driver_new = (((to_push->RDHR >> 16) & 0x7) << 8) | ((to_push->RDHR >> 24) & 0xFF);
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);
@ -44,14 +44,14 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
if ((addr == 0x1F1) && (bus_number == 0)) {
//Bit 5 should be ignition "on"
//Backup plan is Bit 2 (accessory power)
bool ign = ((to_push->RDLR) & 0x20) != 0;
bool ign = (GET_BYTE(to_push, 0) & 0x20) != 0;
gm_ignition_started = ign;
}
// sample speed, really only care if car is moving or not
// rear left wheel speed
if (addr == 842) {
gm_speed = to_push->RDLR & 0xFFFF;
gm_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1);
}
// Check if ASCM or LKA camera are online
@ -65,7 +65,7 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// ACC steering wheel buttons
if (addr == 481) {
int button = (to_push->RDHR >> 12) & 0x7;
int button = (GET_BYTE(to_push, 5) & 0x70) >> 4;
switch (button) {
case 2: // resume
case 3: // set
@ -82,13 +82,13 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of brake press or on brake press when
// speed > 0
if (addr == 241) {
int brake = (to_push->RDLR & 0xFF00) >> 8;
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_speed)) {
if (brake && (!gm_brake_prev || gm_moving)) {
controls_allowed = 0;
}
gm_brake_prev = brake;
@ -96,7 +96,7 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of gas press
if (addr == 417) {
int gas = to_push->RDHR & 0xFF0000;
int gas = GET_BYTE(to_push, 6);
if (gas && !gm_gas_prev && long_controls_allowed) {
controls_allowed = 0;
}
@ -105,7 +105,7 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on regen paddle
if (addr == 189) {
bool regen = to_push->RDLR & 0x20;
bool regen = GET_BYTE(to_push, 0) & 0x20;
if (regen) {
controls_allowed = 0;
}
@ -129,15 +129,14 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *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 = gm_gas_prev || (gm_brake_prev && gm_speed);
int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_moving);
bool current_controls_allowed = controls_allowed && !pedal_pressed;
int addr = GET_ADDR(to_send);
// BRAKE: safety check
if (addr == 789) {
uint32_t rdlr = to_send->RDLR;
int brake = ((rdlr & 0xFU) << 8) + ((rdlr & 0xFF00U) >> 8);
int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1);
brake = (0x1000 - brake) & 0xFFF;
if (!current_controls_allowed || !long_controls_allowed) {
if (brake != 0) {
@ -151,8 +150,7 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// LKA STEER: safety check
if (addr == 384) {
uint32_t rdlr = to_send->RDLR;
int desired_torque = ((rdlr & 0x7U) << 8) + ((rdlr & 0xFF00U) >> 8);
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);
@ -205,12 +203,11 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// GAS/REGEN: safety check
if (addr == 715) {
uint32_t rdlr = to_send->RDLR;
int gas_regen = ((rdlr & 0x7F0000U) >> 11) + ((rdlr & 0xF8000000U) >> 27);
int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3);
// Disabled message is !engaed with gas
// value that corresponds to max regen.
if (!current_controls_allowed || !long_controls_allowed) {
bool apply = (rdlr & 1U) != 0U;
bool apply = GET_BYTE(to_send, 0) & 1U;
if (apply || (gas_regen != GM_MAX_REGEN)) {
tx = 0;
}

View File

@ -13,7 +13,7 @@ static int gm_ascm_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
// 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)) {
int supercruise_on = (to_fwd->RDHR >> 4) & 0x1; // bit 36
bool supercruise_on = (GET_BYTE(to_fwd, 4) & 0x10) != 0; // bit 36
if (!supercruise_on) {
bus_fwd = -1;
}

View File

@ -10,7 +10,7 @@
const int HONDA_GAS_INTERCEPTOR_THRESHOLD = 328; // ratio between offset and gain from dbc file
int honda_brake_prev = 0;
int honda_gas_prev = 0;
int honda_ego_speed = 0;
bool honda_moving = false;
bool honda_bosch_hardware = false;
bool honda_alt_brake_msg = false;
@ -22,13 +22,13 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// sample speed
if (addr == 0x158) {
// first 2 bytes
honda_ego_speed = to_push->RDLR & 0xFFFF;
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 = (to_push->RDLR & 0xE0) >> 5;
int button = (GET_BYTE(to_push, 0) & 0xE0) >> 5;
switch (button) {
case 2: // cancel
controls_allowed = 0;
@ -48,14 +48,11 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// in these cases, this is used instead.
// most hondas: 0x17C bit 53
// accord, crv: 0x1BE bit 4
#define IS_USER_BRAKE_MSG(addr) (!honda_alt_brake_msg ? ((addr) == 0x17C) : ((addr) == 0x1BE))
#define USER_BRAKE_VALUE(to_push) (!honda_alt_brake_msg ? ((to_push)->RDHR & 0x200000) : ((to_push)->RDLR & 0x10))
// exit controls on rising edge of brake press or on brake press when
// speed > 0
bool is_user_brake_msg = IS_USER_BRAKE_MSG(addr); // needed to enforce type
// 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) {
int brake = USER_BRAKE_VALUE(to_push);
if (brake && (!(honda_brake_prev) || honda_ego_speed)) {
int brake = honda_alt_brake_msg ? (GET_BYTE((to_push), 0) & 0x10) : (GET_BYTE((to_push), 6) & 0x20);
if (brake && (!(honda_brake_prev) || honda_moving)) {
controls_allowed = 0;
}
honda_brake_prev = brake;
@ -65,7 +62,7 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// 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 = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8);
int gas_interceptor = GET_INTERCEPTOR(to_push);
if ((gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD) &&
(gas_interceptor_prev <= HONDA_GAS_INTERCEPTOR_THRESHOLD) &&
long_controls_allowed) {
@ -77,7 +74,7 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of gas press if no interceptor
if (!gas_interceptor_detected) {
if (addr == 0x17C) {
int gas = to_push->RDLR & 0xFF;
int gas = GET_BYTE(to_push, 0);
if (gas && !(honda_gas_prev) && long_controls_allowed) {
controls_allowed = 0;
}
@ -101,17 +98,18 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *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 = honda_gas_prev || (gas_interceptor_prev > HONDA_GAS_INTERCEPTOR_THRESHOLD) ||
(honda_brake_prev && honda_ego_speed);
(honda_brake_prev && honda_moving);
bool current_controls_allowed = controls_allowed && !(pedal_pressed);
// BRAKE: safety check
if (addr == 0x1FA) {
int brake = (GET_BYTE(to_send, 0) << 2) + (GET_BYTE(to_send, 1) & 0x3);
if (!current_controls_allowed || !long_controls_allowed) {
if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) {
if (brake != 0) {
tx = 0;
}
}
if ((to_send->RDLR & 0xFFFFFF3F) != to_send->RDLR) {
if (brake > 255) {
tx = 0;
}
}
@ -119,7 +117,8 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// STEER: safety check
if ((addr == 0xE4) || (addr == 0x194)) {
if (!current_controls_allowed) {
if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) {
bool steer_applied = GET_BYTE(to_send, 0) | GET_BYTE(to_send, 1);
if (steer_applied) {
tx = 0;
}
}
@ -128,7 +127,7 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// GAS: safety check
if (addr == 0x200) {
if (!current_controls_allowed || !long_controls_allowed) {
if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) {
if (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)) {
tx = 0;
}
}
@ -139,7 +138,7 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// This avoids unintended engagements while still allowing resume spam
if ((addr == 0x296) && honda_bosch_hardware &&
!current_controls_allowed && (bus == 0)) {
if (((to_send->RDLR >> 5) & 0x7) != 2) {
if (((GET_BYTE(to_send, 0) >> 5) & 0x7) != 2) {
tx = 0;
}
}

View File

@ -20,7 +20,7 @@ static void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
int addr = GET_ADDR(to_push);
if (addr == 897) {
int torque_driver_new = ((to_push->RDLR >> 11) & 0xfff) - 2048;
int torque_driver_new = ((GET_BYTES_04(to_push) >> 11) & 0xfff) - 2048;
// update array of samples
update_sample(&hyundai_torque_driver, torque_driver_new);
}
@ -39,7 +39,7 @@ static void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// enter controls on rising edge of ACC, exit controls on ACC off
if (addr == 1057) {
// 2 bits: 13-14
int cruise_engaged = (to_push->RDLR >> 13) & 0x3;
int cruise_engaged = (GET_BYTES_04(to_push) >> 13) & 0x3;
if (cruise_engaged && !hyundai_cruise_engaged_last) {
controls_allowed = 1;
}
@ -67,7 +67,7 @@ static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// LKA STEER: safety check
if (addr == 832) {
int desired_torque = ((to_send->RDLR >> 16) & 0x7ff) - 1024;
int desired_torque = ((GET_BYTES_04(to_send) >> 16) & 0x7ff) - 1024;
uint32_t ts = TIM2->CNT;
bool violation = 0;
@ -117,7 +117,7 @@ static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// This avoids unintended engagements while still allowing resume spam
// TODO: fix bug preventing the button msg to be fwd'd on bus 2
//if ((addr == 1265) && !controls_allowed && (bus == 0) {
// if ((to_send->RDLR & 0x7) != 4) {
// if ((GET_BYTES_04(to_send) & 0x7) != 4) {
// tx = 0;
// }
//}

View File

@ -20,7 +20,7 @@ static void subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
int addr = GET_ADDR(to_push);
if ((addr == 0x119) && (bus == 0)){
int torque_driver_new = ((to_push->RDLR >> 16) & 0x7FF);
int torque_driver_new = ((GET_BYTES_04(to_push) >> 16) & 0x7FF);
torque_driver_new = to_signed(torque_driver_new, 11);
// update array of samples
update_sample(&subaru_torque_driver, torque_driver_new);
@ -28,7 +28,7 @@ static void subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// enter controls on rising edge of ACC, exit controls on ACC off
if ((addr == 0x240) && (bus == 0)) {
int cruise_engaged = (to_push->RDHR >> 9) & 1;
int cruise_engaged = GET_BYTE(to_push, 5) & 2;
if (cruise_engaged && !subaru_cruise_engaged_last) {
controls_allowed = 1;
}
@ -45,7 +45,7 @@ static int subaru_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// steer cmd checks
if (addr == 0x122) {
int desired_torque = ((to_send->RDLR >> 16) & 0x1FFF);
int desired_torque = ((GET_BYTES_04(to_send) >> 16) & 0x1FFF);
bool violation = 0;
uint32_t ts = TIM2->CNT;
desired_torque = to_signed(desired_torque, 13);

View File

@ -55,7 +55,7 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
if (addr == 0x45) {
// 6 bits starting at position 0
int lever_position = (to_push->RDLR & 0x3F);
int lever_position = GET_BYTE(to_push, 0) & 0x3F;
if (lever_position == 2) { // pull forward
// activate openpilot
controls_allowed = 1;
@ -69,7 +69,7 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// Detect drive rail on (ignition) (start recording)
if (addr == 0x348) {
// GTW_status
int drive_rail_on = (to_push->RDLR & 0x0001);
int drive_rail_on = GET_BYTE(to_push, 0) & 0x1;
tesla_ignition_started = drive_rail_on == 1;
}
@ -77,12 +77,12 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// DI_torque2::DI_brakePedal 0x118
if (addr == 0x118) {
// 1 bit at position 16
if ((((to_push->RDLR & 0x8000)) >> 15) == 1) {
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 = ((((((to_push->RDLR >> 24) & 0xF) << 8) + ((to_push->RDLR >> 16) & 0xFF)) * 0.05) - 25) * 1.609 / 3.6;
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;
}
@ -92,7 +92,7 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// EPAS_sysStatus::EPAS_eacStatus 0x370
if (addr == 0x370) {
// if EPAS_eacStatus is not 1 or 2, disable control
eac_status = ((to_push->RDHR >> 21)) & 0x7;
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)) {
@ -102,7 +102,7 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
}
//get latest steering wheel angle
if (addr == 0x00E) {
float angle_meas_now = (int)(((((to_push->RDLR & 0x3F) << 8) + ((to_push->RDLR >> 8) & 0xFF)) * 0.1) - 819.2);
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);
@ -146,10 +146,10 @@ static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// do not transmit CAN message if steering angle too high
// DAS_steeringControl::DAS_steeringAngleRequest
if (addr == 0x488) {
float angle_raw = ((to_send->RDLR & 0x7F) << 8) + ((to_send->RDLR & 0xFF00) >> 8);
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 = (to_send->RDLR & 0x400000) >> 22;
int st_enabled = GET_BYTE(to_send, 2) & 0x40;
if (st_enabled == 0) {
//steering is not enabled, do not check angles and do send
@ -204,10 +204,10 @@ static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
bus_fwd = 2; // Custom EPAS bus
}
if (addr == 0x101) {
to_fwd->RDLR = to_fwd->RDLR | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque)
uint32_t checksum = (((to_fwd->RDLR & 0xFF00) >> 8) + (to_fwd->RDLR & 0xFF) + 2) & 0xFF;
to_fwd->RDLR = to_fwd->RDLR & 0xFFFF;
to_fwd->RDLR = to_fwd->RDLR + (checksum << 16);
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) {

View File

@ -39,7 +39,7 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// get eps motor torque (0.66 factor in dbc)
if (addr == 0x260) {
int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF));
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
@ -56,7 +56,7 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// enter controls on rising edge of ACC, exit controls on ACC off
if (addr == 0x1D2) {
// 5th bit is CRUISE_ACTIVE
int cruise_engaged = to_push->RDLR & 0x20;
int cruise_engaged = GET_BYTE(to_push, 0) & 0x20;
if (!cruise_engaged) {
controls_allowed = 0;
}
@ -69,7 +69,7 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of interceptor gas press
if (addr == 0x201) {
gas_interceptor_detected = 1;
int gas_interceptor = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8);
int gas_interceptor = GET_INTERCEPTOR(to_push);
if ((gas_interceptor > TOYOTA_GAS_INTERCEPTOR_THRESHOLD) &&
(gas_interceptor_prev <= TOYOTA_GAS_INTERCEPTOR_THRESHOLD) &&
long_controls_allowed) {
@ -80,7 +80,7 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// exit controls on rising edge of gas press
if (addr == 0x2C1) {
int gas = (to_push->RDHR >> 16) & 0xFF;
int gas = GET_BYTE(to_push, 6) & 0xFF;
if ((gas > 0) && (toyota_gas_prev == 0) && !gas_interceptor_detected && long_controls_allowed) {
controls_allowed = 0;
}
@ -115,7 +115,7 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// GAS PEDAL: safety check
if (addr == 0x200) {
if (!controls_allowed || !long_controls_allowed) {
if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) {
if (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)) {
tx = 0;
}
}
@ -123,7 +123,7 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// ACCEL: safety check on byte 1-2
if (addr == 0x343) {
int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF);
int desired_accel = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1);
desired_accel = to_signed(desired_accel, 16);
if (!controls_allowed || !long_controls_allowed) {
if (desired_accel != 0) {
@ -138,7 +138,7 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// STEER: safety check on bytes 2-3
if (addr == 0x2E4) {
int desired_torque = (to_send->RDLR & 0xFF00) | ((to_send->RDLR >> 16) & 0xFF);
int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2);
desired_torque = to_signed(desired_torque, 16);
bool violation = 0;

View File

@ -39,7 +39,7 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
if (addr == 0x260) {
// get driver steering torque
int16_t torque_driver_new = (((to_push->RDLR) & 0xFF00) | ((to_push->RDLR >> 16) & 0xFF));
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);
@ -47,7 +47,7 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// get steer angle
if (addr == 0x25) {
int angle_meas_new = ((to_push->RDLR & 0xf) << 8) + ((to_push->RDLR & 0xff00) >> 8);
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);
@ -81,12 +81,12 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// get speed
if (addr == 0xb4) {
speed = ((float) (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF))) * 0.01 / 3.6;
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 = (to_push->RDLR & 0xf);
ipas_state = GET_BYTE(to_push, 0) & 0xf;
}
// exit controls on high steering override
@ -111,8 +111,8 @@ static int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
if ((addr == 0x266) || (addr == 0x167)) {
angle_control = 1; // we are in angle control mode
int desired_angle = ((to_send->RDLR & 0xf) << 8) + ((to_send->RDLR & 0xff00) >> 8);
int ipas_state_cmd = ((to_send->RDLR & 0xff) >> 4);
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);

View File

@ -1,7 +1,3 @@
#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))
// sample struct that keeps 3 samples in memory
struct sample_t {
int values[6];
@ -54,3 +50,6 @@ int gas_interceptor_prev = 0;
// This is set by USB command 0xdf
bool long_controls_allowed = 1;
// 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)

View File

@ -92,16 +92,26 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
return resp_len;
}
int usb_cb_ep1_in(uint8_t *usbdata, int len, bool hardwired) { return 0; }
void usb_cb_ep3_out(uint8_t *usbdata, int len, bool hardwired) { }
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 usb_cb_enumeration_complete(void) {
puts("USB enumeration complete\n");
is_enumerated = 1;
}
void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {
void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) {
UNUSED(hardwired);
set_led(LED_RED, 0);
for (int i = 0; i < len/4; i++) {
// program byte 1
@ -118,6 +128,7 @@ void usb_cb_ep2_out(uint8_t *usbdata, int len, bool hardwired) {
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
UNUSED(len);
int resp_len = 0;
switch (data[0]) {
case 0:
@ -140,7 +151,7 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
#define CAN_BL_INPUT 0x1
#define CAN_BL_OUTPUT 0x2
void CAN1_TX_IRQHandler() {
void CAN1_TX_IRQHandler(void) {
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
@ -167,12 +178,13 @@ void bl_can_send(uint8_t *odat) {
CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1;
}
void CAN1_RX0_IRQHandler() {
void CAN1_RX0_IRQHandler(void) {
while (CAN->RF0R & CAN_RF0R_FMP0) {
if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) {
uint8_t dat[8];
((uint32_t*)dat)[0] = CAN->sFIFOMailBox[0].RDLR;
((uint32_t*)dat)[1] = CAN->sFIFOMailBox[0].RDHR;
for (int i = 0; i < 8; i++) {
dat[0] = GET_BYTE(&CAN->sFIFOMailBox[0], i);
}
uint8_t odat[8];
uint8_t type = dat[0] & 0xF0;
if (type == 0x30) {
@ -241,13 +253,13 @@ void CAN1_RX0_IRQHandler() {
}
}
void CAN1_SCE_IRQHandler() {
void CAN1_SCE_IRQHandler(void) {
llcan_clear_send(CAN);
}
#endif
void soft_flasher_start() {
void soft_flasher_start(void) {
puts("\n\n\n************************ FLASHER START ************************\n");
enter_bootloader_mode = 0;

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V2.1.2
* @date 29-June-2016
* @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain.
* @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain.
* This module performs:
* - Set the initial SP
* - Set the initial PC == Reset_Handler,
@ -42,7 +42,7 @@
*
******************************************************************************
*/
.syntax unified
.cpu cortex-m3
.thumb
@ -50,10 +50,10 @@
.global g_pfnVectors
.global Default_Handler
/* start address for the initialization values of the .data section.
/* 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 */
/* start address for the .data section. defined in linker script */
.word _sdata
/* end address for the .data section. defined in linker script */
.word _edata
@ -67,7 +67,7 @@ defined in linker script */
* @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.
* supplied main() routine is called.
* @param None
* @retval : None
*/
@ -75,7 +75,7 @@ defined in linker script */
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl __initialize_hardware_early
@ -88,7 +88,7 @@ CopyDataInit:
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
@ -101,7 +101,7 @@ LoopCopyDataInit:
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
@ -113,15 +113,15 @@ LoopFillZerobss:
/*bl __libc_init_array*/
/* Call the application's entry point.*/
bl main
bx lr
bx lr
.size Reset_Handler, .-Reset_Handler
/**
* @brief This is the code that gets called when the processor receives an
* @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
* @param None
* @retval None
*/
.section .text.Default_Handler,"ax",%progbits
Default_Handler:
@ -133,14 +133,14 @@ Infinite_Loop:
* 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
@ -159,7 +159,7 @@ g_pfnVectors:
.word 0
.word PendSV_Handler
.word SysTick_Handler
/* External Interrupts */
.word WWDG_IRQHandler /* Window WatchDog */
.word PVD_IRQHandler /* PVD through EXTI Line detection */
@ -248,7 +248,7 @@ g_pfnVectors:
* 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
@ -302,7 +302,7 @@ g_pfnVectors:
.thumb_set EXTI1_IRQHandler,Default_Handler
.weak EXTI2_IRQHandler
.thumb_set EXTI2_IRQHandler,Default_Handler
.thumb_set EXTI2_IRQHandler,Default_Handler
.weak EXTI3_IRQHandler
.thumb_set EXTI3_IRQHandler,Default_Handler
@ -320,7 +320,7 @@ g_pfnVectors:
.thumb_set DMA1_Stream2_IRQHandler,Default_Handler
.weak DMA1_Stream3_IRQHandler
.thumb_set DMA1_Stream3_IRQHandler,Default_Handler
.thumb_set DMA1_Stream3_IRQHandler,Default_Handler
.weak DMA1_Stream4_IRQHandler
.thumb_set DMA1_Stream4_IRQHandler,Default_Handler
@ -432,7 +432,7 @@ g_pfnVectors:
.weak SPI3_IRQHandler
.thumb_set SPI3_IRQHandler,Default_Handler
.weak UART4_IRQHandler
.thumb_set UART4_IRQHandler,Default_Handler

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V2.6.0
* @date 04-November-2016
* @brief STM32F413xx Devices vector table for GCC based toolchains.
* @brief STM32F413xx Devices vector table for GCC based toolchains.
* This module performs:
* - Set the initial SP
* - Set the initial PC == Reset_Handler,
@ -42,7 +42,7 @@
*
******************************************************************************
*/
.syntax unified
.cpu cortex-m4
.fpu softvfp
@ -51,7 +51,7 @@
.global g_pfnVectors
.global Default_Handler
/* start address for the initialization values of the .data section.
/* 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 */
@ -68,7 +68,7 @@ defined in linker script */
* @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.
* supplied main() routine is called.
* @param None
* @retval : None
*/
@ -76,7 +76,7 @@ defined in linker script */
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl __initialize_hardware_early
@ -89,7 +89,7 @@ CopyDataInit:
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
@ -102,7 +102,7 @@ LoopCopyDataInit:
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
@ -114,15 +114,15 @@ LoopFillZerobss:
/* bl __libc_init_array */
/* Call the application's entry point.*/
bl main
bx lr
bx lr
.size Reset_Handler, .-Reset_Handler
/**
* @brief This is the code that gets called when the processor receives an
* @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
* @param None
* @retval None
*/
.section .text.Default_Handler,"ax",%progbits
Default_Handler:
@ -134,12 +134,12 @@ Infinite_Loop:
* 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
@ -261,11 +261,11 @@ g_pfnVectors:
.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
* 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.
*
*******************************************************************************/
@ -277,7 +277,7 @@ g_pfnVectors:
.weak MemManage_Handler
.thumb_set MemManage_Handler,Default_Handler
.weak BusFault_Handler
.thumb_set BusFault_Handler,Default_Handler
@ -321,7 +321,7 @@ g_pfnVectors:
.thumb_set EXTI1_IRQHandler,Default_Handler
.weak EXTI2_IRQHandler
.thumb_set EXTI2_IRQHandler,Default_Handler
.thumb_set EXTI2_IRQHandler,Default_Handler
.weak EXTI3_IRQHandler
.thumb_set EXTI3_IRQHandler,Default_Handler
@ -439,9 +439,9 @@ g_pfnVectors:
.weak DMA1_Stream7_IRQHandler
.thumb_set DMA1_Stream7_IRQHandler,Default_Handler
.weak FSMC_IRQHandler
.thumb_set FSMC_IRQHandler,Default_Handler
.thumb_set FSMC_IRQHandler,Default_Handler
.weak SDIO_IRQHandler
.thumb_set SDIO_IRQHandler,Default_Handler
@ -451,12 +451,12 @@ g_pfnVectors:
.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
.thumb_set UART5_IRQHandler,Default_Handler
.weak TIM6_DAC_IRQHandler
.thumb_set TIM6_DAC_IRQHandler,Default_Handler
@ -517,7 +517,7 @@ g_pfnVectors:
.weak I2C3_ER_IRQHandler
.thumb_set I2C3_ER_IRQHandler,Default_Handler
.weak CAN3_TX_IRQHandler
.thumb_set CAN3_TX_IRQHandler,Default_Handler
@ -528,26 +528,26 @@ g_pfnVectors:
.thumb_set CAN3_RX1_IRQHandler,Default_Handler
.weak CAN3_SCE_IRQHandler
.thumb_set CAN3_SCE_IRQHandler,Default_Handler
.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
.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
@ -555,7 +555,7 @@ g_pfnVectors:
.thumb_set UART9_IRQHandler,Default_Handler
.weak UART10_IRQHandler
.thumb_set UART10_IRQHandler,Default_Handler
.thumb_set UART10_IRQHandler,Default_Handler
.weak QUADSPI_IRQHandler
.thumb_set QUADSPI_IRQHandler,Default_Handler
@ -565,7 +565,7 @@ g_pfnVectors:
.weak FMPI2C1_ER_IRQHandler
.thumb_set FMPI2C1_ER_IRQHandler,Default_Handler
.weak LPTIM1_IRQHandler
.thumb_set LPTIM1_IRQHandler,Default_Handler

View File

@ -84,7 +84,7 @@ int ICACHE_FLASH_ATTR usb_cmd(int ep, int len, int request,
return recv[0];
}
void ICACHE_FLASH_ATTR st_flash() {
if (st_firmware != NULL) {
@ -212,14 +212,14 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
} else {
ets_strcat(resp, "\nin INSECURE mode...<a href=\"/secure\">secure it</a>");
}
ets_strcat(resp,"\nSet USB Mode:"
"<button onclick=\"var xhr = new XMLHttpRequest(); xhr.open('GET', 'set_property?usb_mode=0'); xhr.send()\" type='button'>Client</button>"
"<button onclick=\"var xhr = new XMLHttpRequest(); xhr.open('GET', 'set_property?usb_mode=1'); xhr.send()\" type='button'>CDP</button>"
"<button onclick=\"var xhr = new XMLHttpRequest(); xhr.open('GET', 'set_property?usb_mode=2'); xhr.send()\" type='button'>DCP</button>\n");
ets_strcat(resp, pagefooter);
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
} else if (memcmp(data, "GET /secure", 11) == 0 && !wifi_secure_mode) {
@ -235,7 +235,7 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
os_sprintf(resp, "%sUSB Mode set to %02x\n\n", OK_header, mode_value);
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
}
}
} else if (memcmp(data, "PUT /stupdate ", 14) == 0 && wifi_secure_mode) {
os_printf("init st firmware\n");
char *cl = strstr(data, "Content-Length: ");
@ -251,7 +251,7 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
memset(st_firmware, 0, real_content_length);
state = RECEIVING_ST_FIRMWARE;
}
} else if (((memcmp(data, "PUT /espupdate1 ", 16) == 0) ||
(memcmp(data, "PUT /espupdate2 ", 16) == 0)) && wifi_secure_mode) {
// 0x1000 = user1.bin

View File

@ -130,7 +130,7 @@ const uint8_t* SHA_final(SHA_CTX* ctx) {
/* Hack - right shift operator with non const argument requires
* libgcc.a which is missing in EON
* thus expanding for loop from
* thus expanding for loop from
for (i = 0; i < 8; ++i) {
uint8_t tmp = (uint8_t) (cnt >> ((7 - i) * 8));

View File

@ -93,7 +93,7 @@ DWORD PandaJ2534Device::can_process_thread() {
if (count == 0) {
continue;
}
for (int i = 0; i < count; i++) {
auto msg_in = msg_recv[i];
J2534Frame msg_out(msg_in);

View File

@ -3,7 +3,7 @@
// Used by pandaJ2534DLL.rc
// Next default values for new objects
//
//
#ifdef APSTUDIO_INVOKED
#ifndef APSTUDIO_READONLY_SYMBOLS
#define _APS_NEXT_RESOURCE_VALUE 101

View File

@ -10,8 +10,8 @@ First record a few minutes of background CAN messages with all the doors closed
./can_logger.py
mv output.csv background.csv
```
Then run can_logger.py for a few seconds while performing the action you're interested, such as opening and then closing the
front-left door and save it as door-fl-1.csv
Then run can_logger.py for a few seconds while performing the action you're interested, such as opening and then closing the
front-left door and save it as door-fl-1.csv
Repeat the process and save it as door-f1-2.csv to have an easy way to confirm any suspicions.
Now we'll use can_unique.py to look for unique bits:

View File

@ -2,11 +2,11 @@
from panda import Panda
def get_panda_password():
try:
print("Trying to connect to Panda over USB...")
p = Panda()
except AssertionError:
print("USB connection failed")
sys.exit(0)
@ -15,6 +15,6 @@ def get_panda_password():
#print('[%s]' % ', '.join(map(str, wifi)))
print("SSID: " + wifi[0])
print("Password: " + wifi[1])
if __name__ == "__main__":
get_panda_password()

View File

@ -4,14 +4,14 @@ import binascii
from panda import Panda
def tesla_tester():
try:
print("Trying to connect to Panda over USB...")
p = Panda()
except AssertionError:
print("USB connection failed. Trying WiFi...")
try:
p = Panda("WIFI")
except:
@ -21,12 +21,12 @@ def tesla_tester():
body_bus_speed = 125 # Tesla Body busses (B, BF) are 125kbps, rest are 500kbps
body_bus_num = 1 # My TDC to OBD adapter has PT on bus0 BDY on bus1 and CH on bus2
p.set_can_speed_kbps(body_bus_num, body_bus_speed)
# Now set the panda from its default of SAFETY_NOOUTPUT (read only) to SAFETY_ALLOUTPUT
# Careful, as this will let us send any CAN messages we want (which could be very bad!)
print("Setting Panda to output mode...")
p.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
# BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock:
print("Unlocking Tesla...")
p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num)
@ -34,13 +34,13 @@ def tesla_tester():
#Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both)
print("Opening Frunk...")
p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num)
#Back to safety...
print("Disabling output on Panda...")
p.set_safety_mode(Panda.SAFETY_NOOUTPUT)
print("Reading VIN from 0x568. This is painfully slow and can take up to 3 minutes (1 minute per message; 3 messages needed for full VIN)...")
vin = {}
while True:
#Read the VIN

View File

@ -1216,7 +1216,7 @@ def main():
operation_func = globals()[args.operation]
operation_args,_,_,_ = inspect.getargspec(operation_func)
if operation_args[0] == 'esp': # operation function takes an ESPROM connection object
initial_baud = MIN(ESPROM.ESP_ROM_BAUD, args.baud) # don't sync faster than the default baud rate
initial_baud = min(ESPROM.ESP_ROM_BAUD, args.baud) # don't sync faster than the default baud rate
esp = ESPROM(args.port, initial_baud)
esp.connect()
operation_func(esp, args)

View File

@ -89,7 +89,7 @@ def flash_release(path=None, st_serial=None):
# done!
status("6. Success!")
if __name__ == "__main__":
flash_release(*sys.argv[1:])

View File

@ -29,7 +29,7 @@ def recv(panda, cnt, addr, nbus):
def isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr):
msg = recv(panda, 1, addr, bus)[0]
# TODO: handle other subaddr also communicating
# TODO: handle other subaddr also communicating
assert ord(msg[0]) == subaddr
if ord(msg[1])&0xf0 == 0x10:

View File

@ -1,14 +1,21 @@
#!/bin/bash
#!/bin/bash -e
TEST_FILENAME=${TEST_FILENAME:-nosetests.xml}
if [ ! -f "/EON" ]; then
if [ -f "/EON" ]; then
TESTSUITE_NAME="Panda_Test-EON"
else
TESTSUITE_NAME="Panda_Test-DEV"
fi
cd boardesp
make flashall
cd ..
if [ ! -z "${SKIPWIFI}" ] || [ -f "/EON" ]; then
TEST_SCRIPTS=$(ls tests/automated/$1*.py | grep -v wifi)
else
TEST_SCRIPTS=$(ls tests/automated/$1*.py)
fi
IFS=$'\n'
for NAME in $(nmcli --fields NAME con show | grep panda | awk '{$1=$1};1')
do
nmcli connection delete "$NAME"
done
PYTHONPATH="." python $(which nosetests) -v --with-xunit --xunit-file=./$TEST_FILENAME --xunit-testsuite-name=$TESTSUITE_NAME -s tests/automated/$1*.py
PYTHONPATH="." python $(which nosetests) -v --with-xunit --xunit-file=./$TEST_FILENAME --xunit-testsuite-name=$TESTSUITE_NAME -s $TEST_SCRIPTS

View File

@ -34,7 +34,7 @@ def test_udp_doesnt_drop(serial=None):
sys.stdout.flush()
else:
print("UDP WIFI loopback %d messages at speed %d, comp speed is %.2f, percent %.2f" % (msg_count, speed, comp_kbps, saturation_pct))
assert_greater(saturation_pct, 15) #sometimes the wifi can be slow...
assert_greater(saturation_pct, 20) #sometimes the wifi can be slow...
assert_less(saturation_pct, 100)
saturation_pcts.append(saturation_pct)
if len(saturation_pcts) > 0:

View File

@ -1,9 +0,0 @@
FROM ubuntu:16.04
RUN apt-get update && apt-get install -y gcc-arm-none-eabi libnewlib-arm-none-eabi python python-pip gcc g++
RUN pip install pycrypto==2.6.1
COPY . /panda
WORKDIR /panda

View File

@ -1,15 +0,0 @@
#!/bin/bash -e
cd ../../board/
make -f Makefile.strict clean
make -f Makefile.strict bin 2> compiler_output.txt
if [[ -s "compiler_output.txt" ]]
then
echo "Found alerts from the compiler:"
cat compiler_output.txt
exit 1
fi

View File

@ -152,7 +152,7 @@ class ELMCarSimulator():
if len(outmsg) <= 5:
self._lin_send(0x10, obd_header + outmsg)
else:
first_msg_len = MIN(4, len(outmsg)%4) or 4
first_msg_len = min(4, len(outmsg)%4) or 4
self._lin_send(0x10, obd_header + b'\x01' +
b'\x00'*(4-first_msg_len) +
outmsg[:first_msg_len])
@ -229,7 +229,7 @@ class ELMCarSimulator():
outaddr = 0x7E8 if address == 0x7DF or address == 0x7E0 else 0x18DAF110
msgnum = 1
while(self.__can_multipart_data):
datalen = MIN(7, len(self.__can_multipart_data))
datalen = min(7, len(self.__can_multipart_data))
msgpiece = struct.pack("B", 0x20 | msgnum) + self.__can_multipart_data[:datalen]
self._can_send(outaddr, msgpiece)
self.__can_multipart_data = self.__can_multipart_data[7:]
@ -246,7 +246,7 @@ class ELMCarSimulator():
self._can_send(outaddr,
struct.pack("BBB", len(outmsg)+2, 0x40|data[1], pid) + outmsg)
else:
first_msg_len = MIN(3, len(outmsg)%7)
first_msg_len = min(3, len(outmsg)%7)
payload_len = len(outmsg)+3
msgpiece = struct.pack("BBBBB", 0x10 | ((payload_len>>8)&0xF),
payload_len&0xFF,

View File

@ -5,7 +5,7 @@ from panda import Panda
p = Panda()
p.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
# ack any crap on bus
# hack anything on bus
p.set_gmlan(bus=2)
time.sleep(0.1)
while len(p.can_recv()) > 0:

View File

@ -0,0 +1,6 @@
FROM ubuntu:16.04
RUN apt-get update && apt-get install -y make python python-pip
COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt
RUN pip install -r /panda/tests/safety/requirements.txt
COPY . /panda

View File

@ -0,0 +1,201 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "{}"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright {yyyy} {name of copyright owner}
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
http://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.

View File

@ -0,0 +1,451 @@
4r5e
5h1t
5hit
a55
anal
anus
ar5e
arrse
arse
ass
ass-fucker
asses
assfucker
assfukka
asshole
assholes
asswhole
a_s_s
b!tch
b00bs
b17ch
b1tch
ballbag
balls
ballsack
bastard
beastial
beastiality
bellend
bestial
bestiality
bi+ch
biatch
bitch
bitcher
bitchers
bitches
bitchin
bitching
bloody
blow job
blowjob
blowjobs
boiolas
bollock
bollok
boner
boob
boobs
booobs
boooobs
booooobs
booooooobs
breasts
buceta
bugger
bum
bunny fucker
bullshit
butt
butthole
buttmuch
buttplug
c0ck
c0cksucker
carpet muncher
cawk
chink
cipa
cl1t
clit
clitoris
clits
cnut
cock
cock-sucker
cockface
cockhead
cockmunch
cockmuncher
cocks
cocksuck
cocksucked
cocksucker
cocksucking
cocksucks
cocksuka
cocksukka
cok
cokmuncher
coksucka
coon
cox
crap
cum
cummer
cumming
cums
cumshot
cunilingus
cunillingus
cunnilingus
cunt
cuntlick
cuntlicker
cuntlicking
cunts
cyalis
cyberfuc
cyberfuck
cyberfucked
cyberfucker
cyberfuckers
cyberfucking
d1ck
damn
dick
dickhead
dildo
dildos
dink
dinks
dirsa
dlck
dog-fucker
doggin
dogging
donkeyribber
doosh
duche
dyke
ejaculate
ejaculated
ejaculates
ejaculating
ejaculatings
ejaculation
ejakulate
f u c k
f u c k e r
f4nny
fag
fagging
faggitt
faggot
faggs
fagot
fagots
fags
fanny
fannyflaps
fannyfucker
fanyy
fatass
fcuk
fcuker
fcuking
feck
fecker
felching
fellate
fellatio
fingerfuck
fingerfucked
fingerfucker
fingerfuckers
fingerfucking
fingerfucks
fistfuck
fistfucked
fistfucker
fistfuckers
fistfucking
fistfuckings
fistfucks
flange
fook
fooker
fuck
fucka
fucked
fucker
fuckers
fuckhead
fuckheads
fuckin
fucking
fuckings
fuckingshitmotherfucker
fuckme
fucks
fuckwhit
fuckwit
fudge packer
fudgepacker
fuk
fuker
fukker
fukkin
fuks
fukwhit
fukwit
fux
fux0r
f_u_c_k
gangbang
gangbanged
gangbangs
gaylord
gaysex
goatse
God
god-dam
god-damned
goddamn
goddamned
hardcoresex
hell
heshe
hoar
hoare
hoer
homo
hore
horniest
horny
hotsex
jack-off
jackoff
jap
jerk-off
jism
jiz
jizm
jizz
kawk
knob
knobead
knobed
knobend
knobhead
knobjocky
knobjokey
kock
kondum
kondums
kum
kummer
kumming
kums
kunilingus
l3i+ch
l3itch
labia
lmfao
lust
lusting
m0f0
m0fo
m45terbate
ma5terb8
ma5terbate
masochist
master-bate
masterb8
masterbat*
masterbat3
masterbate
masterbation
masterbations
masturbate
mo-fo
mof0
mofo
mothafuck
mothafucka
mothafuckas
mothafuckaz
mothafucked
mothafucker
mothafuckers
mothafuckin
mothafucking
mothafuckings
mothafucks
mother fucker
motherfuck
motherfucked
motherfucker
motherfuckers
motherfuckin
motherfucking
motherfuckings
motherfuckka
motherfucks
muff
mutha
muthafecker
muthafuckker
muther
mutherfucker
n1gga
n1gger
nazi
nigg3r
nigg4h
nigga
niggah
niggas
niggaz
nigger
niggers
nob
nob jokey
nobhead
nobjocky
nobjokey
numbnuts
nutsack
orgasim
orgasims
orgasm
orgasms
p0rn
pawn
pecker
penis
penisfucker
phonesex
phuck
phuk
phuked
phuking
phukked
phukking
phuks
phuq
pigfucker
pimpis
piss
pissed
pisser
pissers
pisses
pissflaps
pissin
pissing
pissoff
poop
porn
porno
pornography
pornos
prick
pricks
pron
pube
pusse
pussi
pussies
pussy
pussys
rectum
retard
rimjaw
rimming
s hit
s.o.b.
sadist
schlong
screwing
scroat
scrote
scrotum
semen
sex
sh!+
sh!t
sh1t
shag
shagger
shaggin
shagging
shemale
shi+
shit
shitdick
shite
shited
shitey
shitfuck
shitfull
shithead
shiting
shitings
shits
shitted
shitter
shitters
shitting
shittings
shitty
skank
slut
sluts
smegma
smut
snatch
son-of-a-bitch
spac
spunk
s_h_i_t
t1tt1e5
t1tties
teets
teez
testical
testicle
tit
titfuck
tits
titt
tittie5
tittiefucker
titties
tittyfuck
tittywank
titwank
tosser
turd
tw4t
twat
twathead
twatty
twunt
twunter
v14gra
v1gra
vagina
viagra
vulva
w00se
wang
wank
wanker
wanky
whoar
whore
willies
willy
xrated

View File

@ -0,0 +1,28 @@
#!/usr/bin/env python
import subprocess
import sys
checked_ext = ["h", "c", "py", "pyx", "cpp", "hpp", "md", "mk"]
if __name__ == "__main__":
with open("list.txt", 'r') as handle:
suffix_cmd = " "
for i in checked_ext:
suffix_cmd += "--include \*." + i + " "
found_bad_language = False
for line in handle:
line = line.rstrip('\n').rstrip(" ")
try:
cmd = "cd ../../; grep -R -i -w " + suffix_cmd + " '" + line + "'"
res = subprocess.check_output(cmd, shell=True, stderr=subprocess.STDOUT)
print res
found_bad_language = True
except subprocess.CalledProcessError as e:
pass
if found_bad_language:
sys.exit("Failed: found bad language")
else:
print "Success"

View File

@ -0,0 +1,8 @@
# Advisory: union types can be used
misra.19.2
# FIXME: add it back when fixed in cppcheck. Macro identifiers are unique but it false triggers on defines in #ifdef..#else conditions
misra.5.4
# Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well
misra.11.4
# Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well
misra.11.5

View File

@ -1,24 +1,53 @@
#!/bin/bash -e
mkdir /tmp/misra || true
git clone https://github.com/danmar/cppcheck.git || true
cd cppcheck
git fetch
git checkout 44d6066c6fad32e2b0332b3f2b24bd340febaef8
git checkout 862c4ef87b109ae86c2d5f12769b7c8d199f35c5
make -j4
cd ../../../
# whole panda code
tests/misra/cppcheck/cppcheck --dump --enable=all --inline-suppr board/main.c 2>/tmp/misra/cppcheck_output.txt || true
python tests/misra/cppcheck/addons/misra.py board/main.c.dump 2>/tmp/misra/misra_output.txt || true
# violations in safety files
(cat /tmp/misra/misra_output.txt | grep safety) > /tmp/misra/misra_safety_output.txt || true
(cat /tmp/misra/cppcheck_output.txt | grep safety) > /tmp/misra/cppcheck_safety_output.txt || true
printf "\nPANDA CODE\n"
tests/misra/cppcheck/cppcheck -DPANDA -UPEDAL -DCAN3 -DUID_BASE -DEON \
--suppressions-list=tests/misra/suppressions.txt \
--dump --enable=all --inline-suppr --force \
board/main.c 2>/tmp/misra/cppcheck_output.txt
if [[ -s "/tmp/misra/misra_safety_output.txt" ]] || [[ -s "/tmp/misra/cppcheck_safety_output.txt" ]]
python tests/misra/cppcheck/addons/misra.py board/main.c.dump 2> /tmp/misra/misra_output.txt || true
# strip (information) lines
cppcheck_output=$( cat /tmp/misra/cppcheck_output.txt | grep -v "(information) " ) || true
misra_output=$( cat /tmp/misra/misra_output.txt | grep -v "(information) " ) || true
printf "\nPEDAL CODE\n"
tests/misra/cppcheck/cppcheck -UPANDA -DPEDAL -UCAN3 \
--suppressions-list=tests/misra/suppressions.txt \
-I board/ --dump --enable=all --inline-suppr --force \
board/pedal/main.c 2>/tmp/misra/cppcheck_pedal_output.txt
python tests/misra/cppcheck/addons/misra.py board/pedal/main.c.dump 2> /tmp/misra/misra_pedal_output.txt || true
# strip (information) lines
cppcheck_pedal_output=$( cat /tmp/misra/cppcheck_pedal_output.txt | grep -v "(information) " ) || true
misra_pedal_output=$( cat /tmp/misra/misra_pedal_output.txt | grep -v "(information) " ) || true
if [[ -n "$misra_output" ]] || [[ -n "$cppcheck_output" ]]
then
echo "Found Misra violations in the safety code:"
cat /tmp/misra/misra_safety_output.txt
cat /tmp/misra/cppcheck_safety_output.txt
echo "Failed! found Misra violations in panda code:"
echo "$misra_output"
echo "$cppcheck_output"
exit 1
fi
if [[ -n "$misra_pedal_output" ]] || [[ -n "$cppcheck_pedal_output" ]]
then
echo "Failed! found Misra violations in pedal code:"
echo "$misra_pedal_output"
echo "$cppcheck_pedal_output"
exit 1
fi
echo "Success"

View File

@ -55,7 +55,7 @@ void set_toyota_camera_forwarded(int t);
void set_toyota_rt_torque_last(int t);
void init_tests_honda(void);
int get_honda_ego_speed(void);
bool get_honda_moving(void);
int get_honda_brake_prev(void);
int get_honda_gas_prev(void);
void set_honda_alt_brake_msg(bool);

View File

@ -32,6 +32,7 @@ struct sample_t subaru_torque_driver;
TIM_TypeDef timer;
TIM_TypeDef *TIM2 = &timer;
// from config.h
#define MIN(a,b) \
({ __typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
@ -42,6 +43,14 @@ TIM_TypeDef *TIM2 = &timer;
__typeof__ (b) _b = (b); \
_a > _b ? _a : _b; })
// from llcan.h
#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)
#define UNUSED(x) (void)(x)
#define PANDA
@ -199,8 +208,8 @@ void set_subaru_desired_torque_last(int t){
subaru_desired_torque_last = t;
}
int get_honda_ego_speed(void){
return honda_ego_speed;
bool get_honda_moving(void){
return honda_moving;
}
int get_honda_brake_prev(void){
@ -274,7 +283,7 @@ void init_tests_subaru(void){
}
void init_tests_honda(void){
honda_ego_speed = 0;
honda_moving = false;
honda_brake_prev = 0;
honda_gas_prev = 0;
}

View File

@ -5,6 +5,8 @@ import libpandasafety_py
MAX_BRAKE = 255
INTERCEPTOR_THRESHOLD = 328
class TestHondaSafety(unittest.TestCase):
@classmethod
def setUp(cls):
@ -66,7 +68,9 @@ class TestHondaSafety(unittest.TestCase):
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
to_send[0].RIR = addr << 21
to_send[0].RDTR = 6
to_send[0].RDLR = ((gas & 0xff) << 8) | ((gas & 0xff00) >> 8)
gas2 = gas * 2
to_send[0].RDLR = ((gas & 0xff) << 8) | ((gas & 0xff00) >> 8) | \
((gas2 & 0xff) << 24) | ((gas2 & 0xff00) << 8)
return to_send
@ -99,9 +103,9 @@ class TestHondaSafety(unittest.TestCase):
self.assertFalse(self.safety.get_controls_allowed())
def test_sample_speed(self):
self.assertEqual(0, self.safety.get_honda_ego_speed())
self.assertEqual(0, self.safety.get_honda_moving())
self.safety.safety_rx_hook(self._speed_msg(100))
self.assertEqual(100, self.safety.get_honda_ego_speed())
self.assertEqual(1, self.safety.get_honda_moving())
def test_prev_brake(self):
self.assertFalse(self.safety.get_honda_brake_prev())
@ -176,16 +180,15 @@ class TestHondaSafety(unittest.TestCase):
def test_disengage_on_gas_interceptor(self):
for long_controls_allowed in [0, 1]:
self.safety.set_long_controls_allowed(long_controls_allowed)
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_controls_allowed(1)
self.safety.safety_rx_hook(self._send_interceptor_msg(0x1000, 0x201))
if long_controls_allowed:
self.assertFalse(self.safety.get_controls_allowed())
else:
self.assertTrue(self.safety.get_controls_allowed())
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_gas_interceptor_detected(False)
for g in range(0, 0x1000):
self.safety.set_long_controls_allowed(long_controls_allowed)
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_controls_allowed(True)
self.safety.safety_rx_hook(self._send_interceptor_msg(g, 0x201))
remain_enabled = (not long_controls_allowed or g <= INTERCEPTOR_THRESHOLD)
self.assertEqual(remain_enabled, self.safety.get_controls_allowed())
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_gas_interceptor_detected(False)
self.safety.set_long_controls_allowed(True)
def test_allow_engage_with_gas_interceptor_pressed(self):

View File

@ -15,6 +15,8 @@ RT_INTERVAL = 250000
MAX_TORQUE_ERROR = 350
INTERCEPTOR_THRESHOLD = 475
def twos_comp(val, bits):
if val >= 0:
return val
@ -81,7 +83,9 @@ class TestToyotaSafety(unittest.TestCase):
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
to_send[0].RIR = addr << 21
to_send[0].RDTR = 6
to_send[0].RDLR = ((gas & 0xff) << 8) | ((gas & 0xff00) >> 8)
gas2 = gas * 2
to_send[0].RDLR = ((gas & 0xff) << 8) | ((gas & 0xff00) >> 8) | \
((gas2 & 0xff) << 24) | ((gas2 & 0xff00) << 8)
return to_send
@ -145,16 +149,15 @@ class TestToyotaSafety(unittest.TestCase):
def test_disengage_on_gas_interceptor(self):
for long_controls_allowed in [0, 1]:
self.safety.set_long_controls_allowed(long_controls_allowed)
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_controls_allowed(True)
self.safety.safety_rx_hook(self._send_interceptor_msg(0x1000, 0x201))
if long_controls_allowed:
self.assertFalse(self.safety.get_controls_allowed())
else:
self.assertTrue(self.safety.get_controls_allowed())
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_gas_interceptor_detected(False)
for g in range(0, 0x1000):
self.safety.set_long_controls_allowed(long_controls_allowed)
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_controls_allowed(True)
self.safety.safety_rx_hook(self._send_interceptor_msg(g, 0x201))
remain_enabled = (not long_controls_allowed or g <= INTERCEPTOR_THRESHOLD)
self.assertEqual(remain_enabled, self.safety.get_controls_allowed())
self.safety.safety_rx_hook(self._send_interceptor_msg(0, 0x201))
self.safety.set_gas_interceptor_detected(False)
self.safety.set_long_controls_allowed(True)
def test_allow_engage_with_gas_interceptor_pressed(self):

View File

@ -17,4 +17,4 @@ COPY . /openpilot/panda
WORKDIR /openpilot/panda/tests/safety_replay
RUN git clone https://github.com/commaai/openpilot-tools.git tools || true
WORKDIR tools
RUN git checkout b6461274d684915f39dc45efc5292ea890698da9
RUN git checkout feb724a14f0f5223c700c94317efaf46923fd48a

View File

@ -8,13 +8,3 @@ cd capnproto-c++-0.6.1
make -j4
make install
cd ..
git clone https://github.com/commaai/c-capnproto.git
cd c-capnproto
git checkout 2e625acacf58a5f5c8828d8453d1f8dacc700a96
git submodule update --init --recursive
autoreconf -f -i -s
CFLAGS="-fPIC" ./configure --prefix=/usr/local
make -j4
make install