This commit is contained in:
Your Name
2024-04-27 03:19:19 -05:00
parent df418b503f
commit 03af7b6107
306 changed files with 108529 additions and 119 deletions

21
panda/board/SConscript Normal file
View File

@@ -0,0 +1,21 @@
import os
import copy
Import('build_project', 'base_project_f4', 'base_project_h7')
build_projects = {
"panda": base_project_f4,
"panda_h7": base_project_h7,
}
for project_name, project in build_projects.items():
flags = [
"-DPANDA",
]
if ("ENABLE_SPI" in os.environ or "h7" in project_name):
flags.append('-DENABLE_SPI')
if "H723" in os.environ:
flags.append('-DSTM32H723')
build_project(project_name, project, flags)

186
panda/board/boards/black.h Normal file
View File

@@ -0,0 +1,186 @@
// /////////////////////////////// //
// Black Panda (STM32F4) + Harness //
// /////////////////////////////// //
void black_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver){
case 1U:
set_gpio_output(GPIOC, 1, !enabled);
break;
case 2U:
set_gpio_output(GPIOC, 13, !enabled);
break;
case 3U:
set_gpio_output(GPIOA, 0, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 10, !enabled);
break;
default:
print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n");
break;
}
}
void black_enable_can_transceivers(bool enabled) {
for(uint8_t i=1U; i<=4U; i++){
// Leave main CAN always on for CAN-based ignition detection
if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){
black_enable_can_transceiver(i, true);
} else {
black_enable_can_transceiver(i, enabled);
}
}
}
void black_set_led(uint8_t color, bool enabled) {
switch (color){
case LED_RED:
set_gpio_output(GPIOC, 9, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOC, 7, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOC, 6, !enabled);
break;
default:
break;
}
}
void black_set_usb_load_switch(bool enabled) {
set_gpio_output(GPIOB, 1, !enabled);
}
void black_set_can_mode(uint8_t mode) {
black_enable_can_transceiver(2U, false);
black_enable_can_transceiver(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
case CAN_MODE_OBD_CAN2:
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) {
// B12,B13: disable OBD mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
black_enable_can_transceiver(2U, true);
} else {
// B5,B6: disable normal CAN2 mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: OBD mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
black_enable_can_transceiver(4U, true);
}
break;
default:
print("Tried to set unsupported CAN mode: "); puth(mode); print("\n");
break;
}
}
bool black_check_ignition(void){
// ignition is checked through harness
return harness_check_ignition();
}
void black_init(void) {
common_init_gpio();
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
// C0: OBD_SBU1 (orientation detection)
// C3: OBD_SBU2 (orientation detection)
set_gpio_mode(GPIOC, 0, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// GPS OFF
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 12, 0);
// C10: OBD_SBU1_RELAY (harness relay driving output)
// C11: OBD_SBU2_RELAY (harness relay driving output)
set_gpio_mode(GPIOC, 10, MODE_OUTPUT);
set_gpio_mode(GPIOC, 11, MODE_OUTPUT);
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output(GPIOC, 10, 1);
set_gpio_output(GPIOC, 11, 1);
// Turn on USB load switch.
black_set_usb_load_switch(true);
// Initialize harness
harness_init();
// Enable CAN transceivers
black_enable_can_transceivers(true);
// Disable LEDs
black_set_led(LED_RED, false);
black_set_led(LED_GREEN, false);
black_set_led(LED_BLUE, false);
// Set normal CAN mode
black_set_can_mode(CAN_MODE_NORMAL);
// change CAN mapping when flipped
if (harness.status == HARNESS_STATUS_FLIPPED) {
can_flip_buses(0, 2);
}
}
void black_init_bootloader(void) {
// GPS OFF
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 12, 0);
}
const harness_configuration black_harness_config = {
.has_harness = true,
.GPIO_SBU1 = GPIOC,
.GPIO_SBU2 = GPIOC,
.GPIO_relay_SBU1 = GPIOC,
.GPIO_relay_SBU2 = GPIOC,
.pin_SBU1 = 0,
.pin_SBU2 = 3,
.pin_relay_SBU1 = 10,
.pin_relay_SBU2 = 11,
.adc_channel_SBU1 = 10,
.adc_channel_SBU2 = 13
};
const board board_black = {
.set_bootkick = unused_set_bootkick,
.harness_config = &black_harness_config,
.has_obd = true,
.has_spi = false,
.has_canfd = false,
.fan_max_rpm = 0U,
.avdd_mV = 3300U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 0U,
.init = black_init,
.init_bootloader = black_init_bootloader,
.enable_can_transceiver = black_enable_can_transceiver,
.enable_can_transceivers = black_enable_can_transceivers,
.set_led = black_set_led,
.set_can_mode = black_set_can_mode,
.check_ignition = black_check_ignition,
.read_voltage_mV = white_read_voltage_mV,
.read_current_mA = unused_read_current,
.set_fan_enabled = unused_set_fan_enabled,
.set_ir_power = unused_set_ir_power,
.set_siren = unused_set_siren,
.read_som_gpio = unused_read_som_gpio
};

View File

@@ -0,0 +1,77 @@
// ******************** Prototypes ********************
typedef enum {
BOOT_STANDBY,
BOOT_BOOTKICK,
BOOT_RESET,
} BootState;
typedef void (*board_init)(void);
typedef void (*board_init_bootloader)(void);
typedef void (*board_enable_can_transceiver)(uint8_t transceiver, bool enabled);
typedef void (*board_enable_can_transceivers)(bool enabled);
typedef void (*board_set_led)(uint8_t color, bool enabled);
typedef void (*board_set_can_mode)(uint8_t mode);
typedef bool (*board_check_ignition)(void);
typedef uint32_t (*board_read_voltage_mV)(void);
typedef uint32_t (*board_read_current_mA)(void);
typedef void (*board_set_ir_power)(uint8_t percentage);
typedef void (*board_set_fan_enabled)(bool enabled);
typedef void (*board_set_siren)(bool enabled);
typedef void (*board_set_bootkick)(BootState state);
typedef bool (*board_read_som_gpio)(void);
struct board {
const harness_configuration *harness_config;
const bool has_obd;
const bool has_spi;
const bool has_canfd;
const uint16_t fan_max_rpm;
const uint16_t avdd_mV;
const bool fan_stall_recovery;
const uint8_t fan_enable_cooldown_time;
board_init init;
board_init_bootloader init_bootloader;
board_enable_can_transceiver enable_can_transceiver;
board_enable_can_transceivers enable_can_transceivers;
board_set_led set_led;
board_set_can_mode set_can_mode;
board_check_ignition check_ignition;
board_read_voltage_mV read_voltage_mV;
board_read_current_mA read_current_mA;
board_set_ir_power set_ir_power;
board_set_fan_enabled set_fan_enabled;
board_set_siren set_siren;
board_set_bootkick set_bootkick;
board_read_som_gpio read_som_gpio;
};
// ******************* Definitions ********************
// These should match the enums in cereal/log.capnp and __init__.py
#define HW_TYPE_UNKNOWN 0U
#define HW_TYPE_WHITE_PANDA 1U
#define HW_TYPE_GREY_PANDA 2U
#define HW_TYPE_BLACK_PANDA 3U
#define HW_TYPE_PEDAL 4U
#define HW_TYPE_UNO 5U
#define HW_TYPE_DOS 6U
#define HW_TYPE_RED_PANDA 7U
#define HW_TYPE_RED_PANDA_V2 8U
#define HW_TYPE_TRES 9U
#define HW_TYPE_CUATRO 10U
// LED colors
#define LED_RED 0U
#define LED_GREEN 1U
#define LED_BLUE 2U
// USB power modes (from cereal.log.health)
#define USB_POWER_NONE 0U
#define USB_POWER_CLIENT 1U
#define USB_POWER_CDP 2U
#define USB_POWER_DCP 3U
// CAN modes
#define CAN_MODE_NORMAL 0U
#define CAN_MODE_GMLAN_CAN2 1U
#define CAN_MODE_GMLAN_CAN3 2U
#define CAN_MODE_OBD_CAN2 3U

129
panda/board/boards/cuatro.h Normal file
View File

@@ -0,0 +1,129 @@
// ////////////////////////// //
// Cuatro (STM32H7) + Harness //
// ////////////////////////// //
void cuatro_set_led(uint8_t color, bool enabled) {
switch (color) {
case LED_RED:
set_gpio_output(GPIOD, 15, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOD, 14, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOE, 2, !enabled);
break;
default:
break;
}
}
void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver) {
case 1U:
set_gpio_output(GPIOB, 7, !enabled);
break;
case 2U:
set_gpio_output(GPIOB, 10, !enabled);
break;
case 3U:
set_gpio_output(GPIOD, 8, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 11, !enabled);
break;
default:
break;
}
}
void cuatro_enable_can_transceivers(bool enabled) {
uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U;
for (uint8_t i=1U; i<=4U; i++) {
// Leave main CAN always on for CAN-based ignition detection
if (i == main_bus) {
cuatro_enable_can_transceiver(i, true);
} else {
cuatro_enable_can_transceiver(i, enabled);
}
}
}
uint32_t cuatro_read_voltage_mV(void) {
return adc_get_mV(8) * 11U;
}
uint32_t cuatro_read_current_mA(void) {
return adc_get_mV(3) * 2U;
}
void cuatro_init(void) {
red_chiplet_init();
// Power readout
set_gpio_mode(GPIOC, 5, MODE_ANALOG);
set_gpio_mode(GPIOA, 6, MODE_ANALOG);
// CAN transceiver enables
set_gpio_pullup(GPIOB, 7, PULL_NONE);
set_gpio_mode(GPIOB, 7, MODE_OUTPUT);
set_gpio_pullup(GPIOD, 8, PULL_NONE);
set_gpio_mode(GPIOD, 8, MODE_OUTPUT);
// FDCAN3, different pins on this package than the rest of the reds
set_gpio_pullup(GPIOD, 12, PULL_NONE);
set_gpio_alternate(GPIOD, 12, GPIO_AF5_FDCAN3);
set_gpio_pullup(GPIOD, 13, PULL_NONE);
set_gpio_alternate(GPIOD, 13, GPIO_AF5_FDCAN3);
// C2: SOM GPIO used as input (fan control at boot)
set_gpio_mode(GPIOC, 2, MODE_INPUT);
set_gpio_pullup(GPIOC, 2, PULL_DOWN);
// SOM bootkick + reset lines
set_gpio_mode(GPIOC, 12, MODE_OUTPUT);
tres_set_bootkick(BOOT_BOOTKICK);
// SOM debugging UART
gpio_uart7_init();
uart_init(&uart_ring_som_debug, 115200);
// SPI init
gpio_spi_init();
// fan setup
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// Initialize IR PWM and set to 0%
set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3);
pwm_init(TIM3, 4);
tres_set_ir_power(0U);
// Clock source
clock_source_init();
}
const board board_cuatro = {
.harness_config = &red_chiplet_harness_config,
.has_obd = true,
.has_spi = true,
.has_canfd = true,
.fan_max_rpm = 6600U,
.avdd_mV = 1800U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 3U,
.init = cuatro_init,
.init_bootloader = unused_init_bootloader,
.enable_can_transceiver = cuatro_enable_can_transceiver,
.enable_can_transceivers = cuatro_enable_can_transceivers,
.set_led = cuatro_set_led,
.set_can_mode = red_chiplet_set_can_mode,
.check_ignition = red_check_ignition,
.read_voltage_mV = cuatro_read_voltage_mV,
.read_current_mA = cuatro_read_current_mA,
.set_fan_enabled = tres_set_fan_enabled,
.set_ir_power = tres_set_ir_power,
.set_siren = unused_set_siren,
.set_bootkick = tres_set_bootkick,
.read_som_gpio = tres_read_som_gpio
};

215
panda/board/boards/dos.h Normal file
View File

@@ -0,0 +1,215 @@
// /////////////////////// //
// Dos (STM32F4) + Harness //
// /////////////////////// //
void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver){
case 1U:
set_gpio_output(GPIOC, 1, !enabled);
break;
case 2U:
set_gpio_output(GPIOC, 13, !enabled);
break;
case 3U:
set_gpio_output(GPIOA, 0, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 10, !enabled);
break;
default:
print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n");
break;
}
}
void dos_enable_can_transceivers(bool enabled) {
for(uint8_t i=1U; i<=4U; i++){
// Leave main CAN always on for CAN-based ignition detection
if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){
dos_enable_can_transceiver(i, true);
} else {
dos_enable_can_transceiver(i, enabled);
}
}
}
void dos_set_led(uint8_t color, bool enabled) {
switch (color){
case LED_RED:
set_gpio_output(GPIOC, 9, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOC, 7, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOC, 6, !enabled);
break;
default:
break;
}
}
void dos_set_bootkick(BootState state) {
set_gpio_output(GPIOC, 4, state != BOOT_BOOTKICK);
}
void dos_set_can_mode(uint8_t mode) {
dos_enable_can_transceiver(2U, false);
dos_enable_can_transceiver(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
case CAN_MODE_OBD_CAN2:
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) {
// B12,B13: disable OBD mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
dos_enable_can_transceiver(2U, true);
} else {
// B5,B6: disable normal CAN2 mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: OBD mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
dos_enable_can_transceiver(4U, true);
}
break;
default:
print("Tried to set unsupported CAN mode: "); puth(mode); print("\n");
break;
}
}
bool dos_check_ignition(void){
// ignition is checked through harness
return harness_check_ignition();
}
void dos_set_ir_power(uint8_t percentage){
pwm_set(TIM4, 2, percentage);
}
void dos_set_fan_enabled(bool enabled){
set_gpio_output(GPIOA, 1, enabled);
}
void dos_set_siren(bool enabled){
set_gpio_output(GPIOC, 12, enabled);
}
bool dos_read_som_gpio (void){
return (get_gpio_input(GPIOC, 2) != 0);
}
void dos_init(void) {
common_init_gpio();
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
// C0: OBD_SBU1 (orientation detection)
// C3: OBD_SBU2 (orientation detection)
set_gpio_mode(GPIOC, 0, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// C10: OBD_SBU1_RELAY (harness relay driving output)
// C11: OBD_SBU2_RELAY (harness relay driving output)
set_gpio_mode(GPIOC, 10, MODE_OUTPUT);
set_gpio_mode(GPIOC, 11, MODE_OUTPUT);
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output(GPIOC, 10, 1);
set_gpio_output(GPIOC, 11, 1);
#ifdef ENABLE_SPI
// SPI init
gpio_spi_init();
#endif
// C8: FAN PWM aka TIM3_CH3
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// C2: SOM GPIO used as input (fan control at boot)
set_gpio_mode(GPIOC, 2, MODE_INPUT);
set_gpio_pullup(GPIOC, 2, PULL_DOWN);
// Initialize IR PWM and set to 0%
set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4);
pwm_init(TIM4, 2);
dos_set_ir_power(0U);
// Initialize harness
harness_init();
// Enable CAN transceivers
dos_enable_can_transceivers(true);
// Disable LEDs
dos_set_led(LED_RED, false);
dos_set_led(LED_GREEN, false);
dos_set_led(LED_BLUE, false);
// Bootkick
dos_set_bootkick(true);
// Set normal CAN mode
dos_set_can_mode(CAN_MODE_NORMAL);
// change CAN mapping when flipped
if (harness.status == HARNESS_STATUS_FLIPPED) {
can_flip_buses(0, 2);
}
// Init clock source (camera strobe) using PWM
clock_source_init();
}
const harness_configuration dos_harness_config = {
.has_harness = true,
.GPIO_SBU1 = GPIOC,
.GPIO_SBU2 = GPIOC,
.GPIO_relay_SBU1 = GPIOC,
.GPIO_relay_SBU2 = GPIOC,
.pin_SBU1 = 0,
.pin_SBU2 = 3,
.pin_relay_SBU1 = 10,
.pin_relay_SBU2 = 11,
.adc_channel_SBU1 = 10,
.adc_channel_SBU2 = 13
};
const board board_dos = {
.harness_config = &dos_harness_config,
.has_obd = true,
#ifdef ENABLE_SPI
.has_spi = true,
#else
.has_spi = false,
#endif
.has_canfd = false,
.fan_max_rpm = 6500U,
.avdd_mV = 3300U,
.fan_stall_recovery = true,
.fan_enable_cooldown_time = 3U,
.init = dos_init,
.init_bootloader = unused_init_bootloader,
.enable_can_transceiver = dos_enable_can_transceiver,
.enable_can_transceivers = dos_enable_can_transceivers,
.set_led = dos_set_led,
.set_can_mode = dos_set_can_mode,
.check_ignition = dos_check_ignition,
.read_voltage_mV = white_read_voltage_mV,
.read_current_mA = unused_read_current,
.set_fan_enabled = dos_set_fan_enabled,
.set_ir_power = dos_set_ir_power,
.set_siren = dos_set_siren,
.set_bootkick = dos_set_bootkick,
.read_som_gpio = dos_read_som_gpio
};

30
panda/board/boards/grey.h Normal file
View File

@@ -0,0 +1,30 @@
// //////////////////// //
// Grey Panda (STM32F4) //
// //////////////////// //
// Most hardware functionality is similar to white panda
const board board_grey = {
.set_bootkick = unused_set_bootkick,
.harness_config = &white_harness_config,
.has_obd = false,
.has_spi = false,
.has_canfd = false,
.fan_max_rpm = 0U,
.avdd_mV = 3300U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 0U,
.init = white_grey_init,
.init_bootloader = white_grey_init_bootloader,
.enable_can_transceiver = white_enable_can_transceiver,
.enable_can_transceivers = white_enable_can_transceivers,
.set_led = white_set_led,
.set_can_mode = white_set_can_mode,
.check_ignition = white_check_ignition,
.read_voltage_mV = white_read_voltage_mV,
.read_current_mA = white_read_current_mA,
.set_fan_enabled = unused_set_fan_enabled,
.set_ir_power = unused_set_ir_power,
.set_siren = unused_set_siren,
.read_som_gpio = unused_read_som_gpio
};

198
panda/board/boards/red.h Normal file
View File

@@ -0,0 +1,198 @@
// ///////////////////////////// //
// Red Panda (STM32H7) + Harness //
// ///////////////////////////// //
void red_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver) {
case 1U:
set_gpio_output(GPIOG, 11, !enabled);
break;
case 2U:
set_gpio_output(GPIOB, 3, !enabled);
break;
case 3U:
set_gpio_output(GPIOD, 7, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 4, !enabled);
break;
default:
break;
}
}
void red_enable_can_transceivers(bool enabled) {
uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U;
for (uint8_t i=1U; i<=4U; i++) {
// Leave main CAN always on for CAN-based ignition detection
if (i == main_bus) {
red_enable_can_transceiver(i, true);
} else {
red_enable_can_transceiver(i, enabled);
}
}
}
void red_set_led(uint8_t color, bool enabled) {
switch (color) {
case LED_RED:
set_gpio_output(GPIOE, 4, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOE, 3, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOE, 2, !enabled);
break;
default:
break;
}
}
void red_set_can_mode(uint8_t mode) {
red_enable_can_transceiver(2U, false);
red_enable_can_transceiver(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
case CAN_MODE_OBD_CAN2:
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) {
// B12,B13: disable normal mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_mode(GPIOB, 12, MODE_ANALOG);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_mode(GPIOB, 13, MODE_ANALOG);
// B5,B6: FDCAN2 mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2);
red_enable_can_transceiver(2U, true);
} else {
// B5,B6: disable normal mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_mode(GPIOB, 5, MODE_ANALOG);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_mode(GPIOB, 6, MODE_ANALOG);
// B12,B13: FDCAN2 mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2);
red_enable_can_transceiver(4U, true);
}
break;
default:
break;
}
}
bool red_check_ignition(void) {
// ignition is checked through harness
return harness_check_ignition();
}
uint32_t red_read_voltage_mV(void){
return adc_get_mV(2) * 11U; // TODO: is this correct?
}
void red_init(void) {
common_init_gpio();
//C10,C11 : OBD_SBU1_RELAY, OBD_SBU2_RELAY
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_pullup(GPIOC, 10, PULL_NONE);
set_gpio_mode(GPIOC, 10, MODE_OUTPUT);
set_gpio_output(GPIOC, 10, 1);
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_pullup(GPIOC, 11, PULL_NONE);
set_gpio_mode(GPIOC, 11, MODE_OUTPUT);
set_gpio_output(GPIOC, 11, 1);
// G11,B3,D7,B4: transceiver enable
set_gpio_pullup(GPIOG, 11, PULL_NONE);
set_gpio_mode(GPIOG, 11, MODE_OUTPUT);
set_gpio_pullup(GPIOB, 3, PULL_NONE);
set_gpio_mode(GPIOB, 3, MODE_OUTPUT);
set_gpio_pullup(GPIOD, 7, PULL_NONE);
set_gpio_mode(GPIOD, 7, MODE_OUTPUT);
set_gpio_pullup(GPIOB, 4, PULL_NONE);
set_gpio_mode(GPIOB, 4, MODE_OUTPUT);
//B1: 5VOUT_S
set_gpio_pullup(GPIOB, 1, PULL_NONE);
set_gpio_mode(GPIOB, 1, MODE_ANALOG);
// B14: usb load switch, enabled by pull resistor on board, obsolete for red panda
set_gpio_output_type(GPIOB, 14, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_pullup(GPIOB, 14, PULL_UP);
set_gpio_mode(GPIOB, 14, MODE_OUTPUT);
set_gpio_output(GPIOB, 14, 1);
// Initialize harness
harness_init();
// Enable CAN transceivers
red_enable_can_transceivers(true);
// Disable LEDs
red_set_led(LED_RED, false);
red_set_led(LED_GREEN, false);
red_set_led(LED_BLUE, false);
// Set normal CAN mode
red_set_can_mode(CAN_MODE_NORMAL);
// change CAN mapping when flipped
if (harness.status == HARNESS_STATUS_FLIPPED) {
can_flip_buses(0, 2);
}
}
const harness_configuration red_harness_config = {
.has_harness = true,
.GPIO_SBU1 = GPIOC,
.GPIO_SBU2 = GPIOA,
.GPIO_relay_SBU1 = GPIOC,
.GPIO_relay_SBU2 = GPIOC,
.pin_SBU1 = 4,
.pin_SBU2 = 1,
.pin_relay_SBU1 = 10,
.pin_relay_SBU2 = 11,
.adc_channel_SBU1 = 4, //ADC12_INP4
.adc_channel_SBU2 = 17 //ADC1_INP17
};
const board board_red = {
.set_bootkick = unused_set_bootkick,
.harness_config = &red_harness_config,
.has_obd = true,
.has_spi = false,
.has_canfd = true,
.fan_max_rpm = 0U,
.avdd_mV = 3300U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 0U,
.init = red_init,
.init_bootloader = unused_init_bootloader,
.enable_can_transceiver = red_enable_can_transceiver,
.enable_can_transceivers = red_enable_can_transceivers,
.set_led = red_set_led,
.set_can_mode = red_set_can_mode,
.check_ignition = red_check_ignition,
.read_voltage_mV = red_read_voltage_mV,
.read_current_mA = unused_read_current,
.set_fan_enabled = unused_set_fan_enabled,
.set_ir_power = unused_set_ir_power,
.set_siren = unused_set_siren,
.read_som_gpio = unused_read_som_gpio
};

View File

@@ -0,0 +1,152 @@
// ///////////////////////////////////// //
// Red Panda chiplet (STM32H7) + Harness //
// ///////////////////////////////////// //
// Most hardware functionality is similar to red panda
void red_chiplet_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver) {
case 1U:
set_gpio_output(GPIOG, 11, !enabled);
break;
case 2U:
set_gpio_output(GPIOB, 10, !enabled);
break;
case 3U:
set_gpio_output(GPIOD, 7, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 11, !enabled);
break;
default:
break;
}
}
void red_chiplet_enable_can_transceivers(bool enabled) {
uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U;
for (uint8_t i=1U; i<=4U; i++) {
// Leave main CAN always on for CAN-based ignition detection
if (i == main_bus) {
red_chiplet_enable_can_transceiver(i, true);
} else {
red_chiplet_enable_can_transceiver(i, enabled);
}
}
}
void red_chiplet_set_can_mode(uint8_t mode) {
red_chiplet_enable_can_transceiver(2U, false);
red_chiplet_enable_can_transceiver(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
case CAN_MODE_OBD_CAN2:
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) {
// B12,B13: disable normal mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_mode(GPIOB, 12, MODE_ANALOG);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_mode(GPIOB, 13, MODE_ANALOG);
// B5,B6: FDCAN2 mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2);
red_chiplet_enable_can_transceiver(2U, true);
} else {
// B5,B6: disable normal mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_mode(GPIOB, 5, MODE_ANALOG);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_mode(GPIOB, 6, MODE_ANALOG);
// B12,B13: FDCAN2 mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2);
red_chiplet_enable_can_transceiver(4U, true);
}
break;
default:
break;
}
}
void red_chiplet_set_fan_or_usb_load_switch(bool enabled) {
set_gpio_output(GPIOD, 3, enabled);
}
void red_chiplet_init(void) {
common_init_gpio();
// A8, A3: OBD_SBU1_RELAY, OBD_SBU2_RELAY
set_gpio_output_type(GPIOA, 8, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_pullup(GPIOA, 8, PULL_NONE);
set_gpio_output(GPIOA, 8, 1);
set_gpio_mode(GPIOA, 8, MODE_OUTPUT);
set_gpio_output_type(GPIOA, 3, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_pullup(GPIOA, 3, PULL_NONE);
set_gpio_output(GPIOA, 3, 1);
set_gpio_mode(GPIOA, 3, MODE_OUTPUT);
// G11,B10,D7,B11: transceiver enable
set_gpio_pullup(GPIOG, 11, PULL_NONE);
set_gpio_mode(GPIOG, 11, MODE_OUTPUT);
set_gpio_pullup(GPIOB, 10, PULL_NONE);
set_gpio_mode(GPIOB, 10, MODE_OUTPUT);
set_gpio_pullup(GPIOD, 7, PULL_NONE);
set_gpio_mode(GPIOD, 7, MODE_OUTPUT);
set_gpio_pullup(GPIOB, 11, PULL_NONE);
set_gpio_mode(GPIOB, 11, MODE_OUTPUT);
// D3: usb load switch
set_gpio_pullup(GPIOD, 3, PULL_NONE);
set_gpio_mode(GPIOD, 3, MODE_OUTPUT);
// B0: 5VOUT_S
set_gpio_pullup(GPIOB, 0, PULL_NONE);
set_gpio_mode(GPIOB, 0, MODE_ANALOG);
// Initialize harness
harness_init();
// Enable CAN transceivers
red_chiplet_enable_can_transceivers(true);
// Disable LEDs
red_set_led(LED_RED, false);
red_set_led(LED_GREEN, false);
red_set_led(LED_BLUE, false);
// Set normal CAN mode
red_chiplet_set_can_mode(CAN_MODE_NORMAL);
// change CAN mapping when flipped
if (harness.status == HARNESS_STATUS_FLIPPED) {
can_flip_buses(0, 2);
}
}
const harness_configuration red_chiplet_harness_config = {
.has_harness = true,
.GPIO_SBU1 = GPIOC,
.GPIO_SBU2 = GPIOA,
.GPIO_relay_SBU1 = GPIOA,
.GPIO_relay_SBU2 = GPIOA,
.pin_SBU1 = 4,
.pin_SBU2 = 1,
.pin_relay_SBU1 = 8,
.pin_relay_SBU2 = 3,
.adc_channel_SBU1 = 4, // ADC12_INP4
.adc_channel_SBU2 = 17 // ADC1_INP17
};

96
panda/board/boards/tres.h Normal file
View File

@@ -0,0 +1,96 @@
// ///////////////////////////
// Tres (STM32H7) + Harness //
// ///////////////////////////
bool tres_ir_enabled;
bool tres_fan_enabled;
void tres_update_fan_ir_power(void) {
red_chiplet_set_fan_or_usb_load_switch(tres_ir_enabled || tres_fan_enabled);
}
void tres_set_ir_power(uint8_t percentage){
tres_ir_enabled = (percentage > 0U);
tres_update_fan_ir_power();
pwm_set(TIM3, 4, percentage);
}
void tres_set_bootkick(BootState state) {
set_gpio_output(GPIOA, 0, state != BOOT_BOOTKICK);
set_gpio_output(GPIOC, 12, state != BOOT_RESET);
}
void tres_set_fan_enabled(bool enabled) {
// NOTE: fan controller reset doesn't work on a tres if IR is enabled
tres_fan_enabled = enabled;
tres_update_fan_ir_power();
}
bool tres_read_som_gpio (void) {
return (get_gpio_input(GPIOC, 2) != 0);
}
void tres_init(void) {
// Enable USB 3.3V LDO for USB block
register_set_bits(&(PWR->CR3), PWR_CR3_USBREGEN);
register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN);
while ((PWR->CR3 & PWR_CR3_USB33RDY) == 0);
red_chiplet_init();
// C2: SOM GPIO used as input (fan control at boot)
set_gpio_mode(GPIOC, 2, MODE_INPUT);
set_gpio_pullup(GPIOC, 2, PULL_DOWN);
// SOM bootkick + reset lines
set_gpio_mode(GPIOC, 12, MODE_OUTPUT);
tres_set_bootkick(BOOT_BOOTKICK);
// SOM debugging UART
gpio_uart7_init();
uart_init(&uart_ring_som_debug, 115200);
// SPI init
gpio_spi_init();
// fan setup
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// Initialize IR PWM and set to 0%
set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3);
pwm_init(TIM3, 4);
tres_set_ir_power(0U);
// Fake siren
set_gpio_alternate(GPIOC, 10, GPIO_AF4_I2C5);
set_gpio_alternate(GPIOC, 11, GPIO_AF4_I2C5);
register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT10 | GPIO_OTYPER_OT11); // open drain
fake_siren_init();
// Clock source
clock_source_init();
}
const board board_tres = {
.harness_config = &red_chiplet_harness_config,
.has_obd = true,
.has_spi = true,
.has_canfd = true,
.fan_max_rpm = 6600U,
.avdd_mV = 1800U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 3U,
.init = tres_init,
.init_bootloader = unused_init_bootloader,
.enable_can_transceiver = red_chiplet_enable_can_transceiver,
.enable_can_transceivers = red_chiplet_enable_can_transceivers,
.set_led = red_set_led,
.set_can_mode = red_chiplet_set_can_mode,
.check_ignition = red_check_ignition,
.read_voltage_mV = red_read_voltage_mV,
.read_current_mA = unused_read_current,
.set_fan_enabled = tres_set_fan_enabled,
.set_ir_power = tres_set_ir_power,
.set_siren = fake_siren_set,
.set_bootkick = tres_set_bootkick,
.read_som_gpio = tres_read_som_gpio
};

222
panda/board/boards/uno.h Normal file
View File

@@ -0,0 +1,222 @@
// /////////////////////// //
// Uno (STM32F4) + Harness //
// /////////////////////// //
void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver){
case 1U:
set_gpio_output(GPIOC, 1, !enabled);
break;
case 2U:
set_gpio_output(GPIOC, 13, !enabled);
break;
case 3U:
set_gpio_output(GPIOA, 0, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 10, !enabled);
break;
default:
print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n");
break;
}
}
void uno_enable_can_transceivers(bool enabled) {
for(uint8_t i=1U; i<=4U; i++){
// Leave main CAN always on for CAN-based ignition detection
if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){
uno_enable_can_transceiver(i, true);
} else {
uno_enable_can_transceiver(i, enabled);
}
}
}
void uno_set_led(uint8_t color, bool enabled) {
switch (color){
case LED_RED:
set_gpio_output(GPIOC, 9, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOC, 7, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOC, 6, !enabled);
break;
default:
break;
}
}
void uno_set_bootkick(BootState state) {
if (state == BOOT_BOOTKICK) {
set_gpio_output(GPIOB, 14, false);
} else {
// We want the pin to be floating, not forced high!
set_gpio_mode(GPIOB, 14, MODE_INPUT);
}
}
void uno_set_can_mode(uint8_t mode) {
uno_enable_can_transceiver(2U, false);
uno_enable_can_transceiver(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
case CAN_MODE_OBD_CAN2:
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) {
// B12,B13: disable OBD mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
uno_enable_can_transceiver(2U, true);
} else {
// B5,B6: disable normal CAN2 mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: OBD mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
uno_enable_can_transceiver(4U, true);
}
break;
default:
print("Tried to set unsupported CAN mode: "); puth(mode); print("\n");
break;
}
}
bool uno_check_ignition(void){
// ignition is checked through harness
return harness_check_ignition();
}
void uno_set_usb_switch(bool phone){
set_gpio_output(GPIOB, 3, phone);
}
void uno_set_ir_power(uint8_t percentage){
pwm_set(TIM4, 2, percentage);
}
void uno_set_fan_enabled(bool enabled){
set_gpio_output(GPIOA, 1, enabled);
}
void uno_init(void) {
common_init_gpio();
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
// C0: OBD_SBU1 (orientation detection)
// C3: OBD_SBU2 (orientation detection)
set_gpio_mode(GPIOC, 0, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// GPS off
set_gpio_output(GPIOB, 1, 0);
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 12, 0);
// C10: OBD_SBU1_RELAY (harness relay driving output)
// C11: OBD_SBU2_RELAY (harness relay driving output)
set_gpio_mode(GPIOC, 10, MODE_OUTPUT);
set_gpio_mode(GPIOC, 11, MODE_OUTPUT);
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN);
set_gpio_output(GPIOC, 10, 1);
set_gpio_output(GPIOC, 11, 1);
// C8: FAN PWM aka TIM3_CH3
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// Turn on phone regulator
set_gpio_output(GPIOB, 4, true);
// Initialize IR PWM and set to 0%
set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4);
pwm_init(TIM4, 2);
uno_set_ir_power(0U);
// Initialize harness
harness_init();
// Enable CAN transceivers
uno_enable_can_transceivers(true);
// Disable LEDs
uno_set_led(LED_RED, false);
uno_set_led(LED_GREEN, false);
uno_set_led(LED_BLUE, false);
// Set normal CAN mode
uno_set_can_mode(CAN_MODE_NORMAL);
// change CAN mapping when flipped
if (harness.status == HARNESS_STATUS_FLIPPED) {
can_flip_buses(0, 2);
}
// Switch to phone usb mode if harness connection is powered by less than 7V
if(white_read_voltage_mV() < 7000U){
uno_set_usb_switch(true);
} else {
uno_set_usb_switch(false);
}
// Bootkick phone
uno_set_bootkick(BOOT_BOOTKICK);
}
void uno_init_bootloader(void) {
// GPS off
set_gpio_output(GPIOB, 1, 0);
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 12, 0);
}
const harness_configuration uno_harness_config = {
.has_harness = true,
.GPIO_SBU1 = GPIOC,
.GPIO_SBU2 = GPIOC,
.GPIO_relay_SBU1 = GPIOC,
.GPIO_relay_SBU2 = GPIOC,
.pin_SBU1 = 0,
.pin_SBU2 = 3,
.pin_relay_SBU1 = 10,
.pin_relay_SBU2 = 11,
.adc_channel_SBU1 = 10,
.adc_channel_SBU2 = 13
};
const board board_uno = {
.harness_config = &uno_harness_config,
.has_obd = true,
.has_spi = false,
.has_canfd = false,
.fan_max_rpm = 5100U,
.avdd_mV = 3300U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 0U,
.init = uno_init,
.init_bootloader = uno_init_bootloader,
.enable_can_transceiver = uno_enable_can_transceiver,
.enable_can_transceivers = uno_enable_can_transceivers,
.set_led = uno_set_led,
.set_can_mode = uno_set_can_mode,
.check_ignition = uno_check_ignition,
.read_voltage_mV = white_read_voltage_mV,
.read_current_mA = unused_read_current,
.set_fan_enabled = uno_set_fan_enabled,
.set_ir_power = uno_set_ir_power,
.set_siren = unused_set_siren,
.set_bootkick = uno_set_bootkick,
.read_som_gpio = unused_read_som_gpio
};

View File

@@ -0,0 +1,26 @@
void unused_init_bootloader(void) {
}
void unused_set_ir_power(uint8_t percentage) {
UNUSED(percentage);
}
void unused_set_fan_enabled(bool enabled) {
UNUSED(enabled);
}
void unused_set_siren(bool enabled) {
UNUSED(enabled);
}
uint32_t unused_read_current(void) {
return 0U;
}
void unused_set_bootkick(BootState state) {
UNUSED(state);
}
bool unused_read_som_gpio(void) {
return false;
}

249
panda/board/boards/white.h Normal file
View File

@@ -0,0 +1,249 @@
// ///////////////////// //
// White Panda (STM32F4) //
// ///////////////////// //
void white_enable_can_transceiver(uint8_t transceiver, bool enabled) {
switch (transceiver){
case 1U:
set_gpio_output(GPIOC, 1, !enabled);
break;
case 2U:
set_gpio_output(GPIOC, 13, !enabled);
break;
case 3U:
set_gpio_output(GPIOA, 0, !enabled);
break;
default:
print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n");
break;
}
}
void white_enable_can_transceivers(bool enabled) {
uint8_t t1 = enabled ? 1U : 2U; // leave transceiver 1 enabled to detect CAN ignition
for(uint8_t i=t1; i<=3U; i++) {
white_enable_can_transceiver(i, enabled);
}
}
void white_set_led(uint8_t color, bool enabled) {
switch (color){
case LED_RED:
set_gpio_output(GPIOC, 9, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOC, 7, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOC, 6, !enabled);
break;
default:
break;
}
}
void white_set_usb_power_mode(uint8_t mode){
switch (mode) {
case USB_POWER_CLIENT:
// B2,A13: set client mode
set_gpio_output(GPIOB, 2, 0);
set_gpio_output(GPIOA, 13, 1);
break;
case USB_POWER_CDP:
// B2,A13: set CDP mode
set_gpio_output(GPIOB, 2, 1);
set_gpio_output(GPIOA, 13, 1);
break;
case USB_POWER_DCP:
// B2,A13: set DCP mode on the charger (breaks USB!)
set_gpio_output(GPIOB, 2, 0);
set_gpio_output(GPIOA, 13, 0);
break;
default:
print("Invalid usb power mode\n");
break;
}
}
void white_set_can_mode(uint8_t mode){
switch (mode) {
case CAN_MODE_NORMAL:
// B12,B13: disable GMLAN mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B3,B4: disable GMLAN mode
set_gpio_mode(GPIOB, 3, MODE_INPUT);
set_gpio_mode(GPIOB, 4, MODE_INPUT);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
break;
case CAN_MODE_GMLAN_CAN2:
// B5,B6: disable CAN2 mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B3,B4: disable GMLAN mode
set_gpio_mode(GPIOB, 3, MODE_INPUT);
set_gpio_mode(GPIOB, 4, MODE_INPUT);
// B12,B13: GMLAN mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
break;
case CAN_MODE_GMLAN_CAN3:
// A8,A15: disable CAN3 mode
set_gpio_mode(GPIOA, 8, MODE_INPUT);
set_gpio_mode(GPIOA, 15, MODE_INPUT);
// B12,B13: disable GMLAN mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B3,B4: GMLAN mode
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
break;
default:
print("Tried to set unsupported CAN mode: "); puth(mode); print("\n");
break;
}
}
uint32_t white_read_voltage_mV(void){
return adc_get_mV(12) * 11U;
}
uint32_t white_read_current_mA(void){
// This isn't in mA, but we're keeping it for backwards compatibility
return adc_get_raw(13);
}
bool white_check_ignition(void){
// ignition is on PA1
return !get_gpio_input(GPIOA, 1);
}
void white_grey_init(void) {
common_init_gpio();
// C3: current sense
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// A1: started_alt
set_gpio_pullup(GPIOA, 1, PULL_UP);
// A2, A3: USART 2 for debugging
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2);
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2);
// A4, A5, A6, A7: SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1);
// B12: GMLAN, ignition sense, pull up
set_gpio_pullup(GPIOB, 12, PULL_UP);
/* GMLAN mode pins:
M0(B15) M1(B14) mode
=======================
0 0 sleep
1 0 100kbit
0 1 high voltage wakeup
1 1 33kbit (normal)
*/
set_gpio_output(GPIOB, 14, 1);
set_gpio_output(GPIOB, 15, 1);
// B7: K-line enable
set_gpio_output(GPIOB, 7, 1);
// C12, D2: Setup K-line (UART5)
set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5);
set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5);
set_gpio_pullup(GPIOD, 2, PULL_UP);
// L-line enable
set_gpio_output(GPIOA, 14, 1);
// C10, C11: L-Line setup (USART3)
set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3);
set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3);
set_gpio_pullup(GPIOC, 11, PULL_UP);
// Enable CAN transceivers
white_enable_can_transceivers(true);
// Disable LEDs
white_set_led(LED_RED, false);
white_set_led(LED_GREEN, false);
white_set_led(LED_BLUE, false);
// Set normal CAN mode
white_set_can_mode(CAN_MODE_NORMAL);
// Init usb power mode
// Init in CDP mode only if panda is powered by 12V.
// Otherwise a PC would not be able to flash a standalone panda
if (white_read_voltage_mV() > 8000U) { // 8V threshold
white_set_usb_power_mode(USB_POWER_CDP);
} else {
white_set_usb_power_mode(USB_POWER_CLIENT);
}
// ESP/GPS off
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 14, 0);
}
void white_grey_init_bootloader(void) {
// ESP/GPS off
set_gpio_output(GPIOC, 5, 0);
set_gpio_output(GPIOC, 14, 0);
}
const harness_configuration white_harness_config = {
.has_harness = false
};
const board board_white = {
.set_bootkick = unused_set_bootkick,
.harness_config = &white_harness_config,
.has_obd = false,
.has_spi = false,
.has_canfd = false,
.fan_max_rpm = 0U,
.avdd_mV = 3300U,
.fan_stall_recovery = false,
.fan_enable_cooldown_time = 0U,
.init = white_grey_init,
.init_bootloader = white_grey_init_bootloader,
.enable_can_transceiver = white_enable_can_transceiver,
.enable_can_transceivers = white_enable_can_transceivers,
.set_led = white_set_led,
.set_can_mode = white_set_can_mode,
.check_ignition = white_check_ignition,
.read_voltage_mV = white_read_voltage_mV,
.read_current_mA = white_read_current_mA,
.set_fan_enabled = unused_set_fan_enabled,
.set_ir_power = unused_set_ir_power,
.set_siren = unused_set_siren,
.read_som_gpio = unused_read_som_gpio
};

View File

@@ -0,0 +1,20 @@
// ******************** Prototypes ********************
void print(const char *a){ UNUSED(a); }
void puth(uint8_t i){ UNUSED(i); }
void puth2(uint8_t i){ UNUSED(i); }
void puth4(uint8_t i){ UNUSED(i); }
void hexdump(const void *a, int l){ UNUSED(a); UNUSED(l); }
typedef struct board board;
typedef struct harness_configuration harness_configuration;
// No CAN support on bootloader
void can_flip_buses(uint8_t bus1, uint8_t bus2){UNUSED(bus1); UNUSED(bus2);}
void pwm_init(TIM_TypeDef *TIM, uint8_t channel);
void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage);
// No UART support in bootloader
typedef struct uart_ring {} uart_ring;
uart_ring uart_ring_som_debug;
void uart_init(uart_ring *q, int baud) { UNUSED(q); UNUSED(baud); }
// ********************* Globals **********************
uint8_t hw_type = 0;
const board *current_board;

122
panda/board/can_comms.h Normal file
View File

@@ -0,0 +1,122 @@
/*
CAN transactions to and from the host come in the form of
a certain number of CANPacket_t. The transaction is split
into multiple transfers or chunks.
* comms_can_read outputs this buffer in chunks of a specified length.
chunks are always the given length, except the last one.
* comms_can_write reads in this buffer in chunks.
* both functions maintain an overflow buffer for a partial CANPacket_t that
spans multiple transfers/chunks.
* the overflow buffers are reset by a dedicated control transfer handler,
which is sent by the host on each start of a connection.
*/
typedef struct {
uint32_t ptr;
uint32_t tail_size;
uint8_t data[72];
} asm_buffer;
asm_buffer can_read_buffer = {.ptr = 0U, .tail_size = 0U};
int comms_can_read(uint8_t *data, uint32_t max_len) {
uint32_t pos = 0U;
// Send tail of previous message if it is in buffer
if (can_read_buffer.ptr > 0U) {
uint32_t overflow_len = MIN(max_len - pos, can_read_buffer.ptr);
(void)memcpy(&data[pos], can_read_buffer.data, overflow_len);
pos += overflow_len;
(void)memcpy(can_read_buffer.data, &can_read_buffer.data[overflow_len], can_read_buffer.ptr - overflow_len);
can_read_buffer.ptr -= overflow_len;
}
if (can_read_buffer.ptr == 0U) {
// Fill rest of buffer with new data
CANPacket_t can_packet;
while ((pos < max_len) && can_pop(&can_rx_q, &can_packet)) {
uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[can_packet.data_len_code];
if ((pos + pckt_len) <= max_len) {
(void)memcpy(&data[pos], &can_packet, pckt_len);
pos += pckt_len;
} else {
(void)memcpy(&data[pos], &can_packet, max_len - pos);
can_read_buffer.ptr += pckt_len - (max_len - pos);
// cppcheck-suppress objectIndex
(void)memcpy(can_read_buffer.data, &((uint8_t*)&can_packet)[(max_len - pos)], can_read_buffer.ptr);
pos = max_len;
}
}
}
return pos;
}
asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U};
// send on CAN
void comms_can_write(const uint8_t *data, uint32_t len) {
uint32_t pos = 0U;
// Assembling can message with data from buffer
if (can_write_buffer.ptr != 0U) {
if (can_write_buffer.tail_size <= (len - pos)) {
// we have enough data to complete the buffer
CANPacket_t to_push;
(void)memcpy(&can_write_buffer.data[can_write_buffer.ptr], &data[pos], can_write_buffer.tail_size);
can_write_buffer.ptr += can_write_buffer.tail_size;
pos += can_write_buffer.tail_size;
// send out
(void)memcpy(&to_push, can_write_buffer.data, can_write_buffer.ptr);
can_send(&to_push, to_push.bus, false);
// reset overflow buffer
can_write_buffer.ptr = 0U;
can_write_buffer.tail_size = 0U;
} else {
// maybe next time
uint32_t data_size = len - pos;
(void) memcpy(&can_write_buffer.data[can_write_buffer.ptr], &data[pos], data_size);
can_write_buffer.tail_size -= data_size;
can_write_buffer.ptr += data_size;
pos += data_size;
}
}
// rest of the message
while (pos < len) {
uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[(data[pos] >> 4U)];
if ((pos + pckt_len) <= len) {
CANPacket_t to_push;
(void)memcpy(&to_push, &data[pos], pckt_len);
can_send(&to_push, to_push.bus, false);
pos += pckt_len;
} else {
(void)memcpy(can_write_buffer.data, &data[pos], len - pos);
can_write_buffer.ptr = len - pos;
can_write_buffer.tail_size = pckt_len - can_write_buffer.ptr;
pos += can_write_buffer.ptr;
}
}
refresh_can_tx_slots_available();
}
void comms_can_reset(void) {
can_write_buffer.ptr = 0U;
can_write_buffer.tail_size = 0U;
can_read_buffer.ptr = 0U;
can_read_buffer.tail_size = 0U;
}
// TODO: make this more general!
void refresh_can_tx_slots_available(void) {
if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_USB_BULK_TRANSFER)) {
can_tx_comms_resume_usb();
}
if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_SPI_BULK_TRANSFER)) {
can_tx_comms_resume_spi();
}
}

View File

@@ -0,0 +1,34 @@
#pragma once
const uint8_t PANDA_CAN_CNT = 3U;
const uint8_t PANDA_BUS_CNT = 4U;
// bump this when changing the CAN packet
#define CAN_PACKET_VERSION 4
#define CANPACKET_HEAD_SIZE 6U
#if !defined(STM32F4)
#define CANFD
#define CANPACKET_DATA_SIZE_MAX 64U
#else
#define CANPACKET_DATA_SIZE_MAX 8U
#endif
typedef struct {
unsigned char reserved : 1;
unsigned char bus : 3;
unsigned char data_len_code : 4; // lookup length with dlc_to_len
unsigned char rejected : 1;
unsigned char returned : 1;
unsigned char extended : 1;
unsigned int addr : 29;
unsigned char checksum;
unsigned char data[CANPACKET_DATA_SIZE_MAX];
} __attribute__((packed, aligned(4))) CANPacket_t;
const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U};
#define GET_BUS(msg) ((msg)->bus)
#define GET_LEN(msg) (dlc_to_len[(msg)->data_len_code])
#define GET_ADDR(msg) ((msg)->addr)

View File

@@ -0,0 +1,12 @@
typedef struct {
uint8_t request;
uint16_t param1;
uint16_t param2;
uint16_t length;
} __attribute__((packed)) ControlPacket_t;
int comms_control_handler(ControlPacket_t *req, uint8_t *resp);
void comms_endpoint2_write(const uint8_t *data, uint32_t len);
void comms_can_write(const uint8_t *data, uint32_t len);
int comms_can_read(uint8_t *data, uint32_t max_len);
void comms_can_reset(void);

45
panda/board/config.h Normal file
View File

@@ -0,0 +1,45 @@
#pragma once
#include <stdbool.h>
//#define DEBUG
//#define DEBUG_UART
//#define DEBUG_USB
//#define DEBUG_SPI
//#define DEBUG_FAULTS
//#define DEBUG_COMMS
//#define DEBUG_FAN
#define CAN_INIT_TIMEOUT_MS 500U
#define DEEPSLEEP_WAKEUP_DELAY 3U
#define USBPACKET_MAX_SIZE 0x40U
#define MAX_CAN_MSGS_PER_USB_BULK_TRANSFER 51U
#define MAX_CAN_MSGS_PER_SPI_BULK_TRANSFER 170U
// USB definitions
#define USB_VID 0xBBAAU
#ifdef PANDA_JUNGLE
#ifdef BOOTSTUB
#define USB_PID 0xDDEFU
#else
#define USB_PID 0xDDCFU
#endif
#else
#ifdef BOOTSTUB
#define USB_PID 0xDDEEU
#else
#define USB_PID 0xDDCCU
#endif
#endif
// platform includes
#ifdef STM32H7
#include "stm32h7/stm32h7_config.h"
#elif defined(STM32F4)
#include "stm32f4/stm32f4_config.h"
#else
// TODO: uncomment this, cppcheck complains
// building for tests
//#include "fake_stm.h"
#endif

19
panda/board/crc.h Normal file
View File

@@ -0,0 +1,19 @@
#pragma once
uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) {
uint8_t crc = 0xFFU;
int i;
int j;
for (i = len - 1; i >= 0; i--) {
crc ^= dat[i];
for (j = 0; j < 8; j++) {
if ((crc & 0x80U) != 0U) {
crc = (uint8_t)((crc << 1) ^ poly);
}
else {
crc <<= 1;
}
}
}
return crc;
}

23
panda/board/critical.h Normal file
View File

@@ -0,0 +1,23 @@
// ********************* Critical section helpers *********************
volatile bool interrupts_enabled = false;
void enable_interrupts(void) {
interrupts_enabled = true;
__enable_irq();
}
void disable_interrupts(void) {
interrupts_enabled = false;
__disable_irq();
}
uint8_t global_critical_depth = 0U;
#define ENTER_CRITICAL() \
__disable_irq(); \
global_critical_depth += 1U;
#define EXIT_CRITICAL() \
global_critical_depth -= 1U; \
if ((global_critical_depth == 0U) && interrupts_enabled) { \
__enable_irq(); \
}

View File

@@ -0,0 +1,67 @@
bool bootkick_ign_prev = false;
BootState boot_state = BOOT_BOOTKICK;
uint8_t bootkick_harness_status_prev = HARNESS_STATUS_NC;
uint8_t boot_reset_countdown = 0;
uint8_t waiting_to_boot_countdown = 0;
bool bootkick_reset_triggered = false;
uint16_t bootkick_last_serial_ptr = 0;
void bootkick_tick(bool ignition, bool recent_heartbeat) {
BootState boot_state_prev = boot_state;
const bool harness_inserted = (harness.status != bootkick_harness_status_prev) && (harness.status != HARNESS_STATUS_NC);
if ((ignition && !bootkick_ign_prev) || harness_inserted) {
// bootkick on rising edge of ignition or harness insertion
boot_state = BOOT_BOOTKICK;
} else if (recent_heartbeat) {
// disable bootkick once openpilot is up
boot_state = BOOT_STANDBY;
} else {
}
/*
Ensure SOM boots in case it goes into QDL mode. Reset behavior:
* shouldn't trigger on the first boot after power-on
* only try reset once per bootkick, i.e. don't keep trying until booted
* only try once per panda boot, since openpilot will reset panda on startup
* once BOOT_RESET is triggered, it stays until countdown is finished
*/
if (!bootkick_reset_triggered && (boot_state == BOOT_BOOTKICK) && (boot_state_prev == BOOT_STANDBY)) {
waiting_to_boot_countdown = 45U;
}
if (waiting_to_boot_countdown > 0U) {
bool serial_activity = uart_ring_som_debug.w_ptr_tx != bootkick_last_serial_ptr;
if (serial_activity || current_board->read_som_gpio() || (boot_state != BOOT_BOOTKICK)) {
waiting_to_boot_countdown = 0U;
} else {
// try a reset
if (waiting_to_boot_countdown == 1U) {
boot_reset_countdown = 5U;
}
}
}
// handle reset state
if (boot_reset_countdown > 0U) {
boot_state = BOOT_RESET;
bootkick_reset_triggered = true;
} else {
if (boot_state == BOOT_RESET) {
boot_state = BOOT_BOOTKICK;
}
}
// update state
bootkick_ign_prev = ignition;
bootkick_harness_status_prev = harness.status;
bootkick_last_serial_ptr = uart_ring_som_debug.w_ptr_tx;
if (waiting_to_boot_countdown > 0U) {
waiting_to_boot_countdown--;
}
if (boot_reset_countdown > 0U) {
boot_reset_countdown--;
}
current_board->set_bootkick(boot_state);
}

213
panda/board/drivers/bxcan.h Normal file
View File

@@ -0,0 +1,213 @@
// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE
// CAN2_TX, CAN2_RX0, CAN2_SCE
// CAN3_TX, CAN3_RX0, CAN3_SCE
CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3};
uint8_t can_irq_number[3][3] = {
{ CAN1_TX_IRQn, CAN1_RX0_IRQn, CAN1_SCE_IRQn },
{ CAN2_TX_IRQn, CAN2_RX0_IRQn, CAN2_SCE_IRQn },
{ CAN3_TX_IRQn, CAN3_RX0_IRQn, CAN3_SCE_IRQn },
};
bool can_set_speed(uint8_t can_number) {
bool ret = true;
CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
ret &= llcan_set_speed(
CANx,
bus_config[bus_number].can_speed,
can_loopback,
(unsigned int)(can_silent) & (1U << can_number)
);
return ret;
}
void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) {
CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number);
uint32_t esr_reg = CANx->ESR;
can_health[can_number].bus_off = ((esr_reg & CAN_ESR_BOFF) >> CAN_ESR_BOFF_Pos);
can_health[can_number].bus_off_cnt += can_health[can_number].bus_off;
can_health[can_number].error_warning = ((esr_reg & CAN_ESR_EWGF) >> CAN_ESR_EWGF_Pos);
can_health[can_number].error_passive = ((esr_reg & CAN_ESR_EPVF) >> CAN_ESR_EPVF_Pos);
can_health[can_number].last_error = ((esr_reg & CAN_ESR_LEC) >> CAN_ESR_LEC_Pos);
if ((can_health[can_number].last_error != 0U) && (can_health[can_number].last_error != 7U)) {
can_health[can_number].last_stored_error = can_health[can_number].last_error;
}
can_health[can_number].receive_error_cnt = ((esr_reg & CAN_ESR_REC) >> CAN_ESR_REC_Pos);
can_health[can_number].transmit_error_cnt = ((esr_reg & CAN_ESR_TEC) >> CAN_ESR_TEC_Pos);
can_health[can_number].irq0_call_rate = interrupts[can_irq_number[can_number][0]].call_rate;
can_health[can_number].irq1_call_rate = interrupts[can_irq_number[can_number][1]].call_rate;
can_health[can_number].irq2_call_rate = interrupts[can_irq_number[can_number][2]].call_rate;
if (ir_reg != 0U) {
can_health[can_number].total_error_cnt += 1U;
// RX message lost due to FIFO overrun
if ((CANx->RF0R & (CAN_RF0R_FOVR0)) != 0) {
can_health[can_number].total_rx_lost_cnt += 1U;
CANx->RF0R &= ~(CAN_RF0R_FOVR0);
}
can_health[can_number].can_core_reset_cnt += 1U;
llcan_clear_send(CANx);
}
}
// ***************************** CAN *****************************
// CANx_SCE IRQ Handler
void can_sce(uint8_t can_number) {
update_can_health_pkt(can_number, 1U);
}
// CANx_TX IRQ Handler
void process_can(uint8_t can_number) {
if (can_number != 0xffU) {
ENTER_CRITICAL();
CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
// check for empty mailbox
CANPacket_t to_send;
if ((CANx->TSR & (CAN_TSR_TERR0 | CAN_TSR_ALST0)) != 0) { // last TX failed due to error arbitration lost
can_health[can_number].total_tx_lost_cnt += 1U;
CANx->TSR |= (CAN_TSR_TERR0 | CAN_TSR_ALST0);
}
if ((CANx->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
// add successfully transmitted message to my fifo
if ((CANx->TSR & CAN_TSR_RQCP0) == CAN_TSR_RQCP0) {
if ((CANx->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) {
CANPacket_t to_push;
to_push.returned = 1U;
to_push.rejected = 0U;
to_push.extended = (CANx->sTxMailBox[0].TIR >> 2) & 0x1U;
to_push.addr = (to_push.extended != 0U) ? (CANx->sTxMailBox[0].TIR >> 3) : (CANx->sTxMailBox[0].TIR >> 21);
to_push.data_len_code = CANx->sTxMailBox[0].TDTR & 0xFU;
to_push.bus = bus_number;
WORD_TO_BYTE_ARRAY(&to_push.data[0], CANx->sTxMailBox[0].TDLR);
WORD_TO_BYTE_ARRAY(&to_push.data[4], CANx->sTxMailBox[0].TDHR);
can_set_checksum(&to_push);
rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U;
}
// clear interrupt
// careful, this can also be cleared by requesting a transmission
CANx->TSR |= CAN_TSR_RQCP0;
}
if (can_pop(can_queues[bus_number], &to_send)) {
if (can_check_checksum(&to_send)) {
can_health[can_number].total_tx_cnt += 1U;
// only send if we have received a packet
CANx->sTxMailBox[0].TIR = ((to_send.extended != 0U) ? (to_send.addr << 3) : (to_send.addr << 21)) | (to_send.extended << 2);
CANx->sTxMailBox[0].TDTR = to_send.data_len_code;
BYTE_ARRAY_TO_WORD(CANx->sTxMailBox[0].TDLR, &to_send.data[0]);
BYTE_ARRAY_TO_WORD(CANx->sTxMailBox[0].TDHR, &to_send.data[4]);
// Send request TXRQ
CANx->sTxMailBox[0].TIR |= 0x1U;
} else {
can_health[can_number].total_tx_checksum_error_cnt += 1U;
}
refresh_can_tx_slots_available();
}
}
EXIT_CRITICAL();
}
}
// CANx_RX0 IRQ Handler
// blink blue when we are receiving CAN messages
void can_rx(uint8_t can_number) {
CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
while ((CANx->RF0R & CAN_RF0R_FMP0) != 0) {
can_health[can_number].total_rx_cnt += 1U;
// can is live
pending_can_live = 1;
// add to my fifo
CANPacket_t to_push;
to_push.returned = 0U;
to_push.rejected = 0U;
to_push.extended = (CANx->sFIFOMailBox[0].RIR >> 2) & 0x1U;
to_push.addr = (to_push.extended != 0U) ? (CANx->sFIFOMailBox[0].RIR >> 3) : (CANx->sFIFOMailBox[0].RIR >> 21);
to_push.data_len_code = CANx->sFIFOMailBox[0].RDTR & 0xFU;
to_push.bus = bus_number;
WORD_TO_BYTE_ARRAY(&to_push.data[0], CANx->sFIFOMailBox[0].RDLR);
WORD_TO_BYTE_ARRAY(&to_push.data[4], CANx->sFIFOMailBox[0].RDHR);
can_set_checksum(&to_push);
// forwarding (panda only)
int bus_fwd_num = safety_fwd_hook(bus_number, to_push.addr);
if (bus_fwd_num != -1) {
CANPacket_t to_send;
to_send.returned = 0U;
to_send.rejected = 0U;
to_send.extended = to_push.extended; // TXRQ
to_send.addr = to_push.addr;
to_send.bus = to_push.bus;
to_send.data_len_code = to_push.data_len_code;
(void)memcpy(to_send.data, to_push.data, dlc_to_len[to_push.data_len_code]);
can_set_checksum(&to_send);
can_send(&to_send, bus_fwd_num, true);
can_health[can_number].total_fwd_cnt += 1U;
}
safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U;
ignition_can_hook(&to_push);
current_board->set_led(LED_BLUE, true);
rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U;
// next
CANx->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_TX_IRQ_Handler(void) { process_can(0); }
void CAN1_RX0_IRQ_Handler(void) { can_rx(0); }
void CAN1_SCE_IRQ_Handler(void) { can_sce(0); }
void CAN2_TX_IRQ_Handler(void) { process_can(1); }
void CAN2_RX0_IRQ_Handler(void) { can_rx(1); }
void CAN2_SCE_IRQ_Handler(void) { can_sce(1); }
void CAN3_TX_IRQ_Handler(void) { process_can(2); }
void CAN3_RX0_IRQ_Handler(void) { can_rx(2); }
void CAN3_SCE_IRQ_Handler(void) { can_sce(2); }
bool can_init(uint8_t can_number) {
bool ret = false;
REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1)
REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1)
REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1)
REGISTER_INTERRUPT(CAN2_TX_IRQn, CAN2_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2)
REGISTER_INTERRUPT(CAN2_RX0_IRQn, CAN2_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2)
REGISTER_INTERRUPT(CAN2_SCE_IRQn, CAN2_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2)
REGISTER_INTERRUPT(CAN3_TX_IRQn, CAN3_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3)
REGISTER_INTERRUPT(CAN3_RX0_IRQn, CAN3_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3)
REGISTER_INTERRUPT(CAN3_SCE_IRQn, CAN3_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3)
if (can_number != 0xffU) {
CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number);
ret &= can_set_speed(can_number);
ret &= llcan_init(CANx);
// in case there are queued up messages
process_can(can_number);
}
return ret;
}

View File

@@ -0,0 +1,295 @@
typedef struct {
volatile uint32_t w_ptr;
volatile uint32_t r_ptr;
uint32_t fifo_size;
CANPacket_t *elems;
} can_ring;
typedef struct {
uint8_t bus_lookup;
uint8_t can_num_lookup;
int8_t forwarding_bus;
uint32_t can_speed;
uint32_t can_data_speed;
bool canfd_enabled;
bool brs_enabled;
bool canfd_non_iso;
} bus_config_t;
uint32_t safety_tx_blocked = 0;
uint32_t safety_rx_invalid = 0;
uint32_t tx_buffer_overflow = 0;
uint32_t rx_buffer_overflow = 0;
uint32_t gmlan_send_errs = 0;
can_health_t can_health[] = {{0}, {0}, {0}};
extern int can_live;
extern int pending_can_live;
// must reinit after changing these
extern int can_silent;
extern bool can_loopback;
// Ignition detected from CAN meessages
bool ignition_can = false;
uint32_t ignition_can_cnt = 0U;
#define ALL_CAN_SILENT 0xFF
#define ALL_CAN_LIVE 0
int can_live = 0;
int pending_can_live = 0;
int can_silent = ALL_CAN_SILENT;
bool can_loopback = false;
// ******************* functions prototypes *********************
bool can_init(uint8_t can_number);
void process_can(uint8_t can_number);
// ********************* instantiate queues *********************
#define can_buffer(x, size) \
CANPacket_t elems_##x[size]; \
can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CANPacket_t *)&(elems_##x) };
#define CAN_RX_BUFFER_SIZE 4096U
#define CAN_TX_BUFFER_SIZE 416U
#define GMLAN_TX_BUFFER_SIZE 416U
#ifdef STM32H7
// ITCM RAM and DTCM RAM are the fastest for Cortex-M7 core access
__attribute__((section(".axisram"))) can_buffer(rx_q, CAN_RX_BUFFER_SIZE)
__attribute__((section(".itcmram"))) can_buffer(tx1_q, CAN_TX_BUFFER_SIZE)
__attribute__((section(".itcmram"))) can_buffer(tx2_q, CAN_TX_BUFFER_SIZE)
#else
can_buffer(rx_q, CAN_RX_BUFFER_SIZE)
can_buffer(tx1_q, CAN_TX_BUFFER_SIZE)
can_buffer(tx2_q, CAN_TX_BUFFER_SIZE)
#endif
can_buffer(tx3_q, CAN_TX_BUFFER_SIZE)
can_buffer(txgmlan_q, GMLAN_TX_BUFFER_SIZE)
// FIXME:
// cppcheck-suppress misra-c2012-9.3
can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q};
// helpers
#define WORD_TO_BYTE_ARRAY(dst8, src32) 0[dst8] = ((src32) & 0xFFU); 1[dst8] = (((src32) >> 8U) & 0xFFU); 2[dst8] = (((src32) >> 16U) & 0xFFU); 3[dst8] = (((src32) >> 24U) & 0xFFU)
#define BYTE_ARRAY_TO_WORD(dst32, src8) ((dst32) = 0[src8] | (1[src8] << 8U) | (2[src8] << 16U) | (3[src8] << 24U))
// ********************* interrupt safe queue *********************
bool can_pop(can_ring *q, CANPacket_t *elem) {
bool ret = 0;
ENTER_CRITICAL();
if (q->w_ptr != q->r_ptr) {
*elem = q->elems[q->r_ptr];
if ((q->r_ptr + 1U) == q->fifo_size) {
q->r_ptr = 0;
} else {
q->r_ptr += 1U;
}
ret = 1;
}
EXIT_CRITICAL();
return ret;
}
bool can_push(can_ring *q, const CANPacket_t *elem) {
bool ret = false;
uint32_t next_w_ptr;
ENTER_CRITICAL();
if ((q->w_ptr + 1U) == q->fifo_size) {
next_w_ptr = 0;
} else {
next_w_ptr = q->w_ptr + 1U;
}
if (next_w_ptr != q->r_ptr) {
q->elems[q->w_ptr] = *elem;
q->w_ptr = next_w_ptr;
ret = true;
}
EXIT_CRITICAL();
if (!ret) {
#ifdef DEBUG
print("can_push to ");
if (q == &can_rx_q) {
print("can_rx_q");
} else if (q == &can_tx1_q) {
print("can_tx1_q");
} else if (q == &can_tx2_q) {
print("can_tx2_q");
} else if (q == &can_tx3_q) {
print("can_tx3_q");
} else if (q == &can_txgmlan_q) {
print("can_txgmlan_q");
} else {
print("unknown");
}
print(" failed!\n");
#endif
}
return ret;
}
uint32_t can_slots_empty(const can_ring *q) {
uint32_t ret = 0;
ENTER_CRITICAL();
if (q->w_ptr >= q->r_ptr) {
ret = q->fifo_size - 1U - q->w_ptr + q->r_ptr;
} else {
ret = q->r_ptr - q->w_ptr - 1U;
}
EXIT_CRITICAL();
return ret;
}
void can_clear(can_ring *q) {
ENTER_CRITICAL();
q->w_ptr = 0;
q->r_ptr = 0;
EXIT_CRITICAL();
// handle TX buffer full with zero ECUs awake on the bus
refresh_can_tx_slots_available();
}
// assign CAN numbering
// bus num: Can bus number on ODB connector. Sent to/from USB
// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1)
// cans: Look up MCU can interface from bus number
// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc);
// bus_lookup: Translates from 'can number' to 'bus number'.
// can_num_lookup: Translates from 'bus number' to 'can number'.
// forwarding bus: If >= 0, forward all messages from this bus to the specified bus.
// Helpers
// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3
bus_config_t bus_config[] = {
{ .bus_lookup = 0U, .can_num_lookup = 0U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false },
{ .bus_lookup = 1U, .can_num_lookup = 1U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false },
{ .bus_lookup = 2U, .can_num_lookup = 2U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false },
{ .bus_lookup = 0xFFU, .can_num_lookup = 0xFFU, .forwarding_bus = -1, .can_speed = 333U, .can_data_speed = 333U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false },
};
#define CANIF_FROM_CAN_NUM(num) (cans[num])
#define BUS_NUM_FROM_CAN_NUM(num) (bus_config[num].bus_lookup)
#define CAN_NUM_FROM_BUS_NUM(num) (bus_config[num].can_num_lookup)
void can_init_all(void) {
bool ret = true;
for (uint8_t i=0U; i < PANDA_CAN_CNT; i++) {
if (!current_board->has_canfd) {
bus_config[i].can_data_speed = 0U;
}
can_clear(can_queues[i]);
ret &= can_init(i);
}
UNUSED(ret);
}
void can_flip_buses(uint8_t bus1, uint8_t bus2){
bus_config[bus1].bus_lookup = bus2;
bus_config[bus2].bus_lookup = bus1;
bus_config[bus1].can_num_lookup = bus2;
bus_config[bus2].can_num_lookup = bus1;
}
void can_set_forwarding(uint8_t from, uint8_t to) {
bus_config[from].forwarding_bus = to;
}
void ignition_can_hook(CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
int len = GET_LEN(to_push);
if (bus == 0) {
// GM exception
if ((addr == 0x1F1) && (len == 8)) {
// SystemPowerMode (2=Run, 3=Crank Request)
ignition_can = (GET_BYTE(to_push, 0) & 0x2U) != 0U;
ignition_can_cnt = 0U;
}
// Tesla exception
if ((addr == 0x348) && (len == 8)) {
// GTW_status
ignition_can = (GET_BYTE(to_push, 0) & 0x1U) != 0U;
ignition_can_cnt = 0U;
}
// Mazda exception
if ((addr == 0x9E) && (len == 8)) {
ignition_can = (GET_BYTE(to_push, 0) >> 5) == 0x6U;
ignition_can_cnt = 0U;
}
} else if (bus == 2) {
// GM exception, SDGM cars have this message on bus 2
if ((addr == 0x1F1) && (len == 8)) {
// SystemPowerMode (2=Run, 3=Crank Request)
ignition_can = (GET_BYTE(to_push, 0) & 0x2U) != 0U;
ignition_can_cnt = 0U;
}
}
}
bool can_tx_check_min_slots_free(uint32_t min) {
return
(can_slots_empty(&can_tx1_q) >= min) &&
(can_slots_empty(&can_tx2_q) >= min) &&
(can_slots_empty(&can_tx3_q) >= min) &&
(can_slots_empty(&can_txgmlan_q) >= min);
}
uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) {
uint8_t checksum = 0U;
for (uint32_t i = 0U; i < len; i++) {
checksum ^= dat[i];
}
return checksum;
}
void can_set_checksum(CANPacket_t *packet) {
packet->checksum = 0U;
packet->checksum = calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet));
}
bool can_check_checksum(CANPacket_t *packet) {
return (calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)) == 0U);
}
void can_send(CANPacket_t *to_push, uint8_t bus_number, bool skip_tx_hook) {
if (skip_tx_hook || safety_tx_hook(to_push) != 0) {
if (bus_number < PANDA_BUS_CNT) {
// add CAN packet to send queue
if ((bus_number == 3U) && (bus_config[3].can_num_lookup == 0xFFU)) {
gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U;
} else {
tx_buffer_overflow += can_push(can_queues[bus_number], to_push) ? 0U : 1U;
process_can(CAN_NUM_FROM_BUS_NUM(bus_number));
}
}
} else {
safety_tx_blocked += 1U;
to_push->returned = 0U;
to_push->rejected = 1U;
// data changed
can_set_checksum(to_push);
rx_buffer_overflow += can_push(&can_rx_q, to_push) ? 0U : 1U;
}
}
bool is_speed_valid(uint32_t speed, const uint32_t *all_speeds, uint8_t len) {
bool ret = false;
for (uint8_t i = 0U; i < len; i++) {
if (all_speeds[i] == speed) {
ret = true;
}
}
return ret;
}

View File

@@ -0,0 +1,37 @@
#define CLOCK_SOURCE_PERIOD_MS 50U
#define CLOCK_SOURCE_PULSE_LEN_MS 2U
void clock_source_set_period(uint8_t period) {
register_set(&(TIM1->ARR), ((period*10U) - 1U), 0xFFFFU);
}
void clock_source_init(void) {
// Setup timer
register_set(&(TIM1->PSC), ((APB2_TIMER_FREQ*100U)-1U), 0xFFFFU); // Tick on 0.1 ms
register_set(&(TIM1->ARR), ((CLOCK_SOURCE_PERIOD_MS*10U) - 1U), 0xFFFFU); // Period
register_set(&(TIM1->CCMR1), 0U, 0xFFFFU); // No output on compare
register_set(&(TIM1->CCER), TIM_CCER_CC1E, 0xFFFFU); // Enable compare 1
register_set(&(TIM1->CCR1), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value
register_set(&(TIM1->CCR2), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value
register_set(&(TIM1->CCR3), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value
register_set_bits(&(TIM1->DIER), TIM_DIER_UIE | TIM_DIER_CC1IE); // Enable interrupts
register_set(&(TIM1->CR1), TIM_CR1_CEN, 0x3FU); // Enable timer
// No interrupts
NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn);
NVIC_DisableIRQ(TIM1_CC_IRQn);
// Set GPIO as timer channels
set_gpio_alternate(GPIOB, 14, GPIO_AF1_TIM1);
set_gpio_alternate(GPIOB, 15, GPIO_AF1_TIM1);
// Set PWM mode
register_set(&(TIM1->CCMR1), (0b110 << TIM_CCMR1_OC2M_Pos), 0xFFFFU);
register_set(&(TIM1->CCMR2), (0b110 << TIM_CCMR2_OC3M_Pos), 0xFFFFU);
// Enable output
register_set(&(TIM1->BDTR), TIM_BDTR_MOE, 0xFFFFU);
// Enable complementary compares
register_set_bits(&(TIM1->CCER), TIM_CCER_CC2NE | TIM_CCER_CC3NE);
}

View File

@@ -0,0 +1,76 @@
#include "stm32h7/lli2c.h"
#define CODEC_I2C_ADDR 0x10
// 1Vpp sine wave with 1V offset
const uint8_t fake_siren_lut[360] = { 134U, 135U, 137U, 138U, 139U, 140U, 141U, 143U, 144U, 145U, 146U, 148U, 149U, 150U, 151U, 152U, 154U, 155U, 156U, 157U, 158U, 159U, 160U, 162U, 163U, 164U, 165U, 166U, 167U, 168U, 169U, 170U, 171U, 172U, 174U, 175U, 176U, 177U, 177U, 178U, 179U, 180U, 181U, 182U, 183U, 184U, 185U, 186U, 186U, 187U, 188U, 189U, 190U, 190U, 191U, 192U, 193U, 193U, 194U, 195U, 195U, 196U, 196U, 197U, 197U, 198U, 199U, 199U, 199U, 200U, 200U, 201U, 201U, 202U, 202U, 202U, 203U, 203U, 203U, 203U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 205U, 205U, 205U, 205U, 205U, 205U, 205U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 203U, 203U, 203U, 203U, 202U, 202U, 202U, 201U, 201U, 200U, 200U, 199U, 199U, 199U, 198U, 197U, 197U, 196U, 196U, 195U, 195U, 194U, 193U, 193U, 192U, 191U, 190U, 190U, 189U, 188U, 187U, 186U, 186U, 185U, 184U, 183U, 182U, 181U, 180U, 179U, 178U, 177U, 177U, 176U, 175U, 174U, 172U, 171U, 170U, 169U, 168U, 167U, 166U, 165U, 164U, 163U, 162U, 160U, 159U, 158U, 157U, 156U, 155U, 154U, 152U, 151U, 150U, 149U, 148U, 146U, 145U, 144U, 143U, 141U, 140U, 139U, 138U, 137U, 135U, 134U, 133U, 132U, 130U, 129U, 128U, 127U, 125U, 124U, 123U, 122U, 121U, 119U, 118U, 117U, 116U, 115U, 113U, 112U, 111U, 110U, 109U, 108U, 106U, 105U, 104U, 103U, 102U, 101U, 100U, 99U, 98U, 97U, 96U, 95U, 94U, 93U, 92U, 91U, 90U, 89U, 88U, 87U, 86U, 85U, 84U, 83U, 82U, 82U, 81U, 80U, 79U, 78U, 78U, 77U, 76U, 76U, 75U, 74U, 74U, 73U, 72U, 72U, 71U, 71U, 70U, 70U, 69U, 69U, 68U, 68U, 67U, 67U, 67U, 66U, 66U, 66U, 65U, 65U, 65U, 65U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 63U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 65U, 65U, 65U, 65U, 66U, 66U, 66U, 67U, 67U, 67U, 68U, 68U, 69U, 69U, 70U, 70U, 71U, 71U, 72U, 72U, 73U, 74U, 74U, 75U, 76U, 76U, 77U, 78U, 78U, 79U, 80U, 81U, 82U, 82U, 83U, 84U, 85U, 86U, 87U, 88U, 89U, 90U, 91U, 92U, 93U, 94U, 95U, 96U, 97U, 98U, 99U, 100U, 101U, 102U, 103U, 104U, 105U, 106U, 108U, 109U, 110U, 111U, 112U, 113U, 115U, 116U, 117U, 118U, 119U, 121U, 122U, 123U, 124U, 125U, 127U, 128U, 129U, 130U, 132U, 133U };
bool fake_siren_enabled = false;
void fake_siren_codec_enable(bool enabled) {
if (enabled) {
bool success = true;
success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x2B, (1U << 1)); // Left speaker mix from INA1
success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x2C, (1U << 1)); // Right speaker mix from INA1
success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x3D, 0x17, 0b11111); // Left speaker volume
success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x3E, 0x17, 0b11111); // Right speaker volume
success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x37, 0b101, 0b111); // INA gain
success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x4C, (1U << 7)); // Enable INA
success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x51, (1U << 7)); // Disable global shutdown
if (!success) {
print("Siren codec enable failed\n");
fault_occurred(FAULT_SIREN_MALFUNCTION);
}
} else {
// Disable INA input. Make sure to retry a few times if the I2C bus is busy.
for (uint8_t i=0U; i<10U; i++) {
if (i2c_clear_reg_bits(I2C5, CODEC_I2C_ADDR, 0x4C, (1U << 7))) {
break;
}
}
}
}
void fake_siren_set(bool enabled) {
if (enabled != fake_siren_enabled) {
fake_siren_codec_enable(enabled);
}
if (enabled) {
register_set_bits(&DMA1_Stream1->CR, DMA_SxCR_EN);
} else {
register_clear_bits(&DMA1_Stream1->CR, DMA_SxCR_EN);
}
fake_siren_enabled = enabled;
}
void fake_siren_init(void) {
// Init DAC
register_set(&DAC1->MCR, 0U, 0xFFFFFFFFU);
register_set(&DAC1->CR, DAC_CR_TEN1 | (6U << DAC_CR_TSEL1_Pos) | DAC_CR_DMAEN1, 0xFFFFFFFFU);
register_set_bits(&DAC1->CR, DAC_CR_EN1);
// Setup DMAMUX (DAC_CH1_DMA as input)
register_set(&DMAMUX1_Channel1->CCR, 67U, DMAMUX_CxCR_DMAREQ_ID_Msk);
// Setup DMA
register_set(&DMA1_Stream1->M0AR, (uint32_t) fake_siren_lut, 0xFFFFFFFFU);
register_set(&DMA1_Stream1->PAR, (uint32_t) &(DAC1->DHR8R1), 0xFFFFFFFFU);
DMA1_Stream1->NDTR = sizeof(fake_siren_lut);
register_set(&DMA1_Stream1->FCR, 0U, 0x00000083U);
DMA1_Stream1->CR = (0b11 << DMA_SxCR_PL_Pos);
DMA1_Stream1->CR |= DMA_SxCR_MINC | DMA_SxCR_CIRC | (1 << DMA_SxCR_DIR_Pos);
// Init trigger timer (around 2.5kHz)
register_set(&TIM7->PSC, 0U, 0xFFFFU);
register_set(&TIM7->ARR, 133U, 0xFFFFU);
register_set(&TIM7->CR2, (0b10 << TIM_CR2_MMS_Pos), TIM_CR2_MMS_Msk);
register_set(&TIM7->CR1, TIM_CR1_ARPE | TIM_CR1_URS, 0x088EU);
TIM7->SR = 0U;
TIM7->CR1 |= TIM_CR1_CEN;
// Enable the I2C to the codec
i2c_init(I2C5);
fake_siren_codec_enable(false);
}

95
panda/board/drivers/fan.h Normal file
View File

@@ -0,0 +1,95 @@
struct fan_state_t {
uint16_t tach_counter;
uint16_t rpm;
uint16_t target_rpm;
uint8_t power;
float error_integral;
uint8_t stall_counter;
uint8_t stall_threshold;
uint8_t total_stall_count;
uint8_t cooldown_counter;
} fan_state_t;
struct fan_state_t fan_state;
const float FAN_I = 0.001f;
const uint8_t FAN_TICK_FREQ = 8U;
const uint8_t FAN_STALL_THRESHOLD_MIN = 3U;
const uint8_t FAN_STALL_THRESHOLD_MAX = 8U;
void fan_set_power(uint8_t percentage) {
fan_state.target_rpm = ((current_board->fan_max_rpm * CLAMP(percentage, 0U, 100U)) / 100U);
}
void llfan_init(void);
void fan_init(void) {
fan_state.stall_threshold = FAN_STALL_THRESHOLD_MIN;
fan_state.cooldown_counter = current_board->fan_enable_cooldown_time * FAN_TICK_FREQ;
llfan_init();
}
// Call this at FAN_TICK_FREQ
void fan_tick(void) {
if (current_board->fan_max_rpm > 0U) {
// Measure fan RPM
uint16_t fan_rpm_fast = fan_state.tach_counter * (60U * FAN_TICK_FREQ / 4U); // 4 interrupts per rotation
fan_state.tach_counter = 0U;
fan_state.rpm = (fan_rpm_fast + (3U * fan_state.rpm)) / 4U;
// Stall detection
bool fan_stalled = false;
if (current_board->fan_stall_recovery) {
if (fan_state.target_rpm > 0U) {
if (fan_rpm_fast == 0U) {
fan_state.stall_counter = MIN(fan_state.stall_counter + 1U, 255U);
} else {
fan_state.stall_counter = 0U;
}
if (fan_state.stall_counter > (fan_state.stall_threshold*FAN_TICK_FREQ)) {
fan_stalled = true;
fan_state.stall_counter = 0U;
fan_state.stall_threshold = CLAMP(fan_state.stall_threshold + 2U, FAN_STALL_THRESHOLD_MIN, FAN_STALL_THRESHOLD_MAX);
fan_state.total_stall_count += 1U;
// datasheet gives this range as the minimum startup duty
fan_state.error_integral = CLAMP(fan_state.error_integral, 20.0f, 45.0f);
}
} else {
fan_state.stall_counter = 0U;
fan_state.stall_threshold = FAN_STALL_THRESHOLD_MIN;
}
}
#ifdef DEBUG_FAN
puth(fan_state.target_rpm);
print(" "); puth(fan_rpm_fast);
print(" "); puth(fan_state.power);
print(" "); puth(fan_state.stall_counter);
print("\n");
#endif
// Cooldown counter
if (fan_state.target_rpm > 0U) {
fan_state.cooldown_counter = current_board->fan_enable_cooldown_time * FAN_TICK_FREQ;
} else {
if (fan_state.cooldown_counter > 0U) {
fan_state.cooldown_counter--;
}
}
// Update controller
if (fan_state.target_rpm == 0U) {
fan_state.error_integral = 0.0f;
} else {
float error = fan_state.target_rpm - fan_rpm_fast;
fan_state.error_integral += FAN_I * error;
}
fan_state.power = CLAMP(fan_state.error_integral, 0U, 100U);
// Set PWM and enable line
pwm_set(TIM3, 3, fan_state.power);
current_board->set_fan_enabled(!fan_stalled && ((fan_state.target_rpm > 0U) || (fan_state.cooldown_counter > 0U)));
}
}

267
panda/board/drivers/fdcan.h Normal file
View File

@@ -0,0 +1,267 @@
// IRQs: FDCAN1_IT0, FDCAN1_IT1
// FDCAN2_IT0, FDCAN2_IT1
// FDCAN3_IT0, FDCAN3_IT1
#define CANFD
typedef struct {
volatile uint32_t header[2];
volatile uint32_t data_word[CANPACKET_DATA_SIZE_MAX/4U];
} canfd_fifo;
FDCAN_GlobalTypeDef *cans[] = {FDCAN1, FDCAN2, FDCAN3};
uint8_t can_irq_number[3][2] = {
{ FDCAN1_IT0_IRQn, FDCAN1_IT1_IRQn },
{ FDCAN2_IT0_IRQn, FDCAN2_IT1_IRQn },
{ FDCAN3_IT0_IRQn, FDCAN3_IT1_IRQn },
};
#define CAN_ACK_ERROR 3U
bool can_set_speed(uint8_t can_number) {
bool ret = true;
FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
ret &= llcan_set_speed(
FDCANx,
bus_config[bus_number].can_speed,
bus_config[bus_number].can_data_speed,
bus_config[bus_number].canfd_non_iso,
can_loopback,
(unsigned int)(can_silent) & (1U << can_number)
);
return ret;
}
void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) {
FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number);
uint32_t psr_reg = FDCANx->PSR;
uint32_t ecr_reg = FDCANx->ECR;
can_health[can_number].bus_off = ((psr_reg & FDCAN_PSR_BO) >> FDCAN_PSR_BO_Pos);
can_health[can_number].bus_off_cnt += can_health[can_number].bus_off;
can_health[can_number].error_warning = ((psr_reg & FDCAN_PSR_EW) >> FDCAN_PSR_EW_Pos);
can_health[can_number].error_passive = ((psr_reg & FDCAN_PSR_EP) >> FDCAN_PSR_EP_Pos);
can_health[can_number].last_error = ((psr_reg & FDCAN_PSR_LEC) >> FDCAN_PSR_LEC_Pos);
if ((can_health[can_number].last_error != 0U) && (can_health[can_number].last_error != 7U)) {
can_health[can_number].last_stored_error = can_health[can_number].last_error;
}
can_health[can_number].last_data_error = ((psr_reg & FDCAN_PSR_DLEC) >> FDCAN_PSR_DLEC_Pos);
if ((can_health[can_number].last_data_error != 0U) && (can_health[can_number].last_data_error != 7U)) {
can_health[can_number].last_data_stored_error = can_health[can_number].last_data_error;
}
can_health[can_number].receive_error_cnt = ((ecr_reg & FDCAN_ECR_REC) >> FDCAN_ECR_REC_Pos);
can_health[can_number].transmit_error_cnt = ((ecr_reg & FDCAN_ECR_TEC) >> FDCAN_ECR_TEC_Pos);
can_health[can_number].irq0_call_rate = interrupts[can_irq_number[can_number][0]].call_rate;
can_health[can_number].irq1_call_rate = interrupts[can_irq_number[can_number][1]].call_rate;
if (ir_reg != 0U) {
// Clear error interrupts
FDCANx->IR |= (FDCAN_IR_PED | FDCAN_IR_PEA | FDCAN_IR_EP | FDCAN_IR_BO | FDCAN_IR_RF0L);
can_health[can_number].total_error_cnt += 1U;
// Check for RX FIFO overflow
if ((ir_reg & (FDCAN_IR_RF0L)) != 0) {
can_health[can_number].total_rx_lost_cnt += 1U;
}
// Cases:
// 1. while multiplexing between buses 1 and 3 we are getting ACK errors that overwhelm CAN core, by resetting it recovers faster
// 2. H7 gets stuck in bus off recovery state indefinitely
if ((((can_health[can_number].last_error == CAN_ACK_ERROR) || (can_health[can_number].last_data_error == CAN_ACK_ERROR)) && (can_health[can_number].transmit_error_cnt > 127U)) ||
((ir_reg & FDCAN_IR_BO) != 0)) {
can_health[can_number].can_core_reset_cnt += 1U;
can_health[can_number].total_tx_lost_cnt += (FDCAN_TX_FIFO_EL_CNT - (FDCANx->TXFQS & FDCAN_TXFQS_TFFL)); // TX FIFO msgs will be lost after reset
llcan_clear_send(FDCANx);
}
}
}
// ***************************** CAN *****************************
// FDFDCANx_IT1 IRQ Handler (TX)
void process_can(uint8_t can_number) {
if (can_number != 0xffU) {
ENTER_CRITICAL();
FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
FDCANx->IR |= FDCAN_IR_TFE; // Clear Tx FIFO Empty flag
if ((FDCANx->TXFQS & FDCAN_TXFQS_TFQF) == 0) {
CANPacket_t to_send;
if (can_pop(can_queues[bus_number], &to_send)) {
if (can_check_checksum(&to_send)) {
can_health[can_number].total_tx_cnt += 1U;
uint32_t TxFIFOSA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET) + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE);
// get the index of the next TX FIFO element (0 to FDCAN_TX_FIFO_EL_CNT - 1)
uint32_t tx_index = (FDCANx->TXFQS >> FDCAN_TXFQS_TFQPI_Pos) & 0x1F;
// only send if we have received a packet
canfd_fifo *fifo;
fifo = (canfd_fifo *)(TxFIFOSA + (tx_index * FDCAN_TX_FIFO_EL_SIZE));
fifo->header[0] = (to_send.extended << 30) | ((to_send.extended != 0U) ? (to_send.addr) : (to_send.addr << 18));
uint32_t canfd_enabled_header = bus_config[can_number].canfd_enabled ? (1UL << 21) : 0UL;
uint32_t brs_enabled_header = bus_config[can_number].brs_enabled ? (1UL << 20) : 0UL;
fifo->header[1] = (to_send.data_len_code << 16) | canfd_enabled_header | brs_enabled_header;
uint8_t data_len_w = (dlc_to_len[to_send.data_len_code] / 4U);
data_len_w += ((dlc_to_len[to_send.data_len_code] % 4U) > 0U) ? 1U : 0U;
for (unsigned int i = 0; i < data_len_w; i++) {
BYTE_ARRAY_TO_WORD(fifo->data_word[i], &to_send.data[i*4U]);
}
FDCANx->TXBAR = (1UL << tx_index);
// Send back to USB
CANPacket_t to_push;
to_push.returned = 1U;
to_push.rejected = 0U;
to_push.extended = to_send.extended;
to_push.addr = to_send.addr;
to_push.bus = bus_number;
to_push.data_len_code = to_send.data_len_code;
(void)memcpy(to_push.data, to_send.data, dlc_to_len[to_push.data_len_code]);
can_set_checksum(&to_push);
rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U;
} else {
can_health[can_number].total_tx_checksum_error_cnt += 1U;
}
refresh_can_tx_slots_available();
}
}
EXIT_CRITICAL();
}
}
// FDFDCANx_IT0 IRQ Handler (RX and errors)
// blink blue when we are receiving CAN messages
void can_rx(uint8_t can_number) {
FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
uint32_t ir_reg = FDCANx->IR;
// Clear all new messages from Rx FIFO 0
FDCANx->IR |= FDCAN_IR_RF0N;
while((FDCANx->RXF0S & FDCAN_RXF0S_F0FL) != 0) {
can_health[can_number].total_rx_cnt += 1U;
// can is live
pending_can_live = 1;
// get the index of the next RX FIFO element (0 to FDCAN_RX_FIFO_0_EL_CNT - 1)
uint32_t rx_fifo_idx = (uint8_t)((FDCANx->RXF0S >> FDCAN_RXF0S_F0GI_Pos) & 0x3F);
// Recommended to offset get index by at least +1 if RX FIFO is in overwrite mode and full (datasheet)
if((FDCANx->RXF0S & FDCAN_RXF0S_F0F) == FDCAN_RXF0S_F0F) {
rx_fifo_idx = ((rx_fifo_idx + 1U) >= FDCAN_RX_FIFO_0_EL_CNT) ? 0U : (rx_fifo_idx + 1U);
can_health[can_number].total_rx_lost_cnt += 1U; // At least one message was lost
}
uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET);
CANPacket_t to_push;
canfd_fifo *fifo;
// getting address
fifo = (canfd_fifo *)(RxFIFO0SA + (rx_fifo_idx * FDCAN_RX_FIFO_0_EL_SIZE));
to_push.returned = 0U;
to_push.rejected = 0U;
to_push.extended = (fifo->header[0] >> 30) & 0x1U;
to_push.addr = ((to_push.extended != 0U) ? (fifo->header[0] & 0x1FFFFFFFU) : ((fifo->header[0] >> 18) & 0x7FFU));
to_push.bus = bus_number;
to_push.data_len_code = ((fifo->header[1] >> 16) & 0xFU);
bool canfd_frame = ((fifo->header[1] >> 21) & 0x1U);
bool brs_frame = ((fifo->header[1] >> 20) & 0x1U);
uint8_t data_len_w = (dlc_to_len[to_push.data_len_code] / 4U);
data_len_w += ((dlc_to_len[to_push.data_len_code] % 4U) > 0U) ? 1U : 0U;
for (unsigned int i = 0; i < data_len_w; i++) {
WORD_TO_BYTE_ARRAY(&to_push.data[i*4U], fifo->data_word[i]);
}
can_set_checksum(&to_push);
// forwarding (panda only)
int bus_fwd_num = safety_fwd_hook(bus_number, to_push.addr);
if (bus_fwd_num < 0) {
bus_fwd_num = bus_config[can_number].forwarding_bus;
}
if (bus_fwd_num != -1) {
CANPacket_t to_send;
to_send.returned = 0U;
to_send.rejected = 0U;
to_send.extended = to_push.extended;
to_send.addr = to_push.addr;
to_send.bus = to_push.bus;
to_send.data_len_code = to_push.data_len_code;
(void)memcpy(to_send.data, to_push.data, dlc_to_len[to_push.data_len_code]);
can_set_checksum(&to_send);
can_send(&to_send, bus_fwd_num, true);
can_health[can_number].total_fwd_cnt += 1U;
}
safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U;
ignition_can_hook(&to_push);
current_board->set_led(LED_BLUE, true);
rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U;
// Enable CAN FD and BRS if CAN FD message was received
if (!(bus_config[can_number].canfd_enabled) && (canfd_frame)) {
bus_config[can_number].canfd_enabled = true;
}
if (!(bus_config[can_number].brs_enabled) && (brs_frame)) {
bus_config[can_number].brs_enabled = true;
}
// update read index
FDCANx->RXF0A = rx_fifo_idx;
}
// Error handling
if ((ir_reg & (FDCAN_IR_PED | FDCAN_IR_PEA | FDCAN_IR_EP | FDCAN_IR_BO | FDCAN_IR_RF0L)) != 0) {
update_can_health_pkt(can_number, ir_reg);
}
}
void FDCAN1_IT0_IRQ_Handler(void) { can_rx(0); }
void FDCAN1_IT1_IRQ_Handler(void) { process_can(0); }
void FDCAN2_IT0_IRQ_Handler(void) { can_rx(1); }
void FDCAN2_IT1_IRQ_Handler(void) { process_can(1); }
void FDCAN3_IT0_IRQ_Handler(void) { can_rx(2); }
void FDCAN3_IT1_IRQ_Handler(void) { process_can(2); }
bool can_init(uint8_t can_number) {
bool ret = false;
REGISTER_INTERRUPT(FDCAN1_IT0_IRQn, FDCAN1_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1)
REGISTER_INTERRUPT(FDCAN1_IT1_IRQn, FDCAN1_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1)
REGISTER_INTERRUPT(FDCAN2_IT0_IRQn, FDCAN2_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2)
REGISTER_INTERRUPT(FDCAN2_IT1_IRQn, FDCAN2_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2)
REGISTER_INTERRUPT(FDCAN3_IT0_IRQn, FDCAN3_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3)
REGISTER_INTERRUPT(FDCAN3_IT1_IRQn, FDCAN3_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3)
if (can_number != 0xffU) {
FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number);
ret &= can_set_speed(can_number);
ret &= llcan_init(FDCANx);
// in case there are queued up messages
process_can(can_number);
}
return ret;
}

View File

@@ -0,0 +1,270 @@
#define GMLAN_TICKS_PER_SECOND 33300 //1sec @ 33.3kbps
#define GMLAN_TICKS_PER_TIMEOUT_TICKLE 500 //15ms @ 33.3kbps
#define GMLAN_HIGH 0 //0 is high on bus (dominant)
#define GMLAN_LOW 1 //1 is low on bus
#define DISABLED -1
#define BITBANG 0
#define GPIO_SWITCH 1
#define MAX_BITS_CAN_PACKET (200)
int gmlan_alt_mode = DISABLED;
// returns out_len
int do_bitstuff(char *out, const char *in, int in_len) {
int last_bit = -1;
int bit_cnt = 0;
int j = 0;
for (int i = 0; i < in_len; i++) {
char bit = in[i];
out[j] = bit;
j++;
// do the stuffing
if (bit == (char)last_bit) {
bit_cnt++;
if (bit_cnt == 5) {
// 5 in a row the same, do stuff
last_bit = !bit ? 1 : 0;
out[j] = last_bit;
j++;
bit_cnt = 1;
}
} else {
// this is a new bit
last_bit = (int)bit;
bit_cnt = 1;
}
}
return j;
}
int append_crc(char *in, int in_len) {
unsigned int crc = 0;
for (int i = 0; i < in_len; i++) {
crc <<= 1;
if (((unsigned int)(in[i]) ^ ((crc >> 15) & 1U)) != 0U) {
crc = crc ^ 0x4599U;
}
crc &= 0x7fffU;
}
int in_len_copy = in_len;
for (int i = 14; i >= 0; i--) {
in[in_len_copy] = (crc >> (unsigned int)(i)) & 1U;
in_len_copy++;
}
return in_len_copy;
}
int append_bits(char *in, int in_len, const char *app, int app_len) {
int in_len_copy = in_len;
for (int i = 0; i < app_len; i++) {
in[in_len_copy] = app[i];
in_len_copy++;
}
return in_len_copy;
}
int append_int(char *in, int in_len, int val, int val_len) {
int in_len_copy = in_len;
for (int i = val_len - 1; i >= 0; i--) {
in[in_len_copy] = ((unsigned int)(val) & (1U << (unsigned int)(i))) != 0U;
in_len_copy++;
}
return in_len_copy;
}
int get_bit_message(char *out, const CANPacket_t *to_bang) {
char pkt[MAX_BITS_CAN_PACKET];
char footer[] = {
1, // CRC delimiter
1, // ACK
1, // ACK delimiter
1,1,1,1,1,1,1, // EOF
1,1,1, // IFS
};
int len = 0;
// test packet
int dlc_len = GET_LEN(to_bang);
len = append_int(pkt, len, 0, 1); // Start-of-frame
if (to_bang->extended != 0U) {
// extended identifier
len = append_int(pkt, len, GET_ADDR(to_bang) >> 18, 11); // Identifier
len = append_int(pkt, len, 3, 2); // SRR+IDE
len = append_int(pkt, len, (GET_ADDR(to_bang)) & ((1UL << 18) - 1U), 18); // Identifier
len = append_int(pkt, len, 0, 3); // RTR+r1+r0
} else {
// standard identifier
len = append_int(pkt, len, GET_ADDR(to_bang), 11); // Identifier
len = append_int(pkt, len, 0, 3); // RTR+IDE+reserved
}
len = append_int(pkt, len, dlc_len, 4); // Data length code
// append data
for (int i = 0; i < dlc_len; i++) {
len = append_int(pkt, len, to_bang->data[i], 8);
}
// append crc
len = append_crc(pkt, len);
// do bitstuffing
len = do_bitstuff(out, pkt, len);
// append footer
len = append_bits(out, len, footer, sizeof(footer));
return len;
}
void TIM12_IRQ_Handler(void);
void setup_timer(void) {
// register interrupt
REGISTER_INTERRUPT(TIM8_BRK_TIM12_IRQn, TIM12_IRQ_Handler, 40000U, FAULT_INTERRUPT_RATE_GMLAN)
// setup
register_set(&(TIM12->PSC), (APB1_TIMER_FREQ-1U), 0xFFFFU); // Tick on 1 us
register_set(&(TIM12->CR1), TIM_CR1_CEN, 0x3FU); // Enable
register_set(&(TIM12->ARR), (30U-1U), 0xFFFFU); // 33.3 kbps
// in case it's disabled
NVIC_EnableIRQ(TIM8_BRK_TIM12_IRQn);
// run the interrupt
register_set(&(TIM12->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt
TIM12->SR = 0;
}
int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms
int can_timeout_counter = GMLAN_TICKS_PER_SECOND; //1 second
int inverted_bit_to_send = GMLAN_HIGH;
int gmlan_switch_below_timeout = -1;
int gmlan_switch_timeout_enable = 0;
void set_bitbanged_gmlan(int val) {
if (val != 0) {
register_set_bits(&(GPIOB->ODR), (1UL << 13));
} else {
register_clear_bits(&(GPIOB->ODR), (1UL << 13));
}
}
char pkt_stuffed[MAX_BITS_CAN_PACKET];
int gmlan_sending = -1;
int gmlan_sendmax = -1;
bool gmlan_send_ok = true;
int gmlan_silent_count = 0;
int gmlan_fail_count = 0;
#define REQUIRED_SILENT_TIME 10
#define MAX_FAIL_COUNT 10
void TIM12_IRQ_Handler(void) {
if (gmlan_alt_mode == BITBANG) {
if ((TIM12->SR & TIM_SR_UIF) && (gmlan_sendmax != -1)) {
int read = get_gpio_input(GPIOB, 12);
if (gmlan_silent_count < REQUIRED_SILENT_TIME) {
if (read == 0) {
gmlan_silent_count = 0;
} else {
gmlan_silent_count++;
}
} else {
bool retry = 0;
// in send loop
if ((gmlan_sending > 0) && // not first bit
((read == 0) && (pkt_stuffed[gmlan_sending-1] == (char)1)) && // bus wrongly dominant
(gmlan_sending != (gmlan_sendmax - 11))) { //not ack bit
print("GMLAN ERR: bus driven at ");
puth(gmlan_sending);
print("\n");
retry = 1;
} else if ((read == 1) && (gmlan_sending == (gmlan_sendmax - 11))) { // recessive during ACK
print("GMLAN ERR: didn't recv ACK\n");
retry = 1;
} else {
// do not retry
}
if (retry) {
// reset sender (retry after 7 silent)
set_bitbanged_gmlan(1); // recessive
gmlan_silent_count = 0;
gmlan_sending = 0;
gmlan_fail_count++;
if (gmlan_fail_count == MAX_FAIL_COUNT) {
print("GMLAN ERR: giving up send\n");
gmlan_send_ok = false;
}
} else {
set_bitbanged_gmlan(pkt_stuffed[gmlan_sending]);
gmlan_sending++;
}
}
if ((gmlan_sending == gmlan_sendmax) || (gmlan_fail_count == MAX_FAIL_COUNT)) {
set_bitbanged_gmlan(1); // recessive
set_gpio_mode(GPIOB, 13, MODE_INPUT);
register_clear_bits(&(TIM12->DIER), TIM_DIER_UIE); // No update interrupt
register_set(&(TIM12->CR1), 0U, 0x3FU); // Disable timer
gmlan_sendmax = -1; // exit
}
}
} else if (gmlan_alt_mode == GPIO_SWITCH) {
if ((TIM12->SR & TIM_SR_UIF) && (gmlan_switch_below_timeout != -1)) {
if ((can_timeout_counter == 0) && gmlan_switch_timeout_enable) {
//it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output
set_gpio_output(GPIOB, 13, GMLAN_LOW);
gmlan_switch_below_timeout = -1;
gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE;
gmlan_alt_mode = DISABLED;
}
else {
can_timeout_counter--;
if (gmlan_timeout_counter == 0) {
//Send a 1 (bus low) every 15ms to reset the GMLAN transceivers timeout
gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE;
set_gpio_output(GPIOB, 13, GMLAN_LOW);
}
else {
set_gpio_output(GPIOB, 13, inverted_bit_to_send);
gmlan_timeout_counter--;
}
}
}
} else {
// Invalid GMLAN mode. Do not put a print statement here, way too fast to keep up with
}
TIM12->SR = 0;
}
bool bitbang_gmlan(const CANPacket_t *to_bang) {
gmlan_send_ok = true;
gmlan_alt_mode = BITBANG;
#ifdef HW_TYPE_DOS
if (hw_type == HW_TYPE_DOS) {
if (gmlan_sendmax == -1) {
int len = get_bit_message(pkt_stuffed, to_bang);
gmlan_fail_count = 0;
gmlan_silent_count = 0;
gmlan_sending = 0;
gmlan_sendmax = len;
// setup for bitbang loop
set_bitbanged_gmlan(1); // recessive
set_gpio_mode(GPIOB, 13, MODE_OUTPUT);
// 33kbps
setup_timer();
}
}
#else
UNUSED(to_bang);
#endif
return gmlan_send_ok;
}

View File

@@ -0,0 +1,92 @@
#define MODE_INPUT 0
#define MODE_OUTPUT 1
#define MODE_ALTERNATE 2
#define MODE_ANALOG 3
#define PULL_NONE 0
#define PULL_UP 1
#define PULL_DOWN 2
#define OUTPUT_TYPE_PUSH_PULL 0U
#define OUTPUT_TYPE_OPEN_DRAIN 1U
typedef struct {
GPIO_TypeDef *bank;
uint8_t pin;
} gpio_t;
void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
ENTER_CRITICAL();
uint32_t tmp = GPIO->MODER;
tmp &= ~(3U << (pin * 2U));
tmp |= (mode << (pin * 2U));
register_set(&(GPIO->MODER), tmp, 0xFFFFFFFFU);
EXIT_CRITICAL();
}
void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) {
ENTER_CRITICAL();
if (enabled) {
register_set_bits(&(GPIO->ODR), (1UL << pin));
} else {
register_clear_bits(&(GPIO->ODR), (1UL << pin));
}
set_gpio_mode(GPIO, pin, MODE_OUTPUT);
EXIT_CRITICAL();
}
void set_gpio_output_type(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int output_type){
ENTER_CRITICAL();
if(output_type == OUTPUT_TYPE_OPEN_DRAIN) {
register_set_bits(&(GPIO->OTYPER), (1UL << pin));
} else {
register_clear_bits(&(GPIO->OTYPER), (1U << pin));
}
EXIT_CRITICAL();
}
void set_gpio_alternate(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
ENTER_CRITICAL();
uint32_t tmp = GPIO->AFR[pin >> 3U];
tmp &= ~(0xFU << ((pin & 7U) * 4U));
tmp |= mode << ((pin & 7U) * 4U);
register_set(&(GPIO->AFR[pin >> 3]), tmp, 0xFFFFFFFFU);
set_gpio_mode(GPIO, pin, MODE_ALTERNATE);
EXIT_CRITICAL();
}
void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) {
ENTER_CRITICAL();
uint32_t tmp = GPIO->PUPDR;
tmp &= ~(3U << (pin * 2U));
tmp |= (mode << (pin * 2U));
register_set(&(GPIO->PUPDR), tmp, 0xFFFFFFFFU);
EXIT_CRITICAL();
}
int get_gpio_input(const GPIO_TypeDef *GPIO, unsigned int pin) {
return (GPIO->IDR & (1UL << pin)) == (1UL << pin);
}
void gpio_set_all_output(const gpio_t *pins, uint8_t num_pins, bool enabled) {
for (uint8_t i = 0; i < num_pins; i++) {
set_gpio_output(pins[i].bank, pins[i].pin, enabled);
}
}
void gpio_set_bitmask(const gpio_t *pins, uint8_t num_pins, uint32_t bitmask) {
for (uint8_t i = 0; i < num_pins; i++) {
set_gpio_output(pins[i].bank, pins[i].pin, (bitmask >> i) & 1U);
}
}
// Detection with internal pullup
#define PULL_EFFECTIVE_DELAY 4096
bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) {
set_gpio_mode(GPIO, pin, MODE_INPUT);
set_gpio_pullup(GPIO, pin, mode);
for (volatile int i=0; i<PULL_EFFECTIVE_DELAY; i++);
bool ret = get_gpio_input(GPIO, pin);
set_gpio_pullup(GPIO, pin, PULL_NONE);
return ret;
}

View File

@@ -0,0 +1,135 @@
#define HARNESS_STATUS_NC 0U
#define HARNESS_STATUS_NORMAL 1U
#define HARNESS_STATUS_FLIPPED 2U
struct harness_t {
uint8_t status;
uint16_t sbu1_voltage_mV;
uint16_t sbu2_voltage_mV;
bool relay_driven;
bool sbu_adc_lock;
};
struct harness_t harness;
struct harness_configuration {
const bool has_harness;
GPIO_TypeDef *GPIO_SBU1;
GPIO_TypeDef *GPIO_SBU2;
GPIO_TypeDef *GPIO_relay_SBU1;
GPIO_TypeDef *GPIO_relay_SBU2;
uint8_t pin_SBU1;
uint8_t pin_SBU2;
uint8_t pin_relay_SBU1;
uint8_t pin_relay_SBU2;
uint8_t adc_channel_SBU1;
uint8_t adc_channel_SBU2;
};
// The ignition relay is only used for testing purposes
void set_intercept_relay(bool intercept, bool ignition_relay) {
if (current_board->harness_config->has_harness) {
bool drive_relay = intercept;
if (harness.status == HARNESS_STATUS_NC) {
// no harness, no relay to drive
drive_relay = false;
}
if (drive_relay || ignition_relay) {
harness.relay_driven = true;
}
// wait until we're not reading the analog voltages anymore
while (harness.sbu_adc_lock) {}
if (harness.status == HARNESS_STATUS_NORMAL) {
set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, !ignition_relay);
set_gpio_output(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, !drive_relay);
} else {
set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, !drive_relay);
set_gpio_output(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, !ignition_relay);
}
if (!(drive_relay || ignition_relay)) {
harness.relay_driven = false;
}
}
}
bool harness_check_ignition(void) {
bool ret = false;
// wait until we're not reading the analog voltages anymore
while (harness.sbu_adc_lock) {}
switch(harness.status){
case HARNESS_STATUS_NORMAL:
ret = !get_gpio_input(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1);
break;
case HARNESS_STATUS_FLIPPED:
ret = !get_gpio_input(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2);
break;
default:
break;
}
return ret;
}
uint8_t harness_detect_orientation(void) {
uint8_t ret = harness.status;
#ifndef BOOTSTUB
// We can't detect orientation if the relay is being driven
if (!harness.relay_driven && current_board->harness_config->has_harness) {
harness.sbu_adc_lock = true;
set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_ANALOG);
set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_ANALOG);
harness.sbu1_voltage_mV = adc_get_mV(current_board->harness_config->adc_channel_SBU1);
harness.sbu2_voltage_mV = adc_get_mV(current_board->harness_config->adc_channel_SBU2);
uint16_t detection_threshold = current_board->avdd_mV / 2U;
// Detect connection and orientation
if((harness.sbu1_voltage_mV < detection_threshold) || (harness.sbu2_voltage_mV < detection_threshold)){
if (harness.sbu1_voltage_mV < harness.sbu2_voltage_mV) {
// orientation flipped (PANDA_SBU1->HARNESS_SBU1(relay), PANDA_SBU2->HARNESS_SBU2(ign))
ret = HARNESS_STATUS_FLIPPED;
} else {
// orientation normal (PANDA_SBU2->HARNESS_SBU1(relay), PANDA_SBU1->HARNESS_SBU2(ign))
// (SBU1->SBU2 is the normal orientation connection per USB-C cable spec)
ret = HARNESS_STATUS_NORMAL;
}
} else {
ret = HARNESS_STATUS_NC;
}
// Pins are not 5V tolerant in ADC mode
set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_INPUT);
set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_INPUT);
harness.sbu_adc_lock = false;
}
#endif
return ret;
}
void harness_tick(void) {
harness.status = harness_detect_orientation();
}
void harness_init(void) {
// delay such that the connection is fully made before trying orientation detection
current_board->set_led(LED_BLUE, true);
delay(10000000);
current_board->set_led(LED_BLUE, false);
// try to detect orientation
harness.status = harness_detect_orientation();
if (harness.status != HARNESS_STATUS_NC) {
print("detected car harness with orientation "); puth2(harness.status); print("\n");
} else {
print("failed to detect car harness!\n");
}
// keep buses connected by default
set_intercept_relay(false, false);
}

View File

@@ -0,0 +1,99 @@
typedef struct interrupt {
IRQn_Type irq_type;
void (*handler)(void);
uint32_t call_counter;
uint32_t call_rate;
uint32_t max_call_rate; // Call rate is defined as the amount of calls each second
uint32_t call_rate_fault;
} interrupt;
void interrupt_timer_init(void);
uint32_t microsecond_timer_get(void);
void unused_interrupt_handler(void) {
// Something is wrong if this handler is called!
print("Unused interrupt handler called!\n");
fault_occurred(FAULT_UNUSED_INTERRUPT_HANDLED);
}
interrupt interrupts[NUM_INTERRUPTS];
#define REGISTER_INTERRUPT(irq_num, func_ptr, call_rate_max, rate_fault) \
interrupts[irq_num].irq_type = (irq_num); \
interrupts[irq_num].handler = (func_ptr); \
interrupts[irq_num].call_counter = 0U; \
interrupts[irq_num].call_rate = 0U; \
interrupts[irq_num].max_call_rate = (call_rate_max); \
interrupts[irq_num].call_rate_fault = (rate_fault);
bool check_interrupt_rate = false;
uint8_t interrupt_depth = 0U;
uint32_t last_time = 0U;
uint32_t idle_time = 0U;
uint32_t busy_time = 0U;
float interrupt_load = 0.0f;
void handle_interrupt(IRQn_Type irq_type){
ENTER_CRITICAL();
if (interrupt_depth == 0U) {
uint32_t time = microsecond_timer_get();
idle_time += get_ts_elapsed(time, last_time);
last_time = time;
}
interrupt_depth += 1U;
EXIT_CRITICAL();
interrupts[irq_type].call_counter++;
interrupts[irq_type].handler();
// Check that the interrupts don't fire too often
if (check_interrupt_rate && (interrupts[irq_type].call_counter > interrupts[irq_type].max_call_rate)) {
fault_occurred(interrupts[irq_type].call_rate_fault);
}
ENTER_CRITICAL();
interrupt_depth -= 1U;
if (interrupt_depth == 0U) {
uint32_t time = microsecond_timer_get();
busy_time += get_ts_elapsed(time, last_time);
last_time = time;
}
EXIT_CRITICAL();
}
// Every second
void interrupt_timer_handler(void) {
if (INTERRUPT_TIMER->SR != 0) {
for (uint16_t i = 0U; i < NUM_INTERRUPTS; i++) {
// Log IRQ call rate faults
if (check_interrupt_rate && (interrupts[i].call_counter > interrupts[i].max_call_rate)) {
print("Interrupt 0x"); puth(i); print(" fired too often (0x"); puth(interrupts[i].call_counter); print("/s)!\n");
}
// Reset interrupt counters
interrupts[i].call_rate = interrupts[i].call_counter;
interrupts[i].call_counter = 0U;
}
// Calculate interrupt load
// The bootstub does not have the FPU enabled, so can't do float operations.
#if !defined(BOOTSTUB)
interrupt_load = ((busy_time + idle_time) > 0U) ? ((float) (((float) busy_time) / (busy_time + idle_time))) : 0.0f;
#endif
idle_time = 0U;
busy_time = 0U;
}
INTERRUPT_TIMER->SR = 0;
}
void init_interrupts(bool check_rate_limit){
check_interrupt_rate = check_rate_limit;
for(uint16_t i=0U; i<NUM_INTERRUPTS; i++){
interrupts[i].handler = unused_interrupt_handler;
}
// Init interrupt timer for a 1s interval
interrupt_timer_init();
}

56
panda/board/drivers/pwm.h Normal file
View File

@@ -0,0 +1,56 @@
#define PWM_COUNTER_OVERFLOW 2000U // To get ~50kHz
// TODO: Implement for 32-bit timers
void pwm_init(TIM_TypeDef *TIM, uint8_t channel){
// Enable timer and auto-reload
register_set(&(TIM->CR1), TIM_CR1_CEN | TIM_CR1_ARPE, 0x3FU);
// Set channel as PWM mode 1 and enable output
switch(channel){
case 1U:
register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE));
register_set_bits(&(TIM->CCER), TIM_CCER_CC1E);
break;
case 2U:
register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE));
register_set_bits(&(TIM->CCER), TIM_CCER_CC2E);
break;
case 3U:
register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE));
register_set_bits(&(TIM->CCER), TIM_CCER_CC3E);
break;
case 4U:
register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4PE));
register_set_bits(&(TIM->CCER), TIM_CCER_CC4E);
break;
default:
break;
}
// Set max counter value
register_set(&(TIM->ARR), PWM_COUNTER_OVERFLOW, 0xFFFFU);
// Update registers and clear counter
TIM->EGR |= TIM_EGR_UG;
}
void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){
uint16_t comp_value = (((uint16_t) percentage * PWM_COUNTER_OVERFLOW) / 100U);
switch(channel){
case 1U:
register_set(&(TIM->CCR1), comp_value, 0xFFFFU);
break;
case 2U:
register_set(&(TIM->CCR2), comp_value, 0xFFFFU);
break;
case 3U:
register_set(&(TIM->CCR3), comp_value, 0xFFFFU);
break;
case 4U:
register_set(&(TIM->CCR4), comp_value, 0xFFFFU);
break;
default:
break;
}
}

View File

@@ -0,0 +1,81 @@
typedef struct reg {
volatile uint32_t *address;
uint32_t value;
uint32_t check_mask;
} reg;
// 10 bit hash with 23 as a prime
#define REGISTER_MAP_SIZE 0x3FFU
#define HASHING_PRIME 23U
#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != (addr)))
reg register_map[REGISTER_MAP_SIZE];
// Hash spread in first and second iterations seems to be reasonable.
// See: tests/development/register_hashmap_spread.py
// Also, check the collision warnings in the debug output, and minimize those.
uint16_t hash_addr(uint32_t input){
return (((input >> 16U) ^ ((((input + 1U) & 0xFFFFU) * HASHING_PRIME) & 0xFFFFU)) & REGISTER_MAP_SIZE);
}
// Do not put bits in the check mask that get changed by the hardware
void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask){
ENTER_CRITICAL()
// Set bits in register that are also in the mask
(*addr) = ((*addr) & (~mask)) | (val & mask);
// Add these values to the map
uint16_t hash = hash_addr((uint32_t) addr);
uint16_t tries = REGISTER_MAP_SIZE;
while(CHECK_COLLISION(hash, addr) && (tries > 0U)) { hash = hash_addr((uint32_t) hash); tries--;}
if (tries != 0U){
register_map[hash].address = addr;
register_map[hash].value = (register_map[hash].value & (~mask)) | (val & mask);
register_map[hash].check_mask |= mask;
} else {
#ifdef DEBUG_FAULTS
print("Hash collision: address 0x"); puth((uint32_t) addr); print("!\n");
#endif
}
EXIT_CRITICAL()
}
// Set individual bits. Also add them to the check_mask.
// Do not use this to change bits that get reset by the hardware
void register_set_bits(volatile uint32_t *addr, uint32_t val) {
return register_set(addr, val, val);
}
// Clear individual bits. Also add them to the check_mask.
// Do not use this to clear bits that get set by the hardware
void register_clear_bits(volatile uint32_t *addr, uint32_t val) {
return register_set(addr, (~val), val);
}
// To be called periodically
void check_registers(void){
for(uint16_t i=0U; i<REGISTER_MAP_SIZE; i++){
if((uint32_t) register_map[i].address != 0U){
ENTER_CRITICAL()
if((*(register_map[i].address) & register_map[i].check_mask) != (register_map[i].value & register_map[i].check_mask)){
#ifdef DEBUG_FAULTS
print("Register at address 0x"); puth((uint32_t) register_map[i].address); print(" is divergent!");
print(" Map: 0x"); puth(register_map[i].value);
print(" Register: 0x"); puth(*(register_map[i].address));
print(" Mask: 0x"); puth(register_map[i].check_mask);
print("\n");
#endif
fault_occurred(FAULT_REGISTER_DIVERGENT);
}
EXIT_CRITICAL()
}
}
}
void init_registers(void) {
for(uint16_t i=0U; i<REGISTER_MAP_SIZE; i++){
register_map[i].address = (volatile uint32_t *) 0U;
register_map[i].check_mask = 0U;
}
}

View File

@@ -0,0 +1,26 @@
typedef struct simple_watchdog_state_t {
uint32_t fault;
uint32_t last_ts;
uint32_t threshold;
} simple_watchdog_state_t;
simple_watchdog_state_t wd_state;
void simple_watchdog_kick(void) {
uint32_t ts = microsecond_timer_get();
uint32_t et = get_ts_elapsed(ts, wd_state.last_ts);
if (et > wd_state.threshold) {
print("WD timeout 0x"); puth(et); print("\n");
fault_occurred(wd_state.fault);
}
wd_state.last_ts = ts;
}
void simple_watchdog_init(uint32_t fault, uint32_t threshold) {
wd_state.fault = fault;
wd_state.threshold = threshold;
wd_state.last_ts = microsecond_timer_get();
}

258
panda/board/drivers/spi.h Normal file
View File

@@ -0,0 +1,258 @@
#pragma once
#include "crc.h"
#define SPI_TIMEOUT_US 10000U
// got max rate from hitting a non-existent endpoint
// in a tight loop, plus some buffer
#define SPI_IRQ_RATE 16000U
#ifdef STM32H7
#define SPI_BUF_SIZE 2048U
// H7 DMA2 located in D2 domain, so we need to use SRAM1/SRAM2
__attribute__((section(".sram12"))) uint8_t spi_buf_rx[SPI_BUF_SIZE];
__attribute__((section(".sram12"))) uint8_t spi_buf_tx[SPI_BUF_SIZE];
#else
#define SPI_BUF_SIZE 1024U
uint8_t spi_buf_rx[SPI_BUF_SIZE];
uint8_t spi_buf_tx[SPI_BUF_SIZE];
#endif
#define SPI_CHECKSUM_START 0xABU
#define SPI_SYNC_BYTE 0x5AU
#define SPI_HACK 0x79U
#define SPI_DACK 0x85U
#define SPI_NACK 0x1FU
// SPI states
enum {
SPI_STATE_HEADER,
SPI_STATE_HEADER_ACK,
SPI_STATE_HEADER_NACK,
SPI_STATE_DATA_RX,
SPI_STATE_DATA_RX_ACK,
SPI_STATE_DATA_TX
};
bool spi_tx_dma_done = false;
uint8_t spi_state = SPI_STATE_HEADER;
uint8_t spi_endpoint;
uint16_t spi_data_len_mosi;
uint16_t spi_data_len_miso;
uint16_t spi_checksum_error_count = 0;
bool spi_can_tx_ready = false;
const char version_text[] = "VERSION";
#define SPI_HEADER_SIZE 7U
// low level SPI prototypes
void llspi_init(void);
void llspi_mosi_dma(uint8_t *addr, int len);
void llspi_miso_dma(uint8_t *addr, int len);
void can_tx_comms_resume_spi(void) {
spi_can_tx_ready = true;
}
uint16_t spi_version_packet(uint8_t *out) {
// this protocol version request is a stable portion of
// the panda's SPI protocol. its contents match that of the
// panda USB descriptors and are sufficent to list/enumerate
// a panda, determine panda type, and bootstub status.
// the response is:
// VERSION + 2 byte data length + data + CRC8
// echo "VERSION"
(void)memcpy(out, version_text, 7);
// write response
uint16_t data_len = 0;
uint16_t data_pos = 7U + 2U;
// write serial
#ifdef UID_BASE
(void)memcpy(&out[data_pos], ((uint8_t *)UID_BASE), 12);
data_len += 12U;
#endif
// HW type
out[data_pos + data_len] = hw_type;
data_len += 1U;
// bootstub
out[data_pos + data_len] = USB_PID & 0xFFU;
data_len += 1U;
// SPI protocol version
out[data_pos + data_len] = 0x2;
data_len += 1U;
// data length
out[7] = data_len & 0xFFU;
out[8] = (data_len >> 8) & 0xFFU;
// CRC8
uint16_t resp_len = data_pos + data_len;
out[resp_len] = crc_checksum(out, resp_len, 0xD5U);
resp_len += 1U;
return resp_len;
}
void spi_init(void) {
// platform init
llspi_init();
// Start the first packet!
spi_state = SPI_STATE_HEADER;
llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE);
}
bool validate_checksum(const uint8_t *data, uint16_t len) {
// TODO: can speed this up by casting the bulk to uint32_t and xor-ing the bytes afterwards
uint8_t checksum = SPI_CHECKSUM_START;
for(uint16_t i = 0U; i < len; i++){
checksum ^= data[i];
}
return checksum == 0U;
}
void spi_rx_done(void) {
uint16_t response_len = 0U;
uint8_t next_rx_state = SPI_STATE_HEADER_NACK;
bool checksum_valid = false;
// parse header
spi_endpoint = spi_buf_rx[1];
spi_data_len_mosi = (spi_buf_rx[3] << 8) | spi_buf_rx[2];
spi_data_len_miso = (spi_buf_rx[5] << 8) | spi_buf_rx[4];
if (memcmp(spi_buf_rx, version_text, 7) == 0) {
response_len = spi_version_packet(spi_buf_tx);
next_rx_state = SPI_STATE_HEADER_NACK;;
} else if (spi_state == SPI_STATE_HEADER) {
checksum_valid = validate_checksum(spi_buf_rx, SPI_HEADER_SIZE);
if ((spi_buf_rx[0] == SPI_SYNC_BYTE) && checksum_valid) {
// response: ACK and start receiving data portion
spi_buf_tx[0] = SPI_HACK;
next_rx_state = SPI_STATE_HEADER_ACK;
response_len = 1U;
} else {
// response: NACK and reset state machine
print("- incorrect header sync or checksum "); hexdump(spi_buf_rx, SPI_HEADER_SIZE);
spi_buf_tx[0] = SPI_NACK;
next_rx_state = SPI_STATE_HEADER_NACK;
response_len = 1U;
}
} else if (spi_state == SPI_STATE_DATA_RX) {
// We got everything! Based on the endpoint specified, call the appropriate handler
bool response_ack = false;
checksum_valid = validate_checksum(&(spi_buf_rx[SPI_HEADER_SIZE]), spi_data_len_mosi + 1U);
if (checksum_valid) {
if (spi_endpoint == 0U) {
if (spi_data_len_mosi >= sizeof(ControlPacket_t)) {
ControlPacket_t ctrl;
(void)memcpy(&ctrl, &spi_buf_rx[SPI_HEADER_SIZE], sizeof(ControlPacket_t));
response_len = comms_control_handler(&ctrl, &spi_buf_tx[3]);
response_ack = true;
} else {
print("SPI: insufficient data for control handler\n");
}
} else if ((spi_endpoint == 1U) || (spi_endpoint == 0x81U)) {
if (spi_data_len_mosi == 0U) {
response_len = comms_can_read(&(spi_buf_tx[3]), spi_data_len_miso);
response_ack = true;
} else {
print("SPI: did not expect data for can_read\n");
}
} else if (spi_endpoint == 2U) {
comms_endpoint2_write(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi);
response_ack = true;
} else if (spi_endpoint == 3U) {
if (spi_data_len_mosi > 0U) {
if (spi_can_tx_ready) {
spi_can_tx_ready = false;
comms_can_write(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi);
response_ack = true;
} else {
response_ack = false;
print("SPI: CAN NACK\n");
}
} else {
print("SPI: did expect data for can_write\n");
}
} else {
print("SPI: unexpected endpoint"); puth(spi_endpoint); print("\n");
}
} else {
// Checksum was incorrect
response_ack = false;
print("- incorrect data checksum ");
puth4(spi_data_len_mosi);
print("\n");
hexdump(spi_buf_rx, SPI_HEADER_SIZE);
hexdump(&(spi_buf_rx[SPI_HEADER_SIZE]), MIN(spi_data_len_mosi, 64));
print("\n");
}
if (!response_ack) {
spi_buf_tx[0] = SPI_NACK;
next_rx_state = SPI_STATE_HEADER_NACK;
response_len = 1U;
} else {
// Setup response header
spi_buf_tx[0] = SPI_DACK;
spi_buf_tx[1] = response_len & 0xFFU;
spi_buf_tx[2] = (response_len >> 8) & 0xFFU;
// Add checksum
uint8_t checksum = SPI_CHECKSUM_START;
for(uint16_t i = 0U; i < (response_len + 3U); i++) {
checksum ^= spi_buf_tx[i];
}
spi_buf_tx[response_len + 3U] = checksum;
response_len += 4U;
next_rx_state = SPI_STATE_DATA_TX;
}
} else {
print("SPI: RX unexpected state: "); puth(spi_state); print("\n");
}
// send out response
if (response_len == 0U) {
print("SPI: no response\n");
spi_buf_tx[0] = SPI_NACK;
spi_state = SPI_STATE_HEADER_NACK;
response_len = 1U;
}
llspi_miso_dma(spi_buf_tx, response_len);
spi_state = next_rx_state;
if (!checksum_valid && (spi_checksum_error_count < __UINT16_MAX__)) {
spi_checksum_error_count += 1U;
}
}
void spi_tx_done(bool reset) {
if ((spi_state == SPI_STATE_HEADER_NACK) || reset) {
// Reset state
spi_state = SPI_STATE_HEADER;
llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE);
} else if (spi_state == SPI_STATE_HEADER_ACK) {
// ACK was sent, queue up the RX buf for the data + checksum
spi_state = SPI_STATE_DATA_RX;
llspi_mosi_dma(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi + 1U);
} else if (spi_state == SPI_STATE_DATA_TX) {
// Reset state
spi_state = SPI_STATE_HEADER;
llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE);
} else {
spi_state = SPI_STATE_HEADER;
llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE);
print("SPI: TX unexpected state: "); puth(spi_state); print("\n");
}
}

View File

@@ -0,0 +1,31 @@
void timer_init(TIM_TypeDef *TIM, int psc) {
register_set(&(TIM->PSC), (psc-1), 0xFFFFU);
register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU);
register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU);
TIM->SR = 0;
}
void microsecond_timer_init(void) {
MICROSECOND_TIMER->PSC = (APB1_TIMER_FREQ - 1U);
MICROSECOND_TIMER->CR1 = TIM_CR1_CEN;
MICROSECOND_TIMER->EGR = TIM_EGR_UG;
}
uint32_t microsecond_timer_get(void) {
return MICROSECOND_TIMER->CNT;
}
void interrupt_timer_init(void) {
enable_interrupt_timer();
REGISTER_INTERRUPT(INTERRUPT_TIMER_IRQ, interrupt_timer_handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS)
register_set(&(INTERRUPT_TIMER->PSC), ((uint16_t)(15.25*APB1_TIMER_FREQ)-1U), 0xFFFFU);
register_set(&(INTERRUPT_TIMER->DIER), TIM_DIER_UIE, 0x5F5FU);
register_set(&(INTERRUPT_TIMER->CR1), TIM_CR1_CEN, 0x3FU);
INTERRUPT_TIMER->SR = 0;
NVIC_EnableIRQ(INTERRUPT_TIMER_IRQ);
}
void tick_timer_init(void) {
timer_init(TICK_TIMER, (uint16_t)((15.25*APB2_TIMER_FREQ)/8U));
NVIC_EnableIRQ(TICK_TIMER_IRQ);
}

196
panda/board/drivers/uart.h Normal file
View File

@@ -0,0 +1,196 @@
// IRQs: USART2, USART3, UART5
// ***************************** Definitions *****************************
#define FIFO_SIZE_INT 0x400U
typedef struct uart_ring {
volatile uint16_t w_ptr_tx;
volatile uint16_t r_ptr_tx;
uint8_t *elems_tx;
uint32_t tx_fifo_size;
volatile uint16_t w_ptr_rx;
volatile uint16_t r_ptr_rx;
uint8_t *elems_rx;
uint32_t rx_fifo_size;
USART_TypeDef *uart;
void (*callback)(struct uart_ring*);
bool overwrite;
} uart_ring;
#define UART_BUFFER(x, size_rx, size_tx, uart_ptr, callback_ptr, overwrite_mode) \
uint8_t elems_rx_##x[size_rx]; \
uint8_t elems_tx_##x[size_tx]; \
uart_ring uart_ring_##x = { \
.w_ptr_tx = 0, \
.r_ptr_tx = 0, \
.elems_tx = ((uint8_t *)&(elems_tx_##x)), \
.tx_fifo_size = (size_tx), \
.w_ptr_rx = 0, \
.r_ptr_rx = 0, \
.elems_rx = ((uint8_t *)&(elems_rx_##x)), \
.rx_fifo_size = (size_rx), \
.uart = (uart_ptr), \
.callback = (callback_ptr), \
.overwrite = (overwrite_mode) \
};
// ***************************** Function prototypes *****************************
void debug_ring_callback(uart_ring *ring);
void uart_tx_ring(uart_ring *q);
void uart_send_break(uart_ring *u);
// ******************************** UART buffers ********************************
// debug = USART2
UART_BUFFER(debug, FIFO_SIZE_INT, FIFO_SIZE_INT, USART2, debug_ring_callback, true)
// SOM debug = UART7
#ifdef STM32H7
UART_BUFFER(som_debug, FIFO_SIZE_INT, FIFO_SIZE_INT, UART7, NULL, true)
#else
// UART7 is not available on F4
UART_BUFFER(som_debug, 1U, 1U, NULL, NULL, true)
#endif
uart_ring *get_ring_by_number(int a) {
uart_ring *ring = NULL;
switch(a) {
case 0:
ring = &uart_ring_debug;
break;
case 4:
ring = &uart_ring_som_debug;
break;
default:
ring = NULL;
break;
}
return ring;
}
// ************************* Low-level buffer functions *************************
bool get_char(uart_ring *q, char *elem) {
bool ret = false;
ENTER_CRITICAL();
if (q->w_ptr_rx != q->r_ptr_rx) {
if (elem != NULL) *elem = q->elems_rx[q->r_ptr_rx];
q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size;
ret = true;
}
EXIT_CRITICAL();
return ret;
}
bool injectc(uart_ring *q, char elem) {
int ret = false;
uint16_t next_w_ptr;
ENTER_CRITICAL();
next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size;
if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) {
// overwrite mode: drop oldest byte
q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size;
}
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = elem;
q->w_ptr_rx = next_w_ptr;
ret = true;
}
EXIT_CRITICAL();
return ret;
}
bool put_char(uart_ring *q, char elem) {
bool ret = false;
uint16_t next_w_ptr;
ENTER_CRITICAL();
next_w_ptr = (q->w_ptr_tx + 1U) % q->tx_fifo_size;
if ((next_w_ptr == q->r_ptr_tx) && q->overwrite) {
// overwrite mode: drop oldest byte
q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size;
}
if (next_w_ptr != q->r_ptr_tx) {
q->elems_tx[q->w_ptr_tx] = elem;
q->w_ptr_tx = next_w_ptr;
ret = true;
}
EXIT_CRITICAL();
uart_tx_ring(q);
return ret;
}
void clear_uart_buff(uart_ring *q) {
ENTER_CRITICAL();
q->w_ptr_tx = 0;
q->r_ptr_tx = 0;
q->w_ptr_rx = 0;
q->r_ptr_rx = 0;
EXIT_CRITICAL();
}
// ************************ High-level debug functions **********************
void putch(const char a) {
// misra-c2012-17.7: serial debug function, ok to ignore output
(void)injectc(&uart_ring_debug, a);
}
void print(const char *a) {
for (const char *in = a; *in; in++) {
if (*in == '\n') putch('\r');
putch(*in);
}
}
void putui(uint32_t i) {
uint32_t i_copy = i;
char str[11];
uint8_t idx = 10;
str[idx] = '\0';
idx--;
do {
str[idx] = (i_copy % 10U) + 0x30U;
idx--;
i_copy /= 10;
} while (i_copy != 0U);
print(&str[idx + 1U]);
}
void puthx(uint32_t i, uint8_t len) {
const char c[] = "0123456789abcdef";
for (int pos = ((int)len * 4) - 4; pos > -4; pos -= 4) {
putch(c[(i >> (unsigned int)(pos)) & 0xFU]);
}
}
void puth(unsigned int i) {
puthx(i, 8U);
}
void puth2(unsigned int i) {
puthx(i, 2U);
}
void puth4(unsigned int i) {
puthx(i, 4U);
}
void hexdump(const void *a, int l) {
if (a != NULL) {
for (int i=0; i < l; i++) {
if ((i != 0) && ((i & 0xf) == 0)) print("\n");
puth2(((const unsigned char*)a)[i]);
print(" ");
}
}
print("\n");
}

943
panda/board/drivers/usb.h Normal file
View File

@@ -0,0 +1,943 @@
// IRQs: OTG_FS
typedef union {
uint16_t w;
struct BW {
uint8_t msb;
uint8_t lsb;
}
bw;
}
uint16_t_uint8_t;
typedef union _USB_Setup {
uint32_t d8[2];
struct _SetupPkt_Struc
{
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t_uint8_t wValue;
uint16_t_uint8_t wIndex;
uint16_t_uint8_t wLength;
} b;
}
USB_Setup_TypeDef;
bool usb_enumerated = false;
uint16_t usb_last_frame_num = 0U;
void usb_init(void);
void refresh_can_tx_slots_available(void);
// **** supporting defines ****
#define USB_REQ_GET_STATUS 0x00
#define USB_REQ_CLEAR_FEATURE 0x01
#define USB_REQ_SET_FEATURE 0x03
#define USB_REQ_SET_ADDRESS 0x05
#define USB_REQ_GET_DESCRIPTOR 0x06
#define USB_REQ_SET_DESCRIPTOR 0x07
#define USB_REQ_GET_CONFIGURATION 0x08
#define USB_REQ_SET_CONFIGURATION 0x09
#define USB_REQ_GET_INTERFACE 0x0A
#define USB_REQ_SET_INTERFACE 0x0B
#define USB_REQ_SYNCH_FRAME 0x0C
#define USB_DESC_TYPE_DEVICE 0x01
#define USB_DESC_TYPE_CONFIGURATION 0x02
#define USB_DESC_TYPE_STRING 0x03
#define USB_DESC_TYPE_INTERFACE 0x04
#define USB_DESC_TYPE_ENDPOINT 0x05
#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06
#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07
#define USB_DESC_TYPE_BINARY_OBJECT_STORE 0x0f
// offsets for configuration strings
#define STRING_OFFSET_LANGID 0x00
#define STRING_OFFSET_IMANUFACTURER 0x01
#define STRING_OFFSET_IPRODUCT 0x02
#define STRING_OFFSET_ISERIAL 0x03
#define STRING_OFFSET_ICONFIGURATION 0x04
#define STRING_OFFSET_IINTERFACE 0x05
// WebUSB requests
#define WEBUSB_REQ_GET_URL 0x02
// WebUSB types
#define WEBUSB_DESC_TYPE_URL 0x03
#define WEBUSB_URL_SCHEME_HTTPS 0x01
#define WEBUSB_URL_SCHEME_HTTP 0x00
// WinUSB requests
#define WINUSB_REQ_GET_COMPATID_DESCRIPTOR 0x04
#define WINUSB_REQ_GET_EXT_PROPS_OS 0x05
#define WINUSB_REQ_GET_DESCRIPTOR 0x07
#define STS_GOUT_NAK 1
#define STS_DATA_UPDT 2
#define STS_XFER_COMP 3
#define STS_SETUP_COMP 4
#define STS_SETUP_UPDT 6
uint8_t response[USBPACKET_MAX_SIZE];
// for the repeating interfaces
#define DSCR_INTERFACE_LEN 9
#define DSCR_ENDPOINT_LEN 7
#define DSCR_CONFIG_LEN 9
#define DSCR_DEVICE_LEN 18
// endpoint types
#define ENDPOINT_TYPE_CONTROL 0
#define ENDPOINT_TYPE_ISO 1
#define ENDPOINT_TYPE_BULK 2
#define ENDPOINT_TYPE_INT 3
// These are arbitrary values used in bRequest
#define MS_VENDOR_CODE 0x20
#define WEBUSB_VENDOR_CODE 0x30
// BOS constants
#define BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH 0x05
#define BINARY_OBJECT_STORE_DESCRIPTOR 0x0F
#define WINUSB_PLATFORM_DESCRIPTOR_LENGTH 0x9E
// Convert machine byte order to USB byte order
#define TOUSBORDER(num)\
((num) & 0xFFU), (((uint16_t)(num) >> 8) & 0xFFU)
// take in string length and return the first 2 bytes of a string descriptor
#define STRING_DESCRIPTOR_HEADER(size)\
(((((size) * 2) + 2) & 0xFF) | 0x0300)
uint8_t device_desc[] = {
DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type
0x10, 0x02, // bcdUSB max version of USB supported (2.1)
0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size
TOUSBORDER(USB_VID), // idVendor
TOUSBORDER(USB_PID), // idProduct
0x00, 0x00, // bcdDevice
0x01, 0x02, // Manufacturer, Product
0x03, 0x01 // Serial Number, Num Configurations
};
uint8_t device_qualifier[] = {
0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type
0x10, 0x02, // bcdUSB max version of USB supported (2.1)
0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0
0x01, 0x00 // bNumConfigurations, bReserved
};
#define ENDPOINT_RCV 0x80
#define ENDPOINT_SND 0x00
uint8_t configuration_desc[] = {
DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type,
TOUSBORDER(0x0045U), // Total Len (uint16)
0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration
0xc0, 0x32, // Attributes, Max Power
// interface 0 ALT 0
DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type
0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
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(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(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
// interface 0 ALT 1
DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type
0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type
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(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(0x0040U), // Max Packet (0x0040)
0x00, // Polling Interval
};
// STRING_DESCRIPTOR_HEADER is for uint16 string descriptors
// it takes in a string length, which is bytes/2 because unicode
uint16_t string_language_desc[] = {
STRING_DESCRIPTOR_HEADER(1),
0x0409 // american english
};
// these strings are all uint16's so that we don't need to spam ,0 after every character
uint16_t string_manufacturer_desc[] = {
STRING_DESCRIPTOR_HEADER(8),
'c', 'o', 'm', 'm', 'a', '.', 'a', 'i'
};
uint16_t string_product_desc[] = {
STRING_DESCRIPTOR_HEADER(5),
'p', 'a', 'n', 'd', 'a'
};
// default serial number when we're not a panda
uint16_t string_serial_desc[] = {
STRING_DESCRIPTOR_HEADER(4),
'n', 'o', 'n', 'e'
};
// a string containing the default configuration index
uint16_t string_configuration_desc[] = {
STRING_DESCRIPTOR_HEADER(2),
'0', '1' // "01"
};
// WCID (auto install WinUSB driver)
// https://github.com/pbatard/libwdi/wiki/WCID-Devices
// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file
// WinUSB 1.0 descriptors, this is mostly used by Windows XP
uint8_t string_238_desc[] = {
0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType
'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100)
MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad
};
uint8_t winusb_ext_compatid_os_desc[] = {
0x28, 0x00, 0x00, 0x00, // dwLength
0x00, 0x01, // bcdVersion
0x04, 0x00, // wIndex
0x01, // bCount
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved
0x00, // bFirstInterfaceNumber
0x00, // Reserved
'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB)
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none)
0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved
};
uint8_t winusb_ext_prop_os_desc[] = {
0x8e, 0x00, 0x00, 0x00, // dwLength
0x00, 0x01, // bcdVersion
0x05, 0x00, // wIndex
0x01, 0x00, // wCount
// first property
0x84, 0x00, 0x00, 0x00, // dwSize
0x01, 0x00, 0x00, 0x00, // dwPropertyDataType
0x28, 0x00, // wPropertyNameLength
'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID)
0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength
'{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9})
};
/*
Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata
comments are from the wicg spec
References used:
https://wicg.github.io/webusb/#webusb-platform-capability-descriptor
https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c
https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/
*/
uint8_t binary_object_store_desc[] = {
// BOS header
BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header
BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType
0x39, 0x00, // wTotalLength (LSB, MSB)
0x02, // bNumDeviceCaps (WebUSB + WinUSB)
// -------------------------------------------------
// WebUSB descriptor
// header
0x18, // bLength, Size of this descriptor. Must be set to 24.
0x10, // bDescriptorType, DEVICE CAPABILITY descriptor
0x05, // bDevCapabilityType, PLATFORM capability
0x00, // bReserved, This field is reserved and shall be set to zero.
// PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}.
0x38, 0xB6, 0x08, 0x34,
0xA9, 0x09, 0xA0, 0x47,
0x8B, 0xFD, 0xA0, 0x76,
0x88, 0x15, 0xB6, 0x65,
// </PlatformCapabilityUUID>
0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100.
WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests.
// there used to be a concept of "allowed origins", but it was removed from the spec
// it was intended to be a security feature, but then the entire security model relies on domain ownership
// https://github.com/WICG/webusb/issues/49
// other implementations use various other indexed to leverate this no-longer-valid feature. we wont.
// the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index
0x03, // iLandingPage, URL descriptor index of the devices landing page.
// -------------------------------------------------
// WinUSB descriptor
// header
0x1C, // Descriptor size (28 bytes)
0x10, // Descriptor type (Device Capability)
0x05, // Capability type (Platform)
0x00, // Reserved
// MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F)
// Indicates the device supports the Microsoft OS 2.0 descriptor
0xDF, 0x60, 0xDD, 0xD8,
0x89, 0x45, 0xC7, 0x4C,
0x9C, 0xD2, 0x65, 0x9D,
0x9E, 0x64, 0x8A, 0x9F,
0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000)
WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word)
MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration
};
uint8_t webusb_url_descriptor[] = {
0x14, /* bLength */
WEBUSB_DESC_TYPE_URL, // bDescriptorType
WEBUSB_URL_SCHEME_HTTPS, // bScheme
'u', 's', 'b', 'p', 'a', 'n', 'd', 'a', '.', 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i'
};
// WinUSB 2.0 descriptor. This is what modern systems use
// https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c
// http://janaxelson.com/files/ms_os_20_descriptors.c
// https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353
uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = {
// Microsoft OS 2.0 descriptor set header (table 10)
0x0A, 0x00, // Descriptor size (10 bytes)
0x00, 0x00, // MS OS 2.0 descriptor set header
0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000)
WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set
// Microsoft OS 2.0 compatible ID descriptor
0x14, 0x00, // Descriptor size (20 bytes)
0x03, 0x00, // MS OS 2.0 compatible ID descriptor
'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB)
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID
// Registry property descriptor
0x80, 0x00, // Descriptor size (130 bytes)
0x04, 0x00, // Registry Property descriptor
0x01, 0x00, // Strings are null-terminated Unicode
0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID"
// bPropertyName (DeviceInterfaceGUID)
'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00,
't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00,
'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00,
0x4E, 0x00, // Size of Property Data (78 bytes)
// Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}
'{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16
'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32
'9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48
'-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64
'1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes
};
// current packet
USB_Setup_TypeDef setup;
uint8_t usbdata[0x100] __attribute__((aligned(4)));
uint8_t* ep0_txdata = NULL;
uint16_t ep0_txlen = 0;
bool outep3_processing = false;
// Store the current interface alt setting.
int current_int0_alt_setting = 0;
// packet read and write
void *USB_ReadPacket(void *dest, uint16_t len) {
uint32_t *dest_copy = (uint32_t *)dest;
uint32_t count32b = ((uint32_t)len + 3U) / 4U;
for (uint32_t i = 0; i < count32b; i++) {
*dest_copy = USBx_DFIFO(0);
dest_copy++;
}
return ((void *)dest_copy);
}
void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) {
#ifdef DEBUG_USB
print("writing ");
hexdump(src, len);
#endif
uint32_t numpacket = ((uint32_t)len + (USBPACKET_MAX_SIZE - 1U)) / USBPACKET_MAX_SIZE;
uint32_t count32b = 0;
count32b = ((uint32_t)len + 3U) / 4U;
// 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
if (src != NULL) {
const uint32_t *src_copy = (const uint32_t *)src;
for (uint32_t i = 0; i < count32b; i++) {
USBx_DFIFO(ep) = *src_copy;
src_copy++;
}
}
}
// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest)
// so use TX FIFO empty interrupt to send larger amounts of data
void USB_WritePacket_EP0(uint8_t *src, uint16_t len) {
#ifdef DEBUG_USB
print("writing ");
hexdump(src, len);
#endif
uint16_t wplen = MIN(len, 0x40);
USB_WritePacket(src, wplen, 0);
if (wplen < len) {
ep0_txdata = &src[wplen];
ep0_txlen = len - wplen;
USBx_DEVICE->DIEPEMPMSK |= 1;
} else {
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
void usb_reset(void) {
// unmask endpoint interrupts, so many sets
USBx_DEVICE->DAINT = 0xFFFFFFFFU;
USBx_DEVICE->DAINTMSK = 0xFFFFFFFFU;
//USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM);
// all interrupts for debugging
USBx_DEVICE->DIEPMSK = 0xFFFFFFFFU;
USBx_DEVICE->DOEPMSK = 0xFFFFFFFFU;
// clear interrupts
USBx_INEP(0)->DIEPINT = 0xFF;
USBx_OUTEP(0)->DOEPINT = 0xFF;
// unset the address
USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD;
// set up USB FIFOs
// RX start address is fixed to 0
USBx->GRXFSIZ = 0x40;
// 0x100 to offset past GRXFSIZ
USBx->DIEPTXF0_HNPTXFSIZ = (0x40UL << 16) | 0x40U;
// EP1, massive
USBx->DIEPTXF[0] = (0x40UL << 16) | 0x80U;
// flush TX fifo
USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH);
// flush RX FIFO
USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH);
// no global NAK
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK;
// ready to receive setup packets
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (3U << 3);
}
char to_hex_char(uint8_t a) {
char ret;
if (a < 10U) {
ret = '0' + a;
} else {
ret = 'a' + (a - 10U);
}
return ret;
}
void usb_tick(void) {
uint16_t current_frame_num = (USBx_DEVICE->DSTS & USB_OTG_DSTS_FNSOF_Msk) >> USB_OTG_DSTS_FNSOF_Pos;
usb_enumerated = (current_frame_num != usb_last_frame_num);
usb_last_frame_num = current_frame_num;
}
void usb_setup(void) {
int resp_len;
ControlPacket_t control_req;
// setup packet is ready
switch (setup.b.bRequest) {
case USB_REQ_SET_CONFIGURATION:
// enable other endpoints, has to be here?
USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2UL << 18) | (1UL << 22) |
USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP;
USBx_INEP(1)->DIEPINT = 0xFF;
USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U;
USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(2)->DOEPINT = 0xFF;
USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U;
USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(3)->DOEPINT = 0xFF;
// mark ready to receive
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_ADDRESS:
// set now?
USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7fU) << 4);
#ifdef DEBUG_USB
print(" set address\n");
#endif
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_GET_DESCRIPTOR:
switch (setup.b.wValue.bw.lsb) {
case USB_DESC_TYPE_DEVICE:
//print(" writing device descriptor\n");
// set bcdDevice to hardware type
device_desc[13] = hw_type;
// setup transfer
USB_WritePacket(device_desc, MIN(sizeof(device_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
//print("D");
break;
case USB_DESC_TYPE_CONFIGURATION:
USB_WritePacket(configuration_desc, MIN(sizeof(configuration_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_DESC_TYPE_DEVICE_QUALIFIER:
USB_WritePacket(device_qualifier, MIN(sizeof(device_qualifier), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_DESC_TYPE_STRING:
switch (setup.b.wValue.bw.msb) {
case STRING_OFFSET_LANGID:
USB_WritePacket((uint8_t*)string_language_desc, MIN(sizeof(string_language_desc), setup.b.wLength.w), 0);
break;
case STRING_OFFSET_IMANUFACTURER:
USB_WritePacket((uint8_t*)string_manufacturer_desc, MIN(sizeof(string_manufacturer_desc), setup.b.wLength.w), 0);
break;
case STRING_OFFSET_IPRODUCT:
USB_WritePacket((uint8_t*)string_product_desc, MIN(sizeof(string_product_desc), setup.b.wLength.w), 0);
break;
case STRING_OFFSET_ISERIAL:
#ifdef UID_BASE
response[0] = 0x02 + (12 * 4);
response[1] = 0x03;
// 96 bits = 12 bytes
for (int i = 0; i < 12; i++){
uint8_t cc = ((uint8_t *)UID_BASE)[i];
response[2 + (i * 4)] = to_hex_char((cc >> 4) & 0xFU);
response[2 + (i * 4) + 1] = '\0';
response[2 + (i * 4) + 2] = to_hex_char((cc >> 0) & 0xFU);
response[2 + (i * 4) + 3] = '\0';
}
USB_WritePacket(response, MIN(response[0], setup.b.wLength.w), 0);
#else
USB_WritePacket((const uint8_t *)string_serial_desc, MIN(sizeof(string_serial_desc), setup.b.wLength.w), 0);
#endif
break;
case STRING_OFFSET_ICONFIGURATION:
USB_WritePacket((uint8_t*)string_configuration_desc, MIN(sizeof(string_configuration_desc), setup.b.wLength.w), 0);
break;
case 238:
USB_WritePacket((uint8_t*)string_238_desc, MIN(sizeof(string_238_desc), setup.b.wLength.w), 0);
break;
default:
// nothing
USB_WritePacket(0, 0, 0);
break;
}
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_DESC_TYPE_BINARY_OBJECT_STORE:
USB_WritePacket(binary_object_store_desc, MIN(sizeof(binary_object_store_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
default:
// nothing here?
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
}
break;
case USB_REQ_GET_STATUS:
// empty response?
response[0] = 0;
response[1] = 0;
USB_WritePacket((void*)&response, 2, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_INTERFACE:
// Store the alt setting number for IN EP behavior.
current_int0_alt_setting = setup.b.wValue.w;
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case WEBUSB_VENDOR_CODE:
switch (setup.b.wIndex.w) {
case WEBUSB_REQ_GET_URL:
USB_WritePacket(webusb_url_descriptor, MIN(sizeof(webusb_url_descriptor), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
default:
// probably asking for allowed origins, which was removed from the spec
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
}
break;
case MS_VENDOR_CODE:
switch (setup.b.wIndex.w) {
// winusb 2.0 descriptor from BOS
case WINUSB_REQ_GET_DESCRIPTOR:
USB_WritePacket_EP0((uint8_t*)winusb_20_desc, MIN(sizeof(winusb_20_desc), setup.b.wLength.w));
break;
// Extended Compat ID OS Descriptor
case WINUSB_REQ_GET_COMPATID_DESCRIPTOR:
USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, MIN(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w));
break;
// Extended Properties OS Descriptor
case WINUSB_REQ_GET_EXT_PROPS_OS:
USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, MIN(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w));
break;
default:
USB_WritePacket_EP0(0, 0);
}
break;
default:
control_req.request = setup.b.bRequest;
control_req.param1 = setup.b.wValue.w;
control_req.param2 = setup.b.wIndex.w;
control_req.length = setup.b.wLength.w;
resp_len = comms_control_handler(&control_req, response);
// response pending if -1 was returned
if (resp_len != -1) {
USB_WritePacket(response, MIN(resp_len, setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
}
// ***************************** USB port *****************************
void usb_irqhandler(void) {
//USBx->GINTMSK = 0;
unsigned int gintsts = USBx->GINTSTS;
unsigned int gotgint = USBx->GOTGINT;
unsigned int daint = USBx_DEVICE->DAINT;
// gintsts SUSPEND? 04008428
#ifdef DEBUG_USB
puth(gintsts);
print(" ");
/*puth(USBx->GCCFG);
print(" ");*/
puth(gotgint);
print(" ep ");
puth(daint);
print(" USB interrupt!\n");
#endif
if ((gintsts & USB_OTG_GINTSTS_CIDSCHG) != 0) {
print("connector ID status change\n");
}
if ((gintsts & USB_OTG_GINTSTS_USBRST) != 0) {
print("USB reset\n");
usb_reset();
}
if ((gintsts & USB_OTG_GINTSTS_ENUMDNE) != 0) {
print("enumeration done");
// Full speed, ENUMSPD
//puth(USBx_DEVICE->DSTS);
print("\n");
}
if ((gintsts & USB_OTG_GINTSTS_OTGINT) != 0) {
print("OTG int:");
puth(USBx->GOTGINT);
print("\n");
// getting ADTOCHG
//USBx->GOTGINT = USBx->GOTGINT;
}
// RX FIFO first
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
print(" RX FIFO:");
puth(rxst);
print(" status: ");
puth(status);
print(" len: ");
puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4);
print("\n");
#endif
if (status == STS_DATA_UPDT) {
int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM);
int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4;
(void)USB_ReadPacket(&usbdata, len);
#ifdef DEBUG_USB
print(" data ");
puth(len);
print("\n");
hexdump(&usbdata, len);
#endif
if (endpoint == 2) {
comms_endpoint2_write((uint8_t *) usbdata, len);
}
if (endpoint == 3) {
outep3_processing = true;
comms_can_write(usbdata, len);
}
} else if (status == STS_SETUP_UPDT) {
(void)USB_ReadPacket(&setup, 8);
#ifdef DEBUG_USB
print(" setup ");
hexdump(&setup, 8);
print("\n");
#endif
} else {
// status is neither STS_DATA_UPDT or STS_SETUP_UPDT, skip
}
}
/*if (gintsts & USB_OTG_GINTSTS_HPRTINT) {
// host
print("HPRT:");
puth(USBx_HOST_PORT->HPRT);
print("\n");
if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) {
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST;
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET;
}
}*/
if ((gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) || (gintsts & USB_OTG_GINTSTS_GINAKEFF)) {
// no global NAK, why is this getting set?
#ifdef DEBUG_USB
print("GLOBAL NAK\n");
#endif
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK;
}
if ((gintsts & USB_OTG_GINTSTS_SRQINT) != 0) {
// we want to do "A-device host negotiation protocol" since we are the A-device
/*print("start request\n");
puth(USBx->GOTGCTL);
print("\n");*/
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD;
//USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA;
//USBx->GOTGCTL |= USB_OTG_GOTGCTL_SRQ;
}
// out endpoint hit
if ((gintsts & USB_OTG_GINTSTS_OEPINT) != 0) {
#ifdef DEBUG_USB
print(" 0:");
puth(USBx_OUTEP(0)->DOEPINT);
print(" 2:");
puth(USBx_OUTEP(2)->DOEPINT);
print(" 3:");
puth(USBx_OUTEP(3)->DOEPINT);
print(" ");
puth(USBx_OUTEP(3)->DOEPCTL);
print(" 4:");
puth(USBx_OUTEP(4)->DOEPINT);
print(" OUT ENDPOINT\n");
#endif
if ((USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) != 0) {
#ifdef DEBUG_USB
print(" OUT2 PACKET XFRC\n");
#endif
USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U;
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
}
if ((USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) != 0) {
#ifdef DEBUG_USB
print(" OUT3 PACKET XFRC\n");
#endif
// NAK cleared by process_can (if tx buffers have room)
outep3_processing = false;
refresh_can_tx_slots_available();
} else if ((USBx_OUTEP(3)->DOEPINT & 0x2000) != 0) {
#ifdef DEBUG_USB
print(" OUT3 PACKET WTF\n");
#endif
// if NAK was set trigger this, unknown interrupt
// TODO: why was this here? fires when TX buffers when we can't clear NAK
// USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U;
// USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
} else if ((USBx_OUTEP(3)->DOEPINT) != 0) {
#ifdef DEBUG_USB
print("OUTEP3 error ");
puth(USBx_OUTEP(3)->DOEPINT);
print("\n");
#endif
} 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 & (1UL << 19)) | (1U << 3);
}
// respond to setup packets
if ((USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) != 0) {
usb_setup();
}
USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT;
USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT;
USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT;
}
// interrupt endpoint hit (Page 1221)
if ((gintsts & USB_OTG_GINTSTS_IEPINT) != 0) {
#ifdef DEBUG_USB
print(" ");
puth(USBx_INEP(0)->DIEPINT);
print(" ");
puth(USBx_INEP(1)->DIEPINT);
print(" IN ENDPOINT\n");
#endif
// Should likely check the EP of the IN request even if there is
// only one IN endpoint.
// No need to set NAK in OTG_DIEPCTL0 when nothing to send,
// Appears USB core automatically sets NAK. WritePacket clears it.
// Handle the two interface alternate settings. Setting 0 has EP1
// as bulk. Setting 1 has EP1 as interrupt. The code to handle
// these two EP variations are very similar and can be
// restructured for smaller code footprint. Keeping split out for
// now for clarity.
//TODO add default case. Should it NAK?
switch (current_int0_alt_setting) {
case 0: ////// Bulk config
// *** IN token received when TxFIFO is empty
if ((USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) {
#ifdef DEBUG_USB
print(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
USB_WritePacket((void *)response, comms_can_read(response, 0x40), 1);
}
break;
case 1: ////// Interrupt config
// *** IN token received when TxFIFO is empty
if ((USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) {
#ifdef DEBUG_USB
print(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
int len = comms_can_read(response, 0x40);
if (len > 0) {
USB_WritePacket((void *)response, len, 1);
}
}
break;
default:
print("current_int0_alt_setting value invalid\n");
break;
}
if ((USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) {
#ifdef DEBUG_USB
print(" IN PACKET QUEUE\n");
#endif
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 = &ep0_txdata[len];
ep0_txlen -= len;
if (ep0_txlen == 0U) {
ep0_txdata = NULL;
USBx_DEVICE->DIEPEMPMSK &= ~1;
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
}
// clear interrupts
USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0?
USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT;
}
// clear all interrupts we handled
USBx_DEVICE->DAINT = daint;
USBx->GOTGINT = gotgint;
USBx->GINTSTS = gintsts;
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF);
}
void can_tx_comms_resume_usb(void) {
ENTER_CRITICAL();
if (!outep3_processing && (USBx_OUTEP(3)->DOEPCTL & USB_OTG_DOEPCTL_NAKSTS) != 0) {
USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
}
EXIT_CRITICAL();
}
void usb_soft_disconnect(bool enable) {
if (enable) {
USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS;
} else {
USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS;
}
}

View File

@@ -0,0 +1,24 @@
typedef enum {
WATCHDOG_50_MS = (400U - 1U),
WATCHDOG_500_MS = 4000U,
} WatchdogTimeout;
void watchdog_feed(void) {
IND_WDG->KR = 0xAAAAU;
}
void watchdog_init(WatchdogTimeout timeout) {
// enable watchdog
IND_WDG->KR = 0xCCCCU;
IND_WDG->KR = 0x5555U;
// 32KHz / 4 prescaler = 8000Hz
register_set(&(IND_WDG->PR), 0x0U, IWDG_PR_PR_Msk);
register_set(&(IND_WDG->RLR), timeout, IWDG_RLR_RL_Msk);
// wait for watchdog to be updated
while (IND_WDG->SR != 0U);
// start the countdown
watchdog_feed();
}

60
panda/board/early_init.h Normal file
View File

@@ -0,0 +1,60 @@
// Early bringup
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeefU
#define ENTER_SOFTLOADER_MAGIC 0xdeadc0deU
#define BOOT_NORMAL 0xdeadb111U
extern void *g_pfnVectors;
extern uint32_t enter_bootloader_mode;
void jump_to_bootloader(void) {
// do enter bootloader
enter_bootloader_mode = 0;
void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)BOOTLOADER_ADDRESS));
// jump to bootloader
enable_interrupts();
bootloader();
// reset on exit
enter_bootloader_mode = BOOT_NORMAL;
NVIC_SystemReset();
}
void early_initialization(void) {
// Reset global critical depth
disable_interrupts();
global_critical_depth = 0;
// Init register and interrupt tables
init_registers();
// after it's been in the bootloader, things are initted differently, so we reset
if ((enter_bootloader_mode != BOOT_NORMAL) &&
(enter_bootloader_mode != ENTER_BOOTLOADER_MAGIC) &&
(enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC)) {
enter_bootloader_mode = BOOT_NORMAL;
NVIC_SystemReset();
}
// if wrong chip, reboot
volatile unsigned int id = DBGMCU->IDCODE;
if ((id & 0xFFFU) != MCU_IDCODE) {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
}
// setup interrupt table
SCB->VTOR = (uint32_t)&g_pfnVectors;
// early GPIOs float everything
early_gpio_float();
detect_board_type();
if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) {
#ifdef PANDA
current_board->init_bootloader();
#endif
current_board->set_led(LED_GREEN, 1);
jump_to_bootloader();
}
}

33
panda/board/fake_stm.h Normal file
View File

@@ -0,0 +1,33 @@
// minimal code to fake a panda for tests
#include <stdio.h>
#include <stdint.h>
#include <stdlib.h>
#include "utils.h"
#define CANFD
#define ALLOW_DEBUG
#define PANDA
#define ENTER_CRITICAL() 0
#define EXIT_CRITICAL() 0
void print(const char *a) {
printf("%s", a);
}
void puth(unsigned int i) {
printf("%u", i);
}
typedef struct {
uint32_t CNT;
} TIM_TypeDef;
TIM_TypeDef timer;
TIM_TypeDef *MICROSECOND_TIMER = &timer;
uint32_t microsecond_timer_get(void);
uint32_t microsecond_timer_get(void) {
return MICROSECOND_TIMER->CNT;
}

59
panda/board/faults.h Normal file
View File

@@ -0,0 +1,59 @@
#define FAULT_STATUS_NONE 0U
#define FAULT_STATUS_TEMPORARY 1U
#define FAULT_STATUS_PERMANENT 2U
// Fault types, matches cereal.log.PandaState.FaultType
#define FAULT_RELAY_MALFUNCTION (1UL << 0)
#define FAULT_UNUSED_INTERRUPT_HANDLED (1UL << 1)
#define FAULT_INTERRUPT_RATE_CAN_1 (1UL << 2)
#define FAULT_INTERRUPT_RATE_CAN_2 (1UL << 3)
#define FAULT_INTERRUPT_RATE_CAN_3 (1UL << 4)
#define FAULT_INTERRUPT_RATE_TACH (1UL << 5)
#define FAULT_INTERRUPT_RATE_GMLAN (1UL << 6)
#define FAULT_INTERRUPT_RATE_INTERRUPTS (1UL << 7)
#define FAULT_INTERRUPT_RATE_SPI_DMA (1UL << 8)
#define FAULT_INTERRUPT_RATE_SPI_CS (1UL << 9)
#define FAULT_INTERRUPT_RATE_UART_1 (1UL << 10)
#define FAULT_INTERRUPT_RATE_UART_2 (1UL << 11)
#define FAULT_INTERRUPT_RATE_UART_3 (1UL << 12)
#define FAULT_INTERRUPT_RATE_UART_5 (1UL << 13)
#define FAULT_INTERRUPT_RATE_UART_DMA (1UL << 14)
#define FAULT_INTERRUPT_RATE_USB (1UL << 15)
#define FAULT_INTERRUPT_RATE_TIM1 (1UL << 16)
#define FAULT_INTERRUPT_RATE_TIM3 (1UL << 17)
#define FAULT_REGISTER_DIVERGENT (1UL << 18)
#define FAULT_INTERRUPT_RATE_KLINE_INIT (1UL << 19)
#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1UL << 20)
#define FAULT_INTERRUPT_RATE_TICK (1UL << 21)
#define FAULT_INTERRUPT_RATE_EXTI (1UL << 22)
#define FAULT_INTERRUPT_RATE_SPI (1UL << 23)
#define FAULT_INTERRUPT_RATE_UART_7 (1UL << 24)
#define FAULT_SIREN_MALFUNCTION (1UL << 25)
#define FAULT_HEARTBEAT_LOOP_WATCHDOG (1UL << 26)
// Permanent faults
#define PERMANENT_FAULTS 0U
uint8_t fault_status = FAULT_STATUS_NONE;
uint32_t faults = 0U;
void fault_occurred(uint32_t fault) {
if ((faults & fault) == 0U) {
if ((PERMANENT_FAULTS & fault) != 0U) {
print("Permanent fault occurred: 0x"); puth(fault); print("\n");
fault_status = FAULT_STATUS_PERMANENT;
} else {
print("Temporary fault occurred: 0x"); puth(fault); print("\n");
fault_status = FAULT_STATUS_TEMPORARY;
}
}
faults |= fault;
}
void fault_recovered(uint32_t fault) {
if ((PERMANENT_FAULTS & fault) == 0U) {
faults &= ~fault;
} else {
print("Cannot recover from a permanent fault!\n");
}
}

150
panda/board/flasher.h Normal file
View File

@@ -0,0 +1,150 @@
// flasher state variables
uint32_t *prog_ptr = NULL;
bool unlocked = false;
void spi_init(void);
int comms_control_handler(ControlPacket_t *req, uint8_t *resp) {
int resp_len = 0;
// flasher machine
memset(resp, 0, 4);
memcpy(resp+4, "\xde\xad\xd0\x0d", 4);
resp[0] = 0xff;
resp[2] = req->request;
resp[3] = ~req->request;
*((uint32_t **)&resp[8]) = prog_ptr;
resp_len = 0xc;
int sec;
switch (req->request) {
// **** 0xb0: flasher echo
case 0xb0:
resp[1] = 0xff;
break;
// **** 0xb1: unlock flash
case 0xb1:
if (flash_is_locked()) {
flash_unlock();
resp[1] = 0xff;
}
current_board->set_led(LED_GREEN, 1);
unlocked = true;
prog_ptr = (uint32_t *)APP_START_ADDRESS;
break;
// **** 0xb2: erase sector
case 0xb2:
sec = req->param1;
if (flash_erase_sector(sec, unlocked)) {
resp[1] = 0xff;
}
break;
// **** 0xc1: get hardware type
case 0xc1:
resp[0] = hw_type;
resp_len = 1;
break;
// **** 0xc3: fetch MCU UID
case 0xc3:
(void)memcpy(resp, ((uint8_t *)UID_BASE), 12);
resp_len = 12;
break;
// **** 0xd0: fetch serial number
case 0xd0:
// addresses are OTP
if (req->param1 == 1) {
memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10);
resp_len = 0x10;
} else {
get_provision_chunk(resp);
resp_len = PROVISION_CHUNK_LEN;
}
break;
// **** 0xd1: enter bootloader mode
case 0xd1:
// this allows reflashing of the bootstub
switch (req->param1) {
case 0:
print("-> entering bootloader\n");
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
break;
case 1:
print("-> entering softloader\n");
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
NVIC_SystemReset();
break;
}
break;
// **** 0xd6: get version
case 0xd6:
COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE);
memcpy(resp, gitversion, sizeof(gitversion));
resp_len = sizeof(gitversion);
break;
// **** 0xd8: reset ST
case 0xd8:
flush_write_buffer();
NVIC_SystemReset();
break;
}
return resp_len;
}
void comms_can_write(const uint8_t *data, uint32_t len) {
UNUSED(data);
UNUSED(len);
}
int comms_can_read(uint8_t *data, uint32_t max_len) {
UNUSED(data);
UNUSED(max_len);
return 0;
}
void refresh_can_tx_slots_available(void) {}
void comms_endpoint2_write(const uint8_t *data, uint32_t len) {
current_board->set_led(LED_RED, 0);
for (uint32_t i = 0; i < len/4; i++) {
flash_write_word(prog_ptr, *(uint32_t*)(data+(i*4)));
//*(uint64_t*)(&spi_tx_buf[0x30+(i*4)]) = *prog_ptr;
prog_ptr++;
}
current_board->set_led(LED_RED, 1);
}
void soft_flasher_start(void) {
print("\n\n\n************************ FLASHER START ************************\n");
enter_bootloader_mode = 0;
flasher_peripherals_init();
gpio_usart2_init();
gpio_usb_init();
// enable USB
usb_init();
// enable SPI
if (current_board->has_spi) {
gpio_spi_init();
spi_init();
}
// green LED on for flashing
current_board->set_led(LED_GREEN, 1);
enable_interrupts();
for (;;) {
// blink the green LED fast
current_board->set_led(LED_GREEN, 0);
delay(500000);
current_board->set_led(LED_GREEN, 1);
delay(500000);
}
}

62
panda/board/health.h Normal file
View File

@@ -0,0 +1,62 @@
// When changing these structs, python/__init__.py needs to be kept up to date!
#define HEALTH_PACKET_VERSION 15
struct __attribute__((packed)) health_t {
uint32_t uptime_pkt;
uint32_t voltage_pkt;
uint32_t current_pkt;
uint32_t safety_tx_blocked_pkt;
uint32_t safety_rx_invalid_pkt;
uint32_t tx_buffer_overflow_pkt;
uint32_t rx_buffer_overflow_pkt;
uint32_t gmlan_send_errs_pkt;
uint32_t faults_pkt;
uint8_t ignition_line_pkt;
uint8_t ignition_can_pkt;
uint8_t controls_allowed_pkt;
uint8_t car_harness_status_pkt;
uint8_t safety_mode_pkt;
uint16_t safety_param_pkt;
uint8_t fault_status_pkt;
uint8_t power_save_enabled_pkt;
uint8_t heartbeat_lost_pkt;
uint16_t alternative_experience_pkt;
float interrupt_load_pkt;
uint8_t fan_power;
uint8_t safety_rx_checks_invalid_pkt;
uint16_t spi_checksum_error_count_pkt;
uint8_t fan_stall_count;
uint16_t sbu1_voltage_mV;
uint16_t sbu2_voltage_mV;
uint8_t som_reset_triggered;
};
#define CAN_HEALTH_PACKET_VERSION 5
typedef struct __attribute__((packed)) {
uint8_t bus_off;
uint32_t bus_off_cnt;
uint8_t error_warning;
uint8_t error_passive;
uint8_t last_error; // real time LEC value
uint8_t last_stored_error; // last LEC positive error code stored
uint8_t last_data_error; // DLEC (for CANFD only)
uint8_t last_data_stored_error; // last DLEC positive error code stored (for CANFD only)
uint8_t receive_error_cnt; // Actual state of the receive error counter, values between 0 and 127. FDCAN_ECR.REC
uint8_t transmit_error_cnt; // Actual state of the transmit error counter, values between 0 and 255. FDCAN_ECR.TEC
uint32_t total_error_cnt; // How many times any error interrupt was invoked
uint32_t total_tx_lost_cnt; // Tx event FIFO element lost
uint32_t total_rx_lost_cnt; // Rx FIFO 0 message lost due to FIFO full condition
uint32_t total_tx_cnt;
uint32_t total_rx_cnt;
uint32_t total_fwd_cnt; // Messages forwarded from one bus to another
uint32_t total_tx_checksum_error_cnt;
uint16_t can_speed;
uint16_t can_data_speed;
uint8_t canfd_enabled;
uint8_t brs_enabled;
uint8_t canfd_non_iso;
uint32_t irq0_call_rate;
uint32_t irq1_call_rate;
uint32_t irq2_call_rate;
uint32_t can_core_reset_cnt;
} can_health_t;

View File

@@ -0,0 +1,18 @@
import os
import copy
Import('build_project', 'base_project_f4', 'base_project_h7')
build_projects = {
"panda_jungle": base_project_f4,
"panda_jungle_h7": base_project_h7,
}
for project_name, project in build_projects.items():
flags = [
"-DPANDA_JUNGLE",
]
if os.getenv("FINAL_PROVISIONING"):
flags += ["-DFINAL_PROVISIONING"]
build_project(project_name, project, flags)

View File

@@ -2,7 +2,6 @@
import os
import struct
from functools import wraps
from typing import Optional
from panda import Panda, PandaDFU
from panda.python.constants import McuType
@@ -57,7 +56,7 @@ class PandaJungle(Panda):
fn = os.path.join(FW_PATH, self._mcu_type.config.app_fn.replace("panda", "panda_jungle"))
super().flash(fn=fn, code=code, reconnect=reconnect)
def recover(self, timeout: Optional[int] = 60, reset: bool = True) -> bool:
def recover(self, timeout: int | None = 60, reset: bool = True) -> bool:
dfu_serial = self.get_dfu_serial()
if reset:

View File

@@ -0,0 +1,82 @@
// ******************** Prototypes ********************
typedef void (*board_init)(void);
typedef void (*board_set_led)(uint8_t color, bool enabled);
typedef void (*board_board_tick)(void);
typedef bool (*board_get_button)(void);
typedef void (*board_set_panda_power)(bool enabled);
typedef void (*board_set_panda_individual_power)(uint8_t port_num, bool enabled);
typedef void (*board_set_ignition)(bool enabled);
typedef void (*board_set_individual_ignition)(uint8_t bitmask);
typedef void (*board_set_harness_orientation)(uint8_t orientation);
typedef void (*board_set_can_mode)(uint8_t mode);
typedef void (*board_enable_can_transciever)(uint8_t transciever, bool enabled);
typedef void (*board_enable_header_pin)(uint8_t pin_num, bool enabled);
typedef float (*board_get_channel_power)(uint8_t channel);
typedef uint16_t (*board_get_sbu_mV)(uint8_t channel, uint8_t sbu);
struct board {
const bool has_canfd;
const bool has_sbu_sense;
const uint16_t avdd_mV;
board_init init;
board_set_led set_led;
board_board_tick board_tick;
board_get_button get_button;
board_set_panda_power set_panda_power;
board_set_panda_individual_power set_panda_individual_power;
board_set_ignition set_ignition;
board_set_individual_ignition set_individual_ignition;
board_set_harness_orientation set_harness_orientation;
board_set_can_mode set_can_mode;
board_enable_can_transciever enable_can_transciever;
board_enable_header_pin enable_header_pin;
board_get_channel_power get_channel_power;
board_get_sbu_mV get_sbu_mV;
// TODO: shouldn't need these
bool has_spi;
};
// ******************* Definitions ********************
#define HW_TYPE_UNKNOWN 0U
#define HW_TYPE_V1 1U
#define HW_TYPE_V2 2U
// LED colors
#define LED_RED 0U
#define LED_GREEN 1U
#define LED_BLUE 2U
// CAN modes
#define CAN_MODE_NORMAL 0U
#define CAN_MODE_GMLAN_CAN2 1U
#define CAN_MODE_GMLAN_CAN3 2U
#define CAN_MODE_OBD_CAN2 3U
// Harness states
#define HARNESS_ORIENTATION_NONE 0U
#define HARNESS_ORIENTATION_1 1U
#define HARNESS_ORIENTATION_2 2U
#define SBU1 0U
#define SBU2 1U
// ********************* Globals **********************
uint8_t harness_orientation = HARNESS_ORIENTATION_NONE;
uint8_t can_mode = CAN_MODE_NORMAL;
uint8_t ignition = 0U;
void unused_set_individual_ignition(uint8_t bitmask) {
UNUSED(bitmask);
}
void unused_board_enable_header_pin(uint8_t pin_num, bool enabled) {
UNUSED(pin_num);
UNUSED(enabled);
}
void unused_set_panda_individual_power(uint8_t port_num, bool enabled) {
UNUSED(port_num);
UNUSED(enabled);
}

View File

@@ -0,0 +1,178 @@
// ///////////////////////// //
// Jungle board v1 (STM32F4) //
// ///////////////////////// //
void board_v1_set_led(uint8_t color, bool enabled) {
switch (color) {
case LED_RED:
set_gpio_output(GPIOC, 9, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOC, 7, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOC, 6, !enabled);
break;
default:
break;
}
}
void board_v1_enable_can_transciever(uint8_t transciever, bool enabled) {
switch (transciever) {
case 1U:
set_gpio_output(GPIOC, 1, !enabled);
break;
case 2U:
set_gpio_output(GPIOC, 13, !enabled);
break;
case 3U:
set_gpio_output(GPIOA, 0, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 10, !enabled);
break;
default:
print("Invalid CAN transciever ("); puth(transciever); print("): enabling failed\n");
break;
}
}
void board_v1_set_can_mode(uint8_t mode) {
board_v1_enable_can_transciever(2U, false);
board_v1_enable_can_transciever(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
print("Setting normal CAN mode\n");
// B12,B13: disable OBD mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal CAN2 mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
can_mode = CAN_MODE_NORMAL;
board_v1_enable_can_transciever(2U, true);
break;
case CAN_MODE_OBD_CAN2:
print("Setting OBD CAN mode\n");
// B5,B6: disable normal CAN2 mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: OBD mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
can_mode = CAN_MODE_OBD_CAN2;
board_v1_enable_can_transciever(4U, true);
break;
default:
print("Tried to set unsupported CAN mode: "); puth(mode); print("\n");
break;
}
}
void board_v1_set_harness_orientation(uint8_t orientation) {
switch (orientation) {
case HARNESS_ORIENTATION_NONE:
set_gpio_output(GPIOA, 2, false);
set_gpio_output(GPIOA, 3, false);
set_gpio_output(GPIOA, 4, false);
set_gpio_output(GPIOA, 5, false);
harness_orientation = orientation;
break;
case HARNESS_ORIENTATION_1:
set_gpio_output(GPIOA, 2, false);
set_gpio_output(GPIOA, 3, (ignition != 0U));
set_gpio_output(GPIOA, 4, true);
set_gpio_output(GPIOA, 5, false);
harness_orientation = orientation;
break;
case HARNESS_ORIENTATION_2:
set_gpio_output(GPIOA, 2, (ignition != 0U));
set_gpio_output(GPIOA, 3, false);
set_gpio_output(GPIOA, 4, false);
set_gpio_output(GPIOA, 5, true);
harness_orientation = orientation;
break;
default:
print("Tried to set an unsupported harness orientation: "); puth(orientation); print("\n");
break;
}
}
bool panda_power = false;
void board_v1_set_panda_power(bool enable) {
panda_power = enable;
set_gpio_output(GPIOB, 14, enable);
}
bool board_v1_get_button(void) {
return get_gpio_input(GPIOC, 8);
}
void board_v1_set_ignition(bool enabled) {
ignition = enabled ? 0xFFU : 0U;
board_v1_set_harness_orientation(harness_orientation);
}
float board_v1_get_channel_power(uint8_t channel) {
UNUSED(channel);
return 0.0f;
}
uint16_t board_v1_get_sbu_mV(uint8_t channel, uint8_t sbu) {
UNUSED(channel); UNUSED(sbu);
return 0U;
}
void board_v1_init(void) {
common_init_gpio();
// A8,A15: normal CAN3 mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
board_v1_set_can_mode(CAN_MODE_NORMAL);
// Enable CAN transcievers
for(uint8_t i = 1; i <= 4; i++) {
board_v1_enable_can_transciever(i, true);
}
// Disable LEDs
board_v1_set_led(LED_RED, false);
board_v1_set_led(LED_GREEN, false);
board_v1_set_led(LED_BLUE, false);
// Set normal CAN mode
board_v1_set_can_mode(CAN_MODE_NORMAL);
// Set to no harness orientation
board_v1_set_harness_orientation(HARNESS_ORIENTATION_NONE);
// Enable panda power by default
board_v1_set_panda_power(true);
}
void board_v1_tick(void) {}
const board board_v1 = {
.has_canfd = false,
.has_sbu_sense = false,
.avdd_mV = 3300U,
.init = &board_v1_init,
.set_led = &board_v1_set_led,
.board_tick = &board_v1_tick,
.get_button = &board_v1_get_button,
.set_panda_power = &board_v1_set_panda_power,
.set_panda_individual_power = &unused_set_panda_individual_power,
.set_ignition = &board_v1_set_ignition,
.set_individual_ignition = &unused_set_individual_ignition,
.set_harness_orientation = &board_v1_set_harness_orientation,
.set_can_mode = &board_v1_set_can_mode,
.enable_can_transciever = &board_v1_enable_can_transciever,
.enable_header_pin = &unused_board_enable_header_pin,
.get_channel_power = &board_v1_get_channel_power,
.get_sbu_mV = &board_v1_get_sbu_mV,
};

View File

@@ -0,0 +1,328 @@
// ///////////////////////// //
// Jungle board v2 (STM32H7) //
// ///////////////////////// //
const gpio_t power_pins[] = {
{.bank = GPIOA, .pin = 0},
{.bank = GPIOA, .pin = 1},
{.bank = GPIOF, .pin = 12},
{.bank = GPIOA, .pin = 5},
{.bank = GPIOC, .pin = 5},
{.bank = GPIOB, .pin = 2},
};
const gpio_t sbu1_ignition_pins[] = {
{.bank = GPIOD, .pin = 0},
{.bank = GPIOD, .pin = 5},
{.bank = GPIOD, .pin = 12},
{.bank = GPIOD, .pin = 14},
{.bank = GPIOE, .pin = 5},
{.bank = GPIOE, .pin = 9},
};
const gpio_t sbu1_relay_pins[] = {
{.bank = GPIOD, .pin = 1},
{.bank = GPIOD, .pin = 6},
{.bank = GPIOD, .pin = 11},
{.bank = GPIOD, .pin = 15},
{.bank = GPIOE, .pin = 6},
{.bank = GPIOE, .pin = 10},
};
const gpio_t sbu2_ignition_pins[] = {
{.bank = GPIOD, .pin = 3},
{.bank = GPIOD, .pin = 8},
{.bank = GPIOD, .pin = 9},
{.bank = GPIOE, .pin = 0},
{.bank = GPIOE, .pin = 7},
{.bank = GPIOE, .pin = 11},
};
const gpio_t sbu2_relay_pins[] = {
{.bank = GPIOD, .pin = 4},
{.bank = GPIOD, .pin = 10},
{.bank = GPIOD, .pin = 13},
{.bank = GPIOE, .pin = 1},
{.bank = GPIOE, .pin = 8},
{.bank = GPIOE, .pin = 12},
};
const adc_channel_t sbu1_channels[] = {
{.adc = ADC3, .channel = 12},
{.adc = ADC3, .channel = 2},
{.adc = ADC3, .channel = 4},
{.adc = ADC3, .channel = 6},
{.adc = ADC3, .channel = 8},
{.adc = ADC3, .channel = 10},
};
const adc_channel_t sbu2_channels[] = {
{.adc = ADC1, .channel = 13},
{.adc = ADC3, .channel = 3},
{.adc = ADC3, .channel = 5},
{.adc = ADC3, .channel = 7},
{.adc = ADC3, .channel = 9},
{.adc = ADC3, .channel = 11},
};
void board_v2_set_led(uint8_t color, bool enabled) {
switch (color) {
case LED_RED:
set_gpio_output(GPIOE, 4, !enabled);
break;
case LED_GREEN:
set_gpio_output(GPIOE, 3, !enabled);
break;
case LED_BLUE:
set_gpio_output(GPIOE, 2, !enabled);
break;
default:
break;
}
}
void board_v2_set_harness_orientation(uint8_t orientation) {
switch (orientation) {
case HARNESS_ORIENTATION_NONE:
gpio_set_all_output(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), false);
harness_orientation = orientation;
break;
case HARNESS_ORIENTATION_1:
gpio_set_all_output(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), true);
gpio_set_bitmask(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), ignition);
gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), false);
harness_orientation = orientation;
break;
case HARNESS_ORIENTATION_2:
gpio_set_bitmask(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), ignition);
gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), false);
gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), true);
harness_orientation = orientation;
break;
default:
print("Tried to set an unsupported harness orientation: "); puth(orientation); print("\n");
break;
}
}
void board_v2_enable_can_transciever(uint8_t transciever, bool enabled) {
switch (transciever) {
case 1U:
set_gpio_output(GPIOG, 11, !enabled);
break;
case 2U:
set_gpio_output(GPIOB, 3, !enabled);
break;
case 3U:
set_gpio_output(GPIOD, 7, !enabled);
break;
case 4U:
set_gpio_output(GPIOB, 4, !enabled);
break;
default:
print("Invalid CAN transciever ("); puth(transciever); print("): enabling failed\n");
break;
}
}
void board_v2_enable_header_pin(uint8_t pin_num, bool enabled) {
if (pin_num < 8U) {
set_gpio_output(GPIOG, pin_num, enabled);
} else {
print("Invalid pin number ("); puth(pin_num); print("): enabling failed\n");
}
}
void board_v2_set_can_mode(uint8_t mode) {
board_v2_enable_can_transciever(2U, false);
board_v2_enable_can_transciever(4U, false);
switch (mode) {
case CAN_MODE_NORMAL:
// B12,B13: disable normal mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_mode(GPIOB, 12, MODE_ANALOG);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_mode(GPIOB, 13, MODE_ANALOG);
// B5,B6: FDCAN2 mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2);
can_mode = CAN_MODE_NORMAL;
board_v2_enable_can_transciever(2U, true);
break;
case CAN_MODE_OBD_CAN2:
// B5,B6: disable normal mode
set_gpio_pullup(GPIOB, 5, PULL_NONE);
set_gpio_mode(GPIOB, 5, MODE_ANALOG);
set_gpio_pullup(GPIOB, 6, PULL_NONE);
set_gpio_mode(GPIOB, 6, MODE_ANALOG);
// B12,B13: FDCAN2 mode
set_gpio_pullup(GPIOB, 12, PULL_NONE);
set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2);
set_gpio_pullup(GPIOB, 13, PULL_NONE);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2);
can_mode = CAN_MODE_OBD_CAN2;
board_v2_enable_can_transciever(4U, true);
break;
default:
break;
}
}
bool panda_power = false;
uint8_t panda_power_bitmask = 0U;
void board_v2_set_panda_power(bool enable) {
panda_power = enable;
gpio_set_all_output(power_pins, sizeof(power_pins) / sizeof(gpio_t), enable);
if (enable) {
panda_power_bitmask = 0xFFU;
} else {
panda_power_bitmask = 0U;
}
}
void board_v2_set_panda_individual_power(uint8_t port_num, bool enable) {
port_num -= 1U;
if (port_num < 6U) {
panda_power_bitmask &= ~(1U << port_num);
panda_power_bitmask |= (enable ? 1U : 0U) << port_num;
} else {
print("Invalid port number ("); puth(port_num); print("): enabling failed\n");
}
gpio_set_bitmask(power_pins, sizeof(power_pins) / sizeof(gpio_t), (uint32_t)panda_power_bitmask);
}
bool board_v2_get_button(void) {
return get_gpio_input(GPIOG, 15);
}
void board_v2_set_ignition(bool enabled) {
ignition = enabled ? 0xFFU : 0U;
board_v2_set_harness_orientation(harness_orientation);
}
void board_v2_set_individual_ignition(uint8_t bitmask) {
ignition = bitmask;
board_v2_set_harness_orientation(harness_orientation);
}
float board_v2_get_channel_power(uint8_t channel) {
float ret = 0.0f;
if ((channel >= 1U) && (channel <= 6U)) {
uint16_t readout = adc_get_mV(ADC1, channel - 1U); // these are mapped nicely in hardware
ret = (((float) readout / 33e6) - 0.8e-6) / 52e-6 * 12.0f;
} else {
print("Invalid channel ("); puth(channel); print(")\n");
}
return ret;
}
uint16_t board_v2_get_sbu_mV(uint8_t channel, uint8_t sbu) {
uint16_t ret = 0U;
if ((channel >= 1U) && (channel <= 6U)) {
switch(sbu){
case SBU1:
ret = adc_get_mV(sbu1_channels[channel - 1U].adc, sbu1_channels[channel - 1U].channel);
break;
case SBU2:
ret = adc_get_mV(sbu2_channels[channel - 1U].adc, sbu2_channels[channel - 1U].channel);
break;
default:
print("Invalid SBU ("); puth(sbu); print(")\n");
break;
}
} else {
print("Invalid channel ("); puth(channel); print(")\n");
}
return ret;
}
void board_v2_init(void) {
common_init_gpio();
// Disable LEDs
board_v2_set_led(LED_RED, false);
board_v2_set_led(LED_GREEN, false);
board_v2_set_led(LED_BLUE, false);
// Normal CAN mode
board_v2_set_can_mode(CAN_MODE_NORMAL);
// Enable CAN transcievers
for(uint8_t i = 1; i <= 4; i++) {
board_v2_enable_can_transciever(i, true);
}
// Set to no harness orientation
board_v2_set_harness_orientation(HARNESS_ORIENTATION_NONE);
// Enable panda power by default
board_v2_set_panda_power(true);
// Current monitor channels
adc_init(ADC1);
register_set_bits(&SYSCFG->PMCR, SYSCFG_PMCR_PA0SO | SYSCFG_PMCR_PA1SO); // open up analog switches for PA0_C and PA1_C
set_gpio_mode(GPIOF, 11, MODE_ANALOG);
set_gpio_mode(GPIOA, 6, MODE_ANALOG);
set_gpio_mode(GPIOC, 4, MODE_ANALOG);
set_gpio_mode(GPIOB, 1, MODE_ANALOG);
// SBU channels
adc_init(ADC3);
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
set_gpio_mode(GPIOF, 9, MODE_ANALOG);
set_gpio_mode(GPIOF, 7, MODE_ANALOG);
set_gpio_mode(GPIOF, 5, MODE_ANALOG);
set_gpio_mode(GPIOF, 3, MODE_ANALOG);
set_gpio_mode(GPIOF, 10, MODE_ANALOG);
set_gpio_mode(GPIOF, 8, MODE_ANALOG);
set_gpio_mode(GPIOF, 6, MODE_ANALOG);
set_gpio_mode(GPIOF, 4, MODE_ANALOG);
set_gpio_mode(GPIOC, 0, MODE_ANALOG);
set_gpio_mode(GPIOC, 1, MODE_ANALOG);
// Header pins
set_gpio_mode(GPIOG, 0, MODE_OUTPUT);
set_gpio_mode(GPIOG, 1, MODE_OUTPUT);
set_gpio_mode(GPIOG, 2, MODE_OUTPUT);
set_gpio_mode(GPIOG, 3, MODE_OUTPUT);
set_gpio_mode(GPIOG, 4, MODE_OUTPUT);
set_gpio_mode(GPIOG, 5, MODE_OUTPUT);
set_gpio_mode(GPIOG, 6, MODE_OUTPUT);
set_gpio_mode(GPIOG, 7, MODE_OUTPUT);
}
void board_v2_tick(void) {}
const board board_v2 = {
.has_canfd = true,
.has_sbu_sense = true,
.avdd_mV = 3300U,
.init = &board_v2_init,
.set_led = &board_v2_set_led,
.board_tick = &board_v2_tick,
.get_button = &board_v2_get_button,
.set_panda_power = &board_v2_set_panda_power,
.set_panda_individual_power = &board_v2_set_panda_individual_power,
.set_ignition = &board_v2_set_ignition,
.set_individual_ignition = &board_v2_set_individual_ignition,
.set_harness_orientation = &board_v2_set_harness_orientation,
.set_can_mode = &board_v2_set_can_mode,
.enable_can_transciever = &board_v2_enable_can_transciever,
.enable_header_pin = &board_v2_enable_header_pin,
.get_channel_power = &board_v2_get_channel_power,
.get_sbu_mV = &board_v2_get_sbu_mV,
};

View File

@@ -0,0 +1,24 @@
// When changing these structs, python/__init__.py needs to be kept up to date!
#define JUNGLE_HEALTH_PACKET_VERSION 1
struct __attribute__((packed)) jungle_health_t {
uint32_t uptime_pkt;
float ch1_power;
float ch2_power;
float ch3_power;
float ch4_power;
float ch5_power;
float ch6_power;
uint16_t ch1_sbu1_mV;
uint16_t ch1_sbu2_mV;
uint16_t ch2_sbu1_mV;
uint16_t ch2_sbu2_mV;
uint16_t ch3_sbu1_mV;
uint16_t ch3_sbu2_mV;
uint16_t ch4_sbu1_mV;
uint16_t ch4_sbu2_mV;
uint16_t ch5_sbu1_mV;
uint16_t ch5_sbu2_mV;
uint16_t ch6_sbu1_mV;
uint16_t ch6_sbu2_mV;
};

View File

@@ -0,0 +1,261 @@
extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used
int get_jungle_health_pkt(void *dat) {
COMPILE_TIME_ASSERT(sizeof(struct jungle_health_t) <= USBPACKET_MAX_SIZE);
struct jungle_health_t * health = (struct jungle_health_t*)dat;
health->uptime_pkt = uptime_cnt;
health->ch1_power = current_board->get_channel_power(1U);
health->ch2_power = current_board->get_channel_power(2U);
health->ch3_power = current_board->get_channel_power(3U);
health->ch4_power = current_board->get_channel_power(4U);
health->ch5_power = current_board->get_channel_power(5U);
health->ch6_power = current_board->get_channel_power(6U);
health->ch1_sbu1_mV = current_board->get_sbu_mV(1U, SBU1);
health->ch1_sbu2_mV = current_board->get_sbu_mV(1U, SBU2);
health->ch2_sbu1_mV = current_board->get_sbu_mV(2U, SBU1);
health->ch2_sbu2_mV = current_board->get_sbu_mV(2U, SBU2);
health->ch3_sbu1_mV = current_board->get_sbu_mV(3U, SBU1);
health->ch3_sbu2_mV = current_board->get_sbu_mV(3U, SBU2);
health->ch4_sbu1_mV = current_board->get_sbu_mV(4U, SBU1);
health->ch4_sbu2_mV = current_board->get_sbu_mV(4U, SBU2);
health->ch5_sbu1_mV = current_board->get_sbu_mV(5U, SBU1);
health->ch5_sbu2_mV = current_board->get_sbu_mV(5U, SBU2);
health->ch6_sbu1_mV = current_board->get_sbu_mV(6U, SBU1);
health->ch6_sbu2_mV = current_board->get_sbu_mV(6U, SBU2);
return sizeof(*health);
}
// send on serial, first byte to select the ring
void comms_endpoint2_write(const uint8_t *data, uint32_t len) {
UNUSED(data);
UNUSED(len);
}
int comms_control_handler(ControlPacket_t *req, uint8_t *resp) {
unsigned int resp_len = 0;
uint32_t time;
#ifdef DEBUG_COMMS
print("raw control request: "); hexdump(req, sizeof(ControlPacket_t)); print("\n");
print("- request "); puth(req->request); print("\n");
print("- param1 "); puth(req->param1); print("\n");
print("- param2 "); puth(req->param2); print("\n");
#endif
switch (req->request) {
// **** 0xa0: Set panda power.
case 0xa0:
current_board->set_panda_power((req->param1 == 1U));
break;
// **** 0xa1: Set harness orientation.
case 0xa1:
current_board->set_harness_orientation(req->param1);
break;
// **** 0xa2: Set ignition.
case 0xa2:
current_board->set_ignition((req->param1 == 1U));
break;
// **** 0xa0: Set panda power per channel by bitmask.
case 0xa3:
current_board->set_panda_individual_power(req->param1, (req->param2 > 0U));
break;
// **** 0xa8: get microsecond timer
case 0xa8:
time = microsecond_timer_get();
resp[0] = (time & 0x000000FFU);
resp[1] = ((time & 0x0000FF00U) >> 8U);
resp[2] = ((time & 0x00FF0000U) >> 16U);
resp[3] = ((time & 0xFF000000U) >> 24U);
resp_len = 4U;
break;
// **** 0xc0: reset communications
case 0xc0:
comms_can_reset();
break;
// **** 0xc1: get hardware type
case 0xc1:
resp[0] = hw_type;
resp_len = 1;
break;
// **** 0xc2: CAN health stats
case 0xc2:
COMPILE_TIME_ASSERT(sizeof(can_health_t) <= USBPACKET_MAX_SIZE);
if (req->param1 < 3U) {
update_can_health_pkt(req->param1, 0U);
can_health[req->param1].can_speed = (bus_config[req->param1].can_speed / 10U);
can_health[req->param1].can_data_speed = (bus_config[req->param1].can_data_speed / 10U);
can_health[req->param1].canfd_enabled = bus_config[req->param1].canfd_enabled;
can_health[req->param1].brs_enabled = bus_config[req->param1].brs_enabled;
can_health[req->param1].canfd_non_iso = bus_config[req->param1].canfd_non_iso;
resp_len = sizeof(can_health[req->param1]);
(void)memcpy(resp, &can_health[req->param1], resp_len);
}
break;
// **** 0xc3: fetch MCU UID
case 0xc3:
(void)memcpy(resp, ((uint8_t *)UID_BASE), 12);
resp_len = 12;
break;
// **** 0xd0: fetch serial (aka the provisioned dongle ID)
case 0xd0:
// addresses are OTP
if (req->param1 == 1U) {
(void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10);
resp_len = 0x10;
} else {
get_provision_chunk(resp);
resp_len = PROVISION_CHUNK_LEN;
}
break;
// **** 0xd1: enter bootloader mode
case 0xd1:
// this allows reflashing of the bootstub
switch (req->param1) {
case 0:
// only allow bootloader entry on debug builds
#ifdef ALLOW_DEBUG
print("-> entering bootloader\n");
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
#endif
break;
case 1:
print("-> entering softloader\n");
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
NVIC_SystemReset();
break;
default:
print("Bootloader mode invalid\n");
break;
}
break;
// **** 0xd2: get health packet
case 0xd2:
resp_len = get_jungle_health_pkt(resp);
break;
// **** 0xd3: get first 64 bytes of signature
case 0xd3:
{
resp_len = 64;
char * code = (char*)_app_start;
int code_len = _app_start[0];
(void)memcpy(resp, &code[code_len], resp_len);
}
break;
// **** 0xd4: get second 64 bytes of signature
case 0xd4:
{
resp_len = 64;
char * code = (char*)_app_start;
int code_len = _app_start[0];
(void)memcpy(resp, &code[code_len + 64], resp_len);
}
break;
// **** 0xd6: get version
case 0xd6:
COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE);
(void)memcpy(resp, gitversion, sizeof(gitversion));
resp_len = sizeof(gitversion) - 1U;
break;
// **** 0xd8: reset ST
case 0xd8:
NVIC_SystemReset();
break;
// **** 0xdb: set OBD CAN multiplexing mode
case 0xdb:
if (req->param1 == 1U) {
// Enable OBD CAN
current_board->set_can_mode(CAN_MODE_OBD_CAN2);
} else {
// Disable OBD CAN
current_board->set_can_mode(CAN_MODE_NORMAL);
}
break;
// **** 0xdd: get healthpacket and CANPacket versions
case 0xdd:
resp[0] = JUNGLE_HEALTH_PACKET_VERSION;
resp[1] = CAN_PACKET_VERSION;
resp[2] = CAN_HEALTH_PACKET_VERSION;
resp_len = 3;
break;
// **** 0xde: set can bitrate
case 0xde:
if ((req->param1 < PANDA_BUS_CNT) && is_speed_valid(req->param2, speeds, sizeof(speeds)/sizeof(speeds[0]))) {
bus_config[req->param1].can_speed = req->param2;
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
// **** 0xe0: debug read
case 0xe0:
// read
while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && get_char(get_ring_by_number(0), (char*)&resp[resp_len])) {
++resp_len;
}
break;
// **** 0xe5: set CAN loopback (for testing)
case 0xe5:
can_loopback = (req->param1 > 0U);
can_init_all();
break;
// **** 0xf1: Clear CAN ring buffer.
case 0xf1:
if (req->param1 == 0xFFFFU) {
print("Clearing CAN Rx queue\n");
can_clear(&can_rx_q);
} else if (req->param1 < PANDA_BUS_CNT) {
print("Clearing CAN Tx queue\n");
can_clear(can_queues[req->param1]);
} else {
print("Clearing CAN CAN ring buffer failed: wrong bus number\n");
}
break;
// **** 0xf2: Clear debug ring buffer.
case 0xf2:
print("Clearing debug queue.\n");
clear_uart_buff(get_ring_by_number(0));
break;
// **** 0xf4: Set CAN transceiver enable pin
case 0xf4:
current_board->enable_can_transciever(req->param1, req->param2 > 0U);
break;
// **** 0xf5: Set CAN silent mode
case 0xf5:
can_silent = (req->param1 > 0U) ? ALL_CAN_SILENT : ALL_CAN_LIVE;
can_init_all();
break;
// **** 0xf7: enable/disable header pin by number
case 0xf7:
current_board->enable_header_pin(req->param1, req->param2 > 0U);
break;
// **** 0xf9: set CAN FD data bitrate
case 0xf9:
if ((req->param1 < PANDA_CAN_CNT) &&
current_board->has_canfd &&
is_speed_valid(req->param2, data_speeds, sizeof(data_speeds)/sizeof(data_speeds[0]))) {
bus_config[req->param1].can_data_speed = req->param2;
bus_config[req->param1].canfd_enabled = (req->param2 >= bus_config[req->param1].can_speed);
bus_config[req->param1].brs_enabled = (req->param2 > bus_config[req->param1].can_speed);
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
// **** 0xfc: set CAN FD non-ISO mode
case 0xfc:
if ((req->param1 < PANDA_CAN_CNT) && current_board->has_canfd) {
bus_config[req->param1].canfd_non_iso = (req->param2 != 0U);
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
default:
print("NO HANDLER ");
puth(req->request);
print("\n");
break;
}
return resp_len;
}

View File

@@ -4,6 +4,6 @@ from panda import PandaJungle
if __name__ == "__main__":
for p in PandaJungle.list():
pp = PandaJungle(p)
print("%s: %s" % (pp.get_serial()[0], pp.get_version()))
print(f"{pp.get_serial()[0]}: {pp.get_version()}")

View File

@@ -0,0 +1,7 @@
#include "boards/board_declarations.h"
#include "boards/board_v1.h"
void detect_board_type(void) {
hw_type = HW_TYPE_V1;
current_board = &board_v1;
}

View File

@@ -0,0 +1,9 @@
#include "boards/board_declarations.h"
#include "stm32h7/lladc.h"
#include "boards/board_v2.h"
void detect_board_type(void) {
hw_type = HW_TYPE_V2;
current_board = &board_v2;
}

View File

@@ -0,0 +1,54 @@
typedef struct {
ADC_TypeDef *adc;
uint8_t channel;
} adc_channel_t;
void adc_init(ADC_TypeDef *adc) {
adc->CR &= ~(ADC_CR_DEEPPWD); // Reset deep-power-down mode
adc->CR |= ADC_CR_ADVREGEN; // Enable ADC regulator
while(!(adc->ISR & ADC_ISR_LDORDY) && (adc != ADC3));
if (adc != ADC3) {
adc->CR &= ~(ADC_CR_ADCALDIF); // Choose single-ended calibration
adc->CR |= ADC_CR_ADCALLIN; // Lineriality calibration
}
adc->CR |= ADC_CR_ADCAL; // Start calibrtation
while((adc->CR & ADC_CR_ADCAL) != 0);
adc->ISR |= ADC_ISR_ADRDY;
adc->CR |= ADC_CR_ADEN;
while(!(adc->ISR & ADC_ISR_ADRDY));
}
uint16_t adc_get_raw(ADC_TypeDef *adc, uint8_t channel) {
adc->SQR1 &= ~(ADC_SQR1_L);
adc->SQR1 = ((uint32_t) channel << 6U);
if (channel < 10U) {
adc->SMPR1 = (0x7U << (channel * 3U));
} else {
adc->SMPR2 = (0x7U << ((channel - 10U) * 3U));
}
adc->PCSEL_RES0 = (0x1U << channel);
adc->CR |= ADC_CR_ADSTART;
while (!(adc->ISR & ADC_ISR_EOC));
uint16_t res = adc->DR;
while (!(adc->ISR & ADC_ISR_EOS));
adc->ISR |= ADC_ISR_EOS;
return res;
}
uint16_t adc_get_mV(ADC_TypeDef *adc, uint8_t channel) {
uint16_t ret = 0;
if ((adc == ADC1) || (adc == ADC2)) {
ret = (adc_get_raw(adc, channel) * current_board->avdd_mV) / 65535U;
} else if (adc == ADC3) {
ret = (adc_get_raw(adc, channel) * current_board->avdd_mV) / 4095U;
} else {}
return ret;
}

67
panda/board/libc.h Normal file
View File

@@ -0,0 +1,67 @@
// **** libc ****
void delay(uint32_t a) {
volatile uint32_t i;
for (i = 0; i < a; i++);
}
// cppcheck-suppress misra-c2012-21.2
void *memset(void *str, int c, unsigned int n) {
uint8_t *s = str;
for (unsigned int i = 0; i < n; i++) {
*s = c;
s++;
}
return str;
}
#define UNALIGNED(X, Y) \
(((uint32_t)(X) & (sizeof(uint32_t) - 1U)) | ((uint32_t)(Y) & (sizeof(uint32_t) - 1U)))
// cppcheck-suppress misra-c2012-21.2
void *memcpy(void *dest, const void *src, unsigned int len) {
unsigned int n = len;
uint8_t *d8 = dest;
const uint8_t *s8 = src;
if ((n >= 4U) && !UNALIGNED(s8, d8)) {
uint32_t *d32 = (uint32_t *)d8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned
const uint32_t *s32 = (const uint32_t *)s8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned
while(n >= 16U) {
*d32 = *s32; d32++; s32++;
*d32 = *s32; d32++; s32++;
*d32 = *s32; d32++; s32++;
*d32 = *s32; d32++; s32++;
n -= 16U;
}
while(n >= 4U) {
*d32 = *s32; d32++; s32++;
n -= 4U;
}
d8 = (uint8_t *)d32;
s8 = (const uint8_t *)s32;
}
while (n-- > 0U) {
*d8 = *s8; d8++; s8++;
}
return dest;
}
// cppcheck-suppress misra-c2012-21.2
int memcmp(const void * ptr1, const void * ptr2, unsigned int num) {
int ret = 0;
const uint8_t *p1 = ptr1;
const uint8_t *p2 = ptr2;
for (unsigned int i = 0; i < num; i++) {
if (*p1 != *p2) {
ret = -1;
break;
}
p1++;
p2++;
}
return ret;
}

View File

@@ -294,24 +294,6 @@ void EXTI_IRQ_Handler(void) {
}
}
uint8_t rtc_counter = 0;
void RTC_WKUP_IRQ_Handler(void) {
exti_irq_clear();
clock_init();
rtc_counter++;
if ((rtc_counter % 2U) == 0U) {
current_board->set_led(LED_BLUE, false);
} else {
current_board->set_led(LED_BLUE, true);
}
if (rtc_counter == __UINT8_MAX__) {
rtc_counter = 1U;
}
}
int main(void) {
// Init interrupt table
init_interrupts(true);
@@ -422,10 +404,6 @@ int main(void) {
// Init IRQs for CAN transceiver and ignition line
exti_irq_init();
// Init RTC Wakeup event on EXTI22
REGISTER_INTERRUPT(RTC_WKUP_IRQn, RTC_WKUP_IRQ_Handler, 10U, FAULT_INTERRUPT_RATE_EXTI)
rtc_wakeup_init();
// STOP mode
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
}

397
panda/board/main_comms.h Normal file
View File

@@ -0,0 +1,397 @@
extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used
// Prototypes
void set_safety_mode(uint16_t mode, uint16_t param);
bool is_car_safety_mode(uint16_t mode);
int get_health_pkt(void *dat) {
COMPILE_TIME_ASSERT(sizeof(struct health_t) <= USBPACKET_MAX_SIZE);
struct health_t * health = (struct health_t*)dat;
health->uptime_pkt = uptime_cnt;
health->voltage_pkt = current_board->read_voltage_mV();
health->current_pkt = current_board->read_current_mA();
// Use the GPIO pin to determine ignition or use a CAN based logic
health->ignition_line_pkt = (uint8_t)(current_board->check_ignition());
health->ignition_can_pkt = ignition_can;
health->controls_allowed_pkt = controls_allowed;
health->safety_tx_blocked_pkt = safety_tx_blocked;
health->safety_rx_invalid_pkt = safety_rx_invalid;
health->tx_buffer_overflow_pkt = tx_buffer_overflow;
health->rx_buffer_overflow_pkt = rx_buffer_overflow;
health->gmlan_send_errs_pkt = gmlan_send_errs;
health->car_harness_status_pkt = harness.status;
health->safety_mode_pkt = (uint8_t)(current_safety_mode);
health->safety_param_pkt = current_safety_param;
health->alternative_experience_pkt = alternative_experience;
health->power_save_enabled_pkt = power_save_status == POWER_SAVE_STATUS_ENABLED;
health->heartbeat_lost_pkt = heartbeat_lost;
health->safety_rx_checks_invalid_pkt = safety_rx_checks_invalid;
health->spi_checksum_error_count_pkt = spi_checksum_error_count;
health->fault_status_pkt = fault_status;
health->faults_pkt = faults;
health->interrupt_load_pkt = interrupt_load;
health->fan_power = fan_state.power;
health->fan_stall_count = fan_state.total_stall_count;
health->sbu1_voltage_mV = harness.sbu1_voltage_mV;
health->sbu2_voltage_mV = harness.sbu2_voltage_mV;
health->som_reset_triggered = bootkick_reset_triggered;
return sizeof(*health);
}
// send on serial, first byte to select the ring
void comms_endpoint2_write(const uint8_t *data, uint32_t len) {
uart_ring *ur = get_ring_by_number(data[0]);
if ((len != 0U) && (ur != NULL)) {
if ((data[0] < 2U) || (data[0] >= 4U)) {
for (uint32_t i = 1; i < len; i++) {
while (!put_char(ur, data[i])) {
// wait
}
}
}
}
}
int comms_control_handler(ControlPacket_t *req, uint8_t *resp) {
unsigned int resp_len = 0;
uart_ring *ur = NULL;
uint32_t time;
#ifdef DEBUG_COMMS
print("raw control request: "); hexdump(req, sizeof(ControlPacket_t)); print("\n");
print("- request "); puth(req->request); print("\n");
print("- param1 "); puth(req->param1); print("\n");
print("- param2 "); puth(req->param2); print("\n");
#endif
switch (req->request) {
// **** 0xa8: get microsecond timer
case 0xa8:
time = microsecond_timer_get();
resp[0] = (time & 0x000000FFU);
resp[1] = ((time & 0x0000FF00U) >> 8U);
resp[2] = ((time & 0x00FF0000U) >> 16U);
resp[3] = ((time & 0xFF000000U) >> 24U);
resp_len = 4U;
break;
// **** 0xb0: set IR power
case 0xb0:
current_board->set_ir_power(req->param1);
break;
// **** 0xb1: set fan power
case 0xb1:
fan_set_power(req->param1);
break;
// **** 0xb2: get fan rpm
case 0xb2:
resp[0] = (fan_state.rpm & 0x00FFU);
resp[1] = ((fan_state.rpm & 0xFF00U) >> 8U);
resp_len = 2;
break;
// **** 0xc0: reset communications
case 0xc0:
comms_can_reset();
break;
// **** 0xc1: get hardware type
case 0xc1:
resp[0] = hw_type;
resp_len = 1;
break;
// **** 0xc2: CAN health stats
case 0xc2:
COMPILE_TIME_ASSERT(sizeof(can_health_t) <= USBPACKET_MAX_SIZE);
if (req->param1 < 3U) {
update_can_health_pkt(req->param1, 0U);
can_health[req->param1].can_speed = (bus_config[req->param1].can_speed / 10U);
can_health[req->param1].can_data_speed = (bus_config[req->param1].can_data_speed / 10U);
can_health[req->param1].canfd_enabled = bus_config[req->param1].canfd_enabled;
can_health[req->param1].brs_enabled = bus_config[req->param1].brs_enabled;
can_health[req->param1].canfd_non_iso = bus_config[req->param1].canfd_non_iso;
resp_len = sizeof(can_health[req->param1]);
(void)memcpy(resp, &can_health[req->param1], resp_len);
}
break;
// **** 0xc3: fetch MCU UID
case 0xc3:
(void)memcpy(resp, ((uint8_t *)UID_BASE), 12);
resp_len = 12;
break;
// **** 0xc4: get interrupt call rate
case 0xc4:
if (req->param1 < NUM_INTERRUPTS) {
uint32_t load = interrupts[req->param1].call_rate;
resp[0] = (load & 0x000000FFU);
resp[1] = ((load & 0x0000FF00U) >> 8U);
resp[2] = ((load & 0x00FF0000U) >> 16U);
resp[3] = ((load & 0xFF000000U) >> 24U);
resp_len = 4U;
}
break;
// **** 0xc5: DEBUG: drive relay
case 0xc5:
set_intercept_relay((req->param1 & 0x1U), (req->param1 & 0x2U));
break;
// **** 0xc6: DEBUG: read SOM GPIO
case 0xc6:
resp[0] = current_board->read_som_gpio();
resp_len = 1;
break;
// **** 0xd0: fetch serial (aka the provisioned dongle ID)
case 0xd0:
// addresses are OTP
if (req->param1 == 1U) {
(void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10);
resp_len = 0x10;
} else {
get_provision_chunk(resp);
resp_len = PROVISION_CHUNK_LEN;
}
break;
// **** 0xd1: enter bootloader mode
case 0xd1:
// this allows reflashing of the bootstub
switch (req->param1) {
case 0:
// only allow bootloader entry on debug builds
#ifdef ALLOW_DEBUG
print("-> entering bootloader\n");
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
#endif
break;
case 1:
print("-> entering softloader\n");
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
NVIC_SystemReset();
break;
default:
print("Bootloader mode invalid\n");
break;
}
break;
// **** 0xd2: get health packet
case 0xd2:
resp_len = get_health_pkt(resp);
break;
// **** 0xd3: get first 64 bytes of signature
case 0xd3:
{
resp_len = 64;
char * code = (char*)_app_start;
int code_len = _app_start[0];
(void)memcpy(resp, &code[code_len], resp_len);
}
break;
// **** 0xd4: get second 64 bytes of signature
case 0xd4:
{
resp_len = 64;
char * code = (char*)_app_start;
int code_len = _app_start[0];
(void)memcpy(resp, &code[code_len + 64], resp_len);
}
break;
// **** 0xd6: get version
case 0xd6:
COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE);
(void)memcpy(resp, gitversion, sizeof(gitversion));
resp_len = sizeof(gitversion) - 1U;
break;
// **** 0xd8: reset ST
case 0xd8:
NVIC_SystemReset();
break;
// **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode
case 0xdb:
if(current_board->has_obd){
if (req->param1 == 1U) {
// Enable OBD CAN
current_board->set_can_mode(CAN_MODE_OBD_CAN2);
} else {
// Disable OBD CAN
current_board->set_can_mode(CAN_MODE_NORMAL);
}
}
break;
// **** 0xdc: set safety mode
case 0xdc:
set_safety_mode(req->param1, (uint16_t)req->param2);
break;
// **** 0xdd: get healthpacket and CANPacket versions
case 0xdd:
resp[0] = HEALTH_PACKET_VERSION;
resp[1] = CAN_PACKET_VERSION;
resp[2] = CAN_HEALTH_PACKET_VERSION;
resp_len = 3;
break;
// **** 0xde: set can bitrate
case 0xde:
if ((req->param1 < PANDA_BUS_CNT) && is_speed_valid(req->param2, speeds, sizeof(speeds)/sizeof(speeds[0]))) {
bus_config[req->param1].can_speed = req->param2;
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
// **** 0xdf: set alternative experience
case 0xdf:
// you can only set this if you are in a non car safety mode
if (!is_car_safety_mode(current_safety_mode)) {
alternative_experience = req->param1;
}
break;
// **** 0xe0: uart read
case 0xe0:
ur = get_ring_by_number(req->param1);
if (!ur) {
break;
}
// read
uint16_t req_length = MIN(req->length, USBPACKET_MAX_SIZE);
while ((resp_len < req_length) &&
get_char(ur, (char*)&resp[resp_len])) {
++resp_len;
}
break;
// **** 0xe1: uart set baud rate
case 0xe1:
ur = get_ring_by_number(req->param1);
if (!ur) {
break;
}
uart_set_baud(ur->uart, req->param2);
break;
// **** 0xe2: uart set parity
case 0xe2:
ur = get_ring_by_number(req->param1);
if (!ur) {
break;
}
switch (req->param2) {
case 0:
// disable parity, 8-bit
ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M);
break;
case 1:
// even parity, 9-bit
ur->uart->CR1 &= ~USART_CR1_PS;
ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M;
break;
case 2:
// odd parity, 9-bit
ur->uart->CR1 |= USART_CR1_PS;
ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M;
break;
default:
break;
}
break;
// **** 0xe4: uart set baud rate extended
case 0xe4:
ur = get_ring_by_number(req->param1);
if (!ur) {
break;
}
uart_set_baud(ur->uart, (int)req->param2*300);
break;
// **** 0xe5: set CAN loopback (for testing)
case 0xe5:
can_loopback = req->param1 > 0U;
can_init_all();
break;
// **** 0xe6: set custom clock source period
case 0xe6:
clock_source_set_period(req->param1);
break;
// **** 0xe7: set power save state
case 0xe7:
set_power_save_state(req->param1);
break;
// **** 0xf1: Clear CAN ring buffer.
case 0xf1:
if (req->param1 == 0xFFFFU) {
print("Clearing CAN Rx queue\n");
can_clear(&can_rx_q);
} else if (req->param1 < PANDA_BUS_CNT) {
print("Clearing CAN Tx queue\n");
can_clear(can_queues[req->param1]);
} else {
print("Clearing CAN CAN ring buffer failed: wrong bus number\n");
}
break;
// **** 0xf2: Clear UART ring buffer.
case 0xf2:
{
uart_ring * rb = get_ring_by_number(req->param1);
if (rb != NULL) {
print("Clearing UART queue.\n");
clear_uart_buff(rb);
}
break;
}
// **** 0xf3: Heartbeat. Resets heartbeat counter.
case 0xf3:
{
heartbeat_counter = 0U;
heartbeat_lost = false;
heartbeat_disabled = false;
heartbeat_engaged = (req->param1 == 1U);
break;
}
// **** 0xf6: set siren enabled
case 0xf6:
siren_enabled = (req->param1 != 0U);
break;
// **** 0xf7: set green led enabled
case 0xf7:
green_led_enabled = (req->param1 != 0U);
break;
// **** 0xf8: disable heartbeat checks
case 0xf8:
if (!is_car_safety_mode(current_safety_mode)) {
heartbeat_disabled = true;
}
break;
// **** 0xf9: set CAN FD data bitrate
case 0xf9:
if ((req->param1 < PANDA_CAN_CNT) &&
current_board->has_canfd &&
is_speed_valid(req->param2, data_speeds, sizeof(data_speeds)/sizeof(data_speeds[0]))) {
bus_config[req->param1].can_data_speed = req->param2;
bus_config[req->param1].canfd_enabled = (req->param2 >= bus_config[req->param1].can_speed);
bus_config[req->param1].brs_enabled = (req->param2 > bus_config[req->param1].can_speed);
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
// **** 0xfb: allow highest power saving mode (stop) to be entered
case 0xfb:
deepsleep_allowed = true;
break;
// **** 0xfc: set CAN FD non-ISO mode
case 0xfc:
if ((req->param1 < PANDA_CAN_CNT) && current_board->has_canfd) {
bus_config[req->param1].canfd_non_iso = (req->param2 != 0U);
bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1));
UNUSED(ret);
}
break;
default:
print("NO HANDLER ");
puth(req->request);
print("\n");
break;
}
return resp_len;
}

View File

@@ -0,0 +1,32 @@
// ******************** Prototypes ********************
void print(const char *a);
void puth(unsigned int i);
void puth2(unsigned int i);
void puth4(unsigned int i);
void hexdump(const void *a, int l);
typedef struct board board;
typedef struct harness_configuration harness_configuration;
void can_flip_buses(uint8_t bus1, uint8_t bus2);
void pwm_init(TIM_TypeDef *TIM, uint8_t channel);
void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage);
// ********************* Globals **********************
uint8_t hw_type = 0;
const board *current_board;
uint32_t uptime_cnt = 0;
bool green_led_enabled = false;
// heartbeat state
uint32_t heartbeat_counter = 0;
bool heartbeat_lost = false;
bool heartbeat_disabled = false; // set over USB
// Enter deep sleep mode
bool deepsleep_allowed = false;
bool ignition_seen = false;
// siren state
bool siren_enabled = false;
uint32_t siren_countdown = 0; // siren plays while countdown > 0
uint32_t controls_allowed_countdown = 0;

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -1 +0,0 @@
DEV-a165aa11-DEBUG

View File

@@ -0,0 +1,46 @@
// WARNING: To stay in compliance with the SIL2 rules laid out in STM UM1840, we should never implement any of the available hardware low power modes.
// See rule: CoU_3
#define POWER_SAVE_STATUS_DISABLED 0
#define POWER_SAVE_STATUS_ENABLED 1
int power_save_status = POWER_SAVE_STATUS_DISABLED;
void set_power_save_state(int state) {
bool is_valid_state = (state == POWER_SAVE_STATUS_ENABLED) || (state == POWER_SAVE_STATUS_DISABLED);
if (is_valid_state && (state != power_save_status)) {
bool enable = false;
if (state == POWER_SAVE_STATUS_ENABLED) {
print("enable power savings\n");
// Disable CAN interrupts
if (harness.status == HARNESS_STATUS_FLIPPED) {
llcan_irq_disable(cans[0]);
} else {
llcan_irq_disable(cans[2]);
}
llcan_irq_disable(cans[1]);
} else {
print("disable power savings\n");
if (harness.status == HARNESS_STATUS_FLIPPED) {
llcan_irq_enable(cans[0]);
} else {
llcan_irq_enable(cans[2]);
}
llcan_irq_enable(cans[1]);
enable = true;
}
current_board->enable_can_transceivers(enable);
// Switch off IR when in power saving
if(!enable){
current_board->set_ir_power(0U);
}
power_save_status = state;
}
}

13
panda/board/provision.h Normal file
View File

@@ -0,0 +1,13 @@
// this is where we manage the dongle ID assigned during our
// manufacturing. aside from this, there's a UID for the MCU
#define PROVISION_CHUNK_LEN 0x20
const char unprovisioned_text[] = "\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";
void get_provision_chunk(uint8_t *resp) {
(void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN);
if (memcmp(resp, unprovisioned_text, 0x20) == 0) {
(void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20);
}
}

708
panda/board/safety.h Normal file
View File

@@ -0,0 +1,708 @@
#include "safety_declarations.h"
#include "can_definitions.h"
// include the safety policies.
#include "safety/safety_defaults.h"
#include "safety/safety_honda.h"
#include "safety/safety_toyota.h"
#include "safety/safety_tesla.h"
#include "safety/safety_gm.h"
#include "safety/safety_ford.h"
#include "safety/safety_hyundai.h"
#include "safety/safety_chrysler.h"
#include "safety/safety_subaru.h"
#include "safety/safety_subaru_preglobal.h"
#include "safety/safety_mazda.h"
#include "safety/safety_nissan.h"
#include "safety/safety_volkswagen_mqb.h"
#include "safety/safety_volkswagen_pq.h"
#include "safety/safety_elm327.h"
#include "safety/safety_body.h"
// CAN-FD only safety modes
#ifdef CANFD
#include "safety/safety_hyundai_canfd.h"
#endif
// from cereal.car.CarParams.SafetyModel
#define SAFETY_SILENT 0U
#define SAFETY_HONDA_NIDEC 1U
#define SAFETY_TOYOTA 2U
#define SAFETY_ELM327 3U
#define SAFETY_GM 4U
#define SAFETY_HONDA_BOSCH_GIRAFFE 5U
#define SAFETY_FORD 6U
#define SAFETY_HYUNDAI 8U
#define SAFETY_CHRYSLER 9U
#define SAFETY_TESLA 10U
#define SAFETY_SUBARU 11U
#define SAFETY_MAZDA 13U
#define SAFETY_NISSAN 14U
#define SAFETY_VOLKSWAGEN_MQB 15U
#define SAFETY_ALLOUTPUT 17U
#define SAFETY_GM_ASCM 18U
#define SAFETY_NOOUTPUT 19U
#define SAFETY_HONDA_BOSCH 20U
#define SAFETY_VOLKSWAGEN_PQ 21U
#define SAFETY_SUBARU_PREGLOBAL 22U
#define SAFETY_HYUNDAI_LEGACY 23U
#define SAFETY_HYUNDAI_COMMUNITY 24U
#define SAFETY_STELLANTIS 25U
#define SAFETY_FAW 26U
#define SAFETY_BODY 27U
#define SAFETY_HYUNDAI_CANFD 28U
uint16_t current_safety_mode = SAFETY_SILENT;
uint16_t current_safety_param = 0;
const safety_hooks *current_hooks = &nooutput_hooks;
safety_config current_safety_config;
bool safety_rx_hook(const CANPacket_t *to_push) {
bool controls_allowed_prev = controls_allowed;
bool valid = rx_msg_safety_check(to_push, &current_safety_config, current_hooks);
if (valid) {
current_hooks->rx(to_push);
}
// reset mismatches on rising edge of controls_allowed to avoid rare race condition
if (controls_allowed && !controls_allowed_prev) {
heartbeat_engaged_mismatches = 0;
}
return valid;
}
bool safety_tx_hook(CANPacket_t *to_send) {
bool whitelisted = msg_allowed(to_send, current_safety_config.tx_msgs, current_safety_config.tx_msgs_len);
if ((current_safety_mode == SAFETY_ALLOUTPUT) || (current_safety_mode == SAFETY_ELM327)) {
whitelisted = true;
}
const bool safety_allowed = current_hooks->tx(to_send);
return !relay_malfunction && whitelisted && safety_allowed;
}
int safety_fwd_hook(int bus_num, int addr) {
return (relay_malfunction ? -1 : current_hooks->fwd(bus_num, addr));
}
bool get_longitudinal_allowed(void) {
return controls_allowed && !gas_pressed_prev;
}
// Given a CRC-8 poly, generate a static lookup table to use with a fast CRC-8
// algorithm. Called at init time for safety modes using CRC-8.
void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) {
for (uint16_t i = 0U; i <= 0xFFU; i++) {
uint8_t crc = (uint8_t)i;
for (int j = 0; j < 8; j++) {
if ((crc & 0x80U) != 0U) {
crc = (uint8_t)((crc << 1) ^ poly);
} else {
crc <<= 1;
}
}
crc_lut[i] = crc;
}
}
void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) {
for (uint16_t i = 0; i < 256U; i++) {
uint16_t crc = i << 8U;
for (uint16_t j = 0; j < 8U; j++) {
if ((crc & 0x8000U) != 0U) {
crc = (uint16_t)((crc << 1) ^ poly);
} else {
crc <<= 1;
}
}
crc_lut[i] = crc;
}
}
bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len) {
int addr = GET_ADDR(to_send);
int bus = GET_BUS(to_send);
int length = GET_LEN(to_send);
bool allowed = false;
for (int i = 0; i < len; i++) {
if ((addr == msg_list[i].addr) && (bus == msg_list[i].bus) && (length == msg_list[i].len)) {
allowed = true;
break;
}
}
return allowed;
}
int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
int length = GET_LEN(to_push);
int index = -1;
for (int i = 0; i < len; i++) {
// if multiple msgs are allowed, determine which one is present on the bus
if (!addr_list[i].status.msg_seen) {
for (uint8_t j = 0U; (j < MAX_ADDR_CHECK_MSGS) && (addr_list[i].msg[j].addr != 0); j++) {
if ((addr == addr_list[i].msg[j].addr) && (bus == addr_list[i].msg[j].bus) &&
(length == addr_list[i].msg[j].len)) {
addr_list[i].status.index = j;
addr_list[i].status.msg_seen = true;
break;
}
}
}
if (addr_list[i].status.msg_seen) {
int idx = addr_list[i].status.index;
if ((addr == addr_list[i].msg[idx].addr) && (bus == addr_list[i].msg[idx].bus) &&
(length == addr_list[i].msg[idx].len)) {
index = i;
break;
}
}
}
return index;
}
// 1Hz safety function called by main. Now just a check for lagging safety messages
void safety_tick(const safety_config *cfg) {
bool rx_checks_invalid = false;
uint32_t ts = microsecond_timer_get();
if (cfg != NULL) {
for (int i=0; i < cfg->rx_checks_len; i++) {
uint32_t elapsed_time = get_ts_elapsed(ts, cfg->rx_checks[i].status.last_timestamp);
// lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep.
// Quite conservative to not risk false triggers.
// 2s of lag is worse case, since the function is called at 1Hz
uint32_t timestep = 1e6 / cfg->rx_checks[i].msg[cfg->rx_checks[i].status.index].frequency;
bool lagging = elapsed_time > MAX(timestep * MAX_MISSED_MSGS, 1e6);
cfg->rx_checks[i].status.lagging = lagging;
if (lagging) {
controls_allowed = false;
}
if (lagging || !is_msg_valid(cfg->rx_checks, i)) {
rx_checks_invalid = true;
}
}
}
safety_rx_checks_invalid = rx_checks_invalid;
}
void update_counter(RxCheck addr_list[], int index, uint8_t counter) {
if (index != -1) {
uint8_t expected_counter = (addr_list[index].status.last_counter + 1U) % (addr_list[index].msg[addr_list[index].status.index].max_counter + 1U);
addr_list[index].status.wrong_counters += (expected_counter == counter) ? -1 : 1;
addr_list[index].status.wrong_counters = CLAMP(addr_list[index].status.wrong_counters, 0, MAX_WRONG_COUNTERS);
addr_list[index].status.last_counter = counter;
}
}
bool is_msg_valid(RxCheck addr_list[], int index) {
bool valid = true;
if (index != -1) {
if (!addr_list[index].status.valid_checksum || !addr_list[index].status.valid_quality_flag || (addr_list[index].status.wrong_counters >= MAX_WRONG_COUNTERS)) {
valid = false;
controls_allowed = false;
}
}
return valid;
}
void update_addr_timestamp(RxCheck addr_list[], int index) {
if (index != -1) {
uint32_t ts = microsecond_timer_get();
addr_list[index].status.last_timestamp = ts;
}
}
bool rx_msg_safety_check(const CANPacket_t *to_push,
const safety_config *cfg,
const safety_hooks *safety_hooks) {
int index = get_addr_check_index(to_push, cfg->rx_checks, cfg->rx_checks_len);
update_addr_timestamp(cfg->rx_checks, index);
if (index != -1) {
// checksum check
if ((safety_hooks->get_checksum != NULL) && (safety_hooks->compute_checksum != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].check_checksum) {
uint32_t checksum = safety_hooks->get_checksum(to_push);
uint32_t checksum_comp = safety_hooks->compute_checksum(to_push);
cfg->rx_checks[index].status.valid_checksum = checksum_comp == checksum;
} else {
cfg->rx_checks[index].status.valid_checksum = true;
}
// counter check (max_counter == 0 means skip check)
if ((safety_hooks->get_counter != NULL) && (cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].max_counter > 0U)) {
uint8_t counter = safety_hooks->get_counter(to_push);
update_counter(cfg->rx_checks, index, counter);
} else {
cfg->rx_checks[index].status.wrong_counters = 0U;
}
// quality flag check
if ((safety_hooks->get_quality_flag_valid != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].quality_flag) {
cfg->rx_checks[index].status.valid_quality_flag = safety_hooks->get_quality_flag_valid(to_push);
} else {
cfg->rx_checks[index].status.valid_quality_flag = true;
}
}
return is_msg_valid(cfg->rx_checks, index);
}
void generic_rx_checks(bool stock_ecu_detected) {
// exit controls on rising edge of gas press
if (gas_pressed && !gas_pressed_prev && !(alternative_experience & ALT_EXP_DISABLE_DISENGAGE_ON_GAS)) {
controls_allowed = false;
}
gas_pressed_prev = gas_pressed;
// exit controls on rising edge of brake press
if (brake_pressed && (!brake_pressed_prev || vehicle_moving)) {
controls_allowed = false;
}
brake_pressed_prev = brake_pressed;
// exit controls on rising edge of regen paddle
if (regen_braking && (!regen_braking_prev || vehicle_moving)) {
controls_allowed = false;
}
regen_braking_prev = regen_braking;
// check if stock ECU is on bus broken by car harness
if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && stock_ecu_detected && !gm_skip_relay_check) {
relay_malfunction_set();
}
}
void relay_malfunction_set(void) {
relay_malfunction = true;
fault_occurred(FAULT_RELAY_MALFUNCTION);
}
void relay_malfunction_reset(void) {
relay_malfunction = false;
fault_recovered(FAULT_RELAY_MALFUNCTION);
}
typedef struct {
uint16_t id;
const safety_hooks *hooks;
} safety_hook_config;
const safety_hook_config safety_hook_registry[] = {
{SAFETY_SILENT, &nooutput_hooks},
{SAFETY_HONDA_NIDEC, &honda_nidec_hooks},
{SAFETY_TOYOTA, &toyota_hooks},
{SAFETY_ELM327, &elm327_hooks},
{SAFETY_GM, &gm_hooks},
{SAFETY_HONDA_BOSCH, &honda_bosch_hooks},
{SAFETY_HYUNDAI, &hyundai_hooks},
{SAFETY_CHRYSLER, &chrysler_hooks},
{SAFETY_SUBARU, &subaru_hooks},
{SAFETY_VOLKSWAGEN_MQB, &volkswagen_mqb_hooks},
{SAFETY_NISSAN, &nissan_hooks},
{SAFETY_NOOUTPUT, &nooutput_hooks},
{SAFETY_HYUNDAI_LEGACY, &hyundai_legacy_hooks},
{SAFETY_MAZDA, &mazda_hooks},
{SAFETY_BODY, &body_hooks},
{SAFETY_FORD, &ford_hooks},
#ifdef CANFD
{SAFETY_HYUNDAI_CANFD, &hyundai_canfd_hooks},
#endif
#ifdef ALLOW_DEBUG
{SAFETY_TESLA, &tesla_hooks},
{SAFETY_SUBARU_PREGLOBAL, &subaru_preglobal_hooks},
{SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks},
{SAFETY_ALLOUTPUT, &alloutput_hooks},
#endif
};
int set_safety_hooks(uint16_t mode, uint16_t param) {
// reset state set by safety mode
safety_mode_cnt = 0U;
relay_malfunction = false;
enable_gas_interceptor = false;
gas_interceptor_prev = 0;
gas_pressed = false;
gas_pressed_prev = false;
brake_pressed = false;
brake_pressed_prev = false;
regen_braking = false;
regen_braking_prev = false;
cruise_engaged_prev = false;
vehicle_moving = false;
acc_main_on = false;
cruise_button_prev = 0;
desired_torque_last = 0;
rt_torque_last = 0;
ts_angle_last = 0;
desired_angle_last = 0;
ts_torque_check_last = 0;
ts_steer_req_mismatch_last = 0;
valid_steer_req_count = 0;
invalid_steer_req_count = 0;
// reset samples
reset_sample(&vehicle_speed);
reset_sample(&torque_meas);
reset_sample(&torque_driver);
reset_sample(&angle_meas);
controls_allowed = false;
relay_malfunction_reset();
safety_rx_checks_invalid = false;
current_safety_config.rx_checks = NULL;
current_safety_config.rx_checks_len = 0;
current_safety_config.tx_msgs = NULL;
current_safety_config.tx_msgs_len = 0;
int set_status = -1; // not set
int hook_config_count = sizeof(safety_hook_registry) / sizeof(safety_hook_config);
for (int i = 0; i < hook_config_count; i++) {
if (safety_hook_registry[i].id == mode) {
current_hooks = safety_hook_registry[i].hooks;
current_safety_mode = mode;
current_safety_param = param;
set_status = 0; // set
}
}
if ((set_status == 0) && (current_hooks->init != NULL)) {
safety_config cfg = current_hooks->init(param);
current_safety_config.rx_checks = cfg.rx_checks;
current_safety_config.rx_checks_len = cfg.rx_checks_len;
current_safety_config.tx_msgs = cfg.tx_msgs;
current_safety_config.tx_msgs_len = cfg.tx_msgs_len;
// reset all dynamic fields in addr struct
for (int j = 0; j < current_safety_config.rx_checks_len; j++) {
current_safety_config.rx_checks[j].status = (RxStatus){0};
}
}
return set_status;
}
// convert a trimmed integer to signed 32 bit int
int to_signed(int d, int bits) {
int d_signed = d;
int max_value = (1 << MAX((bits - 1), 0));
if (d >= max_value) {
d_signed = d - (1 << MAX(bits, 0));
}
return d_signed;
}
// given a new sample, update the sample_t struct
void update_sample(struct sample_t *sample, int sample_new) {
for (int i = MAX_SAMPLE_VALS - 1; i > 0; i--) {
sample->values[i] = sample->values[i-1];
}
sample->values[0] = sample_new;
// get the minimum and maximum measured samples
sample->min = sample->values[0];
sample->max = sample->values[0];
for (int i = 1; i < MAX_SAMPLE_VALS; i++) {
if (sample->values[i] < sample->min) {
sample->min = sample->values[i];
}
if (sample->values[i] > sample->max) {
sample->max = sample->values[i];
}
}
}
// resets values and min/max for sample_t struct
void reset_sample(struct sample_t *sample) {
for (int i = 0; i < MAX_SAMPLE_VALS; i++) {
sample->values[i] = 0;
}
update_sample(sample, 0);
}
bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) {
return (val > MAX_VAL) || (val < MIN_VAL);
}
// check that commanded torque value isn't too far from measured
bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas,
const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) {
// *** val rate limit check ***
int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP;
int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP;
// if we've exceeded the meas val, we must start moving toward 0
int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, MAX(val_meas->max, 0) + MAX_ERROR));
int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, MIN(val_meas->min, 0) - MAX_ERROR));
// check for violation
return max_limit_check(val, highest_allowed, lowest_allowed);
}
// check that commanded value isn't fighting against driver
bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver,
const int MAX_VAL, const int MAX_RATE_UP, const int MAX_RATE_DOWN,
const int MAX_ALLOWANCE, const int DRIVER_FACTOR) {
// torque delta/rate limits
int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP;
int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP;
// driver
int driver_max_limit = MAX_VAL + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR;
int driver_min_limit = -MAX_VAL + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR;
// if we've exceeded the applied torque, we must start moving toward 0
int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN,
MAX(driver_max_limit, 0)));
int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN,
MIN(driver_min_limit, 0)));
// check for violation
return max_limit_check(val, highest_allowed, lowest_allowed);
}
// real time check, mainly used for steer torque rate limiter
bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) {
// *** torque real time rate limit check ***
int highest_val = MAX(val_last, 0) + MAX_RT_DELTA;
int lowest_val = MIN(val_last, 0) - MAX_RT_DELTA;
// check for violation
return max_limit_check(val, highest_val, lowest_val);
}
// interp function that holds extreme values
float interpolate(struct lookup_t xy, float x) {
int size = sizeof(xy.x) / sizeof(xy.x[0]);
float ret = xy.y[size - 1]; // default output is last point
// x is lower than the first point in the x array. Return the first point
if (x <= xy.x[0]) {
ret = xy.y[0];
} else {
// find the index such that (xy.x[i] <= x < xy.x[i+1]) and linearly interp
for (int i=0; i < (size - 1); i++) {
if (x < xy.x[i+1]) {
float x0 = xy.x[i];
float y0 = xy.y[i];
float dx = xy.x[i+1] - x0;
float dy = xy.y[i+1] - y0;
// dx should not be zero as xy.x is supposed to be monotonic
dx = MAX(dx, 0.0001);
ret = (dy * (x - x0) / dx) + y0;
break;
}
}
}
return ret;
}
int ROUND(float val) {
return val + ((val > 0.0) ? 0.5 : -0.5);
}
// Safety checks for longitudinal actuation
bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits) {
bool accel_valid = get_longitudinal_allowed() && !max_limit_check(desired_accel, limits.max_accel, limits.min_accel);
bool accel_inactive = desired_accel == limits.inactive_accel;
return !(accel_valid || accel_inactive);
}
bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limits) {
return !get_longitudinal_allowed() && (desired_speed != limits.inactive_speed);
}
bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits) {
bool transmission_rpm_valid = get_longitudinal_allowed() && !max_limit_check(desired_transmission_rpm, limits.max_transmission_rpm, limits.min_transmission_rpm);
bool transmission_rpm_inactive = desired_transmission_rpm == limits.inactive_transmission_rpm;
return !(transmission_rpm_valid || transmission_rpm_inactive);
}
bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits) {
bool gas_valid = get_longitudinal_allowed() && !max_limit_check(desired_gas, limits.max_gas, limits.min_gas);
bool gas_inactive = desired_gas == limits.inactive_gas;
return !(gas_valid || gas_inactive);
}
bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limits) {
bool violation = false;
violation |= !get_longitudinal_allowed() && (desired_brake != 0);
violation |= desired_brake > limits.max_brake;
return violation;
}
bool longitudinal_interceptor_checks(const CANPacket_t *to_send) {
return (!get_longitudinal_allowed() || brake_pressed_prev) && (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1));
}
// Safety checks for torque-based steering commands
bool steer_torque_cmd_checks(int desired_torque, int steer_req, const SteeringLimits limits) {
bool violation = false;
uint32_t ts = microsecond_timer_get();
bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_ALWAYS_ON_LATERAL);
if (controls_allowed) {
// acc main must be on if controls are allowed
acc_main_on = controls_allowed;
}
if (controls_allowed || aol_allowed) {
// *** global torque limit check ***
violation |= max_limit_check(desired_torque, limits.max_steer, -limits.max_steer);
// *** torque rate limit check ***
if (limits.type == TorqueDriverLimited) {
violation |= driver_limit_check(desired_torque, desired_torque_last, &torque_driver,
limits.max_steer, limits.max_rate_up, limits.max_rate_down,
limits.driver_torque_allowance, limits.driver_torque_factor);
} else {
violation |= dist_to_meas_check(desired_torque, desired_torque_last, &torque_meas,
limits.max_rate_up, limits.max_rate_down, limits.max_torque_error);
}
desired_torque_last = desired_torque;
// *** torque real time rate limit check ***
violation |= rt_rate_limit_check(desired_torque, rt_torque_last, limits.max_rt_delta);
// every RT_INTERVAL set the new limits
uint32_t ts_elapsed = get_ts_elapsed(ts, ts_torque_check_last);
if (ts_elapsed > limits.max_rt_interval) {
rt_torque_last = desired_torque;
ts_torque_check_last = ts;
}
}
// no torque if controls is not allowed
if (!(controls_allowed || aol_allowed) && (desired_torque != 0)) {
violation = true;
}
// certain safety modes set their steer request bit low for one or more frame at a
// predefined max frequency to avoid steering faults in certain situations
bool steer_req_mismatch = (steer_req == 0) && (desired_torque != 0);
if (!limits.has_steer_req_tolerance) {
if (steer_req_mismatch) {
violation = true;
}
} else {
if (steer_req_mismatch) {
if (invalid_steer_req_count == 0) {
// disallow torque cut if not enough recent matching steer_req messages
if (valid_steer_req_count < limits.min_valid_request_frames) {
violation = true;
}
// or we've cut torque too recently in time
uint32_t ts_elapsed = get_ts_elapsed(ts, ts_steer_req_mismatch_last);
if (ts_elapsed < limits.min_valid_request_rt_interval) {
violation = true;
}
} else {
// or we're cutting more frames consecutively than allowed
if (invalid_steer_req_count >= limits.max_invalid_request_frames) {
violation = true;
}
}
valid_steer_req_count = 0;
ts_steer_req_mismatch_last = ts;
invalid_steer_req_count = MIN(invalid_steer_req_count + 1, limits.max_invalid_request_frames);
} else {
valid_steer_req_count = MIN(valid_steer_req_count + 1, limits.min_valid_request_frames);
invalid_steer_req_count = 0;
}
}
// reset to 0 if either controls is not allowed or there's a violation
if (violation || !(controls_allowed || aol_allowed)) {
valid_steer_req_count = 0;
invalid_steer_req_count = 0;
desired_torque_last = 0;
rt_torque_last = 0;
ts_torque_check_last = ts;
ts_steer_req_mismatch_last = ts;
}
return violation;
}
// Safety checks for angle-based steering commands
bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const SteeringLimits limits) {
bool violation = false;
bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_ALWAYS_ON_LATERAL);
if (controls_allowed) {
// acc main must be on if controls are allowed
acc_main_on = controls_allowed;
}
if ((controls_allowed || aol_allowed) && steer_control_enabled) {
// convert floating point angle rate limits to integers in the scale of the desired angle on CAN,
// add 1 to not false trigger the violation. also fudge the speed by 1 m/s so rate limits are
// always slightly above openpilot's in case we read an updated speed in between angle commands
// TODO: this speed fudge can be much lower, look at data to determine the lowest reasonable offset
int delta_angle_up = (interpolate(limits.angle_rate_up_lookup, (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.) * limits.angle_deg_to_can) + 1.;
int delta_angle_down = (interpolate(limits.angle_rate_down_lookup, (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.) * limits.angle_deg_to_can) + 1.;
// allow down limits at zero since small floats will be rounded to 0
int highest_desired_angle = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up : delta_angle_down);
int lowest_desired_angle = desired_angle_last - ((desired_angle_last >= 0) ? delta_angle_down : delta_angle_up);
// check that commanded angle value isn't too far from measured, used to limit torque for some safety modes
// ensure we start moving in direction of meas while respecting rate limits if error is exceeded
if (limits.enforce_angle_error && ((vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR) > limits.angle_error_min_speed)) {
// the rate limits above are liberally above openpilot's to avoid false positives.
// likewise, allow a lower rate for moving towards meas when error is exceeded
int delta_angle_up_lower = interpolate(limits.angle_rate_up_lookup, (vehicle_speed.max / VEHICLE_SPEED_FACTOR) + 1.) * limits.angle_deg_to_can;
int delta_angle_down_lower = interpolate(limits.angle_rate_down_lookup, (vehicle_speed.max / VEHICLE_SPEED_FACTOR) + 1.) * limits.angle_deg_to_can;
int highest_desired_angle_lower = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up_lower : delta_angle_down_lower);
int lowest_desired_angle_lower = desired_angle_last - ((desired_angle_last >= 0) ? delta_angle_down_lower : delta_angle_up_lower);
lowest_desired_angle = MIN(MAX(lowest_desired_angle, angle_meas.min - limits.max_angle_error - 1), highest_desired_angle_lower);
highest_desired_angle = MAX(MIN(highest_desired_angle, angle_meas.max + limits.max_angle_error + 1), lowest_desired_angle_lower);
// don't enforce above the max steer
lowest_desired_angle = CLAMP(lowest_desired_angle, -limits.max_steer, limits.max_steer);
highest_desired_angle = CLAMP(highest_desired_angle, -limits.max_steer, limits.max_steer);
}
// check for violation;
violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle);
}
desired_angle_last = desired_angle;
// Angle should either be 0 or same as current angle while not steering
if (!steer_control_enabled) {
violation |= (limits.inactive_angle_is_zero ? (desired_angle != 0) :
max_limit_check(desired_angle, angle_meas.max + 1, angle_meas.min - 1));
}
// No angle control allowed when controls are not allowed
violation |= !(controls_allowed || aol_allowed) && steer_control_enabled;
return violation;
}
void pcm_cruise_check(bool cruise_engaged) {
// Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages
if (!cruise_engaged) {
controls_allowed = false;
}
if (cruise_engaged && !cruise_engaged_prev) {
controls_allowed = true;
}
cruise_engaged_prev = cruise_engaged;
}

View File

@@ -0,0 +1,46 @@
const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8}, {0x250, 0, 6}, {0x251, 0, 5}, // body
{0x350, 0, 8}, {0x350, 0, 6}, {0x351, 0, 5}, // knee
{0x1, 0, 8}}; // CAN flasher
RxCheck body_rx_checks[] = {
{.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}},
};
static void body_rx_hook(const CANPacket_t *to_push) {
// body is never at standstill
vehicle_moving = true;
if (GET_ADDR(to_push) == 0x201U) {
controls_allowed = true;
}
}
static bool body_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
int len = GET_LEN(to_send);
if (!controls_allowed && (addr != 0x1)) {
tx = false;
}
// Allow going into CAN flashing mode for base & knee even if controls are not allowed
bool flash_msg = ((addr == 0x250) || (addr == 0x350)) && (len == 8);
if (!controls_allowed && (GET_BYTES(to_send, 0, 4) == 0xdeadfaceU) && (GET_BYTES(to_send, 4, 4) == 0x0ab00b1eU) && flash_msg) {
tx = true;
}
return tx;
}
static safety_config body_init(uint16_t param) {
UNUSED(param);
return BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS);
}
const safety_hooks body_hooks = {
.init = body_init,
.rx = body_rx_hook,
.tx = body_tx_hook,
.fwd = default_fwd_hook,
};

View File

@@ -0,0 +1,296 @@
const SteeringLimits CHRYSLER_STEERING_LIMITS = {
.max_steer = 261,
.max_rt_delta = 112,
.max_rt_interval = 250000,
.max_rate_up = 3,
.max_rate_down = 3,
.max_torque_error = 80,
.type = TorqueMotorLimited,
};
const SteeringLimits CHRYSLER_RAM_DT_STEERING_LIMITS = {
.max_steer = 350,
.max_rt_delta = 112,
.max_rt_interval = 250000,
.max_rate_up = 6,
.max_rate_down = 6,
.max_torque_error = 80,
.type = TorqueMotorLimited,
};
const SteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = {
.max_steer = 361,
.max_rt_delta = 182,
.max_rt_interval = 250000,
.max_rate_up = 14,
.max_rate_down = 14,
.max_torque_error = 80,
.type = TorqueMotorLimited,
};
typedef struct {
const int EPS_2;
const int ESP_1;
const int ESP_8;
const int ECM_5;
const int DAS_3;
const int DAS_6;
const int LKAS_COMMAND;
const int CRUISE_BUTTONS;
} ChryslerAddrs;
// CAN messages for Chrysler/Jeep platforms
const ChryslerAddrs CHRYSLER_ADDRS = {
.EPS_2 = 0x220, // EPS driver input torque
.ESP_1 = 0x140, // Brake pedal and vehicle speed
.ESP_8 = 0x11C, // Brake pedal and vehicle speed
.ECM_5 = 0x22F, // Throttle position sensor
.DAS_3 = 0x1F4, // ACC engagement states from DASM
.DAS_6 = 0x2A6, // LKAS HUD and auto headlight control from DASM
.LKAS_COMMAND = 0x292, // LKAS controls from DASM
.CRUISE_BUTTONS = 0x23B, // Cruise control buttons
};
// CAN messages for the 5th gen RAM DT platform
const ChryslerAddrs CHRYSLER_RAM_DT_ADDRS = {
.EPS_2 = 0x31, // EPS driver input torque
.ESP_1 = 0x83, // Brake pedal and vehicle speed
.ESP_8 = 0x79, // Brake pedal and vehicle speed
.ECM_5 = 0x9D, // Throttle position sensor
.DAS_3 = 0x99, // ACC engagement states from DASM
.DAS_6 = 0xFA, // LKAS HUD and auto headlight control from DASM
.LKAS_COMMAND = 0xA6, // LKAS controls from DASM
.CRUISE_BUTTONS = 0xB1, // Cruise control buttons
};
// CAN messages for the 5th gen RAM HD platform
const ChryslerAddrs CHRYSLER_RAM_HD_ADDRS = {
.EPS_2 = 0x220, // EPS driver input torque
.ESP_1 = 0x140, // Brake pedal and vehicle speed
.ESP_8 = 0x11C, // Brake pedal and vehicle speed
.ECM_5 = 0x22F, // Throttle position sensor
.DAS_3 = 0x1F4, // ACC engagement states from DASM
.DAS_6 = 0x275, // LKAS HUD and auto headlight control from DASM
.LKAS_COMMAND = 0x276, // LKAS controls from DASM
.CRUISE_BUTTONS = 0x23A, // Cruise control buttons
};
const CanMsg CHRYSLER_TX_MSGS[] = {
{CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3},
{CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6},
{CHRYSLER_ADDRS.DAS_6, 0, 8},
};
const CanMsg CHRYSLER_RAM_DT_TX_MSGS[] = {
{CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3},
{CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8},
{CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8},
};
const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = {
{CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3},
{CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8},
{CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8},
};
RxCheck chrysler_rx_checks[] = {
{.msg = {{CHRYSLER_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
//{.msg = {{ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}}},
{.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_ADDRS.DAS_3, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
RxCheck chrysler_ram_dt_rx_checks[] = {
{.msg = {{CHRYSLER_RAM_DT_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_DT_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_DT_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
RxCheck chrysler_ram_hd_rx_checks[] = {
{.msg = {{CHRYSLER_RAM_HD_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_HD_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{CHRYSLER_RAM_HD_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform
const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform
enum {
CHRYSLER_RAM_DT,
CHRYSLER_RAM_HD,
CHRYSLER_PACIFICA, // plus Jeep
} chrysler_platform = CHRYSLER_PACIFICA;
const ChryslerAddrs *chrysler_addrs = &CHRYSLER_ADDRS;
static uint32_t chrysler_get_checksum(const CANPacket_t *to_push) {
int checksum_byte = GET_LEN(to_push) - 1U;
return (uint8_t)(GET_BYTE(to_push, checksum_byte));
}
static uint32_t chrysler_compute_checksum(const CANPacket_t *to_push) {
// TODO: clean this up
// http://illmatics.com/Remote%20Car%20Hacking.pdf
uint8_t checksum = 0xFFU;
int len = GET_LEN(to_push);
for (int j = 0; j < (len - 1); j++) {
uint8_t shift = 0x80U;
uint8_t curr = (uint8_t)GET_BYTE(to_push, j);
for (int i=0; i<8; i++) {
uint8_t bit_sum = curr & shift;
uint8_t temp_chk = checksum & 0x80U;
if (bit_sum != 0U) {
bit_sum = 0x1C;
if (temp_chk != 0U) {
bit_sum = 1;
}
checksum = checksum << 1;
temp_chk = checksum | 1U;
bit_sum ^= temp_chk;
} else {
if (temp_chk != 0U) {
bit_sum = 0x1D;
}
checksum = checksum << 1;
bit_sum ^= checksum;
}
checksum = bit_sum;
shift = shift >> 1;
}
}
return (uint8_t)(~checksum);
}
static uint8_t chrysler_get_counter(const CANPacket_t *to_push) {
return (uint8_t)(GET_BYTE(to_push, 6) >> 4);
}
static void chrysler_rx_hook(const CANPacket_t *to_push) {
const int bus = GET_BUS(to_push);
const int addr = GET_ADDR(to_push);
// Measured EPS torque
if ((bus == 0) && (addr == chrysler_addrs->EPS_2)) {
int torque_meas_new = ((GET_BYTE(to_push, 4) & 0x7U) << 8) + GET_BYTE(to_push, 5) - 1024U;
update_sample(&torque_meas, torque_meas_new);
}
// enter controls on rising edge of ACC, exit controls on ACC off
const int das_3_bus = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 2;
if ((bus == das_3_bus) && (addr == chrysler_addrs->DAS_3)) {
acc_main_on = GET_BIT(to_push, 20U);
bool cruise_engaged = GET_BIT(to_push, 21U);
pcm_cruise_check(cruise_engaged);
}
// TODO: use the same message for both
// update vehicle moving
if ((chrysler_platform != CHRYSLER_PACIFICA) && (bus == 0) && (addr == chrysler_addrs->ESP_8)) {
vehicle_moving = ((GET_BYTE(to_push, 4) << 8) + GET_BYTE(to_push, 5)) != 0U;
}
if ((chrysler_platform == CHRYSLER_PACIFICA) && (bus == 0) && (addr == 514)) {
int speed_l = (GET_BYTE(to_push, 0) << 4) + (GET_BYTE(to_push, 1) >> 4);
int speed_r = (GET_BYTE(to_push, 2) << 4) + (GET_BYTE(to_push, 3) >> 4);
vehicle_moving = (speed_l != 0) || (speed_r != 0);
}
// exit controls on rising edge of gas press
if ((bus == 0) && (addr == chrysler_addrs->ECM_5)) {
gas_pressed = GET_BYTE(to_push, 0U) != 0U;
}
// exit controls on rising edge of brake press
if ((bus == 0) && (addr == chrysler_addrs->ESP_1)) {
brake_pressed = ((GET_BYTE(to_push, 0U) & 0xFU) >> 2U) == 1U;
}
generic_rx_checks((bus == 0) && (addr == chrysler_addrs->LKAS_COMMAND));
}
static bool chrysler_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
// STEERING
if (addr == chrysler_addrs->LKAS_COMMAND) {
int start_byte = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 1;
int desired_torque = ((GET_BYTE(to_send, start_byte) & 0x7U) << 8) | GET_BYTE(to_send, start_byte + 1);
desired_torque -= 1024;
const SteeringLimits limits = (chrysler_platform == CHRYSLER_PACIFICA) ? CHRYSLER_STEERING_LIMITS :
(chrysler_platform == CHRYSLER_RAM_DT) ? CHRYSLER_RAM_DT_STEERING_LIMITS : CHRYSLER_RAM_HD_STEERING_LIMITS;
bool steer_req = (chrysler_platform == CHRYSLER_PACIFICA) ? GET_BIT(to_send, 4U) : (GET_BYTE(to_send, 3) & 0x7U) == 2U;
if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) {
tx = false;
}
}
// FORCE CANCEL: only the cancel button press is allowed
if (addr == chrysler_addrs->CRUISE_BUTTONS) {
const bool is_cancel = GET_BYTE(to_send, 0) == 1U;
const bool is_resume = GET_BYTE(to_send, 0) == 0x10U;
const bool allowed = is_cancel || (is_resume && controls_allowed);
if (!allowed) {
tx = false;
}
}
return tx;
}
static int chrysler_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
// forward to camera
if (bus_num == 0) {
bus_fwd = 2;
}
// forward all messages from camera except LKAS messages
const bool is_lkas = ((addr == chrysler_addrs->LKAS_COMMAND) || (addr == chrysler_addrs->DAS_6));
if ((bus_num == 2) && !is_lkas){
bus_fwd = 0;
}
return bus_fwd;
}
static safety_config chrysler_init(uint16_t param) {
safety_config ret;
bool enable_ram_dt = GET_FLAG(param, CHRYSLER_PARAM_RAM_DT);
if (enable_ram_dt) {
chrysler_platform = CHRYSLER_RAM_DT;
chrysler_addrs = &CHRYSLER_RAM_DT_ADDRS;
ret = BUILD_SAFETY_CFG(chrysler_ram_dt_rx_checks, CHRYSLER_RAM_DT_TX_MSGS);
#ifdef ALLOW_DEBUG
} else if (GET_FLAG(param, CHRYSLER_PARAM_RAM_HD)) {
chrysler_platform = CHRYSLER_RAM_HD;
chrysler_addrs = &CHRYSLER_RAM_HD_ADDRS;
ret = BUILD_SAFETY_CFG(chrysler_ram_hd_rx_checks, CHRYSLER_RAM_HD_TX_MSGS);
#endif
} else {
chrysler_platform = CHRYSLER_PACIFICA;
chrysler_addrs = &CHRYSLER_ADDRS;
ret = BUILD_SAFETY_CFG(chrysler_rx_checks, CHRYSLER_TX_MSGS);
}
return ret;
}
const safety_hooks chrysler_hooks = {
.init = chrysler_init,
.rx = chrysler_rx_hook,
.tx = chrysler_tx_hook,
.fwd = chrysler_fwd_hook,
.get_counter = chrysler_get_counter,
.get_checksum = chrysler_get_checksum,
.compute_checksum = chrysler_compute_checksum,
};

View File

@@ -0,0 +1,68 @@
void default_rx_hook(const CANPacket_t *to_push) {
UNUSED(to_push);
}
// *** no output safety mode ***
static safety_config nooutput_init(uint16_t param) {
UNUSED(param);
return (safety_config){NULL, 0, NULL, 0};
}
static bool nooutput_tx_hook(const CANPacket_t *to_send) {
UNUSED(to_send);
return false;
}
static int default_fwd_hook(int bus_num, int addr) {
UNUSED(bus_num);
UNUSED(addr);
return -1;
}
const safety_hooks nooutput_hooks = {
.init = nooutput_init,
.rx = default_rx_hook,
.tx = nooutput_tx_hook,
.fwd = default_fwd_hook,
};
// *** all output safety mode ***
// Enables passthrough mode where relay is open and bus 0 gets forwarded to bus 2 and vice versa
const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1;
bool alloutput_passthrough = false;
static safety_config alloutput_init(uint16_t param) {
controls_allowed = true;
alloutput_passthrough = GET_FLAG(param, ALLOUTPUT_PARAM_PASSTHROUGH);
return (safety_config){NULL, 0, NULL, 0};
}
static bool alloutput_tx_hook(const CANPacket_t *to_send) {
UNUSED(to_send);
return true;
}
static int alloutput_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
UNUSED(addr);
if (alloutput_passthrough) {
if (bus_num == 0) {
bus_fwd = 2;
}
if (bus_num == 2) {
bus_fwd = 0;
}
}
return bus_fwd;
}
const safety_hooks alloutput_hooks = {
.init = alloutput_init,
.rx = default_rx_hook,
.tx = alloutput_tx_hook,
.fwd = alloutput_fwd_hook,
};

View File

@@ -0,0 +1,37 @@
const int GM_CAMERA_DIAG_ADDR = 0x24B;
static bool elm327_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
int len = GET_LEN(to_send);
// All ISO 15765-4 messages must be 8 bytes long
if (len != 8) {
tx = false;
}
// Check valid 29 bit send addresses for ISO 15765-4
// Check valid 11 bit send addresses for ISO 15765-4
if ((addr != 0x18DB33F1) && ((addr & 0x1FFF00FF) != 0x18DA00F1) &&
((addr & 0x1FFFFF00) != 0x600) && ((addr & 0x1FFFFF00) != 0x700) &&
(addr != GM_CAMERA_DIAG_ADDR)) {
tx = false;
}
// GM camera uses non-standard diagnostic address, this has no control message address collisions
if ((addr == GM_CAMERA_DIAG_ADDR) && (len == 8)) {
// Only allow known frame types for ISO 15765-2
if ((GET_BYTE(to_send, 0) & 0xF0U) > 0x30U) {
tx = false;
}
}
return tx;
}
// If current_board->has_obd and safety_param == 0, bus 1 is multiplexed to the OBD-II port
const safety_hooks elm327_hooks = {
.init = nooutput_init,
.rx = default_rx_hook,
.tx = elm327_tx_hook,
.fwd = default_fwd_hook,
};

View File

@@ -0,0 +1,424 @@
// Safety-relevant CAN messages for Ford vehicles.
#define FORD_EngBrakeData 0x165 // RX from PCM, for driver brake pedal and cruise state
#define FORD_EngVehicleSpThrottle 0x204 // RX from PCM, for driver throttle input
#define FORD_DesiredTorqBrk 0x213 // RX from ABS, for standstill state
#define FORD_BrakeSysFeatures 0x415 // RX from ABS, for vehicle speed
#define FORD_EngVehicleSpThrottle2 0x202 // RX from PCM, for second vehicle speed
#define FORD_Yaw_Data_FD1 0x91 // RX from RCM, for yaw rate
#define FORD_Steering_Data_FD1 0x083 // TX by OP, various driver switches and LKAS/CC buttons
#define FORD_ACCDATA 0x186 // TX by OP, ACC controls
#define FORD_ACCDATA_3 0x18A // TX by OP, ACC/TJA user interface
#define FORD_Lane_Assist_Data1 0x3CA // TX by OP, Lane Keep Assist
#define FORD_LateralMotionControl 0x3D3 // TX by OP, Lateral Control message
#define FORD_LateralMotionControl2 0x3D6 // TX by OP, alternate Lateral Control message
#define FORD_IPMA_Data 0x3D8 // TX by OP, IPMA and LKAS user interface
// CAN bus numbers.
#define FORD_MAIN_BUS 0U
#define FORD_CAM_BUS 2U
const CanMsg FORD_STOCK_TX_MSGS[] = {
{FORD_Steering_Data_FD1, 0, 8},
{FORD_Steering_Data_FD1, 2, 8},
{FORD_ACCDATA_3, 0, 8},
{FORD_Lane_Assist_Data1, 0, 8},
{FORD_LateralMotionControl, 0, 8},
{FORD_IPMA_Data, 0, 8},
};
const CanMsg FORD_LONG_TX_MSGS[] = {
{FORD_Steering_Data_FD1, 0, 8},
{FORD_Steering_Data_FD1, 2, 8},
{FORD_ACCDATA, 0, 8},
{FORD_ACCDATA_3, 0, 8},
{FORD_Lane_Assist_Data1, 0, 8},
{FORD_LateralMotionControl, 0, 8},
{FORD_IPMA_Data, 0, 8},
};
const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = {
{FORD_Steering_Data_FD1, 0, 8},
{FORD_Steering_Data_FD1, 2, 8},
{FORD_ACCDATA_3, 0, 8},
{FORD_Lane_Assist_Data1, 0, 8},
{FORD_LateralMotionControl2, 0, 8},
{FORD_IPMA_Data, 0, 8},
};
const CanMsg FORD_CANFD_LONG_TX_MSGS[] = {
{FORD_Steering_Data_FD1, 0, 8},
{FORD_Steering_Data_FD1, 2, 8},
{FORD_ACCDATA, 0, 8},
{FORD_ACCDATA_3, 0, 8},
{FORD_Lane_Assist_Data1, 0, 8},
{FORD_LateralMotionControl2, 0, 8},
{FORD_IPMA_Data, 0, 8},
};
// warning: quality flags are not yet checked in openpilot's CAN parser,
// this may be the cause of blocked messages
RxCheck ford_rx_checks[] = {
{.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}},
// FORD_EngVehicleSpThrottle2 has a counter that either randomly skips or by 2, likely ECU bug
// Some hybrid models also experience a bug where this checksum mismatches for one or two frames under heavy acceleration with ACC
// It has been confirmed that the Bronco Sport's camera only disallows ACC for bad quality flags, not counters or checksums, so we match that
{.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = false, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{FORD_Yaw_Data_FD1, 0, 8, .check_checksum = true, .max_counter = 255U, .quality_flag=true, .frequency = 100U}, { 0 }, { 0 }}},
// These messages have no counter or checksum
{.msg = {{FORD_EngBrakeData, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}},
};
static uint8_t ford_get_counter(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t cnt = 0;
if (addr == FORD_BrakeSysFeatures) {
// Signal: VehVActlBrk_No_Cnt
cnt = (GET_BYTE(to_push, 2) >> 2) & 0xFU;
} else if (addr == FORD_Yaw_Data_FD1) {
// Signal: VehRollYaw_No_Cnt
cnt = GET_BYTE(to_push, 5);
} else {
}
return cnt;
}
static uint32_t ford_get_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t chksum = 0;
if (addr == FORD_BrakeSysFeatures) {
// Signal: VehVActlBrk_No_Cs
chksum = GET_BYTE(to_push, 3);
} else if (addr == FORD_Yaw_Data_FD1) {
// Signal: VehRollYawW_No_Cs
chksum = GET_BYTE(to_push, 4);
} else {
}
return chksum;
}
static uint32_t ford_compute_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t chksum = 0;
if (addr == FORD_BrakeSysFeatures) {
chksum += GET_BYTE(to_push, 0) + GET_BYTE(to_push, 1); // Veh_V_ActlBrk
chksum += GET_BYTE(to_push, 2) >> 6; // VehVActlBrk_D_Qf
chksum += (GET_BYTE(to_push, 2) >> 2) & 0xFU; // VehVActlBrk_No_Cnt
chksum = 0xFFU - chksum;
} else if (addr == FORD_Yaw_Data_FD1) {
chksum += GET_BYTE(to_push, 0) + GET_BYTE(to_push, 1); // VehRol_W_Actl
chksum += GET_BYTE(to_push, 2) + GET_BYTE(to_push, 3); // VehYaw_W_Actl
chksum += GET_BYTE(to_push, 5); // VehRollYaw_No_Cnt
chksum += GET_BYTE(to_push, 6) >> 6; // VehRolWActl_D_Qf
chksum += (GET_BYTE(to_push, 6) >> 4) & 0x3U; // VehYawWActl_D_Qf
chksum = 0xFFU - chksum;
} else {
}
return chksum;
}
static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
bool valid = false;
if (addr == FORD_BrakeSysFeatures) {
valid = (GET_BYTE(to_push, 2) >> 6) == 0x3U; // VehVActlBrk_D_Qf
} else if (addr == FORD_EngVehicleSpThrottle2) {
valid = ((GET_BYTE(to_push, 4) >> 5) & 0x3U) == 0x3U; // VehVActlEng_D_Qf
} else if (addr == FORD_Yaw_Data_FD1) {
valid = ((GET_BYTE(to_push, 6) >> 4) & 0x3U) == 0x3U; // VehYawWActl_D_Qf
} else {
}
return valid;
}
const uint16_t FORD_PARAM_LONGITUDINAL = 1;
const uint16_t FORD_PARAM_CANFD = 2;
bool ford_longitudinal = false;
bool ford_canfd = false;
const LongitudinalLimits FORD_LONG_LIMITS = {
// acceleration cmd limits (used for brakes)
// Signal: AccBrkTot_A_Rq
.max_accel = 5641, // 1.9999 m/s^s
.min_accel = 4231, // -3.4991 m/s^2
.inactive_accel = 5128, // -0.0008 m/s^2
// gas cmd limits
// Signal: AccPrpl_A_Rq & AccPrpl_A_Pred
.max_gas = 700, // 2.0 m/s^2
.min_gas = 450, // -0.5 m/s^2
.inactive_gas = 0, // -5.0 m/s^2
};
#define FORD_INACTIVE_CURVATURE 1000U
#define FORD_INACTIVE_CURVATURE_RATE 4096U
#define FORD_INACTIVE_PATH_OFFSET 512U
#define FORD_INACTIVE_PATH_ANGLE 1000U
#define FORD_CANFD_INACTIVE_CURVATURE_RATE 1024U
#define FORD_MAX_SPEED_DELTA 2.0 // m/s
static bool ford_lkas_msg_check(int addr) {
return (addr == FORD_ACCDATA_3)
|| (addr == FORD_Lane_Assist_Data1)
|| (addr == FORD_LateralMotionControl)
|| (addr == FORD_LateralMotionControl2)
|| (addr == FORD_IPMA_Data);
}
// Curvature rate limits
const SteeringLimits FORD_STEERING_LIMITS = {
.max_steer = 1000,
.angle_deg_to_can = 50000, // 1 / (2e-5) rad to can
.max_angle_error = 100, // 0.002 * FORD_STEERING_LIMITS.angle_deg_to_can
.angle_rate_up_lookup = {
{5., 25., 25.},
{0.0002, 0.0001, 0.0001}
},
.angle_rate_down_lookup = {
{5., 25., 25.},
{0.000225, 0.00015, 0.00015}
},
// no blending at low speed due to lack of torque wind-up and inaccurate current curvature
.angle_error_min_speed = 10.0, // m/s
.enforce_angle_error = true,
.inactive_angle_is_zero = true,
};
static void ford_rx_hook(const CANPacket_t *to_push) {
if (GET_BUS(to_push) == FORD_MAIN_BUS) {
int addr = GET_ADDR(to_push);
// Update in motion state from standstill signal
if (addr == FORD_DesiredTorqBrk) {
// Signal: VehStop_D_Stat
vehicle_moving = ((GET_BYTE(to_push, 3) >> 3) & 0x3U) != 1U;
}
// Update vehicle speed
if (addr == FORD_BrakeSysFeatures) {
// Signal: Veh_V_ActlBrk
UPDATE_VEHICLE_SPEED(((GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1)) * 0.01 / 3.6);
}
// Check vehicle speed against a second source
if (addr == FORD_EngVehicleSpThrottle2) {
// Disable controls if speeds from ABS and PCM ECUs are too far apart.
// Signal: Veh_V_ActlEng
float filtered_pcm_speed = ((GET_BYTE(to_push, 6) << 8) | GET_BYTE(to_push, 7)) * 0.01 / 3.6;
bool is_invalid_speed = ABS(filtered_pcm_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > FORD_MAX_SPEED_DELTA;
if (is_invalid_speed) {
controls_allowed = false;
}
}
// Update vehicle yaw rate
if (addr == FORD_Yaw_Data_FD1) {
// Signal: VehYaw_W_Actl
float ford_yaw_rate = (((GET_BYTE(to_push, 2) << 8U) | GET_BYTE(to_push, 3)) * 0.0002) - 6.5;
float current_curvature = ford_yaw_rate / MAX(vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR, 0.1);
// convert current curvature into units on CAN for comparison with desired curvature
update_sample(&angle_meas, ROUND(current_curvature * FORD_STEERING_LIMITS.angle_deg_to_can));
}
// Update gas pedal
if (addr == FORD_EngVehicleSpThrottle) {
// Pedal position: (0.1 * val) in percent
// Signal: ApedPos_Pc_ActlArb
gas_pressed = (((GET_BYTE(to_push, 0) & 0x03U) << 8) | GET_BYTE(to_push, 1)) > 0U;
}
// Update brake pedal and cruise state
if (addr == FORD_EngBrakeData) {
// Signal: BpedDrvAppl_D_Actl
brake_pressed = ((GET_BYTE(to_push, 0) >> 4) & 0x3U) == 2U;
// Signal: CcStat_D_Actl
unsigned int cruise_state = GET_BYTE(to_push, 1) & 0x07U;
acc_main_on = (cruise_state == 3U) ||(cruise_state == 4U) || (cruise_state == 5U);
bool cruise_engaged = (cruise_state == 4U) || (cruise_state == 5U);
pcm_cruise_check(cruise_engaged);
}
// If steering controls messages are received on the destination bus, it's an indication
// that the relay might be malfunctioning.
bool stock_ecu_detected = ford_lkas_msg_check(addr);
if (ford_longitudinal) {
stock_ecu_detected = stock_ecu_detected || (addr == FORD_ACCDATA);
}
generic_rx_checks(stock_ecu_detected);
}
}
static bool ford_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
// Safety check for ACCDATA accel and brake requests
if (addr == FORD_ACCDATA) {
// Signal: AccPrpl_A_Rq
int gas = ((GET_BYTE(to_send, 6) & 0x3U) << 8) | GET_BYTE(to_send, 7);
// Signal: AccPrpl_A_Pred
int gas_pred = ((GET_BYTE(to_send, 2) & 0x3U) << 8) | GET_BYTE(to_send, 3);
// Signal: AccBrkTot_A_Rq
int accel = ((GET_BYTE(to_send, 0) & 0x1FU) << 8) | GET_BYTE(to_send, 1);
// Signal: CmbbDeny_B_Actl
bool cmbb_deny = GET_BIT(to_send, 37U);
bool violation = false;
violation |= longitudinal_accel_checks(accel, FORD_LONG_LIMITS);
violation |= longitudinal_gas_checks(gas, FORD_LONG_LIMITS);
violation |= longitudinal_gas_checks(gas_pred, FORD_LONG_LIMITS);
// Safety check for stock AEB
violation |= cmbb_deny; // do not prevent stock AEB actuation
if (violation) {
tx = false;
}
}
// Safety check for Steering_Data_FD1 button signals
// Note: Many other signals in this message are not relevant to safety (e.g. blinkers, wiper switches, high beam)
// which we passthru in OP.
if (addr == FORD_Steering_Data_FD1) {
// Violation if resume button is pressed while controls not allowed, or
// if cancel button is pressed when cruise isn't engaged.
bool violation = false;
violation |= GET_BIT(to_send, 8U) && !cruise_engaged_prev; // Signal: CcAslButtnCnclPress (cancel)
violation |= GET_BIT(to_send, 25U) && !controls_allowed; // Signal: CcAsllButtnResPress (resume)
if (violation) {
tx = false;
}
}
// Safety check for Lane_Assist_Data1 action
if (addr == FORD_Lane_Assist_Data1) {
// Do not allow steering using Lane_Assist_Data1 (Lane-Departure Aid).
// This message must be sent for Lane Centering to work, and can include
// values such as the steering angle or lane curvature for debugging,
// but the action (LkaActvStats_D2_Req) must be set to zero.
unsigned int action = GET_BYTE(to_send, 0) >> 5;
if (action != 0U) {
tx = false;
}
}
// Safety check for LateralMotionControl action
if (addr == FORD_LateralMotionControl) {
// Signal: LatCtl_D_Rq
bool steer_control_enabled = ((GET_BYTE(to_send, 4) >> 2) & 0x7U) != 0U;
unsigned int raw_curvature = (GET_BYTE(to_send, 0) << 3) | (GET_BYTE(to_send, 1) >> 5);
unsigned int raw_curvature_rate = ((GET_BYTE(to_send, 1) & 0x1FU) << 8) | GET_BYTE(to_send, 2);
unsigned int raw_path_angle = (GET_BYTE(to_send, 3) << 3) | (GET_BYTE(to_send, 4) >> 5);
unsigned int raw_path_offset = (GET_BYTE(to_send, 5) << 2) | (GET_BYTE(to_send, 6) >> 6);
// These signals are not yet tested with the current safety limits
bool violation = (raw_curvature_rate != FORD_INACTIVE_CURVATURE_RATE) || (raw_path_angle != FORD_INACTIVE_PATH_ANGLE) || (raw_path_offset != FORD_INACTIVE_PATH_OFFSET);
// Check angle error and steer_control_enabled
int desired_curvature = raw_curvature - FORD_INACTIVE_CURVATURE; // /FORD_STEERING_LIMITS.angle_deg_to_can to get real curvature
violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS);
if (violation) {
tx = false;
}
}
// Safety check for LateralMotionControl2 action
if (addr == FORD_LateralMotionControl2) {
// Signal: LatCtl_D2_Rq
bool steer_control_enabled = ((GET_BYTE(to_send, 0) >> 4) & 0x7U) != 0U;
unsigned int raw_curvature = (GET_BYTE(to_send, 2) << 3) | (GET_BYTE(to_send, 3) >> 5);
unsigned int raw_curvature_rate = (GET_BYTE(to_send, 6) << 3) | (GET_BYTE(to_send, 7) >> 5);
unsigned int raw_path_angle = ((GET_BYTE(to_send, 3) & 0x1FU) << 6) | (GET_BYTE(to_send, 4) >> 2);
unsigned int raw_path_offset = ((GET_BYTE(to_send, 4) & 0x3U) << 8) | GET_BYTE(to_send, 5);
// These signals are not yet tested with the current safety limits
bool violation = (raw_curvature_rate != FORD_CANFD_INACTIVE_CURVATURE_RATE) || (raw_path_angle != FORD_INACTIVE_PATH_ANGLE) || (raw_path_offset != FORD_INACTIVE_PATH_OFFSET);
// Check angle error and steer_control_enabled
int desired_curvature = raw_curvature - FORD_INACTIVE_CURVATURE; // /FORD_STEERING_LIMITS.angle_deg_to_can to get real curvature
violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS);
if (violation) {
tx = false;
}
}
return tx;
}
static int ford_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
switch (bus_num) {
case FORD_MAIN_BUS: {
// Forward all traffic from bus 0 onward
bus_fwd = FORD_CAM_BUS;
break;
}
case FORD_CAM_BUS: {
if (ford_lkas_msg_check(addr)) {
// Block stock LKAS and UI messages
bus_fwd = -1;
} else if (ford_longitudinal && (addr == FORD_ACCDATA)) {
// Block stock ACC message
bus_fwd = -1;
} else {
// Forward remaining traffic
bus_fwd = FORD_MAIN_BUS;
}
break;
}
default: {
// No other buses should be in use; fallback to do-not-forward
bus_fwd = -1;
break;
}
}
return bus_fwd;
}
static safety_config ford_init(uint16_t param) {
UNUSED(param);
#ifdef ALLOW_DEBUG
ford_longitudinal = GET_FLAG(param, FORD_PARAM_LONGITUDINAL);
ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD);
#endif
safety_config ret;
if (ford_canfd) {
ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_STOCK_TX_MSGS);
} else {
ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(ford_rx_checks, FORD_STOCK_TX_MSGS);
}
return ret;
}
const safety_hooks ford_hooks = {
.init = ford_init,
.rx = ford_rx_hook,
.tx = ford_tx_hook,
.fwd = ford_fwd_hook,
.get_counter = ford_get_counter,
.get_checksum = ford_get_checksum,
.compute_checksum = ford_compute_checksum,
.get_quality_flag_valid = ford_get_quality_flag_valid,
};

View File

@@ -0,0 +1,353 @@
const SteeringLimits GM_STEERING_LIMITS = {
.max_steer = 300,
.max_rate_up = 10,
.max_rate_down = 15,
.driver_torque_allowance = 65,
.driver_torque_factor = 4,
.max_rt_delta = 128,
.max_rt_interval = 250000,
.type = TorqueDriverLimited,
};
const LongitudinalLimits GM_ASCM_LONG_LIMITS = {
.max_gas = 3072,
.min_gas = 1404,
.inactive_gas = 1404,
.max_brake = 400,
};
const LongitudinalLimits GM_ASCM_LONG_LIMITS_SPORT = {
.max_gas = 8191,
.min_gas = 5500,
.inactive_gas = 5500,
.max_brake = 400,
};
const LongitudinalLimits GM_CAM_LONG_LIMITS = {
.max_gas = 3400,
.min_gas = 1514,
.inactive_gas = 1554,
.max_brake = 400,
};
const LongitudinalLimits GM_CAM_LONG_LIMITS_SPORT = {
.max_gas = 8848,
.min_gas = 5610,
.inactive_gas = 5650,
.max_brake = 400,
};
const LongitudinalLimits *gm_long_limits;
const int GM_STANDSTILL_THRSLD = 10; // 0.311kph
// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches
// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state
const int GM_GAS_INTERCEPTOR_THRESHOLD = 515; // (610 + 306.25) / 2 ratio between offset and gain from dbc file
#define GM_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks
const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4}, {0x409, 0, 7}, {0x40A, 0, 7}, {0x2CB, 0, 8}, {0x370, 0, 6}, {0x200, 0, 6}, // pt bus
{0xA1, 1, 7}, {0x306, 1, 8}, {0x308, 1, 7}, {0x310, 1, 2}, // obs bus
{0x315, 2, 5}, // ch bus
{0x104c006c, 3, 3}, {0x10400060, 3, 5}}; // gmlan
const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4}, {0x200, 0, 6}, {0x1E1, 0, 7}, // pt bus
{0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus
const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8}, {0x370, 0, 6}, {0x200, 0, 6}, // pt bus
{0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus
const CanMsg GM_SDGM_TX_MSGS[] = {{0x180, 0, 4}, {0x1E1, 0, 7}, // pt bus
{0x184, 2, 8}}; // camera bus
const CanMsg GM_CC_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x1E1, 0, 7}, // pt bus
{0x184, 2, 8}, {0x1E1, 2, 7}}; // camera bus
// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now.
RxCheck gm_rx_checks[] = {
{.msg = {{0x184, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0x34A, 0, 5, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0x1E1, 0, 7, .frequency = 10U}, // Non-SDGM Car
{0x1E1, 2, 7, .frequency = 100000U}}}, // SDGM Car
{.msg = {{0xF1, 0, 6, .frequency = 10U}, // Non-SDGM Car
{0xF1, 2, 6, .frequency = 100000U}}}, // SDGM Car
{.msg = {{0x1C4, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0xC9, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
};
const uint16_t GM_PARAM_HW_CAM = 1;
const uint16_t GM_PARAM_HW_CAM_LONG = 2;
const uint16_t GM_PARAM_HW_SDGM = 4;
const uint16_t GM_PARAM_CC_LONG = 8;
const uint16_t GM_PARAM_HW_ASCM_LONG = 16;
const uint16_t GM_PARAM_NO_CAMERA = 32;
const uint16_t GM_PARAM_NO_ACC = 64;
const uint16_t GM_PARAM_PEDAL_LONG = 128; // TODO: this can be inferred
const uint16_t GM_PARAM_PEDAL_INTERCEPTOR = 256;
enum {
GM_BTN_UNPRESS = 1,
GM_BTN_RESUME = 2,
GM_BTN_SET = 3,
GM_BTN_CANCEL = 6,
};
enum {GM_ASCM, GM_CAM, GM_SDGM} gm_hw = GM_ASCM;
bool gm_cam_long = false;
bool gm_pcm_cruise = false;
bool gm_cc_long = false;
bool gm_has_acc = true;
bool gm_pedal_long = false;
bool gm_skip_relay_check = false;
bool gm_force_ascm = false;
static void handle_gm_wheel_buttons(const CANPacket_t *to_push) {
int button = (GET_BYTE(to_push, 5) & 0x70U) >> 4;
// enter controls on falling edge of set or rising edge of resume (avoids fault)
bool set = (button != GM_BTN_SET) && (cruise_button_prev == GM_BTN_SET);
bool res = (button == GM_BTN_RESUME) && (cruise_button_prev != GM_BTN_RESUME);
if (set || res) {
controls_allowed = true;
}
// exit controls on cancel press
if (button == GM_BTN_CANCEL) {
controls_allowed = false;
}
cruise_button_prev = button;
}
static void gm_rx_hook(const CANPacket_t *to_push) {
if ((GET_BUS(to_push) == 2U) && (GET_ADDR(to_push) == 0x1E1) && (gm_hw == GM_SDGM)) {
// SDGM buttons are on bus 2
handle_gm_wheel_buttons(to_push);
}
if (GET_BUS(to_push) == 0U) {
int addr = GET_ADDR(to_push);
if (addr == 0x184) {
int torque_driver_new = ((GET_BYTE(to_push, 6) & 0x7U) << 8) | GET_BYTE(to_push, 7);
torque_driver_new = to_signed(torque_driver_new, 11);
// update array of samples
update_sample(&torque_driver, torque_driver_new);
}
// sample rear wheel speeds
if (addr == 0x34A) {
int left_rear_speed = (GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1);
int right_rear_speed = (GET_BYTE(to_push, 2) << 8) | GET_BYTE(to_push, 3);
vehicle_moving = (left_rear_speed > GM_STANDSTILL_THRSLD) || (right_rear_speed > GM_STANDSTILL_THRSLD);
}
// ACC steering wheel buttons (GM_CAM and GM_SDGM are tied to the PCM)
if ((addr == 0x1E1) && (!gm_pcm_cruise || gm_cc_long) && (gm_hw != GM_SDGM)) {
handle_gm_wheel_buttons(to_push);
}
// Reference for brake pressed signals:
// https://github.com/commaai/openpilot/blob/master/selfdrive/car/gm/carstate.py
if ((addr == 0xBE) && (gm_hw == GM_ASCM)) {
brake_pressed = GET_BYTE(to_push, 1) >= 8U;
}
if ((addr == 0xC9) && ((gm_hw == GM_CAM) || (gm_hw == GM_SDGM))) {
brake_pressed = GET_BIT(to_push, 40U) != 0U;
}
if (addr == 0xC9) {
acc_main_on = GET_BIT(to_push, 29U) != 0U;
}
if (addr == 0x1C4) {
if (!enable_gas_interceptor) {
gas_pressed = GET_BYTE(to_push, 5) != 0U;
}
// enter controls on rising edge of ACC, exit controls when ACC off
if (gm_pcm_cruise && gm_has_acc) {
bool cruise_engaged = (GET_BYTE(to_push, 1) >> 5) != 0U;
pcm_cruise_check(cruise_engaged);
}
}
// Cruise check for CC only cars
if ((addr == 0x3D1) && !gm_has_acc) {
bool cruise_engaged = (GET_BYTE(to_push, 4) >> 7) != 0U;
if (gm_cc_long) {
pcm_cruise_check(cruise_engaged);
} else {
cruise_engaged_prev = cruise_engaged;
}
}
if (addr == 0xBD) {
regen_braking = (GET_BYTE(to_push, 0) >> 4) != 0U;
}
// Pedal Interceptor
if ((addr == 0x201) && enable_gas_interceptor) {
int gas_interceptor = GM_GET_INTERCEPTOR(to_push);
gas_pressed = gas_interceptor > GM_GAS_INTERCEPTOR_THRESHOLD;
gas_interceptor_prev = gas_interceptor;
}
bool stock_ecu_detected = (addr == 0x180); // ASCMLKASteeringCmd
// Check ASCMGasRegenCmd only if we're blocking it
if (!gm_pcm_cruise && !gm_pedal_long && (addr == 0x2CB)) {
stock_ecu_detected = true;
}
generic_rx_checks(stock_ecu_detected);
}
}
static bool gm_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
// BRAKE: safety check
if (addr == 0x315) {
int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1);
brake = (0x1000 - brake) & 0xFFF;
if (longitudinal_brake_checks(brake, *gm_long_limits)) {
tx = false;
}
}
// LKA STEER: safety check
if (addr == 0x180) {
int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1);
desired_torque = to_signed(desired_torque, 11);
bool steer_req = GET_BIT(to_send, 3U);
if (steer_torque_cmd_checks(desired_torque, steer_req, GM_STEERING_LIMITS)) {
tx = false;
}
}
// GAS: safety check (interceptor)
if (addr == 0x200) {
if (longitudinal_interceptor_checks(to_send)) {
tx = 0;
}
}
// GAS/REGEN: safety check
if (addr == 0x2CB) {
bool apply = GET_BIT(to_send, 0U);
int gas_regen = ((GET_BYTE(to_send, 1) & 0x1U) << 13) + ((GET_BYTE(to_send, 2) & 0xFFU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3);
bool violation = false;
// Allow apply bit in pre-enabled and overriding states
violation |= !controls_allowed && apply;
violation |= longitudinal_gas_checks(gas_regen, *gm_long_limits);
if (violation) {
tx = false;
}
}
// BUTTONS: used for resume spamming and cruise cancellation with stock longitudinal
if ((addr == 0x1E1) && (gm_pcm_cruise || gm_pedal_long || gm_cc_long)) {
int button = (GET_BYTE(to_send, 5) >> 4) & 0x7U;
bool allowed_btn = (button == GM_BTN_CANCEL) && cruise_engaged_prev;
// For standard CC, allow spamming of SET / RESUME
if (gm_cc_long) {
allowed_btn |= cruise_engaged_prev && (button == GM_BTN_SET || button == GM_BTN_RESUME || button == GM_BTN_UNPRESS);
}
if (!allowed_btn) {
tx = false;
}
}
return tx;
}
static int gm_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if ((gm_hw == GM_CAM) || (gm_hw == GM_SDGM)) {
if (bus_num == 0) {
// block PSCMStatus; forwarded through openpilot to hide an alert from the camera
bool is_pscm_msg = (addr == 0x184);
if (!is_pscm_msg) {
bus_fwd = 2;
}
}
if (bus_num == 2) {
// block lkas message and acc messages if gm_cam_long, forward all others
bool is_lkas_msg = (addr == 0x180);
bool is_acc_msg = (addr == 0x315) || (addr == 0x2CB) || (addr == 0x370);
bool block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long);
if (!block_msg) {
bus_fwd = 0;
}
}
}
return bus_fwd;
}
static safety_config gm_init(uint16_t param) {
sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX;
if GET_FLAG(param, GM_PARAM_HW_CAM) {
gm_hw = GM_CAM;
} else if GET_FLAG(param, GM_PARAM_HW_SDGM) {
gm_hw = GM_SDGM;
} else {
gm_hw = GM_ASCM;
}
gm_force_ascm = GET_FLAG(param, GM_PARAM_HW_ASCM_LONG);
if (gm_hw == GM_ASCM || gm_force_ascm) {
if (sport_mode) {
gm_long_limits = &GM_ASCM_LONG_LIMITS_SPORT;
} else {
gm_long_limits = &GM_ASCM_LONG_LIMITS;
}
} else if ((gm_hw == GM_CAM) || (gm_hw == GM_SDGM)) {
if (sport_mode) {
gm_long_limits = &GM_CAM_LONG_LIMITS_SPORT;
} else {
gm_long_limits = &GM_CAM_LONG_LIMITS;
}
} else {
}
gm_pedal_long = GET_FLAG(param, GM_PARAM_PEDAL_LONG);
gm_cc_long = GET_FLAG(param, GM_PARAM_CC_LONG);
gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG) && !gm_cc_long;
gm_pcm_cruise = ((gm_hw == GM_CAM) && (!gm_cam_long || gm_cc_long) && !gm_force_ascm && !gm_pedal_long) || (gm_hw == GM_SDGM);
gm_skip_relay_check = GET_FLAG(param, GM_PARAM_NO_CAMERA);
gm_has_acc = !GET_FLAG(param, GM_PARAM_NO_ACC);
enable_gas_interceptor = GET_FLAG(param, GM_PARAM_PEDAL_INTERCEPTOR);
safety_config ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_ASCM_TX_MSGS);
if (gm_hw == GM_CAM) {
if (gm_cc_long) {
ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CC_LONG_TX_MSGS);
} else if (gm_cam_long) {
ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_LONG_TX_MSGS);
} else {
ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_TX_MSGS);
}
} else if (gm_hw == GM_SDGM) {
ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_SDGM_TX_MSGS);
}
return ret;
}
const safety_hooks gm_hooks = {
.init = gm_init,
.rx = gm_rx_hook,
.tx = gm_tx_hook,
.fwd = gm_fwd_hook,
};

View File

@@ -0,0 +1,526 @@
const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x30C, 0, 8}, {0x33D, 0, 5}};
const CanMsg HONDA_N_INTERCEPTOR_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x200, 0, 6}, {0x30C, 0, 8}, {0x33D, 0, 5}};
const CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}, {0x33DA, 0, 5}, {0x33DB, 0, 8}}; // Bosch
const CanMsg HONDA_BOSCH_LONG_TX_MSGS[] = {{0xE4, 1, 5}, {0x1DF, 1, 8}, {0x1EF, 1, 8}, {0x1FA, 1, 8}, {0x30C, 1, 8}, {0x33D, 1, 5}, {0x33DA, 1, 5}, {0x33DB, 1, 8}, {0x39F, 1, 8}, {0x18DAB0F1, 1, 8}}; // Bosch w/ gas and brakes
const CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5}, {0x296, 2, 4}, {0x33D, 0, 8}}; // Bosch radarless
const CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5}, {0x33D, 0, 8}, {0x1C8, 0, 8}, {0x30C, 0, 8}}; // Bosch radarless w/ gas and brakes
// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches
// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state
// Threshold calculated from DBC gains: round(((83.3 / 0.253984064) + (83.3 / 0.126992032)) / 2) = 492
const int HONDA_GAS_INTERCEPTOR_THRESHOLD = 492;
#define HONDA_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks
const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS = {
.max_accel = 200, // accel is used for brakes
.min_accel = -350,
.max_gas = 2000,
.inactive_gas = -30000,
};
const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS_SPORT = {
.max_accel = 400, // accel is used for brakes
.min_accel = -350,
.max_gas = 2000,
.inactive_gas = -30000,
};
const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = {
.max_gas = 198, // 0xc6
.max_brake = 255,
.inactive_speed = 0,
};
// All common address checks except SCM_BUTTONS which isn't on one Nidec safety configuration
#define HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \
{.msg = {{0x1A6, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, /* SCM_BUTTONS */ \
{0x296, (pt_bus), 4, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, { 0 }}}, \
{.msg = {{0x158, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* ENGINE_DATA */ \
{.msg = {{0x17C, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* POWERTRAIN_DATA */ \
#define HONDA_COMMON_RX_CHECKS(pt_bus) \
HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \
{.msg = {{0x326, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 10U}, { 0 }, { 0 }}}, /* SCM_FEEDBACK */ \
// Alternate brake message is used on some Honda Bosch, and Honda Bosch radarless (where PT bus is 0)
#define HONDA_ALT_BRAKE_ADDR_CHECK(pt_bus) \
{.msg = {{0x1BE, (pt_bus), 3, .check_checksum = true, .max_counter = 3U, .frequency = 50U}, { 0 }, { 0 }}}, /* BRAKE_MODULE */ \
// Nidec and bosch radarless has the powertrain bus on bus 0
RxCheck honda_common_rx_checks[] = {
HONDA_COMMON_RX_CHECKS(0)
};
RxCheck honda_common_interceptor_rx_checks[] = {
HONDA_COMMON_RX_CHECKS(0)
{.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
RxCheck honda_common_alt_brake_rx_checks[] = {
HONDA_COMMON_RX_CHECKS(0)
HONDA_ALT_BRAKE_ADDR_CHECK(0)
};
// For Nidecs with main on signal on an alternate msg (missing 0x326)
RxCheck honda_nidec_alt_rx_checks[] = {
HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0)
};
RxCheck honda_nidec_alt_interceptor_rx_checks[] = {
HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0)
{.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
// Bosch has pt on bus 1, verified 0x1A6 does not exist
RxCheck honda_bosch_rx_checks[] = {
HONDA_COMMON_RX_CHECKS(1)
};
RxCheck honda_bosch_alt_brake_rx_checks[] = {
HONDA_COMMON_RX_CHECKS(1)
HONDA_ALT_BRAKE_ADDR_CHECK(1)
};
const uint16_t HONDA_PARAM_ALT_BRAKE = 1;
const uint16_t HONDA_PARAM_BOSCH_LONG = 2;
const uint16_t HONDA_PARAM_NIDEC_ALT = 4;
const uint16_t HONDA_PARAM_RADARLESS = 8;
const uint16_t HONDA_PARAM_GAS_INTERCEPTOR = 16;
const uint16_t HONDA_PARAM_CLARITY = 32;
enum {
HONDA_BTN_NONE = 0,
HONDA_BTN_MAIN = 1,
HONDA_BTN_CANCEL = 2,
HONDA_BTN_SET = 3,
HONDA_BTN_RESUME = 4,
};
int honda_brake = 0;
bool honda_brake_switch_prev = false;
bool honda_alt_brake_msg = false;
bool honda_fwd_brake = false;
bool honda_bosch_long = false;
bool honda_bosch_radarless = false;
bool honda_clarity_brake_msg = false;
enum {HONDA_NIDEC, HONDA_BOSCH} honda_hw = HONDA_NIDEC;
int honda_get_pt_bus(void) {
return ((honda_hw == HONDA_BOSCH) && !honda_bosch_radarless) ? 1 : 0;
}
static uint32_t honda_get_checksum(const CANPacket_t *to_push) {
int checksum_byte = GET_LEN(to_push) - 1U;
return (uint8_t)(GET_BYTE(to_push, checksum_byte)) & 0xFU;
}
static uint32_t honda_compute_checksum(const CANPacket_t *to_push) {
int len = GET_LEN(to_push);
uint8_t checksum = 0U;
unsigned int addr = GET_ADDR(to_push);
while (addr > 0U) {
checksum += (uint8_t)(addr & 0xFU); addr >>= 4;
}
for (int j = 0; j < len; j++) {
uint8_t byte = GET_BYTE(to_push, j);
checksum += (uint8_t)(byte & 0xFU) + (byte >> 4U);
if (j == (len - 1)) {
checksum -= (byte & 0xFU); // remove checksum in message
}
}
return (uint8_t)((8U - checksum) & 0xFU);
}
static uint8_t honda_get_counter(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t cnt = 0U;
if (addr == 0x201) {
// Signal: COUNTER_PEDAL
cnt = GET_BYTE(to_push, 4) & 0x0FU;
} else {
int counter_byte = GET_LEN(to_push) - 1U;
cnt = (GET_BYTE(to_push, counter_byte) >> 4U) & 0x3U;
}
return cnt;
}
static void honda_rx_hook(const CANPacket_t *to_push) {
const bool pcm_cruise = ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) || \
((honda_hw == HONDA_NIDEC) && !enable_gas_interceptor);
int pt_bus = honda_get_pt_bus();
int addr = GET_ADDR(to_push);
int len = GET_LEN(to_push);
int bus = GET_BUS(to_push);
// sample speed
if (addr == 0x158) {
// first 2 bytes
vehicle_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1);
}
// check ACC main state
// 0x326 for all Bosch and some Nidec, 0x1A6 for some Nidec
if ((addr == 0x326) || (addr == 0x1A6)) {
acc_main_on = GET_BIT(to_push, ((addr == 0x326) ? 28U : 47U));
if (!acc_main_on) {
controls_allowed = false;
}
}
// enter controls when PCM enters cruise state
if (pcm_cruise && (addr == 0x17C)) {
const bool cruise_engaged = GET_BIT(to_push, 38U);
// engage on rising edge
if (cruise_engaged && !cruise_engaged_prev) {
controls_allowed = true;
}
// Since some Nidec cars can brake down to 0 after the PCM disengages,
// we don't disengage when the PCM does.
if (!cruise_engaged && (honda_hw != HONDA_NIDEC)) {
controls_allowed = false;
}
cruise_engaged_prev = cruise_engaged;
}
// state machine to enter and exit controls for button enabling
// 0x1A6 for the ILX, 0x296 for the Civic Touring
if (((addr == 0x1A6) || (addr == 0x296)) && (bus == pt_bus)) {
int button = (GET_BYTE(to_push, 0) & 0xE0U) >> 5;
// enter controls on the falling edge of set or resume
bool set = (button != HONDA_BTN_SET) && (cruise_button_prev == HONDA_BTN_SET);
bool res = (button != HONDA_BTN_RESUME) && (cruise_button_prev == HONDA_BTN_RESUME);
if (acc_main_on && !pcm_cruise && (set || res)) {
controls_allowed = true;
}
// exit controls once main or cancel are pressed
if ((button == HONDA_BTN_MAIN) || (button == HONDA_BTN_CANCEL)) {
controls_allowed = false;
}
cruise_button_prev = button;
}
// user brake signal on 0x17C reports applied brake from computer brake on accord
// and crv, which prevents the usual brake safety from working correctly. these
// cars have a signal on 0x1BE which only detects user's brake being applied so
// in these cases, this is used instead.
// most hondas: 0x17C
// accord, crv: 0x1BE
if (honda_alt_brake_msg) {
if (addr == 0x1BE) {
brake_pressed = GET_BIT(to_push, 4U);
}
} else {
if (addr == 0x17C) {
// also if brake switch is 1 for two CAN frames, as brake pressed is delayed
const bool brake_switch = GET_BIT(to_push, 32U);
brake_pressed = (GET_BIT(to_push, 53U)) || (brake_switch && honda_brake_switch_prev);
honda_brake_switch_prev = brake_switch;
}
}
// length check because bosch hardware also uses this id (0x201 w/ len = 8)
if ((addr == 0x201) && (len == 6) && enable_gas_interceptor) {
int gas_interceptor = HONDA_GET_INTERCEPTOR(to_push);
gas_pressed = gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD;
gas_interceptor_prev = gas_interceptor;
}
if (!enable_gas_interceptor) {
if (addr == 0x17C) {
gas_pressed = GET_BYTE(to_push, 0) != 0U;
}
}
// disable stock Honda AEB in alternative experience
if (!(alternative_experience & ALT_EXP_DISABLE_STOCK_AEB)) {
if ((bus == 2) && (addr == 0x1FA)) {
bool honda_stock_aeb = GET_BIT(to_push, 29U);
int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) | (GET_BYTE(to_push, 1) >> 6);
if (honda_clarity_brake_msg) {
honda_stock_brake = (GET_BYTE(to_push, 6) << 2) + ((GET_BYTE(to_push, 7) >> 6) & 0x3U);
}
// Forward AEB when stock braking is higher than openpilot braking
// only stop forwarding when AEB event is over
if (!honda_stock_aeb) {
honda_fwd_brake = false;
} else if (honda_stock_brake >= honda_brake) {
honda_fwd_brake = true;
} else {
// Leave Honda forward brake as is
}
}
}
int bus_rdr_car = (honda_hw == HONDA_BOSCH) ? 0 : 2; // radar bus, car side
bool stock_ecu_detected = false;
// If steering controls messages are received on the destination bus, it's an indication
// that the relay might be malfunctioning
if ((addr == 0xE4) || (addr == 0x194)) {
if (((honda_hw != HONDA_NIDEC) && (bus == bus_rdr_car)) || ((honda_hw == HONDA_NIDEC) && (bus == 0))) {
stock_ecu_detected = true;
}
}
// If Honda Bosch longitudinal mode is selected we need to ensure the radar is turned off
// Verify this by ensuring ACC_CONTROL (0x1DF) is not received on the PT bus
if (honda_bosch_long && !honda_bosch_radarless && (bus == pt_bus) && (addr == 0x1DF)) {
stock_ecu_detected = true;
}
generic_rx_checks(stock_ecu_detected);
}
static bool honda_tx_hook(const CANPacket_t *to_send) {
sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX;
bool tx = true;
int addr = GET_ADDR(to_send);
int bus = GET_BUS(to_send);
int bus_pt = honda_get_pt_bus();
int bus_buttons = (honda_bosch_radarless) ? 2 : bus_pt; // the camera controls ACC on radarless Bosch cars
// ACC_HUD: safety check (nidec w/o pedal)
if ((addr == 0x30C) && (bus == bus_pt)) {
int pcm_speed = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1);
int pcm_gas = GET_BYTE(to_send, 2);
bool violation = false;
violation |= longitudinal_speed_checks(pcm_speed, HONDA_NIDEC_LONG_LIMITS);
violation |= longitudinal_gas_checks(pcm_gas, HONDA_NIDEC_LONG_LIMITS);
if (violation) {
tx = false;
}
}
// BRAKE: safety check (nidec)
if ((addr == 0x1FA) && (bus == bus_pt)) {
honda_brake = (GET_BYTE(to_send, 0) << 2) + ((GET_BYTE(to_send, 1) >> 6) & 0x3U);
if (honda_clarity_brake_msg) {
honda_brake = (GET_BYTE(to_send, 6) << 2) + ((GET_BYTE(to_send, 7) >> 6) & 0x3U);
}
if (longitudinal_brake_checks(honda_brake, HONDA_NIDEC_LONG_LIMITS)) {
tx = false;
}
if (honda_fwd_brake) {
tx = false;
}
}
// BRAKE/GAS: safety check (bosch)
if ((addr == 0x1DF) && (bus == bus_pt)) {
int accel = (GET_BYTE(to_send, 3) << 3) | ((GET_BYTE(to_send, 4) >> 5) & 0x7U);
accel = to_signed(accel, 11);
int gas = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1);
gas = to_signed(gas, 16);
bool violation = false;
if (sport_mode) {
violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS_SPORT);
violation |= longitudinal_gas_checks(gas, HONDA_BOSCH_LONG_LIMITS_SPORT);
} else {
violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS);
violation |= longitudinal_gas_checks(gas, HONDA_BOSCH_LONG_LIMITS);
}
if (violation) {
tx = false;
}
}
// ACCEL: safety check (radarless)
if ((addr == 0x1C8) && (bus == bus_pt)) {
int accel = (GET_BYTE(to_send, 0) << 4) | (GET_BYTE(to_send, 1) >> 4);
accel = to_signed(accel, 12);
bool violation = false;
if (sport_mode) {
violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS_SPORT);
} else {
violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS);
}
if (violation) {
tx = false;
}
}
// STEER: safety check
if ((addr == 0xE4) || (addr == 0x194)) {
bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_DISABLE_DISENGAGE_ON_GAS);
if (!(controls_allowed || aol_allowed)) {
bool steer_applied = GET_BYTE(to_send, 0) | GET_BYTE(to_send, 1);
if (steer_applied) {
tx = false;
}
}
}
// Bosch supplemental control check
if (addr == 0xE5) {
if ((GET_BYTES(to_send, 0, 4) != 0x10800004U) || ((GET_BYTES(to_send, 4, 4) & 0x00FFFFFFU) != 0x0U)) {
tx = false;
}
}
// GAS: safety check (interceptor)
if (addr == 0x200) {
if (longitudinal_interceptor_checks(to_send)) {
tx = false;
}
}
// FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW
// ensuring that only the cancel button press is sent (VAL 2) when controls are off.
// This avoids unintended engagements while still allowing resume spam
if ((addr == 0x296) && !controls_allowed && (bus == bus_buttons)) {
if (((GET_BYTE(to_send, 0) >> 5) & 0x7U) != 2U) {
tx = false;
}
}
// Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address
if (addr == 0x18DAB0F1) {
if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) {
tx = false;
}
}
return tx;
}
static safety_config honda_nidec_init(uint16_t param) {
honda_hw = HONDA_NIDEC;
honda_brake = 0;
honda_brake_switch_prev = false;
honda_fwd_brake = false;
honda_alt_brake_msg = false;
honda_bosch_long = false;
honda_bosch_radarless = false;
enable_gas_interceptor = GET_FLAG(param, HONDA_PARAM_GAS_INTERCEPTOR);
honda_clarity_brake_msg = GET_FLAG(param, HONDA_PARAM_CLARITY);
safety_config ret;
bool enable_nidec_alt = GET_FLAG(param, HONDA_PARAM_NIDEC_ALT);
if (enable_nidec_alt) {
enable_gas_interceptor ? SET_RX_CHECKS(honda_nidec_alt_interceptor_rx_checks, ret) : \
SET_RX_CHECKS(honda_nidec_alt_rx_checks, ret);
} else {
enable_gas_interceptor ? SET_RX_CHECKS(honda_common_interceptor_rx_checks, ret) : \
SET_RX_CHECKS(honda_common_rx_checks, ret);
}
if (enable_gas_interceptor) {
SET_TX_MSGS(HONDA_N_INTERCEPTOR_TX_MSGS, ret);
} else {
SET_TX_MSGS(HONDA_N_TX_MSGS, ret);
}
return ret;
}
static safety_config honda_bosch_init(uint16_t param) {
honda_hw = HONDA_BOSCH;
honda_brake_switch_prev = false;
honda_bosch_radarless = GET_FLAG(param, HONDA_PARAM_RADARLESS);
// Checking for alternate brake override from safety parameter
honda_alt_brake_msg = GET_FLAG(param, HONDA_PARAM_ALT_BRAKE);
// radar disabled so allow gas/brakes
#ifdef ALLOW_DEBUG
honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG);
#endif
safety_config ret;
if (honda_bosch_radarless && honda_alt_brake_msg) {
SET_RX_CHECKS(honda_common_alt_brake_rx_checks, ret);
} else if (honda_bosch_radarless) {
SET_RX_CHECKS(honda_common_rx_checks, ret);
} else if (honda_alt_brake_msg) {
SET_RX_CHECKS(honda_bosch_alt_brake_rx_checks, ret);
} else {
SET_RX_CHECKS(honda_bosch_rx_checks, ret);
}
if (honda_bosch_radarless) {
honda_bosch_long ? SET_TX_MSGS(HONDA_RADARLESS_LONG_TX_MSGS, ret) : \
SET_TX_MSGS(HONDA_RADARLESS_TX_MSGS, ret);
} else {
honda_bosch_long ? SET_TX_MSGS(HONDA_BOSCH_LONG_TX_MSGS, ret) : \
SET_TX_MSGS(HONDA_BOSCH_TX_MSGS, ret);
}
return ret;
}
static int honda_nidec_fwd_hook(int bus_num, int addr) {
// fwd from car to camera. also fwd certain msgs from camera to car
// 0xE4 is steering on all cars except CRV and RDX, 0x194 for CRV and RDX,
// 0x1FA is brake control, 0x30C is acc hud, 0x33D is lkas hud
int bus_fwd = -1;
if (bus_num == 0) {
bus_fwd = 2;
}
if (bus_num == 2) {
// block stock lkas messages and stock acc messages (if OP is doing ACC)
bool is_lkas_msg = (addr == 0xE4) || (addr == 0x194) || (addr == 0x33D);
bool is_acc_hud_msg = addr == 0x30C;
bool is_brake_msg = addr == 0x1FA;
bool block_fwd = is_lkas_msg || is_acc_hud_msg || (is_brake_msg && !honda_fwd_brake);
if (!block_fwd) {
bus_fwd = 0;
}
}
return bus_fwd;
}
static int honda_bosch_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == 0) {
bus_fwd = 2;
}
if (bus_num == 2) {
bool is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D) || (addr == 0x33DA) || (addr == 0x33DB);
bool is_acc_msg = ((addr == 0x1C8) || (addr == 0x30C)) && honda_bosch_radarless && honda_bosch_long;
bool block_msg = is_lkas_msg || is_acc_msg;
if (!block_msg) {
bus_fwd = 0;
}
}
return bus_fwd;
}
const safety_hooks honda_nidec_hooks = {
.init = honda_nidec_init,
.rx = honda_rx_hook,
.tx = honda_tx_hook,
.fwd = honda_nidec_fwd_hook,
.get_counter = honda_get_counter,
.get_checksum = honda_get_checksum,
.compute_checksum = honda_compute_checksum,
};
const safety_hooks honda_bosch_hooks = {
.init = honda_bosch_init,
.rx = honda_rx_hook,
.tx = honda_tx_hook,
.fwd = honda_bosch_fwd_hook,
.get_counter = honda_get_counter,
.get_checksum = honda_get_checksum,
.compute_checksum = honda_compute_checksum,
};

View File

@@ -0,0 +1,356 @@
#include "safety_hyundai_common.h"
#define HYUNDAI_LIMITS(steer, rate_up, rate_down) { \
.max_steer = (steer), \
.max_rate_up = (rate_up), \
.max_rate_down = (rate_down), \
.max_rt_delta = 112, \
.max_rt_interval = 250000, \
.driver_torque_allowance = 50, \
.driver_torque_factor = 2, \
.type = TorqueDriverLimited, \
/* the EPS faults when the steering angle is above a certain threshold for too long. to prevent this, */ \
/* we allow setting CF_Lkas_ActToi bit to 0 while maintaining the requested torque value for two consecutive frames */ \
.min_valid_request_frames = 89, \
.max_invalid_request_frames = 2, \
.min_valid_request_rt_interval = 810000, /* 810ms; a ~10% buffer on cutting every 90 frames */ \
.has_steer_req_tolerance = true, \
}
const SteeringLimits HYUNDAI_STEERING_LIMITS = HYUNDAI_LIMITS(384, 3, 7);
const SteeringLimits HYUNDAI_STEERING_LIMITS_ALT = HYUNDAI_LIMITS(270, 2, 3);
const LongitudinalLimits HYUNDAI_LONG_LIMITS = {
.max_accel = 200, // 1/100 m/s2
.min_accel = -350, // 1/100 m/s2
};
const LongitudinalLimits HYUNDAI_LONG_LIMITS_SPORT = {
.max_accel = 400, // 1/100 m/s2
.min_accel = -350, // 1/100 m/s2
};
const CanMsg HYUNDAI_TX_MSGS[] = {
{0x340, 0, 8}, // LKAS11 Bus 0
{0x4F1, 0, 4}, // CLU11 Bus 0
{0x485, 0, 4}, // LFAHDA_MFC Bus 0
};
const CanMsg HYUNDAI_LONG_TX_MSGS[] = {
{0x340, 0, 8}, // LKAS11 Bus 0
{0x4F1, 0, 4}, // CLU11 Bus 0
{0x485, 0, 4}, // LFAHDA_MFC Bus 0
{0x420, 0, 8}, // SCC11 Bus 0
{0x421, 0, 8}, // SCC12 Bus 0
{0x50A, 0, 8}, // SCC13 Bus 0
{0x389, 0, 8}, // SCC14 Bus 0
{0x4A2, 0, 2}, // FRT_RADAR11 Bus 0
{0x38D, 0, 8}, // FCA11 Bus 0
{0x483, 0, 8}, // FCA12 Bus 0
{0x7D0, 0, 8}, // radar UDS TX addr Bus 0 (for radar disable)
};
const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = {
{0x340, 0, 8}, // LKAS11 Bus 0
{0x4F1, 2, 4}, // CLU11 Bus 2
{0x485, 0, 4}, // LFAHDA_MFC Bus 0
};
#define HYUNDAI_COMMON_RX_CHECKS(legacy) \
{.msg = {{0x260, 0, 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, \
{0x371, 0, 8, .frequency = 100U}, { 0 }}}, \
{.msg = {{0x386, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 15U, .frequency = 100U}, { 0 }, { 0 }}}, \
{.msg = {{0x394, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 7U, .frequency = 100U}, { 0 }, { 0 }}}, \
#define HYUNDAI_SCC12_ADDR_CHECK(scc_bus) \
{.msg = {{0x421, (scc_bus), 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \
RxCheck hyundai_rx_checks[] = {
HYUNDAI_COMMON_RX_CHECKS(false)
HYUNDAI_SCC12_ADDR_CHECK(0)
};
RxCheck hyundai_cam_scc_rx_checks[] = {
HYUNDAI_COMMON_RX_CHECKS(false)
HYUNDAI_SCC12_ADDR_CHECK(2)
};
RxCheck hyundai_long_rx_checks[] = {
HYUNDAI_COMMON_RX_CHECKS(false)
// Use CLU11 (buttons) to manage controls allowed instead of SCC cruise state
{.msg = {{0x4F1, 0, 4, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
// older hyundai models have less checks due to missing counters and checksums
RxCheck hyundai_legacy_rx_checks[] = {
HYUNDAI_COMMON_RX_CHECKS(true)
HYUNDAI_SCC12_ADDR_CHECK(0)
};
bool hyundai_legacy = false;
static uint8_t hyundai_get_counter(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t cnt = 0;
if (addr == 0x260) {
cnt = (GET_BYTE(to_push, 7) >> 4) & 0x3U;
} else if (addr == 0x386) {
cnt = ((GET_BYTE(to_push, 3) >> 6) << 2) | (GET_BYTE(to_push, 1) >> 6);
} else if (addr == 0x394) {
cnt = (GET_BYTE(to_push, 1) >> 5) & 0x7U;
} else if (addr == 0x421) {
cnt = GET_BYTE(to_push, 7) & 0xFU;
} else if (addr == 0x4F1) {
cnt = (GET_BYTE(to_push, 3) >> 4) & 0xFU;
} else {
}
return cnt;
}
static uint32_t hyundai_get_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t chksum = 0;
if (addr == 0x260) {
chksum = GET_BYTE(to_push, 7) & 0xFU;
} else if (addr == 0x386) {
chksum = ((GET_BYTE(to_push, 7) >> 6) << 2) | (GET_BYTE(to_push, 5) >> 6);
} else if (addr == 0x394) {
chksum = GET_BYTE(to_push, 6) & 0xFU;
} else if (addr == 0x421) {
chksum = GET_BYTE(to_push, 7) >> 4;
} else {
}
return chksum;
}
static uint32_t hyundai_compute_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t chksum = 0;
if (addr == 0x386) {
// count the bits
for (int i = 0; i < 8; i++) {
uint8_t b = GET_BYTE(to_push, i);
for (int j = 0; j < 8; j++) {
uint8_t bit = 0;
// exclude checksum and counter
if (((i != 1) || (j < 6)) && ((i != 3) || (j < 6)) && ((i != 5) || (j < 6)) && ((i != 7) || (j < 6))) {
bit = (b >> (uint8_t)j) & 1U;
}
chksum += bit;
}
}
chksum = (chksum ^ 9U) & 15U;
} else {
// sum of nibbles
for (int i = 0; i < 8; i++) {
if ((addr == 0x394) && (i == 7)) {
continue; // exclude
}
uint8_t b = GET_BYTE(to_push, i);
if (((addr == 0x260) && (i == 7)) || ((addr == 0x394) && (i == 6)) || ((addr == 0x421) && (i == 7))) {
b &= (addr == 0x421) ? 0x0FU : 0xF0U; // remove checksum
}
chksum += (b % 16U) + (b / 16U);
}
chksum = (16U - (chksum % 16U)) % 16U;
}
return chksum;
}
static void hyundai_rx_hook(const CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
// SCC12 is on bus 2 for camera-based SCC cars, bus 0 on all others
if ((addr == 0x421) && (((bus == 0) && !hyundai_camera_scc) || ((bus == 2) && hyundai_camera_scc))) {
// 2 bits: 13-14
int cruise_engaged = (GET_BYTES(to_push, 0, 4) >> 13) & 0x3U;
hyundai_common_cruise_state_check(cruise_engaged);
}
if (bus == 0) {
if (addr == 0x251) {
int torque_driver_new = (GET_BYTES(to_push, 0, 2) & 0x7ffU) - 1024U;
// update array of samples
update_sample(&torque_driver, torque_driver_new);
}
// ACC steering wheel buttons
if (addr == 0x4F1) {
int cruise_button = GET_BYTE(to_push, 0) & 0x7U;
bool main_button = GET_BIT(to_push, 3U);
hyundai_common_cruise_buttons_check(cruise_button, main_button);
}
// gas press, different for EV, hybrid, and ICE models
if ((addr == 0x371) && hyundai_ev_gas_signal) {
gas_pressed = (((GET_BYTE(to_push, 4) & 0x7FU) << 1) | GET_BYTE(to_push, 3) >> 7) != 0U;
} else if ((addr == 0x371) && hyundai_hybrid_gas_signal) {
gas_pressed = GET_BYTE(to_push, 7) != 0U;
} else if ((addr == 0x260) && !hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) {
gas_pressed = (GET_BYTE(to_push, 7) >> 6) != 0U;
} else {
}
// sample wheel speed, averaging opposite corners
if (addr == 0x386) {
uint32_t front_left_speed = GET_BYTES(to_push, 0, 2) & 0x3FFFU;
uint32_t rear_right_speed = GET_BYTES(to_push, 6, 2) & 0x3FFFU;
vehicle_moving = (front_left_speed > HYUNDAI_STANDSTILL_THRSLD) || (rear_right_speed > HYUNDAI_STANDSTILL_THRSLD);
}
if (addr == 0x394) {
brake_pressed = ((GET_BYTE(to_push, 5) >> 5U) & 0x3U) == 0x2U;
}
bool stock_ecu_detected = (addr == 0x340);
// If openpilot is controlling longitudinal we need to ensure the radar is turned off
// Enforce by checking we don't see SCC12
if (hyundai_longitudinal && (addr == 0x421)) {
stock_ecu_detected = true;
}
generic_rx_checks(stock_ecu_detected);
}
}
static bool hyundai_tx_hook(const CANPacket_t *to_send) {
sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX;
bool tx = true;
int addr = GET_ADDR(to_send);
// FCA11: Block any potential actuation
if (addr == 0x38D) {
int CR_VSM_DecCmd = GET_BYTE(to_send, 1);
bool FCA_CmdAct = GET_BIT(to_send, 20U);
bool CF_VSM_DecCmdAct = GET_BIT(to_send, 31U);
if ((CR_VSM_DecCmd != 0) || FCA_CmdAct || CF_VSM_DecCmdAct) {
tx = false;
}
}
// ACCEL: safety check
if (addr == 0x421) {
int desired_accel_raw = (((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) - 1023U;
int desired_accel_val = ((GET_BYTE(to_send, 5) << 3) | (GET_BYTE(to_send, 4) >> 5)) - 1023U;
int aeb_decel_cmd = GET_BYTE(to_send, 2);
bool aeb_req = GET_BIT(to_send, 54U);
bool violation = false;
if (sport_mode) {
violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS_SPORT);
violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS_SPORT);
} else {
violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS);
violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS);
}
violation |= (aeb_decel_cmd != 0);
violation |= aeb_req;
if (violation) {
tx = false;
}
}
// LKA STEER: safety check
if (addr == 0x340) {
int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x7ffU) - 1024U;
bool steer_req = GET_BIT(to_send, 27U);
const SteeringLimits limits = hyundai_alt_limits ? HYUNDAI_STEERING_LIMITS_ALT : HYUNDAI_STEERING_LIMITS;
if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) {
tx = false;
}
}
// UDS: Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address
if (addr == 0x7D0) {
if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) {
tx = false;
}
}
// BUTTONS: used for resume spamming and cruise cancellation
if ((addr == 0x4F1) && !hyundai_longitudinal) {
int button = GET_BYTE(to_send, 0) & 0x7U;
bool allowed_resume = (button == 1) && controls_allowed;
bool allowed_cancel = (button == 4) && cruise_engaged_prev;
if (!(allowed_resume || allowed_cancel)) {
tx = false;
}
}
return tx;
}
static int hyundai_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
// forward cam to ccan and viceversa, except lkas cmd
if (bus_num == 0) {
bus_fwd = 2;
}
if ((bus_num == 2) && (addr != 0x340) && (addr != 0x485)) {
bus_fwd = 0;
}
return bus_fwd;
}
static safety_config hyundai_init(uint16_t param) {
hyundai_common_init(param);
hyundai_legacy = false;
if (hyundai_camera_scc) {
hyundai_longitudinal = false;
}
safety_config ret;
if (hyundai_longitudinal) {
ret = BUILD_SAFETY_CFG(hyundai_long_rx_checks, HYUNDAI_LONG_TX_MSGS);
} else if (hyundai_camera_scc) {
ret = BUILD_SAFETY_CFG(hyundai_cam_scc_rx_checks, HYUNDAI_CAMERA_SCC_TX_MSGS);
} else {
ret = BUILD_SAFETY_CFG(hyundai_rx_checks, HYUNDAI_TX_MSGS);
}
return ret;
}
static safety_config hyundai_legacy_init(uint16_t param) {
hyundai_common_init(param);
hyundai_legacy = true;
hyundai_longitudinal = false;
hyundai_camera_scc = false;
return BUILD_SAFETY_CFG(hyundai_legacy_rx_checks, HYUNDAI_TX_MSGS);
}
const safety_hooks hyundai_hooks = {
.init = hyundai_init,
.rx = hyundai_rx_hook,
.tx = hyundai_tx_hook,
.fwd = hyundai_fwd_hook,
.get_counter = hyundai_get_counter,
.get_checksum = hyundai_get_checksum,
.compute_checksum = hyundai_compute_checksum,
};
const safety_hooks hyundai_legacy_hooks = {
.init = hyundai_legacy_init,
.rx = hyundai_rx_hook,
.tx = hyundai_tx_hook,
.fwd = hyundai_fwd_hook,
.get_counter = hyundai_get_counter,
.get_checksum = hyundai_get_checksum,
.compute_checksum = hyundai_compute_checksum,
};

View File

@@ -0,0 +1,360 @@
#include "safety_hyundai_common.h"
const SteeringLimits HYUNDAI_CANFD_STEERING_LIMITS = {
.max_steer = 270,
.max_rt_delta = 112,
.max_rt_interval = 250000,
.max_rate_up = 2,
.max_rate_down = 3,
.driver_torque_allowance = 250,
.driver_torque_factor = 2,
.type = TorqueDriverLimited,
// the EPS faults when the steering angle is above a certain threshold for too long. to prevent this,
// we allow setting torque actuation bit to 0 while maintaining the requested torque value for two consecutive frames
.min_valid_request_frames = 89,
.max_invalid_request_frames = 2,
.min_valid_request_rt_interval = 810000, // 810ms; a ~10% buffer on cutting every 90 frames
.has_steer_req_tolerance = true,
};
const CanMsg HYUNDAI_CANFD_HDA2_TX_MSGS[] = {
{0x50, 0, 16}, // LKAS
{0x1CF, 1, 8}, // CRUISE_BUTTON
{0x2A4, 0, 24}, // CAM_0x2A4
};
const CanMsg HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS[] = {
{0x110, 0, 32}, // LKAS_ALT
{0x1CF, 1, 8}, // CRUISE_BUTTON
{0x362, 0, 32}, // CAM_0x362
};
const CanMsg HYUNDAI_CANFD_HDA2_LONG_TX_MSGS[] = {
{0x50, 0, 16}, // LKAS
{0x1CF, 1, 8}, // CRUISE_BUTTON
{0x2A4, 0, 24}, // CAM_0x2A4
{0x51, 0, 32}, // ADRV_0x51
{0x730, 1, 8}, // tester present for ADAS ECU disable
{0x12A, 1, 16}, // LFA
{0x160, 1, 16}, // ADRV_0x160
{0x1E0, 1, 16}, // LFAHDA_CLUSTER
{0x1A0, 1, 32}, // CRUISE_INFO
{0x1EA, 1, 32}, // ADRV_0x1ea
{0x200, 1, 8}, // ADRV_0x200
{0x345, 1, 8}, // ADRV_0x345
{0x1DA, 1, 32}, // ADRV_0x1da
};
const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = {
{0x12A, 0, 16}, // LFA
{0x1A0, 0, 32}, // CRUISE_INFO
{0x1CF, 2, 8}, // CRUISE_BUTTON
{0x1E0, 0, 16}, // LFAHDA_CLUSTER
};
// *** Addresses checked in rx hook ***
// EV, ICE, HYBRID: ACCELERATOR (0x35), ACCELERATOR_BRAKE_ALT (0x100), ACCELERATOR_ALT (0x105)
#define HYUNDAI_CANFD_COMMON_RX_CHECKS(pt_bus) \
{.msg = {{0x35, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \
{0x100, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \
{0x105, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}}}, \
{.msg = {{0x175, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \
{.msg = {{0xa0, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \
{.msg = {{0xea, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \
#define HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(pt_bus) \
{.msg = {{0x1cf, (pt_bus), 8, .check_checksum = false, .max_counter = 0xfU, .frequency = 50U}, { 0 }, { 0 }}}, \
#define HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(pt_bus) \
{.msg = {{0x1aa, (pt_bus), 16, .check_checksum = false, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \
// SCC_CONTROL (from ADAS unit or camera)
#define HYUNDAI_CANFD_SCC_ADDR_CHECK(scc_bus) \
{.msg = {{0x1a0, (scc_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \
// *** Non-HDA2 checks ***
// Camera sends SCC messages on HDA1.
// Both button messages exist on some platforms, so we ensure we track the correct one using flag
RxCheck hyundai_canfd_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0)
HYUNDAI_CANFD_SCC_ADDR_CHECK(2)
};
RxCheck hyundai_canfd_alt_buttons_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0)
HYUNDAI_CANFD_SCC_ADDR_CHECK(2)
};
// Longitudinal checks for HDA1
RxCheck hyundai_canfd_long_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0)
};
RxCheck hyundai_canfd_long_alt_buttons_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0)
};
// Radar sends SCC messages on these cars instead of camera
RxCheck hyundai_canfd_radar_scc_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0)
HYUNDAI_CANFD_SCC_ADDR_CHECK(0)
};
RxCheck hyundai_canfd_radar_scc_alt_buttons_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(0)
HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0)
HYUNDAI_CANFD_SCC_ADDR_CHECK(0)
};
// *** HDA2 checks ***
// E-CAN is on bus 1, ADAS unit sends SCC messages on HDA2.
// Does not use the alt buttons message
RxCheck hyundai_canfd_hda2_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(1)
HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1)
HYUNDAI_CANFD_SCC_ADDR_CHECK(1)
};
RxCheck hyundai_canfd_hda2_long_rx_checks[] = {
HYUNDAI_CANFD_COMMON_RX_CHECKS(1)
HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1)
};
const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32;
const int HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING = 128;
bool hyundai_canfd_alt_buttons = false;
bool hyundai_canfd_hda2_alt_steering = false;
int hyundai_canfd_hda2_get_lkas_addr(void) {
return hyundai_canfd_hda2_alt_steering ? 0x110 : 0x50;
}
static uint8_t hyundai_canfd_get_counter(const CANPacket_t *to_push) {
uint8_t ret = 0;
if (GET_LEN(to_push) == 8U) {
ret = GET_BYTE(to_push, 1) >> 4;
} else {
ret = GET_BYTE(to_push, 2);
}
return ret;
}
static uint32_t hyundai_canfd_get_checksum(const CANPacket_t *to_push) {
uint32_t chksum = GET_BYTE(to_push, 0) | (GET_BYTE(to_push, 1) << 8);
return chksum;
}
static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
const int pt_bus = hyundai_canfd_hda2 ? 1 : 0;
const int scc_bus = hyundai_camera_scc ? 2 : pt_bus;
if (bus == pt_bus) {
// driver torque
if (addr == 0xea) {
int torque_driver_new = ((GET_BYTE(to_push, 11) & 0x1fU) << 8U) | GET_BYTE(to_push, 10);
torque_driver_new -= 4095;
update_sample(&torque_driver, torque_driver_new);
}
// cruise buttons
const int button_addr = hyundai_canfd_alt_buttons ? 0x1aa : 0x1cf;
if (addr == button_addr) {
bool main_button = false;
int cruise_button = 0;
if (addr == 0x1cf) {
cruise_button = GET_BYTE(to_push, 2) & 0x7U;
main_button = GET_BIT(to_push, 19U);
} else {
cruise_button = (GET_BYTE(to_push, 4) >> 4) & 0x7U;
main_button = GET_BIT(to_push, 34U);
}
hyundai_common_cruise_buttons_check(cruise_button, main_button);
}
// gas press, different for EV, hybrid, and ICE models
if ((addr == 0x35) && hyundai_ev_gas_signal) {
gas_pressed = GET_BYTE(to_push, 5) != 0U;
} else if ((addr == 0x105) && hyundai_hybrid_gas_signal) {
gas_pressed = GET_BIT(to_push, 103U) || (GET_BYTE(to_push, 13) != 0U) || GET_BIT(to_push, 112U);
} else if ((addr == 0x100) && !hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) {
gas_pressed = GET_BIT(to_push, 176U);
} else {
}
// brake press
if (addr == 0x175) {
brake_pressed = GET_BIT(to_push, 81U);
}
// vehicle moving
if (addr == 0xa0) {
uint32_t front_left_speed = GET_BYTES(to_push, 8, 2);
uint32_t rear_right_speed = GET_BYTES(to_push, 14, 2);
vehicle_moving = (front_left_speed > HYUNDAI_STANDSTILL_THRSLD) || (rear_right_speed > HYUNDAI_STANDSTILL_THRSLD);
}
}
if (bus == scc_bus) {
// cruise state
if ((addr == 0x1a0) && !hyundai_longitudinal) {
// 1=enabled, 2=driver override
int cruise_status = ((GET_BYTE(to_push, 8) >> 4) & 0x7U);
bool cruise_engaged = (cruise_status == 1) || (cruise_status == 2);
hyundai_common_cruise_state_check(cruise_engaged);
}
}
const int steer_addr = hyundai_canfd_hda2 ? hyundai_canfd_hda2_get_lkas_addr() : 0x12a;
bool stock_ecu_detected = (addr == steer_addr) && (bus == 0);
if (hyundai_longitudinal) {
// on HDA2, ensure ADRV ECU is still knocked out
// on others, ensure accel msg is blocked from camera
const int stock_scc_bus = hyundai_canfd_hda2 ? 1 : 0;
stock_ecu_detected = stock_ecu_detected || ((addr == 0x1a0) && (bus == stock_scc_bus));
}
generic_rx_checks(stock_ecu_detected);
}
static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
// steering
const int steer_addr = (hyundai_canfd_hda2 && !hyundai_longitudinal) ? hyundai_canfd_hda2_get_lkas_addr() : 0x12a;
if (addr == steer_addr) {
int desired_torque = (((GET_BYTE(to_send, 6) & 0xFU) << 7U) | (GET_BYTE(to_send, 5) >> 1U)) - 1024U;
bool steer_req = GET_BIT(to_send, 52U);
if (steer_torque_cmd_checks(desired_torque, steer_req, HYUNDAI_CANFD_STEERING_LIMITS)) {
tx = false;
}
}
// cruise buttons check
if (addr == 0x1cf) {
int button = GET_BYTE(to_send, 2) & 0x7U;
bool is_cancel = (button == HYUNDAI_BTN_CANCEL);
bool is_resume = (button == HYUNDAI_BTN_RESUME);
bool allowed = (is_cancel && cruise_engaged_prev) || (is_resume && controls_allowed);
if (!allowed) {
tx = false;
}
}
// UDS: only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address
if ((addr == 0x730) && hyundai_canfd_hda2) {
if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) {
tx = false;
}
}
// ACCEL: safety check
if (addr == 0x1a0) {
int desired_accel_raw = (((GET_BYTE(to_send, 17) & 0x7U) << 8) | GET_BYTE(to_send, 16)) - 1023U;
int desired_accel_val = ((GET_BYTE(to_send, 18) << 4) | (GET_BYTE(to_send, 17) >> 4)) - 1023U;
bool violation = false;
if (hyundai_longitudinal) {
violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS);
violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS);
} else {
// only used to cancel on here
if ((desired_accel_raw != 0) || (desired_accel_val != 0)) {
violation = true;
}
}
if (violation) {
tx = false;
}
}
return tx;
}
static int hyundai_canfd_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == 0) {
bus_fwd = 2;
}
if (bus_num == 2) {
// LKAS for HDA2, LFA for HDA1
int hda2_lfa_block_addr = hyundai_canfd_hda2_alt_steering ? 0x362 : 0x2a4;
bool is_lkas_msg = ((addr == hyundai_canfd_hda2_get_lkas_addr()) || (addr == hda2_lfa_block_addr)) && hyundai_canfd_hda2;
bool is_lfa_msg = ((addr == 0x12a) && !hyundai_canfd_hda2);
// HUD icons
bool is_lfahda_msg = ((addr == 0x1e0) && !hyundai_canfd_hda2);
// CRUISE_INFO for non-HDA2, we send our own longitudinal commands
bool is_scc_msg = ((addr == 0x1a0) && hyundai_longitudinal && !hyundai_canfd_hda2);
bool block_msg = is_lkas_msg || is_lfa_msg || is_lfahda_msg || is_scc_msg;
if (!block_msg) {
bus_fwd = 0;
}
}
return bus_fwd;
}
static safety_config hyundai_canfd_init(uint16_t param) {
hyundai_common_init(param);
gen_crc_lookup_table_16(0x1021, hyundai_canfd_crc_lut);
hyundai_canfd_alt_buttons = GET_FLAG(param, HYUNDAI_PARAM_CANFD_ALT_BUTTONS);
hyundai_canfd_hda2_alt_steering = GET_FLAG(param, HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING);
// no long for radar-SCC HDA1 yet
if (!hyundai_canfd_hda2 && !hyundai_camera_scc) {
hyundai_longitudinal = false;
}
safety_config ret;
if (hyundai_longitudinal) {
if (hyundai_canfd_hda2) {
ret = BUILD_SAFETY_CFG(hyundai_canfd_hda2_long_rx_checks, HYUNDAI_CANFD_HDA2_LONG_TX_MSGS);
} else {
ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_long_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \
BUILD_SAFETY_CFG(hyundai_canfd_long_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS);
}
} else {
if (hyundai_canfd_hda2) {
ret = hyundai_canfd_hda2_alt_steering ? BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS) : \
BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_TX_MSGS);
} else if (!hyundai_camera_scc) {
ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \
BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS);
} else {
ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \
BUILD_SAFETY_CFG(hyundai_canfd_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS);
}
}
return ret;
}
const safety_hooks hyundai_canfd_hooks = {
.init = hyundai_canfd_init,
.rx = hyundai_canfd_rx_hook,
.tx = hyundai_canfd_tx_hook,
.fwd = hyundai_canfd_fwd_hook,
.get_counter = hyundai_canfd_get_counter,
.get_checksum = hyundai_canfd_get_checksum,
.compute_checksum = hyundai_common_canfd_compute_checksum,
};

View File

@@ -0,0 +1,118 @@
#ifndef SAFETY_HYUNDAI_COMMON_H
#define SAFETY_HYUNDAI_COMMON_H
const int HYUNDAI_PARAM_EV_GAS = 1;
const int HYUNDAI_PARAM_HYBRID_GAS = 2;
const int HYUNDAI_PARAM_LONGITUDINAL = 4;
const int HYUNDAI_PARAM_CAMERA_SCC = 8;
const int HYUNDAI_PARAM_CANFD_HDA2 = 16;
const int HYUNDAI_PARAM_ALT_LIMITS = 64; // TODO: shift this down with the rest of the common flags
const uint8_t HYUNDAI_PREV_BUTTON_SAMPLES = 8; // roughly 160 ms
const uint32_t HYUNDAI_STANDSTILL_THRSLD = 12; // 0.375 kph
enum {
HYUNDAI_BTN_NONE = 0,
HYUNDAI_BTN_RESUME = 1,
HYUNDAI_BTN_SET = 2,
HYUNDAI_BTN_CANCEL = 4,
};
// common state
bool hyundai_ev_gas_signal = false;
bool hyundai_hybrid_gas_signal = false;
bool hyundai_longitudinal = false;
bool hyundai_camera_scc = false;
bool hyundai_canfd_hda2 = false;
bool hyundai_alt_limits = false;
uint8_t hyundai_last_button_interaction; // button messages since the user pressed an enable button
uint16_t hyundai_canfd_crc_lut[256];
void hyundai_common_init(uint16_t param) {
hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS);
hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS);
hyundai_camera_scc = GET_FLAG(param, HYUNDAI_PARAM_CAMERA_SCC);
hyundai_canfd_hda2 = GET_FLAG(param, HYUNDAI_PARAM_CANFD_HDA2);
hyundai_alt_limits = GET_FLAG(param, HYUNDAI_PARAM_ALT_LIMITS);
hyundai_last_button_interaction = HYUNDAI_PREV_BUTTON_SAMPLES;
#ifdef ALLOW_DEBUG
hyundai_longitudinal = GET_FLAG(param, HYUNDAI_PARAM_LONGITUDINAL);
#else
hyundai_longitudinal = false;
#endif
}
void hyundai_common_cruise_state_check(const bool cruise_engaged) {
// some newer HKG models can re-enable after spamming cancel button,
// so keep track of user button presses to deny engagement if no interaction
// enter controls on rising edge of ACC and recent user button press, exit controls when ACC off
if (!hyundai_longitudinal) {
if (cruise_engaged && !cruise_engaged_prev && (hyundai_last_button_interaction < HYUNDAI_PREV_BUTTON_SAMPLES)) {
controls_allowed = true;
}
if (!cruise_engaged) {
controls_allowed = false;
}
cruise_engaged_prev = cruise_engaged;
}
}
void hyundai_common_cruise_buttons_check(const int cruise_button, const bool main_button) {
if (main_button && main_button != cruise_main_prev) {
acc_main_on = !acc_main_on;
}
cruise_main_prev = main_button;
if ((cruise_button == HYUNDAI_BTN_RESUME) || (cruise_button == HYUNDAI_BTN_SET) || (cruise_button == HYUNDAI_BTN_CANCEL) || main_button) {
hyundai_last_button_interaction = 0U;
} else {
hyundai_last_button_interaction = MIN(hyundai_last_button_interaction + 1U, HYUNDAI_PREV_BUTTON_SAMPLES);
}
if (hyundai_longitudinal) {
// enter controls on falling edge of resume or set
bool set = (cruise_button != HYUNDAI_BTN_SET) && (cruise_button_prev == HYUNDAI_BTN_SET);
bool res = (cruise_button != HYUNDAI_BTN_RESUME) && (cruise_button_prev == HYUNDAI_BTN_RESUME);
if (set || res) {
controls_allowed = true;
}
// exit controls on cancel press
if (cruise_button == HYUNDAI_BTN_CANCEL) {
controls_allowed = false;
}
cruise_button_prev = cruise_button;
}
}
uint32_t hyundai_common_canfd_compute_checksum(const CANPacket_t *to_push) {
int len = GET_LEN(to_push);
uint32_t address = GET_ADDR(to_push);
uint16_t crc = 0;
for (int i = 2; i < len; i++) {
crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ GET_BYTE(to_push, i)];
}
// Add address to crc
crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ ((address >> 0U) & 0xFFU)];
crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ ((address >> 8U) & 0xFFU)];
if (len == 24) {
crc ^= 0x819dU;
} else if (len == 32) {
crc ^= 0x9f5bU;
} else {
}
return crc;
}
#endif

View File

@@ -0,0 +1,130 @@
// CAN msgs we care about
#define MAZDA_LKAS 0x243
#define MAZDA_LKAS_HUD 0x440
#define MAZDA_CRZ_CTRL 0x21c
#define MAZDA_CRZ_BTNS 0x09d
#define MAZDA_STEER_TORQUE 0x240
#define MAZDA_ENGINE_DATA 0x202
#define MAZDA_PEDALS 0x165
// CAN bus numbers
#define MAZDA_MAIN 0
#define MAZDA_AUX 1
#define MAZDA_CAM 2
const SteeringLimits MAZDA_STEERING_LIMITS = {
.max_steer = 800,
.max_rate_up = 10,
.max_rate_down = 25,
.max_rt_delta = 300,
.max_rt_interval = 250000,
.driver_torque_factor = 1,
.driver_torque_allowance = 15,
.type = TorqueDriverLimited,
};
const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}, {MAZDA_LKAS_HUD, 0, 8}};
RxCheck mazda_rx_checks[] = {
{.msg = {{MAZDA_CRZ_CTRL, 0, 8, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MAZDA_CRZ_BTNS, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{MAZDA_STEER_TORQUE, 0, 8, .frequency = 83U}, { 0 }, { 0 }}},
{.msg = {{MAZDA_ENGINE_DATA, 0, 8, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MAZDA_PEDALS, 0, 8, .frequency = 50U}, { 0 }, { 0 }}},
};
// track msgs coming from OP so that we know what CAM msgs to drop and what to forward
static void mazda_rx_hook(const CANPacket_t *to_push) {
if ((int)GET_BUS(to_push) == MAZDA_MAIN) {
int addr = GET_ADDR(to_push);
if (addr == MAZDA_ENGINE_DATA) {
// sample speed: scale by 0.01 to get kph
int speed = (GET_BYTE(to_push, 2) << 8) | GET_BYTE(to_push, 3);
vehicle_moving = speed > 10; // moving when speed > 0.1 kph
}
if (addr == MAZDA_STEER_TORQUE) {
int torque_driver_new = GET_BYTE(to_push, 0) - 127U;
// update array of samples
update_sample(&torque_driver, torque_driver_new);
}
// enter controls on rising edge of ACC, exit controls on ACC off
if (addr == MAZDA_CRZ_CTRL) {
acc_main_on = GET_BIT(to_push, 17U);
bool cruise_engaged = GET_BYTE(to_push, 0) & 0x8U;
pcm_cruise_check(cruise_engaged);
}
if (addr == MAZDA_ENGINE_DATA) {
gas_pressed = (GET_BYTE(to_push, 4) || (GET_BYTE(to_push, 5) & 0xF0U));
}
if (addr == MAZDA_PEDALS) {
brake_pressed = (GET_BYTE(to_push, 0) & 0x10U);
}
generic_rx_checks((addr == MAZDA_LKAS));
}
}
static bool mazda_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
int bus = GET_BUS(to_send);
// Check if msg is sent on the main BUS
if (bus == MAZDA_MAIN) {
// steer cmd checks
if (addr == MAZDA_LKAS) {
int desired_torque = (((GET_BYTE(to_send, 0) & 0x0FU) << 8) | GET_BYTE(to_send, 1)) - 2048U;
if (steer_torque_cmd_checks(desired_torque, -1, MAZDA_STEERING_LIMITS)) {
tx = false;
}
}
// cruise buttons check
if (addr == MAZDA_CRZ_BTNS) {
// allow resume spamming while controls allowed, but
// only allow cancel while contrls not allowed
bool cancel_cmd = (GET_BYTE(to_send, 0) == 0x1U);
if (!controls_allowed && !cancel_cmd) {
tx = false;
}
}
}
return tx;
}
static int mazda_fwd_hook(int bus, int addr) {
int bus_fwd = -1;
if (bus == MAZDA_MAIN) {
bus_fwd = MAZDA_CAM;
} else if (bus == MAZDA_CAM) {
bool block = (addr == MAZDA_LKAS) || (addr == MAZDA_LKAS_HUD);
if (!block) {
bus_fwd = MAZDA_MAIN;
}
} else {
// don't fwd
}
return bus_fwd;
}
static safety_config mazda_init(uint16_t param) {
UNUSED(param);
return BUILD_SAFETY_CFG(mazda_rx_checks, MAZDA_TX_MSGS);
}
const safety_hooks mazda_hooks = {
.init = mazda_init,
.rx = mazda_rx_hook,
.tx = mazda_tx_hook,
.fwd = mazda_fwd_hook,
};

View File

@@ -0,0 +1,166 @@
const SteeringLimits NISSAN_STEERING_LIMITS = {
.angle_deg_to_can = 100,
.angle_rate_up_lookup = {
{0., 5., 15.},
{5., .8, .15}
},
.angle_rate_down_lookup = {
{0., 5., 15.},
{5., 3.5, .4}
},
};
const CanMsg NISSAN_TX_MSGS[] = {
{0x169, 0, 8}, // LKAS
{0x2b1, 0, 8}, // PROPILOT_HUD
{0x4cc, 0, 8}, // PROPILOT_HUD_INFO_MSG
{0x20b, 2, 6}, // CRUISE_THROTTLE (X-Trail)
{0x20b, 1, 6}, // CRUISE_THROTTLE (Altima)
{0x280, 2, 8} // CANCEL_MSG (Leaf)
};
// Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model.
RxCheck nissan_rx_checks[] = {
{.msg = {{0x1b6, 0, 8, .frequency = 100U},
{0x1b6, 1, 8, .frequency = 100U}, { 0 }}}, // PRO_PILOT (100HZ)
{.msg = {{0x2, 0, 5, .frequency = 100U},
{0x2, 1, 5, .frequency = 100U}, { 0 }}}, // STEER_ANGLE_SENSOR
{.msg = {{0x285, 0, 8, .frequency = 50U},
{0x285, 1, 8, .frequency = 50U}, { 0 }}}, // WHEEL_SPEEDS_REAR
{.msg = {{0x30f, 2, 3, .frequency = 10U},
{0x30f, 1, 3, .frequency = 10U}, { 0 }}}, // CRUISE_STATE
{.msg = {{0x15c, 0, 8, .frequency = 50U},
{0x15c, 1, 8, .frequency = 50U},
{0x239, 0, 8, .frequency = 50U}}}, // GAS_PEDAL
{.msg = {{0x454, 0, 8, .frequency = 10U},
{0x454, 1, 8, .frequency = 10U},
{0x1cc, 0, 4, .frequency = 100U}}}, // DOORS_LIGHTS / BRAKE
};
// EPS Location. false = V-CAN, true = C-CAN
const int NISSAN_PARAM_ALT_EPS_BUS = 1;
bool nissan_alt_eps = false;
static void nissan_rx_hook(const CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
if (bus == (nissan_alt_eps ? 1 : 0)) {
if (addr == 0x2) {
// Current steering angle
// Factor -0.1, little endian
int angle_meas_new = (GET_BYTES(to_push, 0, 4) & 0xFFFFU);
// Multiply by -10 to match scale of LKAS angle
angle_meas_new = to_signed(angle_meas_new, 16) * -10;
// update array of samples
update_sample(&angle_meas, angle_meas_new);
}
if (addr == 0x285) {
// Get current speed and standstill
uint16_t right_rear = (GET_BYTE(to_push, 0) << 8) | (GET_BYTE(to_push, 1));
uint16_t left_rear = (GET_BYTE(to_push, 2) << 8) | (GET_BYTE(to_push, 3));
vehicle_moving = (right_rear | left_rear) != 0U;
UPDATE_VEHICLE_SPEED((right_rear + left_rear) / 2.0 * 0.005 / 3.6);
}
if (addr == 0x1b6) {
acc_main_on = GET_BIT(to_push, 36U);
}
// X-Trail 0x15c, Leaf 0x239
if ((addr == 0x15c) || (addr == 0x239)) {
if (addr == 0x15c){
gas_pressed = ((GET_BYTE(to_push, 5) << 2) | ((GET_BYTE(to_push, 6) >> 6) & 0x3U)) > 3U;
} else {
acc_main_on = GET_BIT(to_push, 17U);
gas_pressed = GET_BYTE(to_push, 0) > 3U;
}
}
// X-trail 0x454, Leaf 0x239
if ((addr == 0x454) || (addr == 0x239)) {
if (addr == 0x454){
brake_pressed = (GET_BYTE(to_push, 2) & 0x80U) != 0U;
} else {
brake_pressed = ((GET_BYTE(to_push, 4) >> 5) & 1U) != 0U;
}
}
}
// Handle cruise enabled
if ((addr == 0x30f) && (bus == (nissan_alt_eps ? 1 : 2))) {
bool cruise_engaged = (GET_BYTE(to_push, 0) >> 3) & 1U;
pcm_cruise_check(cruise_engaged);
}
generic_rx_checks((addr == 0x169) && (bus == 0));
}
static bool nissan_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
bool violation = false;
// steer cmd checks
if (addr == 0x169) {
int desired_angle = ((GET_BYTE(to_send, 0) << 10) | (GET_BYTE(to_send, 1) << 2) | ((GET_BYTE(to_send, 2) >> 6) & 0x3U));
bool lka_active = (GET_BYTE(to_send, 6) >> 4) & 1U;
// Factor is -0.01, offset is 1310. Flip to correct sign, but keep units in CAN scale
desired_angle = -desired_angle + (1310.0f * NISSAN_STEERING_LIMITS.angle_deg_to_can);
if (steer_angle_cmd_checks(desired_angle, lka_active, NISSAN_STEERING_LIMITS)) {
violation = true;
}
}
// acc button check, only allow cancel button to be sent
if (addr == 0x20b) {
// Violation of any button other than cancel is pressed
violation |= ((GET_BYTE(to_send, 1) & 0x3dU) > 0U);
}
if (violation) {
tx = false;
}
return tx;
}
static int nissan_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == 0) {
bool block_msg = (addr == 0x280); // CANCEL_MSG
if (!block_msg) {
bus_fwd = 2; // ADAS
}
}
if (bus_num == 2) {
// 0x169 is LKAS, 0x2b1 LKAS_HUD, 0x4cc LKAS_HUD_INFO_MSG
bool block_msg = ((addr == 0x169) || (addr == 0x2b1) || (addr == 0x4cc));
if (!block_msg) {
bus_fwd = 0; // V-CAN
}
}
return bus_fwd;
}
static safety_config nissan_init(uint16_t param) {
nissan_alt_eps = GET_FLAG(param, NISSAN_PARAM_ALT_EPS_BUS);
return BUILD_SAFETY_CFG(nissan_rx_checks, NISSAN_TX_MSGS);
}
const safety_hooks nissan_hooks = {
.init = nissan_init,
.rx = nissan_rx_hook,
.tx = nissan_tx_hook,
.fwd = nissan_fwd_hook,
};

View File

@@ -0,0 +1,295 @@
#define SUBARU_STEERING_LIMITS_GENERATOR(steer_max, rate_up, rate_down) \
{ \
.max_steer = (steer_max), \
.max_rt_delta = 940, \
.max_rt_interval = 250000, \
.max_rate_up = (rate_up), \
.max_rate_down = (rate_down), \
.driver_torque_factor = 50, \
.driver_torque_allowance = 60, \
.type = TorqueDriverLimited, \
/* the EPS will temporary fault if the steering rate is too high, so we cut the \
the steering torque every 7 frames for 1 frame if the steering rate is high */ \
.min_valid_request_frames = 7, \
.max_invalid_request_frames = 1, \
.min_valid_request_rt_interval = 144000, /* 10% tolerance */ \
.has_steer_req_tolerance = true, \
}
const SteeringLimits SUBARU_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(3071, 50, 70);
const SteeringLimits SUBARU_GEN2_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(1000, 40, 40);
const LongitudinalLimits SUBARU_LONG_LIMITS = {
.min_gas = 808, // appears to be engine braking
.max_gas = 3400, // approx 2 m/s^2 when maxing cruise_rpm and cruise_throttle
.inactive_gas = 1818, // this is zero acceleration
.max_brake = 600, // approx -3.5 m/s^2
.min_transmission_rpm = 0,
.max_transmission_rpm = 2400,
};
#define MSG_SUBARU_Brake_Status 0x13c
#define MSG_SUBARU_CruiseControl 0x240
#define MSG_SUBARU_Throttle 0x40
#define MSG_SUBARU_Steering_Torque 0x119
#define MSG_SUBARU_Wheel_Speeds 0x13a
#define MSG_SUBARU_ES_LKAS 0x122
#define MSG_SUBARU_ES_LKAS_ANGLE 0x124
#define MSG_SUBARU_ES_Brake 0x220
#define MSG_SUBARU_ES_Distance 0x221
#define MSG_SUBARU_ES_Status 0x222
#define MSG_SUBARU_ES_DashStatus 0x321
#define MSG_SUBARU_ES_LKAS_State 0x322
#define MSG_SUBARU_ES_Infotainment 0x323
#define MSG_SUBARU_ES_UDS_Request 0x787
#define MSG_SUBARU_ES_HighBeamAssist 0x121
#define MSG_SUBARU_ES_STATIC_1 0x22a
#define MSG_SUBARU_ES_STATIC_2 0x325
#define SUBARU_MAIN_BUS 0
#define SUBARU_ALT_BUS 1
#define SUBARU_CAM_BUS 2
#define SUBARU_COMMON_TX_MSGS(alt_bus, lkas_msg) \
{lkas_msg, SUBARU_MAIN_BUS, 8}, \
{MSG_SUBARU_ES_Distance, alt_bus, 8}, \
{MSG_SUBARU_ES_DashStatus, SUBARU_MAIN_BUS, 8}, \
{MSG_SUBARU_ES_LKAS_State, SUBARU_MAIN_BUS, 8}, \
{MSG_SUBARU_ES_Infotainment, SUBARU_MAIN_BUS, 8}, \
#define SUBARU_COMMON_LONG_TX_MSGS(alt_bus) \
{MSG_SUBARU_ES_Brake, alt_bus, 8}, \
{MSG_SUBARU_ES_Status, alt_bus, 8}, \
#define SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() \
{MSG_SUBARU_ES_UDS_Request, SUBARU_CAM_BUS, 8}, \
{MSG_SUBARU_ES_HighBeamAssist, SUBARU_MAIN_BUS, 8}, \
{MSG_SUBARU_ES_STATIC_1, SUBARU_MAIN_BUS, 8}, \
{MSG_SUBARU_ES_STATIC_2, SUBARU_MAIN_BUS, 8}, \
#define SUBARU_COMMON_RX_CHECKS(alt_bus) \
{.msg = {{MSG_SUBARU_Throttle, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, \
{.msg = {{MSG_SUBARU_Steering_Torque, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \
{.msg = {{MSG_SUBARU_Wheel_Speeds, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \
{.msg = {{MSG_SUBARU_Brake_Status, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \
{.msg = {{MSG_SUBARU_CruiseControl, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 20U}, { 0 }, { 0 }}}, \
const CanMsg SUBARU_TX_MSGS[] = {
SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS)
};
const CanMsg SUBARU_LONG_TX_MSGS[] = {
SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS)
SUBARU_COMMON_LONG_TX_MSGS(SUBARU_MAIN_BUS)
};
const CanMsg SUBARU_GEN2_TX_MSGS[] = {
SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS)
};
const CanMsg SUBARU_GEN2_LONG_TX_MSGS[] = {
SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS)
SUBARU_COMMON_LONG_TX_MSGS(SUBARU_ALT_BUS)
SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS()
};
RxCheck subaru_rx_checks[] = {
SUBARU_COMMON_RX_CHECKS(SUBARU_MAIN_BUS)
};
RxCheck subaru_gen2_rx_checks[] = {
SUBARU_COMMON_RX_CHECKS(SUBARU_ALT_BUS)
};
const uint16_t SUBARU_PARAM_GEN2 = 1;
const uint16_t SUBARU_PARAM_LONGITUDINAL = 2;
bool subaru_gen2 = false;
bool subaru_longitudinal = false;
static uint32_t subaru_get_checksum(const CANPacket_t *to_push) {
return (uint8_t)GET_BYTE(to_push, 0);
}
static uint8_t subaru_get_counter(const CANPacket_t *to_push) {
return (uint8_t)(GET_BYTE(to_push, 1) & 0xFU);
}
static uint32_t subaru_compute_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
int len = GET_LEN(to_push);
uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U);
for (int i = 1; i < len; i++) {
checksum += (uint8_t)GET_BYTE(to_push, i);
}
return checksum;
}
static void subaru_rx_hook(const CANPacket_t *to_push) {
const int bus = GET_BUS(to_push);
const int alt_main_bus = subaru_gen2 ? SUBARU_ALT_BUS : SUBARU_MAIN_BUS;
int addr = GET_ADDR(to_push);
if ((addr == MSG_SUBARU_Steering_Torque) && (bus == SUBARU_MAIN_BUS)) {
int torque_driver_new;
torque_driver_new = ((GET_BYTES(to_push, 0, 4) >> 16) & 0x7FFU);
torque_driver_new = -1 * to_signed(torque_driver_new, 11);
update_sample(&torque_driver, torque_driver_new);
int angle_meas_new = (GET_BYTES(to_push, 4, 2) & 0xFFFFU);
// convert Steering_Torque -> Steering_Angle to centidegrees, to match the ES_LKAS_ANGLE angle request units
angle_meas_new = ROUND(to_signed(angle_meas_new, 16) * -2.17);
update_sample(&angle_meas, angle_meas_new);
}
// enter controls on rising edge of ACC, exit controls on ACC off
if ((addr == MSG_SUBARU_CruiseControl) && (bus == alt_main_bus)) {
acc_main_on = GET_BIT(to_push, 40U);
bool cruise_engaged = GET_BIT(to_push, 41U);
pcm_cruise_check(cruise_engaged);
}
// update vehicle moving with any non-zero wheel speed
if ((addr == MSG_SUBARU_Wheel_Speeds) && (bus == alt_main_bus)) {
uint32_t fr = (GET_BYTES(to_push, 1, 3) >> 4) & 0x1FFFU;
uint32_t rr = (GET_BYTES(to_push, 3, 3) >> 1) & 0x1FFFU;
uint32_t rl = (GET_BYTES(to_push, 4, 3) >> 6) & 0x1FFFU;
uint32_t fl = (GET_BYTES(to_push, 6, 2) >> 3) & 0x1FFFU;
vehicle_moving = (fr > 0U) || (rr > 0U) || (rl > 0U) || (fl > 0U);
UPDATE_VEHICLE_SPEED((fr + rr + rl + fl) / 4U * 0.057);
}
if ((addr == MSG_SUBARU_Brake_Status) && (bus == alt_main_bus)) {
brake_pressed = GET_BIT(to_push, 62U);
}
if ((addr == MSG_SUBARU_Throttle) && (bus == SUBARU_MAIN_BUS)) {
gas_pressed = GET_BYTE(to_push, 4) != 0U;
}
generic_rx_checks((addr == MSG_SUBARU_ES_LKAS) && (bus == SUBARU_MAIN_BUS));
}
static bool subaru_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
bool violation = false;
// steer cmd checks
if (addr == MSG_SUBARU_ES_LKAS) {
int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x1FFFU);
desired_torque = -1 * to_signed(desired_torque, 13);
bool steer_req = GET_BIT(to_send, 29U);
const SteeringLimits limits = subaru_gen2 ? SUBARU_GEN2_STEERING_LIMITS : SUBARU_STEERING_LIMITS;
violation |= steer_torque_cmd_checks(desired_torque, steer_req, limits);
}
// check es_brake brake_pressure limits
if (addr == MSG_SUBARU_ES_Brake) {
int es_brake_pressure = GET_BYTES(to_send, 2, 2);
violation |= longitudinal_brake_checks(es_brake_pressure, SUBARU_LONG_LIMITS);
}
// check es_distance cruise_throttle limits
if (addr == MSG_SUBARU_ES_Distance) {
int cruise_throttle = (GET_BYTES(to_send, 2, 2) & 0x1FFFU);
bool cruise_cancel = GET_BIT(to_send, 56U);
if (subaru_longitudinal) {
violation |= longitudinal_gas_checks(cruise_throttle, SUBARU_LONG_LIMITS);
} else {
// If openpilot is not controlling long, only allow ES_Distance for cruise cancel requests,
// (when Cruise_Cancel is true, and Cruise_Throttle is inactive)
violation |= (cruise_throttle != SUBARU_LONG_LIMITS.inactive_gas);
violation |= (!cruise_cancel);
}
}
// check es_status transmission_rpm limits
if (addr == MSG_SUBARU_ES_Status) {
int transmission_rpm = (GET_BYTES(to_send, 2, 2) & 0x1FFFU);
violation |= longitudinal_transmission_rpm_checks(transmission_rpm, SUBARU_LONG_LIMITS);
}
if (addr == MSG_SUBARU_ES_UDS_Request) {
// tester present ('\x02\x3E\x80\x00\x00\x00\x00\x00') is allowed for gen2 longitudinal to keep eyesight disabled
bool is_tester_present = (GET_BYTES(to_send, 0, 4) == 0x00803E02U) && (GET_BYTES(to_send, 4, 4) == 0x0U);
// reading ES button data by identifier (b'\x03\x22\x11\x30\x00\x00\x00\x00') is also allowed (DID 0x1130)
bool is_button_rdbi = (GET_BYTES(to_send, 0, 4) == 0x30112203U) && (GET_BYTES(to_send, 4, 4) == 0x0U);
violation |= !(is_tester_present || is_button_rdbi);
}
if (violation){
tx = false;
}
return tx;
}
static int subaru_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == SUBARU_MAIN_BUS) {
bus_fwd = SUBARU_CAM_BUS; // to the eyesight camera
}
if (bus_num == SUBARU_CAM_BUS) {
// Global platform
bool block_lkas = ((addr == MSG_SUBARU_ES_LKAS) ||
(addr == MSG_SUBARU_ES_DashStatus) ||
(addr == MSG_SUBARU_ES_LKAS_State) ||
(addr == MSG_SUBARU_ES_Infotainment));
bool block_long = ((addr == MSG_SUBARU_ES_Brake) ||
(addr == MSG_SUBARU_ES_Distance) ||
(addr == MSG_SUBARU_ES_Status));
bool block_msg = block_lkas || (subaru_longitudinal && block_long);
if (!block_msg) {
bus_fwd = SUBARU_MAIN_BUS; // Main CAN
}
}
return bus_fwd;
}
static safety_config subaru_init(uint16_t param) {
subaru_gen2 = GET_FLAG(param, SUBARU_PARAM_GEN2);
#ifdef ALLOW_DEBUG
subaru_longitudinal = GET_FLAG(param, SUBARU_PARAM_LONGITUDINAL);
#endif
safety_config ret;
if (subaru_gen2) {
ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_TX_MSGS);
} else {
ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_TX_MSGS);
}
return ret;
}
const safety_hooks subaru_hooks = {
.init = subaru_init,
.rx = subaru_rx_hook,
.tx = subaru_tx_hook,
.fwd = subaru_fwd_hook,
.get_counter = subaru_get_counter,
.get_checksum = subaru_get_checksum,
.compute_checksum = subaru_compute_checksum,
};

View File

@@ -0,0 +1,127 @@
const SteeringLimits SUBARU_PG_STEERING_LIMITS = {
.max_steer = 2047,
.max_rt_delta = 940,
.max_rt_interval = 250000,
.max_rate_up = 50,
.max_rate_down = 70,
.driver_torque_factor = 10,
.driver_torque_allowance = 75,
.type = TorqueDriverLimited,
};
// Preglobal platform
// 0x161 is ES_CruiseThrottle
// 0x164 is ES_LKAS
#define MSG_SUBARU_PG_CruiseControl 0x144
#define MSG_SUBARU_PG_Throttle 0x140
#define MSG_SUBARU_PG_Wheel_Speeds 0xD4
#define MSG_SUBARU_PG_Brake_Pedal 0xD1
#define MSG_SUBARU_PG_ES_LKAS 0x164
#define MSG_SUBARU_PG_ES_Distance 0x161
#define MSG_SUBARU_PG_Steering_Torque 0x371
#define SUBARU_PG_MAIN_BUS 0
#define SUBARU_PG_CAM_BUS 2
const CanMsg SUBARU_PG_TX_MSGS[] = {
{MSG_SUBARU_PG_ES_Distance, SUBARU_PG_MAIN_BUS, 8},
{MSG_SUBARU_PG_ES_LKAS, SUBARU_PG_MAIN_BUS, 8}
};
// TODO: do checksum and counter checks after adding the signals to the outback dbc file
RxCheck subaru_preglobal_rx_checks[] = {
{.msg = {{MSG_SUBARU_PG_Throttle, SUBARU_PG_MAIN_BUS, 8, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_SUBARU_PG_Steering_Torque, SUBARU_PG_MAIN_BUS, 8, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_SUBARU_PG_CruiseControl, SUBARU_PG_MAIN_BUS, 8, .frequency = 20U}, { 0 }, { 0 }}},
};
const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1;
bool subaru_pg_reversed_driver_torque = false;
static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) {
const int bus = GET_BUS(to_push);
if (bus == SUBARU_PG_MAIN_BUS) {
int addr = GET_ADDR(to_push);
if (addr == MSG_SUBARU_PG_Steering_Torque) {
int torque_driver_new;
torque_driver_new = (GET_BYTE(to_push, 3) >> 5) + (GET_BYTE(to_push, 4) << 3);
torque_driver_new = to_signed(torque_driver_new, 11);
torque_driver_new = subaru_pg_reversed_driver_torque ? -torque_driver_new : torque_driver_new;
update_sample(&torque_driver, torque_driver_new);
}
// enter controls on rising edge of ACC, exit controls on ACC off
if (addr == MSG_SUBARU_PG_CruiseControl) {
acc_main_on = GET_BIT(to_push, 48U);
bool cruise_engaged = GET_BIT(to_push, 49U);
pcm_cruise_check(cruise_engaged);
}
// update vehicle moving with any non-zero wheel speed
if (addr == MSG_SUBARU_PG_Wheel_Speeds) {
vehicle_moving = ((GET_BYTES(to_push, 0, 4) >> 12) != 0U) || (GET_BYTES(to_push, 4, 4) != 0U);
}
if (addr == MSG_SUBARU_PG_Brake_Pedal) {
brake_pressed = ((GET_BYTES(to_push, 0, 4) >> 16) & 0xFFU) > 0U;
}
if (addr == MSG_SUBARU_PG_Throttle) {
gas_pressed = GET_BYTE(to_push, 0) != 0U;
}
generic_rx_checks((addr == MSG_SUBARU_PG_ES_LKAS));
}
}
static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
// steer cmd checks
if (addr == MSG_SUBARU_PG_ES_LKAS) {
int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 8) & 0x1FFFU);
desired_torque = -1 * to_signed(desired_torque, 13);
bool steer_req = GET_BIT(to_send, 24U);
if (steer_torque_cmd_checks(desired_torque, steer_req, SUBARU_PG_STEERING_LIMITS)) {
tx = false;
}
}
return tx;
}
static int subaru_preglobal_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == SUBARU_PG_MAIN_BUS) {
bus_fwd = SUBARU_PG_CAM_BUS; // Camera CAN
}
if (bus_num == SUBARU_PG_CAM_BUS) {
bool block_msg = ((addr == MSG_SUBARU_PG_ES_Distance) || (addr == MSG_SUBARU_PG_ES_LKAS));
if (!block_msg) {
bus_fwd = SUBARU_PG_MAIN_BUS; // Main CAN
}
}
return bus_fwd;
}
static safety_config subaru_preglobal_init(uint16_t param) {
subaru_pg_reversed_driver_torque = GET_FLAG(param, SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE);
return BUILD_SAFETY_CFG(subaru_preglobal_rx_checks, SUBARU_PG_TX_MSGS);
}
const safety_hooks subaru_preglobal_hooks = {
.init = subaru_preglobal_init,
.rx = subaru_preglobal_rx_hook,
.tx = subaru_preglobal_tx_hook,
.fwd = subaru_preglobal_fwd_hook,
};

View File

@@ -0,0 +1,249 @@
const SteeringLimits TESLA_STEERING_LIMITS = {
.angle_deg_to_can = 10,
.angle_rate_up_lookup = {
{0., 5., 15.},
{10., 1.6, .3}
},
.angle_rate_down_lookup = {
{0., 5., 15.},
{10., 7.0, .8}
},
};
const LongitudinalLimits TESLA_LONG_LIMITS = {
.max_accel = 425, // 2. m/s^2
.min_accel = 287, // -3.52 m/s^2 // TODO: limit to -3.48
.inactive_accel = 375, // 0. m/s^2
};
const int TESLA_FLAG_POWERTRAIN = 1;
const int TESLA_FLAG_LONGITUDINAL_CONTROL = 2;
const int TESLA_FLAG_RAVEN = 4;
const CanMsg TESLA_TX_MSGS[] = {
{0x488, 0, 4}, // DAS_steeringControl
{0x45, 0, 8}, // STW_ACTN_RQ
{0x45, 2, 8}, // STW_ACTN_RQ
{0x2b9, 0, 8}, // DAS_control
};
const CanMsg TESLA_PT_TX_MSGS[] = {
{0x2bf, 0, 8}, // DAS_control
};
RxCheck tesla_rx_checks[] = {
{.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control
{.msg = {{0x370, 0, 8, .frequency = 25U}, { 0 }, { 0 }}}, // EPAS_sysStatus
{.msg = {{0x108, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1
{.msg = {{0x118, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2
{.msg = {{0x20a, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage
{.msg = {{0x368, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state
{.msg = {{0x318, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // GTW_carState
};
RxCheck tesla_raven_rx_checks[] = {
{.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control
{.msg = {{0x131, 2, 8, .frequency = 100U}, { 0 }, { 0 }}}, // EPAS3P_sysStatus
{.msg = {{0x108, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1
{.msg = {{0x118, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2
{.msg = {{0x20a, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage
{.msg = {{0x368, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state
{.msg = {{0x318, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // GTW_carState
};
RxCheck tesla_pt_rx_checks[] = {
{.msg = {{0x106, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1
{.msg = {{0x116, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2
{.msg = {{0x1f8, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage
{.msg = {{0x2bf, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control
{.msg = {{0x256, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state
};
bool tesla_longitudinal = false;
bool tesla_powertrain = false; // Are we the second panda intercepting the powertrain bus?
bool tesla_raven = false;
bool tesla_stock_aeb = false;
static void tesla_rx_hook(const CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
if (!tesla_powertrain) {
if((!tesla_raven && (addr == 0x370) && (bus == 0)) || (tesla_raven && (addr == 0x131) && (bus == 2))) {
// Steering angle: (0.1 * val) - 819.2 in deg.
// Store it 1/10 deg to match steering request
int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U;
update_sample(&angle_meas, angle_meas_new);
}
}
if(bus == 0) {
if(addr == (tesla_powertrain ? 0x116 : 0x118)) {
// Vehicle speed: ((0.05 * val) - 25) * MPH_TO_MPS
float speed = (((((GET_BYTE(to_push, 3) & 0x0FU) << 8) | (GET_BYTE(to_push, 2))) * 0.05) - 25) * 0.447;
vehicle_moving = ABS(speed) > 0.1;
UPDATE_VEHICLE_SPEED(speed);
}
if(addr == (tesla_powertrain ? 0x106 : 0x108)) {
// Gas pressed
gas_pressed = (GET_BYTE(to_push, 6) != 0U);
}
if(addr == (tesla_powertrain ? 0x1f8 : 0x20a)) {
// Brake pressed
brake_pressed = (((GET_BYTE(to_push, 0) & 0x0CU) >> 2) != 1U);
}
if(addr == (tesla_powertrain ? 0x256 : 0x368)) {
// Cruise state
int cruise_state = (GET_BYTE(to_push, 1) >> 4);
acc_main_on = (cruise_state == 1) || // STANDBY
(cruise_state == 2) || // ENABLED
(cruise_state == 3) || // STANDSTILL
(cruise_state == 4) || // OVERRIDE
(cruise_state == 6) || // PRE_FAULT
(cruise_state == 7); // PRE_CANCEL
bool cruise_engaged = (cruise_state == 2) || // ENABLED
(cruise_state == 3) || // STANDSTILL
(cruise_state == 4) || // OVERRIDE
(cruise_state == 6) || // PRE_FAULT
(cruise_state == 7); // PRE_CANCEL
pcm_cruise_check(cruise_engaged);
}
}
if (bus == 2) {
int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9);
if (tesla_longitudinal && (addr == das_control_addr)) {
// "AEB_ACTIVE"
tesla_stock_aeb = ((GET_BYTE(to_push, 2) & 0x03U) == 1U);
}
}
if (tesla_powertrain) {
// 0x2bf: DAS_control should not be received on bus 0
generic_rx_checks((addr == 0x2bf) && (bus == 0));
} else {
// 0x488: DAS_steeringControl should not be received on bus 0
generic_rx_checks((addr == 0x488) && (bus == 0));
}
}
static bool tesla_tx_hook(const CANPacket_t *to_send) {
bool tx = true;
int addr = GET_ADDR(to_send);
bool violation = false;
if(!tesla_powertrain && (addr == 0x488)) {
// Steering control: (0.1 * val) - 1638.35 in deg.
// We use 1/10 deg as a unit here
int raw_angle_can = (((GET_BYTE(to_send, 0) & 0x7FU) << 8) | GET_BYTE(to_send, 1));
int desired_angle = raw_angle_can - 16384;
int steer_control_type = GET_BYTE(to_send, 2) >> 6;
bool steer_control_enabled = (steer_control_type != 0) && // NONE
(steer_control_type != 3); // DISABLED
if (steer_angle_cmd_checks(desired_angle, steer_control_enabled, TESLA_STEERING_LIMITS)) {
violation = true;
}
}
if (!tesla_powertrain && (addr == 0x45)) {
// No button other than cancel can be sent by us
int control_lever_status = (GET_BYTE(to_send, 0) & 0x3FU);
if (control_lever_status != 1) {
violation = true;
}
}
if(addr == (tesla_powertrain ? 0x2bf : 0x2b9)) {
// DAS_control: longitudinal control message
if (tesla_longitudinal) {
// No AEB events may be sent by openpilot
int aeb_event = GET_BYTE(to_send, 2) & 0x03U;
if (aeb_event != 0) {
violation = true;
}
// Don't send messages when the stock AEB system is active
if (tesla_stock_aeb) {
violation = true;
}
// Don't allow any acceleration limits above the safety limits
int raw_accel_max = ((GET_BYTE(to_send, 6) & 0x1FU) << 4) | (GET_BYTE(to_send, 5) >> 4);
int raw_accel_min = ((GET_BYTE(to_send, 5) & 0x0FU) << 5) | (GET_BYTE(to_send, 4) >> 3);
violation |= longitudinal_accel_checks(raw_accel_max, TESLA_LONG_LIMITS);
violation |= longitudinal_accel_checks(raw_accel_min, TESLA_LONG_LIMITS);
} else {
violation = true;
}
}
if (violation) {
tx = false;
}
return tx;
}
static int tesla_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if(bus_num == 0) {
// Chassis/PT to autopilot
bus_fwd = 2;
}
if(bus_num == 2) {
// Autopilot to chassis/PT
int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9);
bool block_msg = false;
if (!tesla_powertrain && (addr == 0x488)) {
block_msg = true;
}
if (tesla_longitudinal && (addr == das_control_addr) && !tesla_stock_aeb) {
block_msg = true;
}
if(!block_msg) {
bus_fwd = 0;
}
}
return bus_fwd;
}
static safety_config tesla_init(uint16_t param) {
tesla_powertrain = GET_FLAG(param, TESLA_FLAG_POWERTRAIN);
tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL);
tesla_raven = GET_FLAG(param, TESLA_FLAG_RAVEN);
tesla_stock_aeb = false;
safety_config ret;
if (tesla_powertrain) {
ret = BUILD_SAFETY_CFG(tesla_pt_rx_checks, TESLA_PT_TX_MSGS);
} else if (tesla_raven) {
ret = BUILD_SAFETY_CFG(tesla_raven_rx_checks, TESLA_TX_MSGS);
} else {
ret = BUILD_SAFETY_CFG(tesla_rx_checks, TESLA_TX_MSGS);
}
return ret;
}
const safety_hooks tesla_hooks = {
.init = tesla_init,
.rx = tesla_rx_hook,
.tx = tesla_tx_hook,
.fwd = tesla_fwd_hook,
};

View File

@@ -0,0 +1,434 @@
const SteeringLimits TOYOTA_STEERING_LIMITS = {
.max_steer = 1500,
.max_rate_up = 15, // ramp up slow
.max_rate_down = 25, // ramp down fast
.max_torque_error = 350, // max torque cmd in excess of motor torque
.max_rt_delta = 450, // the real time limit is 1800/sec, a 20% buffer
.max_rt_interval = 250000,
.type = TorqueMotorLimited,
// the EPS faults when the steering angle rate is above a certain threshold for too long. to prevent this,
// we allow setting STEER_REQUEST bit to 0 while maintaining the requested torque value for a single frame
.min_valid_request_frames = 18,
.max_invalid_request_frames = 1,
.min_valid_request_rt_interval = 170000, // 170ms; a ~10% buffer on cutting every 19 frames
.has_steer_req_tolerance = true,
// LTA angle limits
// factor for STEER_TORQUE_SENSOR->STEER_ANGLE and STEERING_LTA->STEER_ANGLE_CMD (1 / 0.0573)
.angle_deg_to_can = 17.452007,
.angle_rate_up_lookup = {
{5., 25., 25.},
{0.3, 0.15, 0.15}
},
.angle_rate_down_lookup = {
{5., 25., 25.},
{0.36, 0.26, 0.26}
},
};
const int TOYOTA_LTA_MAX_ANGLE = 1657; // EPS only accepts up to 94.9461
const int TOYOTA_LTA_MAX_MEAS_TORQUE = 1500;
const int TOYOTA_LTA_MAX_DRIVER_TORQUE = 150;
// longitudinal limits
const LongitudinalLimits TOYOTA_LONG_LIMITS = {
.max_accel = 2000, // 2.0 m/s2
.min_accel = -3500, // -3.5 m/s2
};
const LongitudinalLimits TOYOTA_LONG_LIMITS_SPORT = {
.max_accel = 4000, // 4.0 m/s2
.min_accel = -3500, // -3.5 m/s2
};
// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches
// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state
// Threshold calculated from DBC gains: round((((15 + 75.555) / 0.159375) + ((15 + 151.111) / 0.159375)) / 2) = 805
const int TOYOTA_GAS_INTERCEPTOR_THRSLD = 805;
#define TOYOTA_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks
// Stock longitudinal
#define TOYOTA_COMMON_TX_MSGS \
{0x2E4, 0, 5}, {0x191, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, /* LKAS + LTA + ACC & PCM cancel cmds */ \
#define TOYOTA_COMMON_LONG_TX_MSGS \
TOYOTA_COMMON_TX_MSGS \
{0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0x33E, 0, 7}, {0x344, 0, 8}, {0x365, 0, 7}, {0x366, 0, 7}, {0x4CB, 0, 8}, /* DSU bus 0 */ \
{0x128, 1, 6}, {0x141, 1, 4}, {0x160, 1, 8}, {0x161, 1, 7}, {0x470, 1, 4}, /* DSU bus 1 */ \
{0x411, 0, 8}, /* PCS_HUD */ \
{0x750, 0, 8}, /* radar diagnostic address */ \
{0x1D3, 0, 8}, \
const CanMsg TOYOTA_TX_MSGS[] = {
TOYOTA_COMMON_TX_MSGS
};
const CanMsg TOYOTA_LONG_TX_MSGS[] = {
TOYOTA_COMMON_LONG_TX_MSGS
};
const CanMsg TOYOTA_INTERCEPTOR_TX_MSGS[] = {
TOYOTA_COMMON_LONG_TX_MSGS
{0x200, 0, 6}, // gas interceptor
};
#define TOYOTA_COMMON_RX_CHECKS(lta) \
{.msg = {{ 0xaa, 0, 8, .check_checksum = false, .frequency = 83U}, { 0 }, { 0 }}}, \
{.msg = {{0x260, 0, 8, .check_checksum = true, .quality_flag = (lta), .frequency = 50U}, { 0 }, { 0 }}}, \
{.msg = {{0x1D2, 0, 8, .check_checksum = true, .frequency = 33U}, { 0 }, { 0 }}}, \
{.msg = {{0x1D3, 0, 8, .check_checksum = true, .frequency = 33U}, { 0 }, { 0 }}}, \
{.msg = {{0x224, 0, 8, .check_checksum = false, .frequency = 40U}, \
{0x226, 0, 8, .check_checksum = false, .frequency = 40U}, { 0 }}}, \
RxCheck toyota_lka_rx_checks[] = {
TOYOTA_COMMON_RX_CHECKS(false)
};
RxCheck toyota_lka_interceptor_rx_checks[] = {
TOYOTA_COMMON_RX_CHECKS(false)
{.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
// Check the quality flag for angle measurement when using LTA, since it's not set on TSS-P cars
RxCheck toyota_lta_rx_checks[] = {
TOYOTA_COMMON_RX_CHECKS(true)
};
RxCheck toyota_lta_interceptor_rx_checks[] = {
TOYOTA_COMMON_RX_CHECKS(true)
{.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
};
// safety param flags
// first byte is for EPS factor, second is for flags
const uint32_t TOYOTA_PARAM_OFFSET = 8U;
const uint32_t TOYOTA_EPS_FACTOR = (1UL << TOYOTA_PARAM_OFFSET) - 1U;
const uint32_t TOYOTA_PARAM_ALT_BRAKE = 1UL << TOYOTA_PARAM_OFFSET;
const uint32_t TOYOTA_PARAM_STOCK_LONGITUDINAL = 2UL << TOYOTA_PARAM_OFFSET;
const uint32_t TOYOTA_PARAM_LTA = 4UL << TOYOTA_PARAM_OFFSET;
const uint32_t TOYOTA_PARAM_GAS_INTERCEPTOR = 8UL << TOYOTA_PARAM_OFFSET;
bool toyota_alt_brake = false;
bool toyota_stock_longitudinal = false;
bool toyota_lta = false;
int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
static uint32_t toyota_compute_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
int len = GET_LEN(to_push);
uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U) + (uint8_t)(len);
for (int i = 0; i < (len - 1); i++) {
checksum += (uint8_t)GET_BYTE(to_push, i);
}
return checksum;
}
static uint32_t toyota_get_checksum(const CANPacket_t *to_push) {
int checksum_byte = GET_LEN(to_push) - 1U;
return (uint8_t)(GET_BYTE(to_push, checksum_byte));
}
static uint8_t toyota_get_counter(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t cnt = 0U;
if (addr == 0x201) {
// Signal: COUNTER_PEDAL
cnt = GET_BYTE(to_push, 4) & 0x0FU;
}
return cnt;
}
static bool toyota_get_quality_flag_valid(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
bool valid = false;
if (addr == 0x260) {
valid = !GET_BIT(to_push, 3U); // STEER_ANGLE_INITIALIZING
}
return valid;
}
static void toyota_rx_hook(const CANPacket_t *to_push) {
if (GET_BUS(to_push) == 0U) {
int addr = GET_ADDR(to_push);
// get eps motor torque (0.66 factor in dbc)
if (addr == 0x260) {
int torque_meas_new = (GET_BYTE(to_push, 5) << 8) | GET_BYTE(to_push, 6);
torque_meas_new = to_signed(torque_meas_new, 16);
// scale by dbc_factor
torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100;
// update array of sample
update_sample(&torque_meas, torque_meas_new);
// increase torque_meas by 1 to be conservative on rounding
torque_meas.min--;
torque_meas.max++;
// driver torque for angle limiting
int torque_driver_new = (GET_BYTE(to_push, 1) << 8) | GET_BYTE(to_push, 2);
torque_driver_new = to_signed(torque_driver_new, 16);
update_sample(&torque_driver, torque_driver_new);
// LTA request angle should match current angle while inactive, clipped to max accepted angle.
// note that angle can be relative to init angle on some TSS2 platforms, LTA has the same offset
bool steer_angle_initializing = GET_BIT(to_push, 3U);
if (!steer_angle_initializing) {
int angle_meas_new = (GET_BYTE(to_push, 3) << 8U) | GET_BYTE(to_push, 4);
angle_meas_new = CLAMP(to_signed(angle_meas_new, 16), -TOYOTA_LTA_MAX_ANGLE, TOYOTA_LTA_MAX_ANGLE);
update_sample(&angle_meas, angle_meas_new);
}
}
if (addr == 0x1D3) {
acc_main_on = GET_BIT(to_push, 15U);
}
// enter controls on rising edge of ACC, exit controls on ACC off
// exit controls on rising edge of gas press
if (addr == 0x1D2) {
// 5th bit is CRUISE_ACTIVE
bool cruise_engaged = GET_BIT(to_push, 5U);
pcm_cruise_check(cruise_engaged);
// sample gas pedal
if (!enable_gas_interceptor) {
gas_pressed = !GET_BIT(to_push, 4U);
}
}
// sample speed
if (addr == 0xaa) {
int speed = 0;
// sum 4 wheel speeds. conversion: raw * 0.01 - 67.67
for (uint8_t i = 0U; i < 8U; i += 2U) {
int wheel_speed = (GET_BYTE(to_push, i) << 8U) | GET_BYTE(to_push, (i + 1U));
speed += wheel_speed - 6767;
}
// check that all wheel speeds are at zero value
vehicle_moving = speed != 0;
UPDATE_VEHICLE_SPEED(speed / 4.0 * 0.01 / 3.6);
}
// most cars have brake_pressed on 0x226, corolla and rav4 on 0x224
if (((addr == 0x224) && toyota_alt_brake) || ((addr == 0x226) && !toyota_alt_brake)) {
uint8_t bit = (addr == 0x224) ? 5U : 37U;
brake_pressed = GET_BIT(to_push, bit);
}
// sample gas interceptor
if ((addr == 0x201) && enable_gas_interceptor) {
int gas_interceptor = TOYOTA_GET_INTERCEPTOR(to_push);
gas_pressed = gas_interceptor > TOYOTA_GAS_INTERCEPTOR_THRSLD;
// TODO: remove this, only left in for gas_interceptor_prev test
gas_interceptor_prev = gas_interceptor;
}
bool stock_ecu_detected = addr == 0x2E4; // STEERING_LKA
if (!toyota_stock_longitudinal && (addr == 0x343)) {
stock_ecu_detected = true; // ACC_CONTROL
}
generic_rx_checks(stock_ecu_detected);
}
}
static bool toyota_tx_hook(const CANPacket_t *to_send) {
sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX;
bool tx = true;
int addr = GET_ADDR(to_send);
int bus = GET_BUS(to_send);
// Check if msg is sent on BUS 0
if (bus == 0) {
// GAS PEDAL: safety check
if (addr == 0x200) {
if (longitudinal_interceptor_checks(to_send)) {
tx = false;
}
}
// ACCEL: safety check on byte 1-2
if (addr == 0x343) {
int desired_accel = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1);
desired_accel = to_signed(desired_accel, 16);
bool violation = false;
if (sport_mode) {
violation |= longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS_SPORT);
} else {
violation |= longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS);
}
// only ACC messages that cancel are allowed when openpilot is not controlling longitudinal
if (toyota_stock_longitudinal) {
bool cancel_req = GET_BIT(to_send, 24U);
if (!cancel_req) {
violation = true;
}
if (desired_accel != TOYOTA_LONG_LIMITS.inactive_accel) {
violation = true;
}
}
if (violation) {
tx = false;
}
}
// AEB: block all actuation. only used when DSU is unplugged
if (addr == 0x283) {
// only allow the checksum, which is the last byte
bool block = (GET_BYTES(to_send, 0, 4) != 0U) || (GET_BYTE(to_send, 4) != 0U) || (GET_BYTE(to_send, 5) != 0U);
if (block) {
tx = false;
}
}
// LTA angle steering check
if (addr == 0x191) {
// check the STEER_REQUEST, STEER_REQUEST_2, TORQUE_WIND_DOWN, STEER_ANGLE_CMD signals
bool lta_request = GET_BIT(to_send, 0U);
bool lta_request2 = GET_BIT(to_send, 25U);
int torque_wind_down = GET_BYTE(to_send, 5);
int lta_angle = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2);
lta_angle = to_signed(lta_angle, 16);
bool steer_control_enabled = lta_request || lta_request2;
if (!toyota_lta) {
// using torque (LKA), block LTA msgs with actuation requests
if (steer_control_enabled || (lta_angle != 0) || (torque_wind_down != 0)) {
tx = false;
}
} else {
// check angle rate limits and inactive angle
if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS)) {
tx = false;
}
if (lta_request != lta_request2) {
tx = false;
}
// TORQUE_WIND_DOWN is gated on steer request
if (!steer_control_enabled && (torque_wind_down != 0)) {
tx = false;
}
// TORQUE_WIND_DOWN can only be no or full torque
if ((torque_wind_down != 0) && (torque_wind_down != 100)) {
tx = false;
}
// check if we should wind down torque
int driver_torque = MIN(ABS(torque_driver.min), ABS(torque_driver.max));
if ((driver_torque > TOYOTA_LTA_MAX_DRIVER_TORQUE) && (torque_wind_down != 0)) {
tx = false;
}
int eps_torque = MIN(ABS(torque_meas.min), ABS(torque_meas.max));
if ((eps_torque > TOYOTA_LTA_MAX_MEAS_TORQUE) && (torque_wind_down != 0)) {
tx = false;
}
}
}
// STEER: safety check on bytes 2-3
if (addr == 0x2E4) {
int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2);
desired_torque = to_signed(desired_torque, 16);
bool steer_req = GET_BIT(to_send, 0U);
// When using LTA (angle control), assert no actuation on LKA message
if (!toyota_lta) {
if (steer_torque_cmd_checks(desired_torque, steer_req, TOYOTA_STEERING_LIMITS)) {
tx = false;
}
} else {
if ((desired_torque != 0) || steer_req) {
tx = false;
}
}
}
}
// UDS: Only tester present ("\x0F\x02\x3E\x00\x00\x00\x00\x00") allowed on diagnostics address
if (addr == 0x750) {
// this address is sub-addressed. only allow tester present to radar (0xF)
bool invalid_uds_msg = (GET_BYTES(to_send, 0, 4) != 0x003E020FU) || (GET_BYTES(to_send, 4, 4) != 0x0U);
if (invalid_uds_msg) {
tx = 0;
}
}
return tx;
}
static safety_config toyota_init(uint16_t param) {
toyota_alt_brake = GET_FLAG(param, TOYOTA_PARAM_ALT_BRAKE);
toyota_stock_longitudinal = GET_FLAG(param, TOYOTA_PARAM_STOCK_LONGITUDINAL);
toyota_lta = GET_FLAG(param, TOYOTA_PARAM_LTA);
enable_gas_interceptor = GET_FLAG(param, TOYOTA_PARAM_GAS_INTERCEPTOR);
toyota_dbc_eps_torque_factor = param & TOYOTA_EPS_FACTOR;
// Gas interceptor should not be used if openpilot is not controlling longitudinal
if (toyota_stock_longitudinal) {
enable_gas_interceptor = false;
}
safety_config ret;
if (toyota_stock_longitudinal) {
SET_TX_MSGS(TOYOTA_TX_MSGS, ret);
} else {
enable_gas_interceptor ? SET_TX_MSGS(TOYOTA_INTERCEPTOR_TX_MSGS, ret) : \
SET_TX_MSGS(TOYOTA_LONG_TX_MSGS, ret);
}
if (enable_gas_interceptor) {
toyota_lta ? SET_RX_CHECKS(toyota_lta_interceptor_rx_checks, ret) : \
SET_RX_CHECKS(toyota_lka_interceptor_rx_checks, ret);
} else {
toyota_lta ? SET_RX_CHECKS(toyota_lta_rx_checks, ret) : \
SET_RX_CHECKS(toyota_lka_rx_checks, ret);
}
return ret;
}
static int toyota_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == 0) {
bus_fwd = 2;
}
if (bus_num == 2) {
// block stock lkas messages and stock acc messages (if OP is doing ACC)
// in TSS2, 0x191 is LTA which we need to block to avoid controls collision
bool is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191));
// in TSS2 the camera does ACC as well, so filter 0x343
bool is_acc_msg = (addr == 0x343);
bool block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal);
if (!block_msg) {
bus_fwd = 0;
}
}
return bus_fwd;
}
const safety_hooks toyota_hooks = {
.init = toyota_init,
.rx = toyota_rx_hook,
.tx = toyota_tx_hook,
.fwd = toyota_fwd_hook,
.get_checksum = toyota_get_checksum,
.compute_checksum = toyota_compute_checksum,
.get_counter = toyota_get_counter,
.get_quality_flag_valid = toyota_get_quality_flag_valid,
};

View File

@@ -0,0 +1,10 @@
#ifndef SAFETY_VOLKSWAGEN_COMMON_H
#define SAFETY_VOLKSWAGEN_COMMON_H
const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL = 1;
bool volkswagen_longitudinal = false;
bool volkswagen_set_button_prev = false;
bool volkswagen_resume_button_prev = false;
#endif

View File

@@ -0,0 +1,312 @@
#include "safety_volkswagen_common.h"
// lateral limits
const SteeringLimits VOLKSWAGEN_MQB_STEERING_LIMITS = {
.max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated)
.max_rt_delta = 75, // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75
.max_rt_interval = 250000, // 250ms between real time checks
.max_rate_up = 4, // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s)
.max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s)
.driver_torque_allowance = 80,
.driver_torque_factor = 3,
.type = TorqueDriverLimited,
};
// longitudinal limits
// acceleration in m/s2 * 1000 to avoid floating point math
const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = {
.max_accel = 2000,
.min_accel = -3500,
.inactive_accel = 3010, // VW sends one increment above the max range when inactive
};
const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS_SPORT = {
.max_accel = 4000,
.min_accel = -3500,
.inactive_accel = 3010, // VW sends one increment above the max range when inactive
};
#define MSG_ESP_19 0x0B2 // RX from ABS, for wheel speeds
#define MSG_LH_EPS_03 0x09F // RX from EPS, for driver steering torque
#define MSG_ESP_05 0x106 // RX from ABS, for brake switch state
#define MSG_TSK_06 0x120 // RX from ECU, for ACC status from drivetrain coordinator
#define MSG_MOTOR_20 0x121 // RX from ECU, for driver throttle input
#define MSG_ACC_06 0x122 // TX by OP, ACC control instructions to the drivetrain coordinator
#define MSG_HCA_01 0x126 // TX by OP, Heading Control Assist steering torque
#define MSG_GRA_ACC_01 0x12B // TX by OP, ACC control buttons for cancel/resume
#define MSG_ACC_07 0x12E // TX by OP, ACC control instructions to the drivetrain coordinator
#define MSG_ACC_02 0x30C // TX by OP, ACC HUD data to the instrument cluster
#define MSG_MOTOR_14 0x3BE // RX from ECU, for brake switch status
#define MSG_LDW_02 0x397 // TX by OP, Lane line recognition and text alerts
// Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8},
{MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8}};
const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8},
{MSG_ACC_02, 0, 8}, {MSG_ACC_06, 0, 8}, {MSG_ACC_07, 0, 8}};
RxCheck volkswagen_mqb_rx_checks[] = {
{.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_MOTOR_14, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{MSG_GRA_ACC_01, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 33U}, { 0 }, { 0 }}},
};
uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR
bool volkswagen_mqb_brake_pedal_switch = false;
bool volkswagen_mqb_brake_pressure_detected = false;
static uint32_t volkswagen_mqb_get_checksum(const CANPacket_t *to_push) {
return (uint8_t)GET_BYTE(to_push, 0);
}
static uint8_t volkswagen_mqb_get_counter(const CANPacket_t *to_push) {
// MQB message counters are consistently found at LSB 8.
return (uint8_t)GET_BYTE(to_push, 1) & 0xFU;
}
static uint32_t volkswagen_mqb_compute_crc(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
int len = GET_LEN(to_push);
// This is CRC-8H2F/AUTOSAR with a twist. See the OpenDBC implementation
// of this algorithm for a version with explanatory comments.
uint8_t crc = 0xFFU;
for (int i = 1; i < len; i++) {
crc ^= (uint8_t)GET_BYTE(to_push, i);
crc = volkswagen_crc8_lut_8h2f[crc];
}
uint8_t counter = volkswagen_mqb_get_counter(to_push);
if (addr == MSG_LH_EPS_03) {
crc ^= (uint8_t[]){0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5}[counter];
} else if (addr == MSG_ESP_05) {
crc ^= (uint8_t[]){0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07}[counter];
} else if (addr == MSG_TSK_06) {
crc ^= (uint8_t[]){0xC4,0xE2,0x4F,0xE4,0xF8,0x2F,0x56,0x81,0x9F,0xE5,0x83,0x44,0x05,0x3F,0x97,0xDF}[counter];
} else if (addr == MSG_MOTOR_20) {
crc ^= (uint8_t[]){0xE9,0x65,0xAE,0x6B,0x7B,0x35,0xE5,0x5F,0x4E,0xC7,0x86,0xA2,0xBB,0xDD,0xEB,0xB4}[counter];
} else if (addr == MSG_GRA_ACC_01) {
crc ^= (uint8_t[]){0x6A,0x38,0xB4,0x27,0x22,0xEF,0xE1,0xBB,0xF8,0x80,0x84,0x49,0xC7,0x9E,0x1E,0x2B}[counter];
} else {
// Undefined CAN message, CRC check expected to fail
}
crc = volkswagen_crc8_lut_8h2f[crc];
return (uint8_t)(crc ^ 0xFFU);
}
static safety_config volkswagen_mqb_init(uint16_t param) {
UNUSED(param);
volkswagen_set_button_prev = false;
volkswagen_resume_button_prev = false;
volkswagen_mqb_brake_pedal_switch = false;
volkswagen_mqb_brake_pressure_detected = false;
#ifdef ALLOW_DEBUG
volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL);
#endif
gen_crc_lookup_table_8(0x2F, volkswagen_crc8_lut_8h2f);
return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_STOCK_TX_MSGS);
}
static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) {
if (GET_BUS(to_push) == 0U) {
int addr = GET_ADDR(to_push);
// Update in-motion state by sampling wheel speeds
if (addr == MSG_ESP_19) {
// sum 4 wheel speeds
int speed = 0;
for (uint8_t i = 0U; i < 8U; i += 2U) {
int wheel_speed = GET_BYTE(to_push, i) | (GET_BYTE(to_push, i + 1U) << 8);
speed += wheel_speed;
}
// Check all wheel speeds for any movement
vehicle_moving = speed > 0;
}
// Update driver input torque samples
// Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque)
// Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction)
if (addr == MSG_LH_EPS_03) {
int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1FU) << 8);
int sign = (GET_BYTE(to_push, 6) & 0x80U) >> 7;
if (sign == 1) {
torque_driver_new *= -1;
}
update_sample(&torque_driver, torque_driver_new);
}
if (addr == MSG_TSK_06) {
// When using stock ACC, enter controls on rising edge of stock ACC engage, exit on disengage
// Always exit controls on main switch off
// Signal: TSK_06.TSK_Status
int acc_status = (GET_BYTE(to_push, 3) & 0x7U);
bool cruise_engaged = (acc_status == 3) || (acc_status == 4) || (acc_status == 5);
acc_main_on = cruise_engaged || (acc_status == 2);
if (!volkswagen_longitudinal) {
pcm_cruise_check(cruise_engaged);
}
if (!acc_main_on) {
controls_allowed = false;
}
}
if (addr == MSG_GRA_ACC_01) {
// If using openpilot longitudinal, enter controls on falling edge of Set or Resume with main switch on
// Signal: GRA_ACC_01.GRA_Tip_Setzen
// Signal: GRA_ACC_01.GRA_Tip_Wiederaufnahme
if (volkswagen_longitudinal) {
bool set_button = GET_BIT(to_push, 16U);
bool resume_button = GET_BIT(to_push, 19U);
if ((volkswagen_set_button_prev && !set_button) || (volkswagen_resume_button_prev && !resume_button)) {
controls_allowed = acc_main_on;
}
volkswagen_set_button_prev = set_button;
volkswagen_resume_button_prev = resume_button;
}
// Always exit controls on rising edge of Cancel
// Signal: GRA_ACC_01.GRA_Abbrechen
if (GET_BIT(to_push, 13U)) {
controls_allowed = false;
}
}
// Signal: Motor_20.MO_Fahrpedalrohwert_01
if (addr == MSG_MOTOR_20) {
gas_pressed = ((GET_BYTES(to_push, 0, 4) >> 12) & 0xFFU) != 0U;
}
// Signal: Motor_14.MO_Fahrer_bremst (ECU detected brake pedal switch F63)
if (addr == MSG_MOTOR_14) {
volkswagen_mqb_brake_pedal_switch = (GET_BYTE(to_push, 3) & 0x10U) >> 4;
}
// Signal: ESP_05.ESP_Fahrer_bremst (ESP detected driver brake pressure above platform specified threshold)
if (addr == MSG_ESP_05) {
volkswagen_mqb_brake_pressure_detected = (GET_BYTE(to_push, 3) & 0x4U) >> 2;
}
brake_pressed = volkswagen_mqb_brake_pedal_switch || volkswagen_mqb_brake_pressure_detected;
generic_rx_checks((addr == MSG_HCA_01));
}
}
static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) {
sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX;
int addr = GET_ADDR(to_send);
bool tx = true;
// Safety check for HCA_01 Heading Control Assist torque
// Signal: HCA_01.HCA_01_LM_Offset (absolute torque)
// Signal: HCA_01.HCA_01_LM_OffSign (direction)
if (addr == MSG_HCA_01) {
int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x1U) << 8);
bool sign = GET_BIT(to_send, 31U);
if (sign) {
desired_torque *= -1;
}
bool steer_req = GET_BIT(to_send, 30U);
if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_MQB_STEERING_LIMITS)) {
tx = false;
}
}
// Safety check for both ACC_06 and ACC_07 acceleration requests
// To avoid floating point math, scale upward and compare to pre-scaled safety m/s2 boundaries
if ((addr == MSG_ACC_06) || (addr == MSG_ACC_07)) {
bool violation = false;
int desired_accel = 0;
if (addr == MSG_ACC_06) {
// Signal: ACC_06.ACC_Sollbeschleunigung_02 (acceleration in m/s2, scale 0.005, offset -7.22)
desired_accel = ((((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) * 5U) - 7220U;
} else {
// Signal: ACC_07.ACC_Folgebeschl (acceleration in m/s2, scale 0.03, offset -4.6)
int secondary_accel = (GET_BYTE(to_send, 4) * 30U) - 4600U;
violation |= (secondary_accel != 3020); // enforce always inactive (one increment above max range) at this time
// Signal: ACC_07.ACC_Sollbeschleunigung_02 (acceleration in m/s2, scale 0.005, offset -7.22)
desired_accel = (((GET_BYTE(to_send, 7) << 3) | ((GET_BYTE(to_send, 6) & 0xE0U) >> 5)) * 5U) - 7220U;
}
if (sport_mode) {
if (desired_accel != 0) {
violation |= longitudinal_accel_checks(desired_accel, VOLKSWAGEN_MQB_LONG_LIMITS_SPORT);
}
} else {
violation |= longitudinal_accel_checks(desired_accel, VOLKSWAGEN_MQB_LONG_LIMITS);
}
if (violation) {
tx = false;
}
}
// FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off.
// This avoids unintended engagements while still allowing resume spam
if ((addr == MSG_GRA_ACC_01) && !controls_allowed) {
// disallow resume and set: bits 16 and 19
if ((GET_BYTE(to_send, 2) & 0x9U) != 0U) {
tx = false;
}
}
return tx;
}
static int volkswagen_mqb_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
switch (bus_num) {
case 0:
if (addr == MSG_LH_EPS_03) {
// openpilot needs to replace apparent driver steering input torque to pacify VW Emergency Assist
bus_fwd = -1;
} else {
// Forward all remaining traffic from Extended CAN onward
bus_fwd = 2;
}
break;
case 2:
if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) {
// openpilot takes over LKAS steering control and related HUD messages from the camera
bus_fwd = -1;
} else if (volkswagen_longitudinal && ((addr == MSG_ACC_02) || (addr == MSG_ACC_06) || (addr == MSG_ACC_07))) {
// openpilot takes over acceleration/braking control and related HUD messages from the stock ACC radar
bus_fwd = -1;
} else {
// Forward all remaining traffic from Extended CAN devices to J533 gateway
bus_fwd = 0;
}
break;
default:
// No other buses should be in use; fallback to do-not-forward
bus_fwd = -1;
break;
}
return bus_fwd;
}
const safety_hooks volkswagen_mqb_hooks = {
.init = volkswagen_mqb_init,
.rx = volkswagen_mqb_rx_hook,
.tx = volkswagen_mqb_tx_hook,
.fwd = volkswagen_mqb_fwd_hook,
.get_counter = volkswagen_mqb_get_counter,
.get_checksum = volkswagen_mqb_get_checksum,
.compute_checksum = volkswagen_mqb_compute_crc,
};

Some files were not shown because too many files have changed in this diff Show More