diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index c87047a8870..718aaa8a6d0 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -120,7 +120,7 @@ jobs: timeout-minutes: 1 run: ${{ env.RUN }} "cd tests/misra && ./test_misra.sh" - name: MISRA mutation tests - timeout-minutes: 2 + timeout-minutes: 3 run: ${{ env.RUN }} "cd tests/misra && ./test_mutation.py" python_linter: diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index b1483862b4d..9d2dfc9c3ad 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,6 +15,6 @@ repos: additional_dependencies: ['git+https://github.com/numpy/numpy-stubs', 'types-requests', 'types-atomicwrites', 'types-pycurl'] - repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.1.13 + rev: v0.1.14 hooks: - id: ruff diff --git a/SConscript b/SConscript index 0aa3aa34eb2..1a79e3880d8 100644 --- a/SConscript +++ b/SConscript @@ -101,7 +101,8 @@ def build_project(project_name, project, extra_flags): ASCOM="$AS $ASFLAGS -o $TARGET -c $SOURCES", BUILDERS={ 'Objcopy': Builder(generator=objcopy, suffix='.bin', src_suffix='.elf') - } + }, + tools=["default", "compilation_db"], ) startup = env.Object(f"obj/startup_{project_name}", project["STARTUP_FILE"]) diff --git a/SConstruct b/SConstruct index e7cd8d8522f..aa13f592299 100644 --- a/SConstruct +++ b/SConstruct @@ -12,5 +12,17 @@ AddOption('--coverage', action='store_true', help='build with test coverage options') +AddOption('--compile_db', + action='store_true', + help='build clang compilation database') + +env = Environment( + COMPILATIONDB_USE_ABSPATH=True, + tools=["default", "compilation_db"], +) + +if GetOption('compile_db'): + env.CompilationDatabase("compile_commands.json") + # panda fw & test files SConscript('SConscript') diff --git a/board/SConscript b/board/SConscript index 45fa0f416e4..81f1ef84ae8 100644 --- a/board/SConscript +++ b/board/SConscript @@ -15,4 +15,7 @@ for project_name, project in build_projects.items(): if ("ENABLE_SPI" in os.environ or "h7" in project_name) and not project_name.startswith('pedal'): flags.append('-DENABLE_SPI') + if "H723" in os.environ: + flags.append('-DSTM32H723') + build_project(project_name, project, flags) diff --git a/board/boards/black.h b/board/boards/black.h index 4b574f6698b..d3d0f8619dc 100644 --- a/board/boards/black.h +++ b/board/boards/black.h @@ -163,7 +163,6 @@ const harness_configuration black_harness_config = { }; const board board_black = { - .board_type = "Black", .set_bootkick = unused_set_bootkick, .harness_config = &black_harness_config, .has_hw_gmlan = false, diff --git a/board/boards/board_declarations.h b/board/boards/board_declarations.h index f0cb30290ba..ee7103b06ac 100644 --- a/board/boards/board_declarations.h +++ b/board/boards/board_declarations.h @@ -20,7 +20,6 @@ typedef void (*board_set_bootkick)(BootState state); typedef bool (*board_read_som_gpio)(void); struct board { - const char *board_type; const harness_configuration *harness_config; const bool has_hw_gmlan; const bool has_obd; @@ -58,6 +57,7 @@ struct board { #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 diff --git a/board/boards/cuatro.h b/board/boards/cuatro.h new file mode 100644 index 00000000000..4eb4bcc283e --- /dev/null +++ b/board/boards/cuatro.h @@ -0,0 +1,71 @@ +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_init(void) { + 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); + + // Clock source + clock_source_init(); +} + +const board board_cuatro = { + .harness_config = &red_chiplet_harness_config, + .has_hw_gmlan = false, + .has_obd = true, + .has_spi = true, + .has_canfd = true, + .has_rtc_battery = 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 = red_chiplet_enable_can_transceiver, + .enable_can_transceivers = red_chiplet_enable_can_transceivers, + .set_led = cuatro_set_led, + .set_can_mode = red_chiplet_set_can_mode, + .check_ignition = red_check_ignition, + .read_current = unused_read_current, + .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 +}; diff --git a/board/boards/dos.h b/board/boards/dos.h index 1a7bc878e53..b76f8993fff 100644 --- a/board/boards/dos.h +++ b/board/boards/dos.h @@ -192,7 +192,6 @@ const harness_configuration dos_harness_config = { }; const board board_dos = { - .board_type = "Dos", .harness_config = &dos_harness_config, .has_hw_gmlan = false, .has_obd = true, diff --git a/board/boards/grey.h b/board/boards/grey.h index 4e13b51cb04..6065c3d227a 100644 --- a/board/boards/grey.h +++ b/board/boards/grey.h @@ -5,7 +5,6 @@ // Most hardware functionality is similar to white panda const board board_grey = { - .board_type = "Grey", .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, .has_hw_gmlan = true, diff --git a/board/boards/pedal.h b/board/boards/pedal.h index bdc4de15681..1909b2a5311 100644 --- a/board/boards/pedal.h +++ b/board/boards/pedal.h @@ -67,7 +67,6 @@ const harness_configuration pedal_harness_config = { }; const board board_pedal = { - .board_type = "Pedal", .set_bootkick = unused_set_bootkick, .harness_config = &pedal_harness_config, .has_hw_gmlan = false, diff --git a/board/boards/red.h b/board/boards/red.h index c618c48ad4f..709d44df50d 100644 --- a/board/boards/red.h +++ b/board/boards/red.h @@ -171,7 +171,6 @@ const harness_configuration red_harness_config = { }; const board board_red = { - .board_type = "Red", .set_bootkick = unused_set_bootkick, .harness_config = &red_harness_config, .has_hw_gmlan = false, diff --git a/board/boards/red_v2.h b/board/boards/red_v2.h deleted file mode 100644 index 2fa18835af2..00000000000 --- a/board/boards/red_v2.h +++ /dev/null @@ -1,38 +0,0 @@ -// ///////////////////// // -// Red Panda V2 with chiplet + Harness // -// ///////////////////// // - -void red_panda_v2_init(void) { - // common chiplet init - red_chiplet_init(); - - // Turn on USB load switch - red_chiplet_set_fan_or_usb_load_switch(true); -} - -const board board_red_v2 = { - .board_type = "Red_v2", - .set_bootkick = unused_set_bootkick, - .harness_config = &red_chiplet_harness_config, - .has_hw_gmlan = false, - .has_obd = true, - .has_spi = false, - .has_canfd = true, - .has_rtc_battery = true, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = red_panda_v2_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_current = 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 -}; diff --git a/board/boards/tres.h b/board/boards/tres.h index 599516e2321..d4faa9c0a33 100644 --- a/board/boards/tres.h +++ b/board/boards/tres.h @@ -71,7 +71,6 @@ void tres_init(void) { } const board board_tres = { - .board_type = "Tres", .harness_config = &red_chiplet_harness_config, .has_hw_gmlan = false, .has_obd = true, diff --git a/board/boards/uno.h b/board/boards/uno.h index d03782cc068..15759b85809 100644 --- a/board/boards/uno.h +++ b/board/boards/uno.h @@ -199,7 +199,6 @@ const harness_configuration uno_harness_config = { }; const board board_uno = { - .board_type = "Uno", .harness_config = &uno_harness_config, .has_hw_gmlan = false, .has_obd = true, diff --git a/board/boards/white.h b/board/boards/white.h index 39bad3e760b..c8b8606bcf4 100644 --- a/board/boards/white.h +++ b/board/boards/white.h @@ -222,7 +222,6 @@ const harness_configuration white_harness_config = { }; const board board_white = { - .board_type = "White", .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, .has_hw_gmlan = true, diff --git a/board/can_comms.h b/board/can_comms.h index 980d12ba8d0..56ca912f8ed 100644 --- a/board/can_comms.h +++ b/board/can_comms.h @@ -56,7 +56,7 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U}; // send on CAN -void comms_can_write(uint8_t *data, uint32_t len) { +void comms_can_write(const uint8_t *data, uint32_t len) { uint32_t pos = 0U; // Assembling can message with data from buffer diff --git a/board/comms_definitions.h b/board/comms_definitions.h index d074514de49..18a6d2f8134 100644 --- a/board/comms_definitions.h +++ b/board/comms_definitions.h @@ -6,7 +6,7 @@ typedef struct { } __attribute__((packed)) ControlPacket_t; int comms_control_handler(ControlPacket_t *req, uint8_t *resp); -void comms_endpoint2_write(uint8_t *data, uint32_t len); -void comms_can_write(uint8_t *data, uint32_t len); +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); diff --git a/board/crc.h b/board/crc.h index 6ceaba07ef2..3e20fb09817 100644 --- a/board/crc.h +++ b/board/crc.h @@ -1,6 +1,6 @@ #pragma once -uint8_t crc_checksum(uint8_t *dat, int len, const uint8_t poly) { +uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) { uint8_t crc = 0xFFU; int i; int j; diff --git a/board/drivers/can_common.h b/board/drivers/can_common.h index 5c53862877e..574c7cfd56f 100644 --- a/board/drivers/can_common.h +++ b/board/drivers/can_common.h @@ -95,7 +95,7 @@ bool can_pop(can_ring *q, CANPacket_t *elem) { return ret; } -bool can_push(can_ring *q, CANPacket_t *elem) { +bool can_push(can_ring *q, const CANPacket_t *elem) { bool ret = false; uint32_t next_w_ptr; @@ -133,7 +133,7 @@ bool can_push(can_ring *q, CANPacket_t *elem) { return ret; } -uint32_t can_slots_empty(can_ring *q) { +uint32_t can_slots_empty(const can_ring *q) { uint32_t ret = 0; ENTER_CRITICAL(); @@ -238,7 +238,7 @@ bool can_tx_check_min_slots_free(uint32_t min) { (can_slots_empty(&can_txgmlan_q) >= min); } -uint8_t calculate_checksum(uint8_t *dat, uint32_t len) { +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]; diff --git a/board/drivers/gmlan_alt.h b/board/drivers/gmlan_alt.h index 9725609f12c..407062bbbd6 100644 --- a/board/drivers/gmlan_alt.h +++ b/board/drivers/gmlan_alt.h @@ -12,7 +12,7 @@ int gmlan_alt_mode = DISABLED; // returns out_len -int do_bitstuff(char *out, char *in, int in_len) { +int do_bitstuff(char *out, const char *in, int in_len) { int last_bit = -1; int bit_cnt = 0; int j = 0; @@ -57,7 +57,7 @@ int append_crc(char *in, int in_len) { return in_len_copy; } -int append_bits(char *in, int in_len, char *app, int app_len) { +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]; @@ -75,7 +75,7 @@ int append_int(char *in, int in_len, int val, int val_len) { return in_len_copy; } -int get_bit_message(char *out, CANPacket_t *to_bang) { +int get_bit_message(char *out, const CANPacket_t *to_bang) { char pkt[MAX_BITS_CAN_PACKET]; char footer[] = { 1, // CRC delimiter @@ -95,7 +95,7 @@ int get_bit_message(char *out, CANPacket_t *to_bang) { // 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)) & ((1U << 18) - 1U), 18); // Identifier + 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 @@ -175,9 +175,9 @@ void reset_gmlan_switch_timeout(void) { void set_bitbanged_gmlan(int val) { if (val != 0) { - register_set_bits(&(GPIOB->ODR), (1U << 13)); + register_set_bits(&(GPIOB->ODR), (1UL << 13)); } else { - register_clear_bits(&(GPIOB->ODR), (1U << 13)); + register_clear_bits(&(GPIOB->ODR), (1UL << 13)); } } @@ -268,26 +268,29 @@ void TIM12_IRQ_Handler(void) { TIM12->SR = 0; } -bool bitbang_gmlan(CANPacket_t *to_bang) { +bool bitbang_gmlan(const CANPacket_t *to_bang) { gmlan_send_ok = true; gmlan_alt_mode = BITBANG; -#ifndef STM32H7 - 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(); +#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; } diff --git a/board/drivers/gpio.h b/board/drivers/gpio.h index fe3194f3bab..bf96a0326e2 100644 --- a/board/drivers/gpio.h +++ b/board/drivers/gpio.h @@ -27,9 +27,9 @@ void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { ENTER_CRITICAL(); if (enabled) { - register_set_bits(&(GPIO->ODR), (1U << pin)); + register_set_bits(&(GPIO->ODR), (1UL << pin)); } else { - register_clear_bits(&(GPIO->ODR), (1U << pin)); + register_clear_bits(&(GPIO->ODR), (1UL << pin)); } set_gpio_mode(GPIO, pin, MODE_OUTPUT); EXIT_CRITICAL(); @@ -38,7 +38,7 @@ void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { void set_gpio_output_type(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int output_type){ ENTER_CRITICAL(); if(output_type == OUTPUT_TYPE_OPEN_DRAIN) { - register_set_bits(&(GPIO->OTYPER), (1U << pin)); + register_set_bits(&(GPIO->OTYPER), (1UL << pin)); } else { register_clear_bits(&(GPIO->OTYPER), (1U << pin)); } @@ -64,8 +64,8 @@ void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { EXIT_CRITICAL(); } -int get_gpio_input(GPIO_TypeDef *GPIO, unsigned int pin) { - return (GPIO->IDR & (1U << pin)) == (1U << pin); +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) { diff --git a/board/drivers/spi.h b/board/drivers/spi.h index ea704eb11a2..1a7b9be5909 100644 --- a/board/drivers/spi.h +++ b/board/drivers/spi.h @@ -111,7 +111,7 @@ void spi_init(void) { llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); } -bool validate_checksum(uint8_t *data, uint16_t len) { +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++){ diff --git a/board/drivers/uart.h b/board/drivers/uart.h index b62bc979985..e37dfcd6bd9 100644 --- a/board/drivers/uart.h +++ b/board/drivers/uart.h @@ -131,7 +131,7 @@ bool put_char(uart_ring *q, char elem) { // Seems dangerous to use (might lock CPU if called with interrupts disabled f.e.) // TODO: Remove? Not used anyways -void uart_flush(uart_ring *q) { +void uart_flush(const uart_ring *q) { while (q->w_ptr_tx != q->r_ptr_tx) { __WFI(); } diff --git a/board/drivers/usb.h b/board/drivers/usb.h index 6fb1ae37737..99ba126cec3 100644 --- a/board/drivers/usb.h +++ b/board/drivers/usb.h @@ -104,7 +104,7 @@ uint8_t resp[USBPACKET_MAX_SIZE]; // Convert machine byte order to USB byte order #define TOUSBORDER(num)\ - ((num) & 0xFFU), (((num) >> 8) & 0xFFU) + ((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)\ @@ -447,10 +447,10 @@ void usb_reset(void) { USBx->GRXFSIZ = 0x40; // 0x100 to offset past GRXFSIZ - USBx->DIEPTXF0_HNPTXFSIZ = (0x40U << 16) | 0x40U; + USBx->DIEPTXF0_HNPTXFSIZ = (0x40UL << 16) | 0x40U; // EP1, massive - USBx->DIEPTXF[0] = (0x40U << 16) | 0x80U; + USBx->DIEPTXF[0] = (0x40UL << 16) | 0x80U; // flush TX fifo USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; @@ -463,7 +463,7 @@ void usb_reset(void) { USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; // ready to receive setup packets - USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)) | (3U << 3); + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (3U << 3); } char to_hex_char(int a) { @@ -490,17 +490,17 @@ void usb_setup(void) { switch (setup.b.bRequest) { case USB_REQ_SET_CONFIGURATION: // enable other endpoints, has to be here? - USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2U << 18) | (1U << 22) | + 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 = (1U << 19) | 0x40U; - USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) | + 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 = (32U << 19) | 0x800U; - USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) | + 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; @@ -802,7 +802,7 @@ void usb_irqhandler(void) { #ifdef DEBUG_USB print(" OUT2 PACKET XFRC\n"); #endif - USBx_OUTEP(2)->DOEPTSIZ = (1U << 19) | 0x40U; + USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U; USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; } @@ -833,7 +833,7 @@ void usb_irqhandler(void) { 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 & (1U << 19)) | (1U << 3); + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (1U << 3); } // respond to setup packets @@ -933,7 +933,7 @@ void usb_irqhandler(void) { 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 = (32U << 19) | 0x800U; + USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U; USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; } EXIT_CRITICAL(); diff --git a/board/faults.h b/board/faults.h index 6c6bef475d9..a7f437dee5d 100644 --- a/board/faults.h +++ b/board/faults.h @@ -3,33 +3,33 @@ #define FAULT_STATUS_PERMANENT 2U // Fault types, matches cereal.log.PandaState.FaultType -#define FAULT_RELAY_MALFUNCTION (1U << 0) -#define FAULT_UNUSED_INTERRUPT_HANDLED (1U << 1) -#define FAULT_INTERRUPT_RATE_CAN_1 (1U << 2) -#define FAULT_INTERRUPT_RATE_CAN_2 (1U << 3) -#define FAULT_INTERRUPT_RATE_CAN_3 (1U << 4) -#define FAULT_INTERRUPT_RATE_TACH (1U << 5) -#define FAULT_INTERRUPT_RATE_GMLAN (1U << 6) -#define FAULT_INTERRUPT_RATE_INTERRUPTS (1U << 7) -#define FAULT_INTERRUPT_RATE_SPI_DMA (1U << 8) -#define FAULT_INTERRUPT_RATE_SPI_CS (1U << 9) -#define FAULT_INTERRUPT_RATE_UART_1 (1U << 10) -#define FAULT_INTERRUPT_RATE_UART_2 (1U << 11) -#define FAULT_INTERRUPT_RATE_UART_3 (1U << 12) -#define FAULT_INTERRUPT_RATE_UART_5 (1U << 13) -#define FAULT_INTERRUPT_RATE_UART_DMA (1U << 14) -#define FAULT_INTERRUPT_RATE_USB (1U << 15) -#define FAULT_INTERRUPT_RATE_TIM1 (1U << 16) -#define FAULT_INTERRUPT_RATE_TIM3 (1U << 17) -#define FAULT_REGISTER_DIVERGENT (1U << 18) -#define FAULT_INTERRUPT_RATE_KLINE_INIT (1U << 19) -#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1U << 20) -#define FAULT_INTERRUPT_RATE_TICK (1U << 21) -#define FAULT_INTERRUPT_RATE_EXTI (1U << 22) -#define FAULT_INTERRUPT_RATE_SPI (1U << 23) -#define FAULT_INTERRUPT_RATE_UART_7 (1U << 24) -#define FAULT_SIREN_MALFUNCTION (1U << 25) -#define FAULT_HEARTBEAT_LOOP_WATCHDOG (1U << 26) +#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 diff --git a/board/flasher.h b/board/flasher.h index 495d9f1691b..eec0ec5d759 100644 --- a/board/flasher.h +++ b/board/flasher.h @@ -99,7 +99,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { return resp_len; } -void comms_can_write(uint8_t *data, uint32_t len) { +void comms_can_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } @@ -112,7 +112,7 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { void refresh_can_tx_slots_available(void) {} -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +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))); diff --git a/board/jungle/boards/board_declarations.h b/board/jungle/boards/board_declarations.h index 6e016af0716..1288b5354df 100644 --- a/board/jungle/boards/board_declarations.h +++ b/board/jungle/boards/board_declarations.h @@ -15,7 +15,6 @@ 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 char *board_type; const bool has_canfd; const bool has_sbu_sense; const uint16_t avdd_mV; diff --git a/board/jungle/boards/board_v1.h b/board/jungle/boards/board_v1.h index d0ad7843eb5..29c23d6df7a 100644 --- a/board/jungle/boards/board_v1.h +++ b/board/jungle/boards/board_v1.h @@ -155,7 +155,6 @@ void board_v1_init(void) { void board_v1_tick(void) {} const board board_v1 = { - .board_type = "V1", .has_canfd = false, .has_sbu_sense = false, .avdd_mV = 3300U, diff --git a/board/jungle/boards/board_v2.h b/board/jungle/boards/board_v2.h index 25ea2fd422e..7bce61ebb30 100644 --- a/board/jungle/boards/board_v2.h +++ b/board/jungle/boards/board_v2.h @@ -305,7 +305,6 @@ void board_v2_init(void) { void board_v2_tick(void) {} const board board_v2 = { - .board_type = "V2", .has_canfd = true, .has_sbu_sense = true, .avdd_mV = 3300U, diff --git a/board/jungle/main.c b/board/jungle/main.c index 25e21472766..f0a09dfbde8 100644 --- a/board/jungle/main.c +++ b/board/jungle/main.c @@ -155,7 +155,7 @@ int main(void) { } print("Config:\n"); - print(" Board type: "); print(current_board->board_type); print("\n"); + print(" Board type: 0x"); puth(hw_type); print("\n"); // init board current_board->init(); diff --git a/board/jungle/main_comms.h b/board/jungle/main_comms.h index 737c90840c8..928c554d1ca 100644 --- a/board/jungle/main_comms.h +++ b/board/jungle/main_comms.h @@ -29,7 +29,7 @@ int get_jungle_health_pkt(void *dat) { } // send on serial, first byte to select the ring -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +void comms_endpoint2_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } diff --git a/board/main.c b/board/main.c index b9f12bff8f4..061a913814b 100644 --- a/board/main.c +++ b/board/main.c @@ -338,7 +338,7 @@ int main(void) { } print("Config:\n"); - print(" Board type: "); print(current_board->board_type); print("\n"); + print(" Board type: 0x"); puth(hw_type); print("\n"); // init board current_board->init(); @@ -384,9 +384,7 @@ int main(void) { enable_interrupts(); // LED should keep on blinking all the time - uint64_t cnt = 0; while (true) { - cnt++; if (power_save_status == POWER_SAVE_STATUS_DISABLED) { #ifdef DEBUG_FAULTS if (fault_status == FAULT_STATUS_NONE) { diff --git a/board/main_comms.h b/board/main_comms.h index 6fd20378708..4adfc8d744a 100644 --- a/board/main_comms.h +++ b/board/main_comms.h @@ -14,7 +14,7 @@ int get_health_pkt(void *dat) { // Use the GPIO pin to determine ignition or use a CAN based logic health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); - health->ignition_can_pkt = (uint8_t)(ignition_can); + health->ignition_can_pkt = ignition_can; health->controls_allowed_pkt = controls_allowed; health->safety_tx_blocked_pkt = safety_tx_blocked; @@ -26,8 +26,8 @@ int get_health_pkt(void *dat) { 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 = (uint8_t)(power_save_status == POWER_SAVE_STATUS_ENABLED); - health->heartbeat_lost_pkt = (uint8_t)(heartbeat_lost); + health->power_save_enabled_pkt = power_save_status == POWER_SAVE_STATUS_ENABLED; + health->heartbeat_lost_pkt = heartbeat_lost; health->safety_rx_checks_invalid = safety_rx_checks_invalid; health->spi_checksum_error_count = spi_checksum_error_count; @@ -55,7 +55,7 @@ int get_rtc_pkt(void *dat) { } // send on serial, first byte to select the ring -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +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)) { diff --git a/board/pedal/main.c b/board/pedal/main.c index 132044b705a..704ee543651 100644 --- a/board/pedal/main.c +++ b/board/pedal/main.c @@ -46,11 +46,11 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { UNUSED(max_len); return 0; } -void comms_can_write(uint8_t *data, uint32_t len) { +void comms_can_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +void comms_endpoint2_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } @@ -92,7 +92,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { // addresses to be used on CAN #define CAN_GAS_INPUT 0x200 -#define CAN_GAS_OUTPUT 0x201U +#define CAN_GAS_OUTPUT 0x201UL #define CAN_GAS_SIZE 6 #define COUNTER_CYCLE 0xFU diff --git a/board/safety.h b/board/safety.h index abbd51d3c35..e48a75502e8 100644 --- a/board/safety.h +++ b/board/safety.h @@ -57,12 +57,10 @@ uint16_t current_safety_param = 0; const safety_hooks *current_hooks = &nooutput_hooks; safety_config current_safety_config; -bool safety_rx_hook(CANPacket_t *to_push) { +bool safety_rx_hook(const CANPacket_t *to_push) { bool controls_allowed_prev = controls_allowed; - bool valid = rx_msg_safety_check(to_push, ¤t_safety_config, current_hooks->get_checksum, - current_hooks->compute_checksum, current_hooks->get_counter, - current_hooks->get_quality_flag_valid); + bool valid = rx_msg_safety_check(to_push, ¤t_safety_config, current_hooks); if (valid) { current_hooks->rx(to_push); } @@ -123,7 +121,7 @@ void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { } } -bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len) { +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); @@ -138,7 +136,7 @@ bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len) { return allowed; } -int get_addr_check_index(CANPacket_t *to_push, RxCheck addr_list[], const int len) { +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); @@ -222,37 +220,34 @@ void update_addr_timestamp(RxCheck addr_list[], int index) { } } -bool rx_msg_safety_check(CANPacket_t *to_push, - const safety_config *cfg, - const get_checksum_t get_checksum, - const compute_checksum_t compute_checksum, - const get_counter_t get_counter, - const get_quality_flag_valid_t get_quality_flag_valid) { +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 ((get_checksum != NULL) && (compute_checksum != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].check_checksum) { - uint32_t checksum = get_checksum(to_push); - uint32_t checksum_comp = compute_checksum(to_push); + 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 ((get_counter != NULL) && (cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].max_counter > 0U)) { - uint8_t counter = get_counter(to_push); + 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 ((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 = get_quality_flag_valid(to_push); + 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; } @@ -450,7 +445,7 @@ bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, } // check that commanded value isn't fighting against driver -bool driver_limit_check(int val, int val_last, struct sample_t *val_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) { @@ -547,7 +542,7 @@ bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limit return violation; } -bool longitudinal_interceptor_checks(CANPacket_t *to_send) { +bool longitudinal_interceptor_checks(const CANPacket_t *to_send) { return !get_longitudinal_allowed() && (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)); } diff --git a/board/safety/safety_body.h b/board/safety/safety_body.h index dc5e786662f..2ebca280f13 100644 --- a/board/safety/safety_body.h +++ b/board/safety/safety_body.h @@ -6,7 +6,7 @@ RxCheck body_rx_checks[] = { {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, }; -static void body_rx_hook(CANPacket_t *to_push) { +static void body_rx_hook(const CANPacket_t *to_push) { // body is never at standstill vehicle_moving = true; @@ -15,7 +15,7 @@ static void body_rx_hook(CANPacket_t *to_push) { } } -static bool body_tx_hook(CANPacket_t *to_send) { +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); diff --git a/board/safety/safety_chrysler.h b/board/safety/safety_chrysler.h index 7fb237c9255..65d2406818b 100644 --- a/board/safety/safety_chrysler.h +++ b/board/safety/safety_chrysler.h @@ -28,12 +28,38 @@ const SteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = { .type = TorqueMotorLimited, }; +const LongitudinalLimits CHRYSLER_LONG_LIMITS = { + // acceleration cmd limits (used for brakes) + // Signal: ACC_DECEL + .max_accel = 3685, // 3685 x 0.004885 - 16 = 2.0 m/s^2 + .min_accel = 2558, // 2558 x 0.004885 - 16 = -3.5 m/s^2 + .inactive_accel = 4094, // 4094 x 0.004885 - 16 = 4.0 m/s^2 + + // gas cmd limits + // Signal: ENGINE_TORQUE_REQUEST + .max_gas = 4000, // 4000 x .25 - 500 = 500.0 Nm + .min_gas = 0, // 0 x .25 - 500 = -500.0 Nm + .inactive_gas = 2000, // 2000 x .25 - 500 = 0.0 Nm +}; + +enum { + CHRYSLER_BTN_NONE = 0, + CHRYSLER_BTN_CANCEL = 1, + CHRYSLER_BTN_ACCEL = 4, + CHRYSLER_BTN_DECEL = 8, + CHRYSLER_BTN_RESUME = 16, +}; + +bool chrysler_longitudinal = false; + 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_4; + const int DAS_5; const int DAS_6; const int LKAS_COMMAND; const int CRUISE_BUTTONS; @@ -45,7 +71,9 @@ const ChryslerAddrs CHRYSLER_ADDRS = { .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_3 = 0x1F4, // ACC state and control from DASM + .DAS_4 = 0x1F5, // ACC and FCW dispaly and config from DASM + .DAS_5 = 0x271, // ACC and FCW dispaly and config 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 @@ -57,7 +85,9 @@ const ChryslerAddrs CHRYSLER_RAM_DT_ADDRS = { .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_3 = 0x99, // ACC state and control from DASM + .DAS_4 = 0xE8, // ACC and FCW dispaly and config from DASM + .DAS_5 = 0xA3, // ACC and FCW dispaly and config 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 @@ -69,59 +99,108 @@ const ChryslerAddrs CHRYSLER_RAM_HD_ADDRS = { .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_3 = 0x1F4, // ACC state and control from DASM + .DAS_4 = 0x1F5, // ACC and FCW dispaly and config from DASM + .DAS_5 = 0x271, // ACC and FCW dispaly and config 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 }; +#define CHRYSLER_COMMON_TX_MSGS(addrs, cruise_buttons_bus, lkas_cmd_len) \ + {(addrs).CRUISE_BUTTONS, (cruise_buttons_bus), 3}, \ + {(addrs).LKAS_COMMAND, 0, (lkas_cmd_len)}, \ + {(addrs).DAS_6, 0, 8}, \ + +#define CHRYSLER_COMMON_LONG_TX_MSGS(addrs) \ + {(addrs).DAS_3, 0, 8}, \ + {(addrs).DAS_4, 0, 8}, \ + {(addrs).DAS_5, 0, 8}, \ + const CanMsg CHRYSLER_TX_MSGS[] = { - {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3}, - {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6}, - {CHRYSLER_ADDRS.DAS_6, 0, 8}, + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_ADDRS, 0, 6) +}; + +const CanMsg CHRYSLER_LONG_TX_MSGS[] = { + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_ADDRS, 0, 6) + CHRYSLER_COMMON_LONG_TX_MSGS(CHRYSLER_ADDRS) }; 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}, + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_RAM_DT_ADDRS, 2, 8) +}; + +const CanMsg CHRYSLER_RAM_DT_LONG_TX_MSGS[] = { + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_RAM_DT_ADDRS, 2, 8) + CHRYSLER_COMMON_LONG_TX_MSGS(CHRYSLER_RAM_DT_ADDRS) }; 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}, + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_RAM_HD_ADDRS, 2, 8) +}; + +const CanMsg CHRYSLER_RAM_HD_LONG_TX_MSGS[] = { + CHRYSLER_COMMON_TX_MSGS(CHRYSLER_RAM_HD_ADDRS, 2, 8) + CHRYSLER_COMMON_LONG_TX_MSGS(CHRYSLER_RAM_HD_ADDRS) }; +#define CHRYSLER_COMMON_RX_CHECKS(addrs) \ + {.msg = {{(addrs).EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ + {.msg = {{(addrs).ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{(addrs).ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + +// TODO: use the same message for both (see vehicle_moving below) +#define CHRYSLER_COMMON_ALT_RX_CHECKS() \ + {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, \ + +#define CHRYSLER_COMMON_RAM_RX_CHECKS(addrs) \ + {.msg = {{(addrs).ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + +#define CHRYSLER_COMMON_ACC_RX_CHECKS(addrs, das_3_bus) \ + {.msg = {{(addrs).DAS_3, (das_3_bus), 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + +#define CHRYSLER_COMMON_BUTTONS_RX_CHECKS(addrs) \ + {.msg = {{(addrs).CRUISE_BUTTONS, 0, 3, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + 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 }}}, + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_ADDRS) + CHRYSLER_COMMON_ALT_RX_CHECKS() + CHRYSLER_COMMON_ACC_RX_CHECKS(CHRYSLER_ADDRS, 0) +}; + +RxCheck chrysler_long_rx_checks[] = { + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_ADDRS) + CHRYSLER_COMMON_ALT_RX_CHECKS() + CHRYSLER_COMMON_BUTTONS_RX_CHECKS(CHRYSLER_ADDRS) }; 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 }}}, + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS) + CHRYSLER_COMMON_RAM_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS) + CHRYSLER_COMMON_ACC_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS, 2) }; -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 }}}, +RxCheck chrysler_ram_dt_long_rx_checks[] = { + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS) + CHRYSLER_COMMON_RAM_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS) + CHRYSLER_COMMON_BUTTONS_RX_CHECKS(CHRYSLER_RAM_DT_ADDRS) }; +RxCheck chrysler_ram_hd_rx_checks[] = { + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS) + CHRYSLER_COMMON_RAM_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS) + CHRYSLER_COMMON_ACC_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS, 2) +}; +RxCheck chrysler_ram_hd_long_rx_checks[] = { + CHRYSLER_COMMON_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS) + CHRYSLER_COMMON_RAM_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS) + CHRYSLER_COMMON_BUTTONS_RX_CHECKS(CHRYSLER_RAM_HD_ADDRS) +}; 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 +const uint32_t CHRYSLER_PARAM_LONGITUDINAL = 4U; enum { CHRYSLER_RAM_DT, @@ -130,12 +209,12 @@ enum { } chrysler_platform = CHRYSLER_PACIFICA; const ChryslerAddrs *chrysler_addrs = &CHRYSLER_ADDRS; -static uint32_t chrysler_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +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; @@ -168,25 +247,53 @@ static uint32_t chrysler_compute_checksum(CANPacket_t *to_push) { return (uint8_t)(~checksum); } -static uint8_t chrysler_get_counter(CANPacket_t *to_push) { - return (uint8_t)(GET_BYTE(to_push, 6) >> 4); +static uint8_t chrysler_get_counter(const CANPacket_t *to_push) { + int counter_byte = GET_LEN(to_push) - 2U; + return (uint8_t)(GET_BYTE(to_push, counter_byte) >> 4); } -static void chrysler_rx_hook(CANPacket_t *to_push) { +static void chrysler_rx_hook(const CANPacket_t *to_push) { const int bus = GET_BUS(to_push); const int addr = GET_ADDR(to_push); + if ((bus == 0) && (addr == chrysler_addrs->CRUISE_BUTTONS) && chrysler_longitudinal) { + int cruise_button = GET_BIT(to_push, 0U); // cancel button + // ensure cancel overrides any multi-button pressed state + if (!cruise_button) { + cruise_button |= GET_BIT(to_push, 2U) << 2U; // accel button + cruise_button |= GET_BIT(to_push, 3U) << 3U; // decel button + cruise_button |= GET_BIT(to_push, 4U) << 4U; // resume button + } + + // enter controls on falling edge of accel/decel/resume + bool accel = (cruise_button != CHRYSLER_BTN_ACCEL) && (cruise_button_prev == CHRYSLER_BTN_ACCEL); + bool decel = (cruise_button != CHRYSLER_BTN_DECEL) && (cruise_button_prev == CHRYSLER_BTN_DECEL); + bool resume = (cruise_button != CHRYSLER_BTN_RESUME) && (cruise_button_prev == CHRYSLER_BTN_RESUME); + if (accel || decel || resume) { + controls_allowed = true; + } + + // exit controls on cancel press + if (cruise_button == CHRYSLER_BTN_CANCEL) { + controls_allowed = false; + } + + cruise_button_prev = cruise_button; + } + // 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)) { - bool cruise_engaged = GET_BIT(to_push, 21U) == 1U; - pcm_cruise_check(cruise_engaged); + if (!chrysler_longitudinal) { + // 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)) { + bool cruise_engaged = GET_BIT(to_push, 21U) == 1U; + pcm_cruise_check(cruise_engaged); + } } // TODO: use the same message for both @@ -213,7 +320,7 @@ static void chrysler_rx_hook(CANPacket_t *to_push) { generic_rx_checks((bus == 0) && (addr == chrysler_addrs->LKAS_COMMAND)); } -static bool chrysler_tx_hook(CANPacket_t *to_send) { +static bool chrysler_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); @@ -232,8 +339,24 @@ static bool chrysler_tx_hook(CANPacket_t *to_send) { } } + // ACCEL + if (tx && (addr == chrysler_addrs->DAS_3)) { + // Signal: ENGINE_TORQUE_REQUEST + int gas = (((GET_BYTE(to_send, 0) & 0x1FU) << 8) | GET_BYTE(to_send, 1)); + // Signal: ACC_DECEL + int accel = (((GET_BYTE(to_send, 2) & 0xFU) << 8) | GET_BYTE(to_send, 3)); + + bool violation = false; + violation |= longitudinal_accel_checks(accel, CHRYSLER_LONG_LIMITS); + violation |= longitudinal_gas_checks(gas, CHRYSLER_LONG_LIMITS); + + if (violation) { + tx = 0; + } + } + // FORCE CANCEL: only the cancel button press is allowed - if (addr == chrysler_addrs->CRUISE_BUTTONS) { + if ((addr == chrysler_addrs->CRUISE_BUTTONS) && !chrysler_longitudinal) { 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); @@ -255,7 +378,8 @@ static int chrysler_fwd_hook(int bus_num, int addr) { // 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){ + const bool is_acc = ((addr == chrysler_addrs->DAS_3) || (addr == chrysler_addrs->DAS_4) || (addr == chrysler_addrs->DAS_5)); + if ((bus_num == 2) && !is_lkas && !(chrysler_longitudinal && is_acc)) { bus_fwd = 0; } @@ -263,21 +387,27 @@ static int chrysler_fwd_hook(int bus_num, int addr) { } static safety_config chrysler_init(uint16_t param) { +#ifdef ALLOW_DEBUG + chrysler_longitudinal = GET_FLAG(param, CHRYSLER_PARAM_LONGITUDINAL); +#else + chrysler_longitudinal = false; +#endif + safety_config ret; if (GET_FLAG(param, CHRYSLER_PARAM_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); + ret = chrysler_longitudinal ? BUILD_SAFETY_CFG(chrysler_ram_dt_long_rx_checks, CHRYSLER_RAM_DT_LONG_TX_MSGS) : 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); + ret = chrysler_longitudinal ? BUILD_SAFETY_CFG(chrysler_ram_hd_long_rx_checks, CHRYSLER_RAM_HD_LONG_TX_MSGS) : 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); + ret = chrysler_longitudinal ? BUILD_SAFETY_CFG(chrysler_long_rx_checks, CHRYSLER_LONG_TX_MSGS) : BUILD_SAFETY_CFG(chrysler_rx_checks, CHRYSLER_TX_MSGS); } return ret; } diff --git a/board/safety/safety_defaults.h b/board/safety/safety_defaults.h index 1ce1ee2edb4..6c47dba3d64 100644 --- a/board/safety/safety_defaults.h +++ b/board/safety/safety_defaults.h @@ -1,4 +1,4 @@ -void default_rx_hook(CANPacket_t *to_push) { +void default_rx_hook(const CANPacket_t *to_push) { UNUSED(to_push); } @@ -9,7 +9,7 @@ static safety_config nooutput_init(uint16_t param) { return (safety_config){NULL, 0, NULL, 0}; } -static bool nooutput_tx_hook(CANPacket_t *to_send) { +static bool nooutput_tx_hook(const CANPacket_t *to_send) { UNUSED(to_send); return false; } @@ -39,7 +39,7 @@ static safety_config alloutput_init(uint16_t param) { return (safety_config){NULL, 0, NULL, 0}; } -static bool alloutput_tx_hook(CANPacket_t *to_send) { +static bool alloutput_tx_hook(const CANPacket_t *to_send) { UNUSED(to_send); return true; } diff --git a/board/safety/safety_elm327.h b/board/safety/safety_elm327.h index 84433239fbe..5c4fd221661 100644 --- a/board/safety/safety_elm327.h +++ b/board/safety/safety_elm327.h @@ -1,4 +1,4 @@ -static bool elm327_tx_hook(CANPacket_t *to_send) { +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); diff --git a/board/safety/safety_ford.h b/board/safety/safety_ford.h index f6c7a29bee8..6ab123be69b 100644 --- a/board/safety/safety_ford.h +++ b/board/safety/safety_ford.h @@ -68,7 +68,7 @@ RxCheck ford_rx_checks[] = { {.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, }; -static uint8_t ford_get_counter(CANPacket_t *to_push) { +static uint8_t ford_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0; @@ -83,7 +83,7 @@ static uint8_t ford_get_counter(CANPacket_t *to_push) { return cnt; } -static uint32_t ford_get_checksum(CANPacket_t *to_push) { +static uint32_t ford_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -101,7 +101,7 @@ static uint32_t ford_get_checksum(CANPacket_t *to_push) { return chksum; } -static uint32_t ford_compute_checksum(CANPacket_t *to_push) { +static uint32_t ford_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -128,7 +128,7 @@ static uint32_t ford_compute_checksum(CANPacket_t *to_push) { return chksum; } -static bool ford_get_quality_flag_valid(CANPacket_t *to_push) { +static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); bool valid = false; @@ -201,7 +201,7 @@ const SteeringLimits FORD_STEERING_LIMITS = { .inactive_angle_is_zero = true, }; -static void ford_rx_hook(CANPacket_t *to_push) { +static void ford_rx_hook(const CANPacket_t *to_push) { if (GET_BUS(to_push) == FORD_MAIN_BUS) { int addr = GET_ADDR(to_push); @@ -265,7 +265,7 @@ static void ford_rx_hook(CANPacket_t *to_push) { } -static bool ford_tx_hook(CANPacket_t *to_send) { +static bool ford_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); diff --git a/board/safety/safety_gm.h b/board/safety/safety_gm.h index 250c103a0cd..fd944761e62 100644 --- a/board/safety/safety_gm.h +++ b/board/safety/safety_gm.h @@ -64,7 +64,7 @@ enum {GM_ASCM, GM_CAM} gm_hw = GM_ASCM; bool gm_cam_long = false; bool gm_pcm_cruise = false; -static void gm_rx_hook(CANPacket_t *to_push) { +static void gm_rx_hook(const CANPacket_t *to_push) { if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -135,7 +135,7 @@ static void gm_rx_hook(CANPacket_t *to_push) { } } -static bool gm_tx_hook(CANPacket_t *to_send) { +static bool gm_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); diff --git a/board/safety/safety_honda.h b/board/safety/safety_honda.h index dde27cdb0f5..7bbc8e66165 100644 --- a/board/safety/safety_honda.h +++ b/board/safety/safety_honda.h @@ -104,12 +104,12 @@ int honda_get_pt_bus(void) { return ((honda_hw == HONDA_BOSCH) && !honda_bosch_radarless) ? 1 : 0; } -static uint32_t honda_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +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); @@ -126,7 +126,7 @@ static uint32_t honda_compute_checksum(CANPacket_t *to_push) { return (uint8_t)((8U - checksum) & 0xFU); } -static uint8_t honda_get_counter(CANPacket_t *to_push) { +static uint8_t honda_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0U; @@ -140,7 +140,7 @@ static uint8_t honda_get_counter(CANPacket_t *to_push) { return cnt; } -static void honda_rx_hook(CANPacket_t *to_push) { +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(); @@ -269,7 +269,7 @@ static void honda_rx_hook(CANPacket_t *to_push) { } -static bool honda_tx_hook(CANPacket_t *to_send) { +static bool honda_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); diff --git a/board/safety/safety_hyundai.h b/board/safety/safety_hyundai.h index 1f468e69ca0..d88762c0d0d 100644 --- a/board/safety/safety_hyundai.h +++ b/board/safety/safety_hyundai.h @@ -85,7 +85,7 @@ RxCheck hyundai_legacy_rx_checks[] = { bool hyundai_legacy = false; -static uint8_t hyundai_get_counter(CANPacket_t *to_push) { +static uint8_t hyundai_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0; @@ -104,7 +104,7 @@ static uint8_t hyundai_get_counter(CANPacket_t *to_push) { return cnt; } -static uint32_t hyundai_get_checksum(CANPacket_t *to_push) { +static uint32_t hyundai_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -121,7 +121,7 @@ static uint32_t hyundai_get_checksum(CANPacket_t *to_push) { return chksum; } -static uint32_t hyundai_compute_checksum(CANPacket_t *to_push) { +static uint32_t hyundai_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -157,7 +157,7 @@ static uint32_t hyundai_compute_checksum(CANPacket_t *to_push) { return chksum; } -static void hyundai_rx_hook(CANPacket_t *to_push) { +static void hyundai_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); @@ -214,7 +214,7 @@ static void hyundai_rx_hook(CANPacket_t *to_push) { } } -static bool hyundai_tx_hook(CANPacket_t *to_send) { +static bool hyundai_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); diff --git a/board/safety/safety_hyundai_canfd.h b/board/safety/safety_hyundai_canfd.h index daa72d2386f..be026a9840c 100644 --- a/board/safety/safety_hyundai_canfd.h +++ b/board/safety/safety_hyundai_canfd.h @@ -137,7 +137,7 @@ int hyundai_canfd_hda2_get_lkas_addr(void) { return hyundai_canfd_hda2_alt_steering ? 0x110 : 0x50; } -static uint8_t hyundai_canfd_get_counter(CANPacket_t *to_push) { +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; @@ -147,12 +147,12 @@ static uint8_t hyundai_canfd_get_counter(CANPacket_t *to_push) { return ret; } -static uint32_t hyundai_canfd_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); @@ -227,7 +227,7 @@ static void hyundai_canfd_rx_hook(CANPacket_t *to_push) { } -static bool hyundai_canfd_tx_hook(CANPacket_t *to_send) { +static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); diff --git a/board/safety/safety_hyundai_common.h b/board/safety/safety_hyundai_common.h index 0b9116d1471..2c89bfb7a83 100644 --- a/board/safety/safety_hyundai_common.h +++ b/board/safety/safety_hyundai_common.h @@ -87,7 +87,7 @@ void hyundai_common_cruise_buttons_check(const int cruise_button, const int main } } -uint32_t hyundai_common_canfd_compute_checksum(CANPacket_t *to_push) { +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); diff --git a/board/safety/safety_mazda.h b/board/safety/safety_mazda.h index 67561a15f1c..7c6d8be9c78 100644 --- a/board/safety/safety_mazda.h +++ b/board/safety/safety_mazda.h @@ -34,7 +34,7 @@ RxCheck mazda_rx_checks[] = { }; // track msgs coming from OP so that we know what CAM msgs to drop and what to forward -static void mazda_rx_hook(CANPacket_t *to_push) { +static void mazda_rx_hook(const CANPacket_t *to_push) { if ((int)GET_BUS(to_push) == MAZDA_MAIN) { int addr = GET_ADDR(to_push); @@ -68,7 +68,7 @@ static void mazda_rx_hook(CANPacket_t *to_push) { } } -static bool mazda_tx_hook(CANPacket_t *to_send) { +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); diff --git a/board/safety/safety_nissan.h b/board/safety/safety_nissan.h index afb135c8272..2317727385d 100644 --- a/board/safety/safety_nissan.h +++ b/board/safety/safety_nissan.h @@ -40,7 +40,7 @@ const int NISSAN_PARAM_ALT_EPS_BUS = 1; bool nissan_alt_eps = false; -static void nissan_rx_hook(CANPacket_t *to_push) { +static void nissan_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); @@ -93,7 +93,7 @@ static void nissan_rx_hook(CANPacket_t *to_push) { } -static bool nissan_tx_hook(CANPacket_t *to_send) { +static bool nissan_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; diff --git a/board/safety/safety_subaru.h b/board/safety/safety_subaru.h index 12868d40fda..201c6fe5e79 100644 --- a/board/safety/safety_subaru.h +++ b/board/safety/safety_subaru.h @@ -115,15 +115,15 @@ bool subaru_gen2 = false; bool subaru_longitudinal = false; -static uint32_t subaru_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +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); @@ -133,7 +133,7 @@ static uint32_t subaru_compute_checksum(CANPacket_t *to_push) { return checksum; } -static void subaru_rx_hook(CANPacket_t *to_push) { +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; @@ -179,7 +179,7 @@ static void subaru_rx_hook(CANPacket_t *to_push) { generic_rx_checks((addr == MSG_SUBARU_ES_LKAS) && (bus == SUBARU_MAIN_BUS)); } -static bool subaru_tx_hook(CANPacket_t *to_send) { +static bool subaru_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; diff --git a/board/safety/safety_subaru_preglobal.h b/board/safety/safety_subaru_preglobal.h index 16a16882272..37e389afb25 100644 --- a/board/safety/safety_subaru_preglobal.h +++ b/board/safety/safety_subaru_preglobal.h @@ -41,7 +41,7 @@ const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1; bool subaru_pg_reversed_driver_torque = false; -static void subaru_preglobal_rx_hook(CANPacket_t *to_push) { +static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { const int bus = GET_BUS(to_push); if (bus == SUBARU_PG_MAIN_BUS) { @@ -77,7 +77,7 @@ static void subaru_preglobal_rx_hook(CANPacket_t *to_push) { } } -static bool subaru_preglobal_tx_hook(CANPacket_t *to_send) { +static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); diff --git a/board/safety/safety_tesla.h b/board/safety/safety_tesla.h index 66d11960a51..4fa0df84aa4 100644 --- a/board/safety/safety_tesla.h +++ b/board/safety/safety_tesla.h @@ -54,7 +54,7 @@ bool tesla_powertrain = false; // Are we the second panda intercepting the powe bool tesla_stock_aeb = false; -static void tesla_rx_hook(CANPacket_t *to_push) { +static void tesla_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); @@ -116,7 +116,7 @@ static void tesla_rx_hook(CANPacket_t *to_push) { } -static bool tesla_tx_hook(CANPacket_t *to_send) { +static bool tesla_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; diff --git a/board/safety/safety_toyota.h b/board/safety/safety_toyota.h index fc87c48f807..0f7e671c4a1 100644 --- a/board/safety/safety_toyota.h +++ b/board/safety/safety_toyota.h @@ -86,18 +86,18 @@ RxCheck toyota_lta_interceptor_rx_checks[] = { // 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 = (1U << TOYOTA_PARAM_OFFSET) - 1U; -const uint32_t TOYOTA_PARAM_ALT_BRAKE = 1U << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_STOCK_LONGITUDINAL = 2U << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_LTA = 4U << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_GAS_INTERCEPTOR = 8U << TOYOTA_PARAM_OFFSET; +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(CANPacket_t *to_push) { +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); @@ -107,12 +107,12 @@ static uint32_t toyota_compute_checksum(CANPacket_t *to_push) { return checksum; } -static uint32_t toyota_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +static uint8_t toyota_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0U; @@ -123,7 +123,7 @@ static uint8_t toyota_get_counter(CANPacket_t *to_push) { return cnt; } -static bool toyota_get_quality_flag_valid(CANPacket_t *to_push) { +static bool toyota_get_quality_flag_valid(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); bool valid = false; @@ -133,7 +133,7 @@ static bool toyota_get_quality_flag_valid(CANPacket_t *to_push) { return valid; } -static void toyota_rx_hook(CANPacket_t *to_push) { +static void toyota_rx_hook(const CANPacket_t *to_push) { if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -213,7 +213,7 @@ static void toyota_rx_hook(CANPacket_t *to_push) { } } -static bool toyota_tx_hook(CANPacket_t *to_send) { +static bool toyota_tx_hook(const CANPacket_t *to_send) { bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); diff --git a/board/safety/safety_volkswagen_mqb.h b/board/safety/safety_volkswagen_mqb.h index f671443f756..3145ea9072e 100644 --- a/board/safety/safety_volkswagen_mqb.h +++ b/board/safety/safety_volkswagen_mqb.h @@ -52,16 +52,16 @@ uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F bool volkswagen_mqb_brake_pedal_switch = false; bool volkswagen_mqb_brake_pressure_detected = false; -static uint32_t volkswagen_mqb_get_checksum(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +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(CANPacket_t *to_push) { +static uint32_t volkswagen_mqb_compute_crc(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); @@ -107,7 +107,7 @@ static safety_config volkswagen_mqb_init(uint16_t param) { BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_STOCK_TX_MSGS); } -static void volkswagen_mqb_rx_hook(CANPacket_t *to_push) { +static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) { if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -193,7 +193,7 @@ static void volkswagen_mqb_rx_hook(CANPacket_t *to_push) { } } -static bool volkswagen_mqb_tx_hook(CANPacket_t *to_send) { +static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { int addr = GET_ADDR(to_send); bool tx = true; diff --git a/board/safety/safety_volkswagen_pq.h b/board/safety/safety_volkswagen_pq.h index b81e0f0bf15..b9a2eedd726 100644 --- a/board/safety/safety_volkswagen_pq.h +++ b/board/safety/safety_volkswagen_pq.h @@ -46,13 +46,13 @@ RxCheck volkswagen_pq_rx_checks[] = { {.msg = {{MSG_GRA_NEU, 0, 4, .check_checksum = true, .max_counter = 15U, .frequency = 30U}, { 0 }, { 0 }}}, }; -static uint32_t volkswagen_pq_get_checksum(CANPacket_t *to_push) { +static uint32_t volkswagen_pq_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); return (uint32_t)GET_BYTE(to_push, (addr == MSG_MOTOR_5) ? 7 : 0); } -static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { +static uint8_t volkswagen_pq_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t counter = 0U; @@ -66,7 +66,7 @@ static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { return counter; } -static uint32_t volkswagen_pq_compute_checksum(CANPacket_t *to_push) { +static uint32_t volkswagen_pq_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); uint8_t checksum = 0U; @@ -95,7 +95,7 @@ static safety_config volkswagen_pq_init(uint16_t param) { BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_STOCK_TX_MSGS); } -static void volkswagen_pq_rx_hook(CANPacket_t *to_push) { +static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) { if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -169,7 +169,7 @@ static void volkswagen_pq_rx_hook(CANPacket_t *to_push) { } } -static bool volkswagen_pq_tx_hook(CANPacket_t *to_send) { +static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { int addr = GET_ADDR(to_send); bool tx = true; diff --git a/board/safety_declarations.h b/board/safety_declarations.h index dbe1a707762..eb4ece47416 100644 --- a/board/safety_declarations.h +++ b/board/safety_declarations.h @@ -144,12 +144,28 @@ typedef struct { int tx_msgs_len; } safety_config; -typedef uint32_t (*get_checksum_t)(CANPacket_t *to_push); -typedef uint32_t (*compute_checksum_t)(CANPacket_t *to_push); -typedef uint8_t (*get_counter_t)(CANPacket_t *to_push); -typedef bool (*get_quality_flag_valid_t)(CANPacket_t *to_push); +typedef uint32_t (*get_checksum_t)(const CANPacket_t *to_push); +typedef uint32_t (*compute_checksum_t)(const CANPacket_t *to_push); +typedef uint8_t (*get_counter_t)(const CANPacket_t *to_push); +typedef bool (*get_quality_flag_valid_t)(const CANPacket_t *to_push); -bool safety_rx_hook(CANPacket_t *to_push); +typedef safety_config (*safety_hook_init)(uint16_t param); +typedef void (*rx_hook)(const CANPacket_t *to_push); +typedef bool (*tx_hook)(const CANPacket_t *to_send); +typedef int (*fwd_hook)(int bus_num, int addr); + +typedef struct { + safety_hook_init init; + rx_hook rx; + tx_hook tx; + fwd_hook fwd; + get_checksum_t get_checksum; + compute_checksum_t compute_checksum; + get_counter_t get_counter; + get_quality_flag_valid_t get_quality_flag_valid; +} safety_hooks; + +bool safety_rx_hook(const CANPacket_t *to_push); bool safety_tx_hook(CANPacket_t *to_send); uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); int to_signed(int d, int bits); @@ -160,7 +176,7 @@ bool angle_dist_to_meas_check(int val, struct sample_t *val_meas, const int MAX_ERROR, const int MAX_VAL); bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); -bool driver_limit_check(int val, int val_last, struct sample_t *val_driver, +bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver, const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ALLOWANCE, const int DRIVER_FACTOR); bool get_longitudinal_allowed(void); @@ -169,17 +185,14 @@ float interpolate(struct lookup_t xy, float x); int ROUND(float val); void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]); void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]); -bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len); -int get_addr_check_index(CANPacket_t *to_push, RxCheck addr_list[], const int len); +bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len); +int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len); void update_counter(RxCheck addr_list[], int index, uint8_t counter); void update_addr_timestamp(RxCheck addr_list[], int index); bool is_msg_valid(RxCheck addr_list[], int index); -bool rx_msg_safety_check(CANPacket_t *to_push, - const safety_config *rx_checks, - const get_checksum_t get_checksum, - const compute_checksum_t compute_checksum, - const get_counter_t get_counter, - const get_quality_flag_valid_t get_quality_flag); +bool rx_msg_safety_check(const CANPacket_t *to_push, + const safety_config *cfg, + const safety_hooks *safety_hooks); void generic_rx_checks(bool stock_ecu_detected); void relay_malfunction_set(void); void relay_malfunction_reset(void); @@ -190,25 +203,9 @@ bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limit bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits); bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits); bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limits); -bool longitudinal_interceptor_checks(CANPacket_t *to_send); +bool longitudinal_interceptor_checks(const CANPacket_t *to_send); void pcm_cruise_check(bool cruise_engaged); -typedef safety_config (*safety_hook_init)(uint16_t param); -typedef void (*rx_hook)(CANPacket_t *to_push); -typedef bool (*tx_hook)(CANPacket_t *to_send); -typedef int (*fwd_hook)(int bus_num, int addr); - -typedef struct { - safety_hook_init init; - rx_hook rx; - tx_hook tx; - fwd_hook fwd; - get_checksum_t get_checksum; - compute_checksum_t compute_checksum; - get_counter_t get_counter; - get_quality_flag_valid_t get_quality_flag_valid; -} safety_hooks; - void safety_tick(const safety_config *safety_config); // This can be set by the safety hooks diff --git a/board/stm32fx/llbxcan.h b/board/stm32fx/llbxcan.h index fd344913f77..a6c5936f050 100644 --- a/board/stm32fx/llbxcan.h +++ b/board/stm32fx/llbxcan.h @@ -75,7 +75,7 @@ bool llcan_set_speed(CAN_TypeDef *CANx, uint32_t speed, bool loopback, bool sile return ret; } -void llcan_irq_disable(CAN_TypeDef *CANx) { +void llcan_irq_disable(const CAN_TypeDef *CANx) { if (CANx == CAN1) { NVIC_DisableIRQ(CAN1_TX_IRQn); NVIC_DisableIRQ(CAN1_RX0_IRQn); @@ -94,7 +94,7 @@ void llcan_irq_disable(CAN_TypeDef *CANx) { } } -void llcan_irq_enable(CAN_TypeDef *CANx) { +void llcan_irq_enable(const CAN_TypeDef *CANx) { if (CANx == CAN1) { NVIC_EnableIRQ(CAN1_TX_IRQn); NVIC_EnableIRQ(CAN1_RX0_IRQn); @@ -140,7 +140,7 @@ bool llcan_init(CAN_TypeDef *CANx) { CANx->sFilterRegister[0].FR2 = 0U; CANx->sFilterRegister[14].FR1 = 0U; CANx->sFilterRegister[14].FR2 = 0U; - CANx->FA1R |= 1U | (1U << 14); + CANx->FA1R |= 1U | (1UL << 14); // Exit init mode, do not wait register_clear_bits(&(CANx->FMR), CAN_FMR_FINIT); diff --git a/board/stm32fx/llusb.h b/board/stm32fx/llusb.h index 26ebd03ce38..b6eea1dad2a 100644 --- a/board/stm32fx/llusb.h +++ b/board/stm32fx/llusb.h @@ -7,7 +7,7 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; #define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) #define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) -#define USBD_FS_TRDT_VALUE 5U +#define USBD_FS_TRDT_VALUE 5UL #define USB_OTG_SPEED_FULL 3 diff --git a/board/stm32h7/board.h b/board/stm32h7/board.h index d991e433b10..d293a54cfe3 100644 --- a/board/stm32h7/board.h +++ b/board/stm32h7/board.h @@ -16,8 +16,8 @@ #include "drivers/clock_source.h" #include "boards/red.h" #include "boards/red_chiplet.h" -#include "boards/red_v2.h" #include "boards/tres.h" +#include "boards/cuatro.h" uint8_t get_board_id(void) { @@ -34,13 +34,22 @@ void detect_board_type(void) { hw_type = HW_TYPE_RED_PANDA; current_board = &board_red; } else if (board_id == 1U) { - hw_type = HW_TYPE_RED_PANDA_V2; - current_board = &board_red_v2; + // deprecated + //hw_type = HW_TYPE_RED_PANDA_V2; } else if (board_id == 2U) { hw_type = HW_TYPE_TRES; current_board = &board_tres; + } else if (board_id == 3U) { + hw_type = HW_TYPE_CUATRO; + current_board = &board_tres; } else { hw_type = HW_TYPE_UNKNOWN; print("Hardware type is UNKNOWN!\n"); } + + // TODO: detect this live +#ifdef STM32H723 + hw_type = HW_TYPE_CUATRO; + current_board = &board_cuatro; +#endif } diff --git a/board/stm32h7/clock.h b/board/stm32h7/clock.h index c5f93cd02ef..fc221c55216 100644 --- a/board/stm32h7/clock.h +++ b/board/stm32h7/clock.h @@ -18,12 +18,14 @@ PCLK1: 60MHz (for USART2,3,4,5,7,8) */ void clock_init(void) { - //Set power mode to direct SMPS power supply(depends on the board layout) + // Set power mode to direct SMPS power supply(depends on the board layout) +#ifndef STM32H723 register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS - //Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) + // Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) register_set(&(PWR->D3CR), PWR_D3CR_VOS_1 | PWR_D3CR_VOS_0, 0xC000U); //VOS1, needed for 80Mhz CAN FD while ((PWR->CSR1 & PWR_CSR1_ACTVOSRDY) == 0); while ((PWR->CSR1 & PWR_CSR1_ACTVOS) != (PWR->D3CR & PWR_D3CR_VOS)); // check that VOS level was actually set +#endif // Configure Flash ACR register LATENCY and WRHIGHFREQ (VOS0 range!) register_set(&(FLASH->ACR), FLASH_ACR_LATENCY_2WS | 0x20U, 0x3FU); // VOS2, AXI 100MHz-150MHz // enable external oscillator HSE diff --git a/board/stm32h7/lldac.h b/board/stm32h7/lldac.h index 77e333e5c8c..5726f62413d 100644 --- a/board/stm32h7/lldac.h +++ b/board/stm32h7/lldac.h @@ -28,7 +28,7 @@ void dac_init(DAC_TypeDef *dac, uint8_t channel, bool dma) { // Set channel 1 value, in mV void dac_set(DAC_TypeDef *dac, uint8_t channel, uint32_t value) { - uint32_t raw_val = MAX(MIN(value * (1U << 8U) / 3300U, (1U << 8U)), 0U); + uint32_t raw_val = MAX(MIN(value * (1UL << 8U) / 3300U, (1UL << 8U)), 0U); switch(channel) { case 1: register_set(&dac->DHR8R1, raw_val, 0xFFU); diff --git a/board/stm32h7/llfdcan.h b/board/stm32h7/llfdcan.h index 323a7764b66..cdce0c4480e 100644 --- a/board/stm32h7/llfdcan.h +++ b/board/stm32h7/llfdcan.h @@ -158,7 +158,7 @@ bool llcan_set_speed(FDCAN_GlobalTypeDef *FDCANx, uint32_t speed, uint32_t data_ return ret; } -void llcan_irq_disable(FDCAN_GlobalTypeDef *FDCANx) { +void llcan_irq_disable(const FDCAN_GlobalTypeDef *FDCANx) { if (FDCANx == FDCAN1) { NVIC_DisableIRQ(FDCAN1_IT0_IRQn); NVIC_DisableIRQ(FDCAN1_IT1_IRQn); @@ -172,7 +172,7 @@ void llcan_irq_disable(FDCAN_GlobalTypeDef *FDCANx) { } } -void llcan_irq_enable(FDCAN_GlobalTypeDef *FDCANx) { +void llcan_irq_enable(const FDCAN_GlobalTypeDef *FDCANx) { if (FDCANx == FDCAN1) { NVIC_EnableIRQ(FDCAN1_IT0_IRQn); NVIC_EnableIRQ(FDCAN1_IT1_IRQn); diff --git a/board/stm32h7/lli2c.h b/board/stm32h7/lli2c.h index 55bbe9cf978..1dd4b4cf7ea 100644 --- a/board/stm32h7/lli2c.h +++ b/board/stm32h7/lli2c.h @@ -5,7 +5,7 @@ #define I2C_TIMEOUT_US 100000U // cppcheck-suppress misra-c2012-2.7; not sure why it triggers here? -bool i2c_status_wait(volatile uint32_t *reg, uint32_t mask, uint32_t val) { +bool i2c_status_wait(const volatile uint32_t *reg, uint32_t mask, uint32_t val) { uint32_t start_time = microsecond_timer_get(); while(((*reg & mask) != val) && (get_ts_elapsed(microsecond_timer_get(), start_time) < I2C_TIMEOUT_US)); return ((*reg & mask) == val); diff --git a/board/stm32h7/llusb.h b/board/stm32h7/llusb.h index 2bb475ff696..ada1630f8bc 100644 --- a/board/stm32h7/llusb.h +++ b/board/stm32h7/llusb.h @@ -7,7 +7,7 @@ USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; #define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) #define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) -#define USBD_FS_TRDT_VALUE 6U +#define USBD_FS_TRDT_VALUE 6UL #define USB_OTG_SPEED_FULL 3U #define DCFG_FRAME_INTERVAL_80 0U diff --git a/board/utils.h b/board/utils.h index c87a9ad0225..fd69db1bbf0 100644 --- a/board/utils.h +++ b/board/utils.h @@ -34,7 +34,7 @@ #define UNUSED(x) ((void)(x)) #endif -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) +#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * (!(pred) ? 1 : 0))])) // compute the time elapsed (in microseconds) from 2 counter samples // case where ts < ts_last is ok: overflow is properly re-casted into uint32_t diff --git a/python/__init__.py b/python/__init__.py index 50d9197adaf..b635e993451 100644 --- a/python/__init__.py +++ b/python/__init__.py @@ -28,6 +28,7 @@ CANPACKET_HEAD_SIZE = 0x6 DLC_TO_LEN = [0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64] LEN_TO_DLC = {length: dlc for (dlc, length) in enumerate(DLC_TO_LEN)} +PANDA_BUS_CNT = 4 def calculate_checksum(data): @@ -166,6 +167,7 @@ class Panda: HW_TYPE_RED_PANDA = b'\x07' HW_TYPE_RED_PANDA_V2 = b'\x08' HW_TYPE_TRES = b'\x09' + HW_TYPE_CUATRO = b'\x0a' CAN_PACKET_VERSION = 4 HEALTH_PACKET_VERSION = 15 @@ -175,15 +177,16 @@ class Panda: F2_DEVICES = [HW_TYPE_PEDAL, ] F4_DEVICES = [HW_TYPE_WHITE_PANDA, HW_TYPE_GREY_PANDA, HW_TYPE_BLACK_PANDA, HW_TYPE_UNO, HW_TYPE_DOS] - H7_DEVICES = [HW_TYPE_RED_PANDA, HW_TYPE_RED_PANDA_V2, HW_TYPE_TRES] + H7_DEVICES = [HW_TYPE_RED_PANDA, HW_TYPE_RED_PANDA_V2, HW_TYPE_TRES, HW_TYPE_CUATRO] - INTERNAL_DEVICES = (HW_TYPE_UNO, HW_TYPE_DOS, HW_TYPE_TRES) - HAS_OBD = (HW_TYPE_BLACK_PANDA, HW_TYPE_UNO, HW_TYPE_DOS, HW_TYPE_RED_PANDA, HW_TYPE_RED_PANDA_V2, HW_TYPE_TRES) + INTERNAL_DEVICES = (HW_TYPE_UNO, HW_TYPE_DOS, HW_TYPE_TRES, HW_TYPE_CUATRO) + HAS_OBD = (HW_TYPE_BLACK_PANDA, HW_TYPE_UNO, HW_TYPE_DOS, HW_TYPE_RED_PANDA, HW_TYPE_RED_PANDA_V2, HW_TYPE_TRES, HW_TYPE_CUATRO) MAX_FAN_RPMs = { HW_TYPE_UNO: 5100, HW_TYPE_DOS: 6500, HW_TYPE_TRES: 6600, + HW_TYPE_CUATRO: 6600, } HARNESS_STATUS_NC = 0 @@ -218,6 +221,7 @@ class Panda: FLAG_CHRYSLER_RAM_DT = 1 FLAG_CHRYSLER_RAM_HD = 2 + FLAG_CHRYSLER_LONG = 4 FLAG_SUBARU_GEN2 = 1 FLAG_SUBARU_LONG = 2 @@ -232,20 +236,18 @@ class Panda: FLAG_FORD_LONG_CONTROL = 1 FLAG_FORD_CANFD = 2 - def __init__(self, serial: Optional[str] = None, claim: bool = True, disable_checks: bool = True): + def __init__(self, serial: Optional[str] = None, claim: bool = True, disable_checks: bool = True, can_speed_kbps: int = 500): self._connect_serial = serial self._disable_checks = disable_checks self._handle: BaseHandle self._handle_open = False self.can_rx_overflow_buffer = b'' + self._can_speed_kbps = can_speed_kbps # connect and set mcu type self.connect(claim) - # reset comms - self.can_reset_communications() - def __enter__(self): return self @@ -303,6 +305,13 @@ def connect(self, claim=True, wait=False): self.set_heartbeat_disabled() self.set_power_save(0) + # reset comms + self.can_reset_communications() + + # set CAN speed + for bus in range(PANDA_BUS_CNT): + self.set_can_speed_kbps(bus, self._can_speed_kbps) + @classmethod def spi_connect(cls, serial, ignore_version=False): # get UID to confirm slave is present and up diff --git a/requirements.txt b/requirements.txt index 3449942902a..5ee8636fd59 100644 --- a/requirements.txt +++ b/requirements.txt @@ -8,10 +8,11 @@ pytest pytest-mock pytest-xdist pytest-timeout +pytest-randomly parameterized cffi pre-commit scons>=4.4.0 flaky spidev -termcolor +termcolor \ No newline at end of file diff --git a/tests/misra/suppressions.txt b/tests/misra/suppressions.txt index 473b22a1d6d..57db05a5fb6 100644 --- a/tests/misra/suppressions.txt +++ b/tests/misra/suppressions.txt @@ -17,19 +17,13 @@ unmatchedSuppression # fixing the violations and all are intended to be removed soon after unusedFunction -constParameterPointer -constParameterCallback -knownConditionTrueFalse misra-config misra-c2012-1.2 # this is from the extensions (e.g. __typeof__) used in the MIN, MAX, ABS, and CLAMP macros misra-c2012-2.5 misra-c2012-8.7 -misra-c2012-8.2 misra-c2012-8.4 misra-c2012-10.6 misra-c2012-10.3 -misra-c2012-10.5 -misra-c2012-12.2 misra-c2012-17.3 misra-c2012-21.15 diff --git a/tests/misra/test_misra.sh b/tests/misra/test_misra.sh index c4e5d3e8032..28249a3d8ab 100755 --- a/tests/misra/test_misra.sh +++ b/tests/misra/test_misra.sh @@ -24,7 +24,9 @@ if ! cmp -s new_table coverage_table; then fi cd $PANDA_DIR -scons -j8 +if [ -z "${SKIP_BUILD}" ]; then + scons -j8 +fi cppcheck() { hashed_args=$(echo -n "$@$DIR" | md5sum | awk '{print $1}') diff --git a/tests/misra/test_mutation.py b/tests/misra/test_mutation.py index 173665dedbf..f50d27c7fc4 100755 --- a/tests/misra/test_mutation.py +++ b/tests/misra/test_mutation.py @@ -1,18 +1,32 @@ #!/usr/bin/env python3 import os +import glob import pytest import shutil import subprocess import tempfile import hashlib +import random HERE = os.path.abspath(os.path.dirname(__file__)) ROOT = os.path.join(HERE, "../../") -# TODO: test more cases -# - at least one violation in each safety/safety*.h file -# - come up with a pattern for each rule (cppcheck tests probably have good ones?) +IGNORED_PATHS = ( + 'board/obj', + 'board/jungle', + 'board/stm32h7/inc', + 'board/stm32fx/inc', + 'board/fake_stm.h', + + # bootstub only files + 'board/flasher.h', + 'board/bootstub.c', + 'board/bootstub_declarations.h', + 'board/stm32fx/llflash.h' +) + mutations = [ + # default (None, None, False), # F4 only ("board/stm32fx/llbxcan.h", "s/1U/1/g", True), @@ -22,6 +36,36 @@ ("board/safety/safety_toyota.h", "s/is_lkas_msg =.*;/is_lkas_msg = addr == 1 || addr == 2;/g", True), ] +patterns = [ + # misra-c2012-13.3 + "$a void test(int tmp) { int tmp2 = tmp++ + 2; if (tmp2) {;}}", + # misra-c2012-13.4 + "$a int test(int x, int y) { return (x=2) && (y=2); }", + # misra-c2012-13.5 + "$a void test(int tmp) { if (true && tmp++) {;} }", + # misra-c2012-13.6 + "$a void test(int tmp) { if (sizeof(tmp++)) {;} }", + # misra-c2012-14.1 + "$a void test(float len) { for (float j = 0; j < len; j++) {;} }", + # misra-c2012-14.4 + "$a void test(int len) { if (len - 8) {;} }", + # misra-c2012-16.4 + r"$a void test(int temp) {switch (temp) { case 1: ; }}\n", + # misra-c2012-17.8 + "$a void test(int cnt) { for (cnt=0;;cnt++) {;} }", + # misra-c2012-20.4 + r"$a #define auto 1\n", + # misra-c2012-20.5 + r"$a #define TEST 1\n#undef TEST\n", +] + +all_files = glob.glob('board/**', root_dir=ROOT, recursive=True) +files = [f for f in all_files if f.endswith(('.c', '.h')) and not f.startswith(IGNORED_PATHS)] +assert len(files) > 70, all(d in files for d in ('board/main.c', 'board/stm32fx/llbxcan.h', 'board/stm32h7/llfdcan.h', 'board/safety/safety_toyota.h')) + +for p in patterns: + mutations.append((random.choice(files), p, True)) + @pytest.mark.parametrize("fn, patch, should_fail", mutations) def test_misra_mutation(fn, patch, should_fail): key = hashlib.md5((str(fn) + str(patch)).encode()).hexdigest() @@ -37,11 +81,12 @@ def test_misra_mutation(fn, patch, should_fail): assert r == 0 # run test - r = subprocess.run("tests/misra/test_misra.sh", cwd=tmp, shell=True) + env = {'SKIP_BUILD': '1'} | os.environ.copy() + r = subprocess.run("tests/misra/test_misra.sh", cwd=tmp, shell=True, env=env) failed = r.returncode != 0 assert failed == should_fail shutil.rmtree(tmp) if __name__ == "__main__": - pytest.main([__file__, "-n 4"]) + pytest.main([__file__, "-n 8"]) diff --git a/tests/safety/common.py b/tests/safety/common.py index 8b70966aea5..3d2631af9ce 100644 --- a/tests/safety/common.py +++ b/tests/safety/common.py @@ -857,6 +857,11 @@ def test_tx_hook_on_wrong_safety_mode(self): continue if {attr, current_test}.issubset({'TestVolkswagenMqbSafety', 'TestVolkswagenMqbStockSafety', 'TestVolkswagenMqbLongSafety'}): continue + if attr.startswith('TestChryslerRamDT') and current_test.startswith('TestChryslerRamDT'): + continue + if {attr, current_test}.issubset({'TestChryslerSafety', 'TestChryslerLongitudinalSafety', + 'TestChryslerRamHDSafety', 'TestChryslerRamHDLongitudinalSafety'}): + continue # overlapping TX addrs, but they're not actuating messages for either car if attr == 'TestHyundaiCanfdHDA2LongEV' and current_test.startswith('TestToyota'): diff --git a/tests/safety/test_chrysler.py b/tests/safety/test_chrysler.py index 5bbb6dd1030..3c44733679d 100755 --- a/tests/safety/test_chrysler.py +++ b/tests/safety/test_chrysler.py @@ -1,5 +1,7 @@ #!/usr/bin/env python3 import unittest +import itertools + from panda import Panda from panda.tests.libpanda import libpanda_py import panda.tests.safety.common as common @@ -24,14 +26,17 @@ class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSa DAS_BUS = 0 + cnt_button = 0 + def setUp(self): self.packer = CANPackerPanda("chrysler_pacifica_2017_hybrid_generated") self.safety = libpanda_py.libpanda self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, 0) self.safety.init_tests() - def _button_msg(self, cancel=False, resume=False): - values = {"ACC_Cancel": cancel, "ACC_Resume": resume} + def _button_msg(self, cancel=False, resume=False, accel=False, decel=False): + values = {"ACC_Cancel": cancel, "ACC_Resume": resume, "ACC_Accel": accel, "ACC_Decel": decel, "COUNTER": self.cnt_button} + self.__class__.cnt_button += 1 return self.packer.make_can_msg_panda("CRUISE_BUTTONS", self.DAS_BUS, values) def _pcm_status_msg(self, enable): @@ -96,8 +101,9 @@ def _speed_msg(self, speed): values = {"Vehicle_Speed": speed} return self.packer.make_can_msg_panda("ESP_8", 0, values) + class TestChryslerRamHDSafety(TestChryslerSafety): - TX_MSGS = [[0x275, 0], [0x276, 0], [0x23A, 2]] + TX_MSGS = [[0x23A, 2], [0x275, 0], [0x276, 0]] RELAY_MALFUNCTION_ADDRS = {0: (0x276,)} FWD_BLACKLISTED_ADDRS = {2: [0x275, 0x276]} @@ -121,5 +127,114 @@ def _speed_msg(self, speed): return self.packer.make_can_msg_panda("ESP_8", 0, values) +class ChryslerLongitudinalBase(TestChryslerSafety): + + DAS_BUS = 0 + + MIN_ENGINE_TORQUE = -500 + MAX_ENGINE_TORQUE = 500 + INACTIVE_ENGINE_TORQUE = 0 + MIN_POSSIBLE_ENGINE_TORQUE = -500 + MAX_POSSIBLE_ENGINE_TORQUE = 1548 + + MIN_ACCEL = -3.5 + MAX_ACCEL = 2.0 + INACTIVE_ACCEL = 4.0 + MIN_POSSIBLE_ACCEL = -16.0 + MAX_POSSIBLE_ACCEL = 4.0 + + # override these tests from PandaCarSafetyTest, chrysler longitudinal uses button enable + def test_disable_control_allowed_from_cruise(self): + pass + + def test_enable_control_allowed_from_cruise(self): + pass + + def test_cruise_engaged_prev(self): + pass + + def _pcm_status_msg(self, enable): + # TODO: falsify the above tests + raise Exception + + def _send_torque_accel_msg(self, enable: bool, torque_active: bool, torque: float, accel_active: int, accel: float): + values = { + "ACC_AVAILABLE": 1, + "ACC_ACTIVE": int(enable), + "ENGINE_TORQUE_REQUEST": torque, + "ENGINE_TORQUE_REQUEST_MAX": int(torque_active), + "ACC_DECEL": accel, + "ACC_DECEL_REQ": accel_active, + } + return self.packer.make_can_msg_panda("DAS_3", self.DAS_BUS, values) + + def _send_accel_msg(self, accel): + return self._send_torque_accel_msg(True, False, self.INACTIVE_ENGINE_TORQUE, 1, accel) + + def _send_torque_msg(self, torque): + return self._send_torque_accel_msg(True, True, torque, 0, self.INACTIVE_ACCEL) + + def test_accel_torque_safety_check(self): + self._generic_limit_safety_check(self._send_accel_msg, + self.MIN_ACCEL, self.MAX_ACCEL, + self.MIN_POSSIBLE_ACCEL, self.MAX_POSSIBLE_ACCEL, + test_delta=0.1, inactive_value=self.INACTIVE_ACCEL) + self._generic_limit_safety_check(self._send_torque_msg, + self.MIN_ENGINE_TORQUE, self.MAX_ENGINE_TORQUE, + self.MIN_POSSIBLE_ENGINE_TORQUE, self.MAX_POSSIBLE_ENGINE_TORQUE, + test_delta=10, inactive_value=self.INACTIVE_ENGINE_TORQUE) + + def test_buttons(self): + enable_buttons = {1 << 2: "resume", 1 << 3: "accel", 1 << 4: "decel"} + for cancel_cur, resume_cur, accel_cur, decel_cur in itertools.product([0, 1], repeat=4): + for cancel_prev, resume_prev, accel_prev, decel_prev in itertools.product([0, 1], repeat=4): + self._rx(self._button_msg(cancel=False, resume=False, accel=False, decel=False)) + self.safety.set_controls_allowed(False) + for _ in range(10): + self._rx(self._button_msg(cancel_prev, resume_prev, accel_prev, decel_prev)) + self.assertFalse(self.safety.get_controls_allowed()) + + # should enter controls allowed on falling edge and not transitioning to cancel + button_cur = enable_buttons.get(cancel_cur if cancel_cur else (resume_cur << 2) | (accel_cur << 3) | (decel_cur << 4)) + button_prev = enable_buttons.get(cancel_prev if cancel_prev else (resume_prev << 2) | (accel_prev << 3) | (decel_prev << 4)) + should_enable = not cancel_cur and not cancel_prev and button_prev is not None and button_prev != button_cur + + self._rx(self._button_msg(cancel_cur, resume_cur, accel_cur, decel_cur)) + self.assertEqual(should_enable, self.safety.get_controls_allowed()) + + +class TestChryslerLongitudinalSafety(ChryslerLongitudinalBase, TestChryslerSafety): + TX_MSGS = [[0x23B, 0], [0x292, 0], [0x2A6, 0], [0x1F4, 0], [0x1F5, 0], [0x271, 0]] + FWD_BLACKLISTED_ADDRS = {2: [0x292, 0x2A6, 0x1F4, 0x1F5, 0x271]} + + def setUp(self): + self.packer = CANPackerPanda("chrysler_pacifica_2017_hybrid_generated") + self.safety = libpanda_py.libpanda + self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, Panda.FLAG_CHRYSLER_LONG) + self.safety.init_tests() + + +class TestChryslerRamDTLongitudinalSafety(ChryslerLongitudinalBase, TestChryslerRamDTSafety): + TX_MSGS = [[0xB1, 0], [0xA6, 0], [0xFA, 0], [0x99, 0], [0xE8, 0], [0xA3, 0]] + FWD_BLACKLISTED_ADDRS = {2: [0xA6, 0xFA, 0x99, 0xE8, 0xA3]} + + def setUp(self): + self.packer = CANPackerPanda("chrysler_ram_dt_generated") + self.safety = libpanda_py.libpanda + self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, Panda.FLAG_CHRYSLER_RAM_DT | Panda.FLAG_CHRYSLER_LONG) + self.safety.init_tests() + + +class TestChryslerRamHDLongitudinalSafety(ChryslerLongitudinalBase, TestChryslerRamHDSafety): + TX_MSGS = [[0x23A, 0], [0x275, 0], [0x276, 0], [0x1F4, 0], [0x1F5, 0], [0x271, 0]] + FWD_BLACKLISTED_ADDRS = {2: [0x275, 0x276, 0x1F4, 0x1F5, 0x271]} + + def setUp(self): + self.packer = CANPackerPanda("chrysler_ram_hd_generated") + self.safety = libpanda_py.libpanda + self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, Panda.FLAG_CHRYSLER_RAM_HD | Panda.FLAG_CHRYSLER_LONG) + self.safety.init_tests() + + if __name__ == "__main__": unittest.main()