Move car safety modes to opendbc (#1713)

* move safety tests

* move libsafety

* move safety

* rename imports

* copy over needed (minimalized) board and driver code

* dont test safety here

* add new job for safety tests

fix

* try fix

* ubsan

* ?

?

* missing cffi

* should be final fix

* mac fix

* no mac

* use setup script

* no cd

* this is the correct way to do it

* add misra

* misra fixes

* run

* setup misra

* add missing files

* is this used?

* add that

* Revert "is this used?"

This reverts commit 2f34762dfa.

* need this

* misra mutation test

* fix

* no race conditions

* test

* cache cppcheck

fix

* setup

* good timeouts

* mutation test

* fix

* no

* Revert "no"

This reverts commit 39e10a045a.

* already tested

* move Safety Model readme section to opendbc

* fix

* fix

* disable mutation tests for merge

* namespace

* test no cache

* 1m

1m
This commit is contained in:
Shane Smiskol
2025-02-19 17:19:31 -08:00
committed by GitHub
parent 0fdb59fd34
commit 6f83fdf9b9
73 changed files with 12201 additions and 8 deletions

View File

@@ -20,3 +20,86 @@ jobs:
- uses: commaai/timeout@v1
- uses: actions/checkout@v4
- run: ./test.sh
safety_tests:
name: safety
runs-on: ${{ ((github.repository == 'commaai/opendbc') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/opendbc'))) && 'namespace-profile-amd64-8x16' || 'ubuntu-latest' }}
strategy:
fail-fast: false
matrix:
flags: ['', '--ubsan']
steps:
- uses: commaai/timeout@v1
- uses: actions/checkout@v4
- name: Run safety tests
run: ./opendbc/safety/tests/test.sh ${{ matrix.flags }}
misra_linter:
name: MISRA C:2012 Linter
runs-on: ${{ ((github.repository == 'commaai/opendbc') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/opendbc'))) && 'namespace-profile-amd64-8x16' || 'ubuntu-latest' }}
timeout-minutes: 20
steps:
- name: Set up
run: sudo apt-get install -y --no-install-recommends gcc-arm-none-eabi libnewlib-arm-none-eabi
- uses: actions/checkout@v4
- name: Restore cached cppcheck
uses: actions/cache@v4
with:
path: opendbc/safety/tests/misra/cppcheck/
key: cppcheck-cache-${{ runner.os }}-${{ github.ref }}
restore-keys: |
cppcheck-cache-${{ runner.os }}-${{ github.ref }}
cppcheck-cache-${{ runner.os }}-
- name: Run MISRA C:2012 analysis
timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 1 || 2) }}
run: cd opendbc/safety/tests/misra && ./test_misra.sh
- name: Save cppcheck cache
uses: actions/cache@v4
with:
path: opendbc/safety/tests/misra/cppcheck/
key: cppcheck-cache-${{ runner.os }}-${{ github.ref }}
misra_mutation:
name: MISRA C:2012 Mutation
runs-on: ${{ ((github.repository == 'commaai/opendbc') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/opendbc'))) && 'namespace-profile-amd64-8x16' || 'ubuntu-latest' }}
timeout-minutes: 20
steps:
- name: Set up
run: sudo apt-get install -y --no-install-recommends gcc-arm-none-eabi libnewlib-arm-none-eabi
- uses: actions/checkout@v4
- name: Restore cached cppcheck
uses: actions/cache@v4
with:
path: opendbc/safety/tests/misra/cppcheck/
key: cppcheck-cache-${{ runner.os }}-${{ github.ref }}
restore-keys: |
cppcheck-cache-${{ runner.os }}-${{ github.ref }}
cppcheck-cache-${{ runner.os }}-
- name: MISRA mutation tests
timeout-minutes: 1
run: |
source setup.sh
scons -j8
cd opendbc/safety/tests/misra
./install.sh # cppcheck
pytest -s -n8 --randomly-seed $RANDOM test_mutation.py
- name: Save cppcheck cache
uses: actions/cache@v4
with:
path: opendbc/safety/tests/misra/cppcheck/
key: cppcheck-cache-${{ runner.os }}-${{ github.ref }}
# mutation:
# name: Safety mutation tests
# runs-on: ${{ ((github.repository == 'commaai/opendbc') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/opendbc'))) && 'namespace-profile-amd64-8x16' || 'ubuntu-latest' }}
# timeout-minutes: 20
# steps:
# - uses: actions/checkout@v4
# with:
# fetch-depth: 0 # need master to get diff
# - name: Run mutation tests
# timeout-minutes: 5
# run: |
# source setup.sh
# scons -j8
# GIT_REF=${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && github.event.before || 'origin/master' }} cd opendbc/safety/tests && ./mutation.sh

View File

@@ -69,7 +69,7 @@ At its most basic, a car port will control the steering on a car. A "complete" c
The first step is to get connected to the car with a comma 3X and a car harness.
The car harness gets you connected to two different CAN buses and splits one of those buses to send our own actuation messages.
If you're lucky, a harness compatible with your car will already be designed and sold on comma.ai/shop.
If you're lucky, a harness compatible with your car will already be designed and sold on comma.ai/shop.
If you're not so lucky, start with a "developer harness" from comma.ai/shop and crimp on whatever connector you need.
### Structure of a port
@@ -78,11 +78,11 @@ Depending on , most of this basic structure will already be in place.
The entirery of a car port lives in `opendbc/car/<brand>/`:
* `carstate.py`: parses out the relevant information from the CAN stream using the car's DBC file
* `carcontroller.py`: outputs CAN messages to control the car
* `carcontroller.py`: outputs CAN messages to control the car
* `<brand>can.py`: thin Python helpers around the DBC file to build CAN messages
* `fingerprints.py`: database of ECU firmware versions for identifying car models
* `interface.py`: high level class for interfacing with the car
* `radar_interface.py`: parses out the radar
* `radar_interface.py`: parses out the radar
* `values.py`: enumerates the brand's supported cars
### Reverse Engineer CAN messages
@@ -97,7 +97,7 @@ Use the [longitudinal maneuvers](https://github.com/commaai/openpilot/tree/maste
## Contributing
All opendbc development is coordinated on GitHub and [Discord](https://discord.comma.ai). Check out the `#dev-opendbc-cars` channel and `Vehicle Specific` section.
All opendbc development is coordinated on GitHub and [Discord](https://discord.comma.ai). Check out the `#dev-opendbc-cars` channel and `Vehicle Specific` section.
### Roadmap
@@ -116,6 +116,29 @@ Longer term
Contributions towards anything here are welcome.
## Safety Model
When a [panda](https://comma.ai/shop/panda) powers up with [opendbc safety firmware](opendbc/safety), by default it's in `SAFETY_SILENT` mode. While in `SAFETY_SILENT` mode, the CAN buses are forced to be silent. In order to send messages, you have to select a safety mode. Some of safety modes (for example `SAFETY_ALLOUTPUT`) are disabled in release firmwares. In order to use them, compile and flash your own build.
Safety modes optionally support `controls_allowed`, which allows or blocks a subset of messages based on a customizable state in the board.
## Code Rigor
The opendbc safety firmware is written for its use in conjunction with [openpilot](https://github.com/commaai/openpilot) and [panda](https://github.com/commaai/panda). The safety firmware, through its safety model, provides and enforces the
[openpilot safety](https://github.com/commaai/openpilot/blob/master/docs/SAFETY.md). Due to its critical function, it's important that the application code rigor within the `safety` folder is held to high standards.
These are the [CI regression tests](https://github.com/commaai/opendbc/actions) we have in place:
* A generic static code analysis is performed by [cppcheck](https://github.com/danmar/cppcheck/).
* In addition, [cppcheck](https://github.com/danmar/cppcheck/) has a specific addon to check for [MISRA C:2012](https://misra.org.uk/) violations. See [current coverage](opendbc/safety/tests/misra/coverage_table).
* Compiler options are relatively strict: the flags `-Wall -Wextra -Wstrict-prototypes -Werror` are enforced.
* The [safety logic](opendbc/safety) is tested and verified by [unit tests](opendbc/safety/tests) for each supported car variant.
The above tests are themselves tested by:
* a [mutation test](opendbc/safety/tests/misra/test_mutation.py) on the MISRA coverage
* 100% line coverage enforced on the safety unit tests
In addition, we run the [ruff linter](https://github.com/astral-sh/ruff) and [mypy](https://mypy-lang.org/) on the car interface library.
### Bounties
Every car port is eligible for a bounty:
@@ -137,7 +160,7 @@ In addition to the standard bounties, we also offer higher value bounties for mo
***How does this work?*** In short, we designed hardware to replace your car's built-in lane keep and adaptive cruise features. See [this talk](https://www.youtube.com/watch?v=FL8CxUSfipM) for an in-depth explanation.
***Is there a timeline or roadmap for adding car support?*** No, most car support comes from the community, with comma doing final safety and quality validation. The more complete the community car port is and the more popular the car is, the more likely we are to pick it up as the next one to validate.
***Is there a timeline or roadmap for adding car support?*** No, most car support comes from the community, with comma doing final safety and quality validation. The more complete the community car port is and the more popular the car is, the more likely we are to pick it up as the next one to validate.
### Terms
@@ -163,7 +186,7 @@ In addition to the standard bounties, we also offer higher value bounties for mo
* [*How to Port a Car*](https://www.youtube.com/watch?v=XxPS5TpTUnI&t=142s&pp=ygUPamFzb24gY29tbWEgY29u) by [@jyoung8607](https://github.com/jyoung8607) from COMMA_CON 2023
* [commaCarSegments](https://huggingface.co/datasets/commaai/commaCarSegments): a massive dataset of CAN data from 300 different car models
* [cabana](https://github.com/commaai/openpilot/tree/master/tools/cabana#readme): our tool for reverse engineering CAN messages
* [can_print_changes.py](https://github.com/commaai/openpilot/blob/master/selfdrive/debug/can_print_changes.py): diff the whole CAN bus across two drives, such as one without any LKAS and one with LKAS
* [can_print_changes.py](https://github.com/commaai/openpilot/blob/master/selfdrive/debug/can_print_changes.py): diff the whole CAN bus across two drives, such as one without any LKAS and one with LKAS
* [longitudinal maneuvers](https://github.com/commaai/openpilot/tree/master/tools/longitudinal_maneuvers): a tool for evaluating and tuning longitudinal control
* [opendbc data](https://commaai.github.io/opendbc-data/): a repository of longitudinal maneuver evaluations

View File

@@ -2,3 +2,7 @@ Import("env")
SConscript(['opendbc/can/SConscript'], exports={'env': env})
SConscript(['opendbc/dbc/SConscript'], exports={'env': env})
# test files
if GetOption('extras'):
SConscript('opendbc/safety/tests/libsafety/SConscript')

View File

@@ -25,6 +25,19 @@ AddOption('--asan',
action='store_true',
help='turn on ASAN')
# safety options
AddOption('--ubsan',
action='store_true',
help='turn on UBSan')
AddOption('--coverage',
action='store_true',
help='build with test coverage options')
AddOption('--mutation',
action='store_true',
help='generate mutation-ready code')
ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else []
ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else []

View File

@@ -1,3 +1,8 @@
# constants from panda/python/__init__.py
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)}
class Safety:
# matches opendbc.structs.CarParams.SafetyModel
# TODO: just use SafetyModel in panda repo

View File

@@ -0,0 +1,4 @@
#pragma once
#include "can_declarations.h"
static const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U};

View File

@@ -0,0 +1,27 @@
#pragma once
#define CANPACKET_HEAD_SIZE 6U
// TODO: this is always CANFD
#if !defined(STM32F4)
#define CANFD
#define CANPACKET_DATA_SIZE_MAX 64U
#else
#define CANPACKET_DATA_SIZE_MAX 8U
#endif
typedef struct {
unsigned char fd : 1;
unsigned char bus : 3;
unsigned char data_len_code : 4; // lookup length with dlc_to_len
unsigned char rejected : 1;
unsigned char returned : 1;
unsigned char extended : 1;
unsigned int addr : 29;
unsigned char checksum;
unsigned char data[CANPACKET_DATA_SIZE_MAX];
} __attribute__((packed, aligned(4))) CANPacket_t;
#define GET_BUS(msg) ((msg)->bus)
#define GET_LEN(msg) (dlc_to_len[(msg)->data_len_code])
#define GET_ADDR(msg) ((msg)->addr)

View File

@@ -0,0 +1,18 @@
#include "can_common_declarations.h"
uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) {
uint8_t checksum = 0U;
for (uint32_t i = 0U; i < len; i++) {
checksum ^= dat[i];
}
return checksum;
}
void can_set_checksum(CANPacket_t *packet) {
packet->checksum = 0U;
packet->checksum = calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet));
}
bool can_check_checksum(CANPacket_t *packet) {
return (calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)) == 0U);
}

View File

@@ -0,0 +1,4 @@
#pragma once
uint8_t calculate_checksum(const uint8_t *dat, uint32_t len);
void can_set_checksum(CANPacket_t *packet);

View File

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

View File

@@ -0,0 +1,25 @@
#include "faults_declarations.h"
uint8_t fault_status = FAULT_STATUS_NONE;
uint32_t faults = 0U;
void fault_occurred(uint32_t fault) {
if ((faults & fault) == 0U) {
if ((PERMANENT_FAULTS & fault) != 0U) {
print("Permanent fault occurred: 0x"); puth(fault); print("\n");
fault_status = FAULT_STATUS_PERMANENT;
} else {
print("Temporary fault occurred: 0x"); puth(fault); print("\n");
fault_status = FAULT_STATUS_TEMPORARY;
}
}
faults |= fault;
}
void fault_recovered(uint32_t fault) {
if ((PERMANENT_FAULTS & fault) == 0U) {
faults &= ~fault;
} else {
print("Cannot recover from a permanent fault!\n");
}
}

View File

@@ -0,0 +1,18 @@
#pragma once
#define FAULT_STATUS_NONE 0U
#define FAULT_STATUS_TEMPORARY 1U
#define FAULT_STATUS_PERMANENT 2U
// Fault types, excerpt from cereal.log.PandaState.FaultType for safety tests
#define FAULT_RELAY_MALFUNCTION (1UL << 0)
// ...
// Permanent faults
#define PERMANENT_FAULTS 0U
extern uint8_t fault_status;
extern uint32_t faults;
void fault_occurred(uint32_t fault);
void fault_recovered(uint32_t fault);

View File

@@ -0,0 +1,47 @@
// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension
#define MIN(a, b) ({ \
__typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
(_a < _b) ? _a : _b; \
})
// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension
#define MAX(a, b) ({ \
__typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
(_a > _b) ? _a : _b; \
})
// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension
#define CLAMP(x, low, high) ({ \
__typeof__(x) __x = (x); \
__typeof__(low) __low = (low);\
__typeof__(high) __high = (high);\
(__x > __high) ? __high : ((__x < __low) ? __low : __x); \
})
// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension
#define ABS(a) ({ \
__typeof__ (a) _a = (a); \
(_a > 0) ? _a : (-_a); \
})
#ifndef NULL
// this just provides a standard implementation of NULL
// in lieu of including libc in the panda build
// cppcheck-suppress [misra-c2012-21.1]
#define NULL ((void*)0)
#endif
// STM32 HAL defines this
#ifndef UNUSED
#define UNUSED(x) ((void)(x))
#endif
#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
uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) {
return ts - ts_last;
}

12
opendbc/safety/main.c Normal file
View File

@@ -0,0 +1,12 @@
#include "safety.h"
// this file is checked by cppcheck
// Ignore misra-c2012-8.7 as these functions are only called from panda and libsafety
UNUSED(heartbeat_engaged);
UNUSED(safety_rx_hook);
UNUSED(safety_tx_hook);
UNUSED(safety_fwd_hook);
UNUSED(safety_tick);
UNUSED(set_safety_hooks);

746
opendbc/safety/safety.h Normal file
View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -0,0 +1,259 @@
#pragma once
#include "safety_declarations.h"
static const LongitudinalLimits *gm_long_limits;
enum {
GM_BTN_UNPRESS = 1,
GM_BTN_RESUME = 2,
GM_BTN_SET = 3,
GM_BTN_CANCEL = 6,
};
typedef enum {
GM_ASCM,
GM_CAM
} GmHardware;
static GmHardware gm_hw = GM_ASCM;
static bool gm_cam_long = false;
static bool gm_pcm_cruise = false;
static void gm_rx_hook(const CANPacket_t *to_push) {
const int GM_STANDSTILL_THRSLD = 10; // 0.311kph
if (GET_BUS(to_push) == 0U) {
int addr = GET_ADDR(to_push);
if (addr == 0x184) {
int torque_driver_new = ((GET_BYTE(to_push, 6) & 0x7U) << 8) | GET_BYTE(to_push, 7);
torque_driver_new = to_signed(torque_driver_new, 11);
// update array of samples
update_sample(&torque_driver, torque_driver_new);
}
// sample rear wheel speeds
if (addr == 0x34A) {
int left_rear_speed = (GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1);
int right_rear_speed = (GET_BYTE(to_push, 2) << 8) | GET_BYTE(to_push, 3);
vehicle_moving = (left_rear_speed > GM_STANDSTILL_THRSLD) || (right_rear_speed > GM_STANDSTILL_THRSLD);
}
// ACC steering wheel buttons (GM_CAM is tied to the PCM)
if ((addr == 0x1E1) && !gm_pcm_cruise) {
int button = (GET_BYTE(to_push, 5) & 0x70U) >> 4;
// enter controls on falling edge of set or rising edge of resume (avoids fault)
bool set = (button != GM_BTN_SET) && (cruise_button_prev == GM_BTN_SET);
bool res = (button == GM_BTN_RESUME) && (cruise_button_prev != GM_BTN_RESUME);
if (set || res) {
controls_allowed = true;
}
// exit controls on cancel press
if (button == GM_BTN_CANCEL) {
controls_allowed = false;
}
cruise_button_prev = button;
}
// Reference for brake pressed signals:
// https://github.com/commaai/openpilot/blob/master/selfdrive/car/gm/carstate.py
if ((addr == 0xBE) && (gm_hw == GM_ASCM)) {
brake_pressed = GET_BYTE(to_push, 1) >= 8U;
}
if ((addr == 0xC9) && (gm_hw == GM_CAM)) {
brake_pressed = GET_BIT(to_push, 40U);
}
if (addr == 0x1C4) {
gas_pressed = GET_BYTE(to_push, 5) != 0U;
// enter controls on rising edge of ACC, exit controls when ACC off
if (gm_pcm_cruise) {
bool cruise_engaged = (GET_BYTE(to_push, 1) >> 5) != 0U;
pcm_cruise_check(cruise_engaged);
}
}
if (addr == 0xBD) {
regen_braking = (GET_BYTE(to_push, 0) >> 4) != 0U;
}
bool stock_ecu_detected = (addr == 0x180); // ASCMLKASteeringCmd
// Check ASCMGasRegenCmd only if we're blocking it
if (!gm_pcm_cruise && (addr == 0x2CB)) {
stock_ecu_detected = true;
}
generic_rx_checks(stock_ecu_detected);
}
}
static bool gm_tx_hook(const CANPacket_t *to_send) {
const SteeringLimits GM_STEERING_LIMITS = {
.max_steer = 300,
.max_rate_up = 10,
.max_rate_down = 15,
.driver_torque_allowance = 65,
.driver_torque_factor = 4,
.max_rt_delta = 128,
.max_rt_interval = 250000,
.type = TorqueDriverLimited,
};
bool tx = true;
int addr = GET_ADDR(to_send);
// BRAKE: safety check
if (addr == 0x315) {
int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1);
brake = (0x1000 - brake) & 0xFFF;
if (longitudinal_brake_checks(brake, *gm_long_limits)) {
tx = false;
}
}
// LKA STEER: safety check
if (addr == 0x180) {
int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1);
desired_torque = to_signed(desired_torque, 11);
bool steer_req = GET_BIT(to_send, 3U);
if (steer_torque_cmd_checks(desired_torque, steer_req, GM_STEERING_LIMITS)) {
tx = false;
}
}
// GAS/REGEN: safety check
if (addr == 0x2CB) {
bool apply = GET_BIT(to_send, 0U);
int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3);
bool violation = false;
// Allow apply bit in pre-enabled and overriding states
violation |= !controls_allowed && apply;
violation |= longitudinal_gas_checks(gas_regen, *gm_long_limits);
if (violation) {
tx = false;
}
}
// BUTTONS: used for resume spamming and cruise cancellation with stock longitudinal
if ((addr == 0x1E1) && gm_pcm_cruise) {
int button = (GET_BYTE(to_send, 5) >> 4) & 0x7U;
bool allowed_cancel = (button == 6) && cruise_engaged_prev;
if (!allowed_cancel) {
tx = false;
}
}
return tx;
}
static int gm_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (gm_hw == GM_CAM) {
if (bus_num == 0) {
// block PSCMStatus; forwarded through openpilot to hide an alert from the camera
bool is_pscm_msg = (addr == 0x184);
if (!is_pscm_msg) {
bus_fwd = 2;
}
}
if (bus_num == 2) {
// block lkas message and acc messages if gm_cam_long, forward all others
bool is_lkas_msg = (addr == 0x180);
bool is_acc_msg = (addr == 0x315) || (addr == 0x2CB) || (addr == 0x370);
bool block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long);
if (!block_msg) {
bus_fwd = 0;
}
}
}
return bus_fwd;
}
static safety_config gm_init(uint16_t param) {
const uint16_t GM_PARAM_HW_CAM = 1;
static const LongitudinalLimits GM_ASCM_LONG_LIMITS = {
.max_gas = 3072,
.min_gas = 1404,
.inactive_gas = 1404,
.max_brake = 400,
};
static const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4}, {0x409, 0, 7}, {0x40A, 0, 7}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus
{0xA1, 1, 7}, {0x306, 1, 8}, {0x308, 1, 7}, {0x310, 1, 2}, // obs bus
{0x315, 2, 5}}; // ch bus
static const LongitudinalLimits GM_CAM_LONG_LIMITS = {
.max_gas = 3400,
.min_gas = 1514,
.inactive_gas = 1554,
.max_brake = 400,
};
static const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus
{0x184, 2, 8}}; // camera bus
// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now.
static RxCheck gm_rx_checks[] = {
{.msg = {{0x184, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0x34A, 0, 5, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0x1E1, 0, 7, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0xBE, 0, 6, .frequency = 10U}, // Volt, Silverado, Acadia Denali
{0xBE, 0, 7, .frequency = 10U}, // Bolt EUV
{0xBE, 0, 8, .frequency = 10U}}}, // Escalade
{.msg = {{0x1C4, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
{.msg = {{0xC9, 0, 8, .frequency = 10U}, { 0 }, { 0 }}},
};
static const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4}, // pt bus
{0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus
gm_hw = GET_FLAG(param, GM_PARAM_HW_CAM) ? GM_CAM : GM_ASCM;
if (gm_hw == GM_ASCM) {
gm_long_limits = &GM_ASCM_LONG_LIMITS;
} else if (gm_hw == GM_CAM) {
gm_long_limits = &GM_CAM_LONG_LIMITS;
} else {
}
#ifdef ALLOW_DEBUG
const uint16_t GM_PARAM_HW_CAM_LONG = 2;
gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG);
#endif
gm_pcm_cruise = (gm_hw == GM_CAM) && !gm_cam_long;
safety_config ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_ASCM_TX_MSGS);
if (gm_hw == GM_CAM) {
// FIXME: cppcheck thinks that gm_cam_long is always false. This is not true
// if ALLOW_DEBUG is defined but cppcheck is run without ALLOW_DEBUG
// cppcheck-suppress knownConditionTrueFalse
ret = gm_cam_long ? BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_LONG_TX_MSGS) : BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_TX_MSGS);
}
return ret;
}
const safety_hooks gm_hooks = {
.init = gm_init,
.rx = gm_rx_hook,
.tx = gm_tx_hook,
.fwd = gm_fwd_hook,
};

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -0,0 +1,213 @@
#pragma once
#include "safety_declarations.h"
static bool tesla_longitudinal = false;
static bool tesla_stock_aeb = false;
static void tesla_rx_hook(const CANPacket_t *to_push) {
int bus = GET_BUS(to_push);
int addr = GET_ADDR(to_push);
if (bus == 0) {
// Steering angle: (0.1 * val) - 819.2 in deg.
if (addr == 0x370) {
// Store it 1/10 deg to match steering request
int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U;
update_sample(&angle_meas, angle_meas_new);
}
// Vehicle speed
if (addr == 0x257) {
// Vehicle speed: ((val * 0.08) - 40) / MS_TO_KPH
float speed = ((((GET_BYTE(to_push, 2) << 4) | (GET_BYTE(to_push, 1) >> 4)) * 0.08) - 40) / 3.6;
UPDATE_VEHICLE_SPEED(speed);
}
// Gas pressed
if (addr == 0x118) {
gas_pressed = (GET_BYTE(to_push, 4) != 0U);
}
// Brake pressed
if (addr == 0x39d) {
brake_pressed = (GET_BYTE(to_push, 2) & 0x03U) == 2U;
}
// Cruise state
if (addr == 0x286) {
int cruise_state = (GET_BYTE(to_push, 1) >> 4) & 0x07U;
bool cruise_engaged = (cruise_state == 2) || // ENABLED
(cruise_state == 3) || // STANDSTILL
(cruise_state == 4) || // OVERRIDE
(cruise_state == 6) || // PRE_FAULT
(cruise_state == 7); // PRE_CANCEL
vehicle_moving = cruise_state != 3; // STANDSTILL
pcm_cruise_check(cruise_engaged);
}
}
if (bus == 2) {
if (tesla_longitudinal && (addr == 0x2b9)) {
// "AEB_ACTIVE"
tesla_stock_aeb = (GET_BYTE(to_push, 2) & 0x03U) == 1U;
}
}
generic_rx_checks((addr == 0x488) && (bus == 0)); // DAS_steeringControl
generic_rx_checks((addr == 0x27d) && (bus == 0)); // APS_eacMonitor
if (tesla_longitudinal) {
generic_rx_checks((addr == 0x2b9) && (bus == 0));
}
}
static bool tesla_tx_hook(const CANPacket_t *to_send) {
const SteeringLimits TESLA_STEERING_LIMITS = {
.angle_deg_to_can = 10,
.angle_rate_up_lookup = {
{0., 5., 15.},
{10., 1.6, .3}
},
.angle_rate_down_lookup = {
{0., 5., 15.},
{10., 7.0, .8}
},
};
const LongitudinalLimits TESLA_LONG_LIMITS = {
.max_accel = 425, // 2 m/s^2
.min_accel = 288, // -3.48 m/s^2
.inactive_accel = 375, // 0. m/s^2
};
bool tx = true;
int addr = GET_ADDR(to_send);
bool violation = false;
// Steering control: (0.1 * val) - 1638.35 in deg.
if (addr == 0x488) {
// We use 1/10 deg as a unit here
int raw_angle_can = ((GET_BYTE(to_send, 0) & 0x7FU) << 8) | GET_BYTE(to_send, 1);
int desired_angle = raw_angle_can - 16384;
int steer_control_type = GET_BYTE(to_send, 2) >> 6;
bool steer_control_enabled = (steer_control_type != 0) && // NONE
(steer_control_type != 3); // DISABLED
if (steer_angle_cmd_checks(desired_angle, steer_control_enabled, TESLA_STEERING_LIMITS)) {
violation = true;
}
}
// DAS_control: longitudinal control message
if (addr == 0x2b9) {
// No AEB events may be sent by openpilot
int aeb_event = GET_BYTE(to_send, 2) & 0x03U;
if (aeb_event != 0) {
violation = true;
}
int raw_accel_max = ((GET_BYTE(to_send, 6) & 0x1FU) << 4) | (GET_BYTE(to_send, 5) >> 4);
int raw_accel_min = ((GET_BYTE(to_send, 5) & 0x0FU) << 5) | (GET_BYTE(to_send, 4) >> 3);
int acc_state = GET_BYTE(to_send, 1) >> 4;
if (tesla_longitudinal) {
// Don't send messages when the stock AEB system is active
if (tesla_stock_aeb) {
violation = true;
}
// Prevent both acceleration from being negative, as this could cause the car to reverse after coming to standstill
if ((raw_accel_max < TESLA_LONG_LIMITS.inactive_accel) && (raw_accel_min < TESLA_LONG_LIMITS.inactive_accel)) {
violation = true;
}
// Don't allow any acceleration limits above the safety limits
violation |= longitudinal_accel_checks(raw_accel_max, TESLA_LONG_LIMITS);
violation |= longitudinal_accel_checks(raw_accel_min, TESLA_LONG_LIMITS);
} else {
// does allowing cancel here disrupt stock AEB? TODO: find out and add safety or remove comment
// Can only send cancel longitudinal messages when not controlling longitudinal
if (acc_state != 13) { // ACC_CANCEL_GENERIC_SILENT
violation = true;
}
// No actuation is allowed when not controlling longitudinal
if ((raw_accel_max != TESLA_LONG_LIMITS.inactive_accel) || (raw_accel_min != TESLA_LONG_LIMITS.inactive_accel)) {
violation = true;
}
}
}
if (violation) {
tx = false;
}
return tx;
}
static int tesla_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
if (bus_num == 0) {
// Party to autopilot
bus_fwd = 2;
}
if (bus_num == 2) {
bool block_msg = false;
// DAS_steeringControl, APS_eacMonitor
if ((addr == 0x488) || (addr == 0x27d)) {
block_msg = true;
}
// DAS_control
if (tesla_longitudinal && (addr == 0x2b9) && !tesla_stock_aeb) {
block_msg = true;
}
if (!block_msg) {
bus_fwd = 0;
}
}
return bus_fwd;
}
static safety_config tesla_init(uint16_t param) {
static const CanMsg TESLA_M3_Y_TX_MSGS[] = {
{0x488, 0, 4}, // DAS_steeringControl
{0x2b9, 0, 8}, // DAS_control
{0x27D, 0, 3}, // APS_eacMonitor
};
UNUSED(param);
#ifdef ALLOW_DEBUG
const int TESLA_FLAG_LONGITUDINAL_CONTROL = 1;
tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL);
#endif
tesla_stock_aeb = false;
static RxCheck tesla_model3_y_rx_checks[] = {
{.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control
{.msg = {{0x257, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // DI_speed (speed in kph)
{.msg = {{0x370, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // EPAS3S_internalSAS (steering angle)
{.msg = {{0x118, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_systemStatus (gas pedal)
{.msg = {{0x39d, 0, 5, .frequency = 25U}, { 0 }, { 0 }}}, // IBST_status (brakes)
{.msg = {{0x286, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state (acc state)
{.msg = {{0x311, 0, 7, .frequency = 10U}, { 0 }, { 0 }}}, // UI_warning (blinkers, buckle switch & doors)
};
return BUILD_SAFETY_CFG(tesla_model3_y_rx_checks, TESLA_M3_Y_TX_MSGS);
}
const safety_hooks tesla_hooks = {
.init = tesla_init,
.rx = tesla_rx_hook,
.tx = tesla_tx_hook,
.fwd = tesla_fwd_hook,
};

View File

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

View File

@@ -0,0 +1,13 @@
#pragma once
extern const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL;
const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL = 1;
extern bool volkswagen_longitudinal;
bool volkswagen_longitudinal = false;
extern bool volkswagen_set_button_prev;
bool volkswagen_set_button_prev = false;
extern bool volkswagen_resume_button_prev;
bool volkswagen_resume_button_prev = false;

View File

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

View File

@@ -0,0 +1,259 @@
#pragma once
#include "safety_declarations.h"
#include "safety_volkswagen_common.h"
#define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque
#define MSG_HCA_1 0x0D2 // TX by OP, Heading Control Assist steering torque
#define MSG_BREMSE_1 0x1A0 // RX from ABS, for ego speed
#define MSG_MOTOR_2 0x288 // RX from ECU, for CC state and brake switch state
#define MSG_ACC_SYSTEM 0x368 // TX by OP, longitudinal acceleration controls
#define MSG_MOTOR_3 0x380 // RX from ECU, for driver throttle input
#define MSG_GRA_NEU 0x38A // TX by OP, ACC control buttons for cancel/resume
#define MSG_MOTOR_5 0x480 // RX from ECU, for ACC main switch state
#define MSG_ACC_GRA_ANZEIGE 0x56A // TX by OP, ACC HUD
#define MSG_LDW_1 0x5BE // TX by OP, Lane line recognition and text alerts
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(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
uint8_t counter = 0U;
if (addr == MSG_LENKHILFE_3) {
counter = (uint8_t)(GET_BYTE(to_push, 1) & 0xF0U) >> 4;
} else if (addr == MSG_GRA_NEU) {
counter = (uint8_t)(GET_BYTE(to_push, 2) & 0xF0U) >> 4;
} else {
}
return counter;
}
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;
int checksum_byte = (addr == MSG_MOTOR_5) ? 7 : 0;
// Simple XOR over the payload, except for the byte where the checksum lives.
for (int i = 0; i < len; i++) {
if (i != checksum_byte) {
checksum ^= (uint8_t)GET_BYTE(to_push, i);
}
}
return checksum;
}
static safety_config volkswagen_pq_init(uint16_t param) {
// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
static const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8},
{MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}};
static const CanMsg VOLKSWAGEN_PQ_LONG_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8},
{MSG_ACC_SYSTEM, 0, 8}, {MSG_ACC_GRA_ANZEIGE, 0, 8}};
static RxCheck volkswagen_pq_rx_checks[] = {
{.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}},
{.msg = {{MSG_MOTOR_5, 0, 8, .check_checksum = true, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}},
{.msg = {{MSG_GRA_NEU, 0, 4, .check_checksum = true, .max_counter = 15U, .frequency = 30U}, { 0 }, { 0 }}},
};
UNUSED(param);
volkswagen_set_button_prev = false;
volkswagen_resume_button_prev = false;
#ifdef ALLOW_DEBUG
volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL);
#endif
return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_LONG_TX_MSGS) : \
BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_STOCK_TX_MSGS);
}
static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) {
if (GET_BUS(to_push) == 0U) {
int addr = GET_ADDR(to_push);
// Update in-motion state from speed value.
// Signal: Bremse_1.Geschwindigkeit_neu__Bremse_1_
if (addr == MSG_BREMSE_1) {
int speed = ((GET_BYTE(to_push, 2) & 0xFEU) >> 1) | (GET_BYTE(to_push, 3) << 7);
vehicle_moving = speed > 0;
}
// Update driver input torque samples
// Signal: Lenkhilfe_3.LH3_LM (absolute torque)
// Signal: Lenkhilfe_3.LH3_LMSign (direction)
if (addr == MSG_LENKHILFE_3) {
int torque_driver_new = GET_BYTE(to_push, 2) | ((GET_BYTE(to_push, 3) & 0x3U) << 8);
int sign = (GET_BYTE(to_push, 3) & 0x4U) >> 2;
if (sign == 1) {
torque_driver_new *= -1;
}
update_sample(&torque_driver, torque_driver_new);
}
if (volkswagen_longitudinal) {
if (addr == MSG_MOTOR_5) {
// ACC main switch on is a prerequisite to enter controls, exit controls immediately on main switch off
// Signal: Motor_5.GRA_Hauptschalter
acc_main_on = GET_BIT(to_push, 50U);
if (!acc_main_on) {
controls_allowed = false;
}
}
if (addr == MSG_GRA_NEU) {
// If ACC main switch is on, enter controls on falling edge of Set or Resume
// Signal: GRA_Neu.GRA_Neu_Setzen
// Signal: GRA_Neu.GRA_Neu_Recall
bool set_button = GET_BIT(to_push, 16U);
bool resume_button = GET_BIT(to_push, 17U);
if ((volkswagen_set_button_prev && !set_button) || (volkswagen_resume_button_prev && !resume_button)) {
controls_allowed = acc_main_on;
}
volkswagen_set_button_prev = set_button;
volkswagen_resume_button_prev = resume_button;
// Exit controls on rising edge of Cancel, override Set/Resume if present simultaneously
// Signal: GRA_ACC_01.GRA_Abbrechen
if (GET_BIT(to_push, 9U)) {
controls_allowed = false;
}
}
} else {
if (addr == MSG_MOTOR_2) {
// Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages
// Signal: Motor_2.GRA_Status
int acc_status = (GET_BYTE(to_push, 2) & 0xC0U) >> 6;
bool cruise_engaged = (acc_status == 1) || (acc_status == 2);
pcm_cruise_check(cruise_engaged);
}
}
// Signal: Motor_3.Fahrpedal_Rohsignal
if (addr == MSG_MOTOR_3) {
gas_pressed = (GET_BYTE(to_push, 2));
}
// Signal: Motor_2.Bremslichtschalter
if (addr == MSG_MOTOR_2) {
brake_pressed = (GET_BYTE(to_push, 2) & 0x1U);
}
generic_rx_checks((addr == MSG_HCA_1));
}
}
static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) {
// lateral limits
const SteeringLimits VOLKSWAGEN_PQ_STEERING_LIMITS = {
.max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated)
.max_rt_delta = 113, // 6 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 75 ; 125 * 1.5 for safety pad = 113
.max_rt_interval = 250000, // 250ms between real time checks
.max_rate_up = 6, // 3.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s)
.max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s)
.driver_torque_factor = 3,
.driver_torque_allowance = 80,
.type = TorqueDriverLimited,
};
// longitudinal limits
// acceleration in m/s2 * 1000 to avoid floating point math
const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS = {
.max_accel = 2000,
.min_accel = -3500,
.inactive_accel = 3010, // VW sends one increment above the max range when inactive
};
int addr = GET_ADDR(to_send);
bool tx = true;
// Safety check for HCA_1 Heading Control Assist torque
// Signal: HCA_1.LM_Offset (absolute torque)
// Signal: HCA_1.LM_Offsign (direction)
if (addr == MSG_HCA_1) {
int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x7FU) << 8);
desired_torque = desired_torque / 32; // DBC scale from PQ network to centi-Nm
int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7;
if (sign == 1) {
desired_torque *= -1;
}
uint32_t hca_status = ((GET_BYTE(to_send, 1) >> 4) & 0xFU);
bool steer_req = ((hca_status == 5U) || (hca_status == 7U));
if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_PQ_STEERING_LIMITS)) {
tx = false;
}
}
// Safety check for acceleration commands
// To avoid floating point math, scale upward and compare to pre-scaled safety m/s2 boundaries
if (addr == MSG_ACC_SYSTEM) {
// Signal: ACC_System.ACS_Sollbeschl (acceleration in m/s2, scale 0.005, offset -7.22)
int desired_accel = ((((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) * 5U) - 7220U;
if (longitudinal_accel_checks(desired_accel, VOLKSWAGEN_PQ_LONG_LIMITS)) {
tx = false;
}
}
// FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off.
// This avoids unintended engagements while still allowing resume spam
if ((addr == MSG_GRA_NEU) && !controls_allowed) {
// Signal: GRA_Neu.GRA_Neu_Setzen
// Signal: GRA_Neu.GRA_Neu_Recall
if (GET_BIT(to_send, 16U) || GET_BIT(to_send, 17U)) {
tx = false;
}
}
return tx;
}
static int volkswagen_pq_fwd_hook(int bus_num, int addr) {
int bus_fwd = -1;
switch (bus_num) {
case 0:
// Forward all traffic from the Extended CAN onward
bus_fwd = 2;
break;
case 2:
if ((addr == MSG_HCA_1) || (addr == MSG_LDW_1)) {
// openpilot takes over LKAS steering control and related HUD messages from the camera
bus_fwd = -1;
} else if (volkswagen_longitudinal && ((addr == MSG_ACC_SYSTEM) || (addr == MSG_ACC_GRA_ANZEIGE))) {
// openpilot takes over acceleration/braking control and related HUD messages from the stock ACC radar
} else {
// Forward all remaining traffic from Extended CAN devices to J533 gateway
bus_fwd = 0;
}
break;
default:
// No other buses should be in use; fallback to do-not-forward
bus_fwd = -1;
break;
}
return bus_fwd;
}
const safety_hooks volkswagen_pq_hooks = {
.init = volkswagen_pq_init,
.rx = volkswagen_pq_rx_hook,
.tx = volkswagen_pq_tx_hook,
.fwd = volkswagen_pq_fwd_hook,
.get_counter = volkswagen_pq_get_counter,
.get_checksum = volkswagen_pq_get_checksum,
.compute_checksum = volkswagen_pq_compute_checksum,
};

View File

@@ -0,0 +1,283 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#define GET_BIT(msg, b) ((bool)!!(((msg)->data[((b) / 8U)] >> ((b) % 8U)) & 0x1U))
#define GET_BYTE(msg, b) ((msg)->data[(b)])
#define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) // cppcheck-suppress misra-c2012-1.2; allow __typeof__
#define BUILD_SAFETY_CFG(rx, tx) ((safety_config){(rx), (sizeof((rx)) / sizeof((rx)[0])), \
(tx), (sizeof((tx)) / sizeof((tx)[0]))})
#define SET_RX_CHECKS(rx, config) \
do { \
(config).rx_checks = (rx); \
(config).rx_checks_len = sizeof((rx)) / sizeof((rx)[0]); \
} while (0);
#define SET_TX_MSGS(tx, config) \
do { \
(config).tx_msgs = (tx); \
(config).tx_msgs_len = sizeof((tx)) / sizeof((tx)[0]); \
} while(0);
#define UPDATE_VEHICLE_SPEED(val_ms) (update_sample(&vehicle_speed, ROUND((val_ms) * VEHICLE_SPEED_FACTOR)))
uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len);
extern const int MAX_WRONG_COUNTERS;
#define MAX_ADDR_CHECK_MSGS 3U
#define MAX_SAMPLE_VALS 6
// used to represent floating point vehicle speed in a sample_t
#define VEHICLE_SPEED_FACTOR 100.0
// sample struct that keeps 6 samples in memory
struct sample_t {
int values[MAX_SAMPLE_VALS];
int min;
int max;
};
// safety code requires floats
struct lookup_t {
float x[3];
float y[3];
};
typedef struct {
int addr;
int bus;
int len;
} CanMsg;
typedef enum {
TorqueMotorLimited, // torque steering command, limited by EPS output torque
TorqueDriverLimited, // torque steering command, limited by driver's input torque
} SteeringControlType;
typedef struct {
// torque cmd limits
const int max_steer;
const int max_rate_up;
const int max_rate_down;
const int max_rt_delta;
const uint32_t max_rt_interval;
const SteeringControlType type;
// driver torque limits
const int driver_torque_allowance;
const int driver_torque_factor;
// motor torque limits
const int max_torque_error;
// safety around steer req bit
const int min_valid_request_frames;
const int max_invalid_request_frames;
const uint32_t min_valid_request_rt_interval;
const bool has_steer_req_tolerance;
// angle cmd limits
const float angle_deg_to_can;
const struct lookup_t angle_rate_up_lookup;
const struct lookup_t angle_rate_down_lookup;
const int max_angle_error; // used to limit error between meas and cmd while enabled
const float angle_error_min_speed; // minimum speed to start limiting angle error
const bool enforce_angle_error; // enables max_angle_error check
const bool inactive_angle_is_zero; // if false, enforces angle near meas when disabled (default)
} SteeringLimits;
typedef struct {
// acceleration cmd limits
const int max_accel;
const int min_accel;
const int inactive_accel;
// gas & brake cmd limits
// inactive and min gas are 0 on most safety modes
const int max_gas;
const int min_gas;
const int inactive_gas;
const int max_brake;
// transmission rpm limits
const int max_transmission_rpm;
const int min_transmission_rpm;
const int inactive_transmission_rpm;
// speed cmd limits
const int inactive_speed;
} LongitudinalLimits;
typedef struct {
const int addr;
const int bus;
const int len;
const bool check_checksum; // true is checksum check is performed
const uint8_t max_counter; // maximum value of the counter. 0 means that the counter check is skipped
const bool quality_flag; // true is quality flag check is performed
const uint32_t frequency; // expected frequency of the message [Hz]
} CanMsgCheck;
typedef struct {
// dynamic flags, reset on safety mode init
bool msg_seen;
int index; // if multiple messages are allowed to be checked, this stores the index of the first one seen. only msg[msg_index] will be used
bool valid_checksum; // true if and only if checksum check is passed
int wrong_counters; // counter of wrong counters, saturated between 0 and MAX_WRONG_COUNTERS
bool valid_quality_flag; // true if the message's quality/health/status signals are valid
uint8_t last_counter; // last counter value
uint32_t last_timestamp; // micro-s
bool lagging; // true if and only if the time between updates is excessive
} RxStatus;
// params and flags about checksum, counter and frequency checks for each monitored address
typedef struct {
const CanMsgCheck msg[MAX_ADDR_CHECK_MSGS]; // check either messages (e.g. honda steer)
RxStatus status;
} RxCheck;
typedef struct {
RxCheck *rx_checks;
int rx_checks_len;
const CanMsg *tx_msgs;
int tx_msgs_len;
} safety_config;
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);
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);
void update_sample(struct sample_t *sample, int sample_new);
bool get_longitudinal_allowed(void);
int ROUND(float val);
void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]);
#ifdef CANFD
void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]);
#endif
void generic_rx_checks(bool stock_ecu_detected);
bool steer_torque_cmd_checks(int desired_torque, int steer_req, const SteeringLimits limits);
bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const SteeringLimits limits);
bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits);
bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limits);
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);
void pcm_cruise_check(bool cruise_engaged);
void safety_tick(const safety_config *safety_config);
// This can be set by the safety hooks
extern bool controls_allowed;
extern bool relay_malfunction;
extern bool gas_pressed;
extern bool gas_pressed_prev;
extern bool brake_pressed;
extern bool brake_pressed_prev;
extern bool regen_braking;
extern bool regen_braking_prev;
extern bool cruise_engaged_prev;
extern struct sample_t vehicle_speed;
extern bool vehicle_moving;
extern bool acc_main_on; // referred to as "ACC off" in ISO 15622:2018
extern int cruise_button_prev;
extern bool safety_rx_checks_invalid;
// for safety modes with torque steering control
extern int desired_torque_last; // last desired steer torque
extern int rt_torque_last; // last desired torque for real time check
extern int valid_steer_req_count; // counter for steer request bit matching non-zero torque
extern int invalid_steer_req_count; // counter to allow multiple frames of mismatching torque request bit
extern struct sample_t torque_meas; // last 6 motor torques produced by the eps
extern struct sample_t torque_driver; // last 6 driver torques measured
extern uint32_t ts_torque_check_last;
extern uint32_t ts_steer_req_mismatch_last; // last timestamp steer req was mismatched with torque
// state for controls_allowed timeout logic
extern bool heartbeat_engaged; // openpilot enabled, passed in heartbeat USB command
extern uint32_t heartbeat_engaged_mismatches; // count of mismatches between heartbeat_engaged and controls_allowed
// for safety modes with angle steering control
extern uint32_t ts_angle_last;
extern int desired_angle_last;
extern struct sample_t angle_meas; // last 6 steer angles/curvatures
// This can be set with a USB command
// It enables features that allow alternative experiences, like not disengaging on gas press
// It is only either 0 or 1 on mainline comma.ai openpilot
#define ALT_EXP_DISABLE_DISENGAGE_ON_GAS 1
// If using this flag, make sure to communicate to your users that a stock safety feature is now disabled.
#define ALT_EXP_DISABLE_STOCK_AEB 2
// If using this flag, be aware that harder braking is more likely to lead to rear endings,
// and that alone this flag doesn't make braking compliant because there's also a time element.
// Setting this flag is used for allowing the full -5.0 to +4.0 m/s^2 at lower speeds
// See ISO 15622:2018 for more information.
#define ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX 8
// This flag allows AEB to be commanded from openpilot.
#define ALT_EXP_ALLOW_AEB 16
extern int alternative_experience;
// time since safety mode has been changed
extern uint32_t safety_mode_cnt;
typedef struct {
uint16_t id;
const safety_hooks *hooks;
} safety_hook_config;
extern uint16_t current_safety_mode;
extern uint16_t current_safety_param;
extern safety_config current_safety_config;
int safety_fwd_hook(int bus_num, int addr);
int set_safety_hooks(uint16_t mode, uint16_t param);
extern const safety_hooks body_hooks;
extern const safety_hooks chrysler_hooks;
extern const safety_hooks elm327_hooks;
extern const safety_hooks nooutput_hooks;
extern const safety_hooks alloutput_hooks;
extern const safety_hooks ford_hooks;
extern const safety_hooks gm_hooks;
extern const safety_hooks honda_nidec_hooks;
extern const safety_hooks honda_bosch_hooks;
extern const safety_hooks hyundai_canfd_hooks;
extern const safety_hooks hyundai_hooks;
extern const safety_hooks hyundai_legacy_hooks;
extern const safety_hooks mazda_hooks;
extern const safety_hooks nissan_hooks;
extern const safety_hooks subaru_hooks;
extern const safety_hooks subaru_preglobal_hooks;
extern const safety_hooks tesla_hooks;
extern const safety_hooks toyota_hooks;
extern const safety_hooks volkswagen_mqb_hooks;
extern const safety_hooks volkswagen_pq_hooks;

View File

View File

@@ -0,0 +1,985 @@
import os
import abc
import unittest
import importlib
import numpy as np
from collections.abc import Callable
from opendbc.can.packer import CANPacker # pylint: disable=import-error
from opendbc.safety import ALTERNATIVE_EXPERIENCE
from opendbc.safety.tests.libsafety import libsafety_py
MAX_WRONG_COUNTERS = 5
MAX_SAMPLE_VALS = 6
VEHICLE_SPEED_FACTOR = 100
MessageFunction = Callable[[float], libsafety_py.CANPacket]
def sign_of(a):
return 1 if a > 0 else -1
def make_msg(bus, addr, length=8, dat=None):
if dat is None:
dat = b'\x00' * length
return libsafety_py.make_CANPacket(addr, bus, dat)
class CANPackerPanda(CANPacker):
def make_can_msg_panda(self, name_or_addr, bus, values, fix_checksum=None):
msg = self.make_can_msg(name_or_addr, bus, values)
if fix_checksum is not None:
msg = fix_checksum(msg)
addr, dat, bus = msg
return libsafety_py.make_CANPacket(addr, bus, dat)
def add_regen_tests(cls):
"""Dynamically adds regen tests for all user brake tests."""
# only rx/user brake tests, not brake command
found_tests = [func for func in dir(cls) if func.startswith("test_") and "user_brake" in func]
assert len(found_tests) >= 3, "Failed to detect known brake tests"
for test in found_tests:
def _make_regen_test(brake_func):
def _regen_test(self):
# only for safety modes with a regen message
if self._user_regen_msg(0) is None:
raise unittest.SkipTest("Safety mode implements no _user_regen_msg")
getattr(self, brake_func)(self._user_regen_msg, self.safety.get_regen_braking_prev)
return _regen_test
setattr(cls, test.replace("brake", "regen"), _make_regen_test(test))
return cls
class PandaSafetyTestBase(unittest.TestCase):
safety: libsafety_py.Panda
@classmethod
def setUpClass(cls):
if cls.__name__ == "PandaSafetyTestBase":
cls.safety = None
raise unittest.SkipTest
def _reset_safety_hooks(self):
self.safety.set_safety_hooks(self.safety.get_current_safety_mode(),
self.safety.get_current_safety_param())
def _rx(self, msg):
return self.safety.safety_rx_hook(msg)
def _tx(self, msg):
return self.safety.safety_tx_hook(msg)
def _generic_limit_safety_check(self, msg_function: MessageFunction, min_allowed_value: float, max_allowed_value: float,
min_possible_value: float, max_possible_value: float, test_delta: float = 1, inactive_value: float = 0,
msg_allowed = True, additional_setup: Callable[[float], None] | None = None):
"""
Enforces that a signal within a message is only allowed to be sent within a specific range, min_allowed_value -> max_allowed_value.
Tests the range of min_possible_value -> max_possible_value with a delta of test_delta.
Message is also only allowed to be sent when controls_allowed is true, unless the value is equal to inactive_value.
Message is never allowed if msg_allowed is false, for example when stock longitudinal is enabled and you are sending acceleration requests.
additional_setup is used for extra setup before each _tx, ex: for setting the previous torque for rate limits
"""
# Ensure that we at least test the allowed_value range
self.assertGreater(max_possible_value, max_allowed_value)
self.assertLessEqual(min_possible_value, min_allowed_value)
for controls_allowed in [False, True]:
# enforce we don't skip over 0 or inactive
for v in np.concatenate((np.arange(min_possible_value, max_possible_value, test_delta), np.array([0, inactive_value]))):
v = round(v, 2) # floats might not hit exact boundary conditions without rounding
self.safety.set_controls_allowed(controls_allowed)
if additional_setup is not None:
additional_setup(v)
should_tx = controls_allowed and min_allowed_value <= v <= max_allowed_value
should_tx = (should_tx or v == inactive_value) and msg_allowed
self.assertEqual(self._tx(msg_function(v)), should_tx, (controls_allowed, should_tx, v))
def _common_measurement_test(self, msg_func: Callable, min_value: float, max_value: float, factor: float,
meas_min_func: Callable[[], int], meas_max_func: Callable[[], int]):
"""Tests accurate measurement parsing, and that the struct is reset on safety mode init"""
for val in np.arange(min_value, max_value, 0.5):
for i in range(MAX_SAMPLE_VALS):
self.assertTrue(self._rx(msg_func(val + i * 0.1)))
# assert close by one decimal place
self.assertAlmostEqual(meas_min_func() / factor, val, delta=0.1)
self.assertAlmostEqual(meas_max_func() / factor - 0.5, val, delta=0.1)
# ensure sample_t is reset on safety init
self._reset_safety_hooks()
self.assertEqual(meas_min_func(), 0)
self.assertEqual(meas_max_func(), 0)
class LongitudinalAccelSafetyTest(PandaSafetyTestBase, abc.ABC):
MAX_ACCEL: float = 2.0
MIN_ACCEL: float = -3.5
INACTIVE_ACCEL: float = 0.0
@classmethod
def setUpClass(cls):
if cls.__name__ == "LongitudinalAccelSafetyTest":
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _accel_msg(self, accel: float):
pass
def test_accel_limits_correct(self):
self.assertGreater(self.MAX_ACCEL, 0)
self.assertLess(self.MIN_ACCEL, 0)
def test_accel_actuation_limits(self, stock_longitudinal=False):
limits = ((self.MIN_ACCEL, self.MAX_ACCEL, ALTERNATIVE_EXPERIENCE.DEFAULT),
(self.MIN_ACCEL, self.MAX_ACCEL, ALTERNATIVE_EXPERIENCE.RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX))
for min_accel, max_accel, alternative_experience in limits:
# enforce we don't skip over 0 or inactive accel
for accel in np.concatenate((np.arange(min_accel - 1, max_accel + 1, 0.05), [0, self.INACTIVE_ACCEL])):
accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding
for controls_allowed in [True, False]:
self.safety.set_controls_allowed(controls_allowed)
self.safety.set_alternative_experience(alternative_experience)
if stock_longitudinal:
should_tx = False
else:
should_tx = controls_allowed and min_accel <= accel <= max_accel
should_tx = should_tx or accel == self.INACTIVE_ACCEL
self.assertEqual(should_tx, self._tx(self._accel_msg(accel)))
class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC):
MIN_BRAKE: int = 0
MAX_BRAKE: int | None = None
MAX_POSSIBLE_BRAKE: int | None = None
MIN_GAS: int = 0
MAX_GAS: int | None = None
INACTIVE_GAS = 0
MAX_POSSIBLE_GAS: int | None = None
def test_gas_brake_limits_correct(self):
self.assertIsNotNone(self.MAX_POSSIBLE_BRAKE)
self.assertIsNotNone(self.MAX_POSSIBLE_GAS)
self.assertGreater(self.MAX_BRAKE, self.MIN_BRAKE)
self.assertGreater(self.MAX_GAS, self.MIN_GAS)
@abc.abstractmethod
def _send_gas_msg(self, gas: int):
pass
@abc.abstractmethod
def _send_brake_msg(self, brake: int):
pass
def test_brake_safety_check(self):
self._generic_limit_safety_check(self._send_brake_msg, self.MIN_BRAKE, self.MAX_BRAKE, 0, self.MAX_POSSIBLE_BRAKE, 1)
def test_gas_safety_check(self):
self._generic_limit_safety_check(self._send_gas_msg, self.MIN_GAS, self.MAX_GAS, 0, self.MAX_POSSIBLE_GAS, 1, self.INACTIVE_GAS)
class TorqueSteeringSafetyTestBase(PandaSafetyTestBase, abc.ABC):
MAX_RATE_UP = 0
MAX_RATE_DOWN = 0
MAX_TORQUE = 0
MAX_RT_DELTA = 0
RT_INTERVAL = 0
NO_STEER_REQ_BIT = False
@classmethod
def setUpClass(cls):
if cls.__name__ == "TorqueSteeringSafetyTestBase":
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _torque_cmd_msg(self, torque, steer_req=1):
pass
def _set_prev_torque(self, t):
self.safety.set_desired_torque_last(t)
self.safety.set_rt_torque_last(t)
def test_steer_safety_check(self):
for enabled in [0, 1]:
for t in range(int(-self.MAX_TORQUE * 1.5), int(self.MAX_TORQUE * 1.5)):
self.safety.set_controls_allowed(enabled)
self._set_prev_torque(t)
if abs(t) > self.MAX_TORQUE or (not enabled and abs(t) > 0):
self.assertFalse(self._tx(self._torque_cmd_msg(t)))
else:
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
def test_non_realtime_limit_up(self):
self.safety.set_controls_allowed(True)
self._set_prev_torque(0)
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP)))
self._set_prev_torque(0)
self.assertTrue(self._tx(self._torque_cmd_msg(-self.MAX_RATE_UP)))
self._set_prev_torque(0)
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP + 1)))
self.safety.set_controls_allowed(True)
self._set_prev_torque(0)
self.assertFalse(self._tx(self._torque_cmd_msg(-self.MAX_RATE_UP - 1)))
def test_steer_req_bit(self):
"""Asserts all torque safety modes check the steering request bit"""
if self.NO_STEER_REQ_BIT:
raise unittest.SkipTest("No steering request bit")
self.safety.set_controls_allowed(True)
self._set_prev_torque(self.MAX_TORQUE)
# Send torque successfully, then only drop the request bit and ensure it stays blocked
for _ in range(10):
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 1)))
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 0)))
for _ in range(10):
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 1)))
class SteerRequestCutSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC):
@classmethod
def setUpClass(cls):
if cls.__name__ == "SteerRequestCutSafetyTest":
cls.safety = None
raise unittest.SkipTest
# Safety around steering request bit mismatch tolerance
MIN_VALID_STEERING_FRAMES: int
MAX_INVALID_STEERING_FRAMES: int
MIN_VALID_STEERING_RT_INTERVAL: int
def test_steer_req_bit_frames(self):
"""
Certain safety modes implement some tolerance on their steer request bits matching the
requested torque to avoid a steering fault or lockout and maintain torque. This tests:
- We can't cut torque for more than one frame
- We can't cut torque until at least the minimum number of matching steer_req messages
- We can always recover from violations if steer_req=1
"""
for min_valid_steer_frames in range(self.MIN_VALID_STEERING_FRAMES * 2):
# Reset match count and rt timer to allow cut (valid_steer_req_count, ts_steer_req_mismatch_last)
self.safety.init_tests()
self.safety.set_timer(self.MIN_VALID_STEERING_RT_INTERVAL)
# Allow torque cut
self.safety.set_controls_allowed(True)
self._set_prev_torque(self.MAX_TORQUE)
for _ in range(min_valid_steer_frames):
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
# should tx if we've sent enough valid frames, and we're not cutting torque for too many frames consecutively
should_tx = min_valid_steer_frames >= self.MIN_VALID_STEERING_FRAMES
for idx in range(self.MAX_INVALID_STEERING_FRAMES * 2):
tx = self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))
self.assertEqual(should_tx and idx < self.MAX_INVALID_STEERING_FRAMES, tx)
# Keep blocking after one steer_req mismatch
for _ in range(100):
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)))
# Make sure we can recover
self.assertTrue(self._tx(self._torque_cmd_msg(0, steer_req=1)))
self._set_prev_torque(self.MAX_TORQUE)
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
def test_steer_req_bit_multi_invalid(self):
"""
For safety modes allowing multiple consecutive invalid frames, this ensures that once a valid frame
is sent after an invalid frame (even without sending the max number of allowed invalid frames),
all counters are reset.
"""
for max_invalid_steer_frames in range(1, self.MAX_INVALID_STEERING_FRAMES * 2):
self.safety.init_tests()
self.safety.set_timer(self.MIN_VALID_STEERING_RT_INTERVAL)
# Allow torque cut
self.safety.set_controls_allowed(True)
self._set_prev_torque(self.MAX_TORQUE)
for _ in range(self.MIN_VALID_STEERING_FRAMES):
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
# Send partial amount of allowed invalid frames
for idx in range(max_invalid_steer_frames):
should_tx = idx < self.MAX_INVALID_STEERING_FRAMES
self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)))
# Send one valid frame, and subsequent invalid should now be blocked
self._set_prev_torque(self.MAX_TORQUE)
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
for _ in range(self.MIN_VALID_STEERING_FRAMES + 1):
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)))
def test_steer_req_bit_realtime(self):
"""
Realtime safety for cutting steer request bit. This tests:
- That we allow messages with mismatching steer request bit if time from last is >= MIN_VALID_STEERING_RT_INTERVAL
- That frame mismatch safety does not interfere with this test
"""
for rt_us in np.arange(self.MIN_VALID_STEERING_RT_INTERVAL - 50000, self.MIN_VALID_STEERING_RT_INTERVAL + 50000, 10000):
# Reset match count and rt timer (valid_steer_req_count, ts_steer_req_mismatch_last)
self.safety.init_tests()
# Make sure valid_steer_req_count doesn't affect this test
self.safety.set_controls_allowed(True)
self._set_prev_torque(self.MAX_TORQUE)
for _ in range(self.MIN_VALID_STEERING_FRAMES):
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
# Normally, sending MIN_VALID_STEERING_FRAMES valid frames should always allow
self.safety.set_timer(max(rt_us, 0))
should_tx = rt_us >= self.MIN_VALID_STEERING_RT_INTERVAL
for _ in range(self.MAX_INVALID_STEERING_FRAMES):
self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)))
# Keep blocking after one steer_req mismatch
for _ in range(100):
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)))
# Make sure we can recover
self.assertTrue(self._tx(self._torque_cmd_msg(0, steer_req=1)))
self._set_prev_torque(self.MAX_TORQUE)
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1)))
class DriverTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC):
DRIVER_TORQUE_ALLOWANCE = 0
DRIVER_TORQUE_FACTOR = 0
@classmethod
def setUpClass(cls):
if cls.__name__ == "DriverTorqueSteeringSafetyTest":
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _torque_driver_msg(self, torque):
pass
def _reset_torque_driver_measurement(self, torque):
for _ in range(MAX_SAMPLE_VALS):
self._rx(self._torque_driver_msg(torque))
def test_non_realtime_limit_up(self):
self._reset_torque_driver_measurement(0)
super().test_non_realtime_limit_up()
def test_against_torque_driver(self):
# Tests down limits and driver torque blending
self.safety.set_controls_allowed(True)
# Cannot stay at MAX_TORQUE if above DRIVER_TORQUE_ALLOWANCE
for sign in [-1, 1]:
for driver_torque in np.arange(0, self.DRIVER_TORQUE_ALLOWANCE * 2, 1):
self._reset_torque_driver_measurement(-driver_torque * sign)
self._set_prev_torque(self.MAX_TORQUE * sign)
should_tx = abs(driver_torque) <= self.DRIVER_TORQUE_ALLOWANCE
self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE * sign)))
# arbitrary high driver torque to ensure max steer torque is allowed
max_driver_torque = int(self.MAX_TORQUE / self.DRIVER_TORQUE_FACTOR + self.DRIVER_TORQUE_ALLOWANCE + 1)
# spot check some individual cases
for sign in [-1, 1]:
# Ensure we wind down factor units for every unit above allowance
driver_torque = (self.DRIVER_TORQUE_ALLOWANCE + 10) * sign
torque_desired = (self.MAX_TORQUE - 10 * self.DRIVER_TORQUE_FACTOR) * sign
delta = 1 * sign
self._set_prev_torque(torque_desired)
self._reset_torque_driver_measurement(-driver_torque)
self.assertTrue(self._tx(self._torque_cmd_msg(torque_desired)))
self._set_prev_torque(torque_desired + delta)
self._reset_torque_driver_measurement(-driver_torque)
self.assertFalse(self._tx(self._torque_cmd_msg(torque_desired + delta)))
# If we're well past the allowance, minimum wind down is MAX_RATE_DOWN
self._set_prev_torque(self.MAX_TORQUE * sign)
self._reset_torque_driver_measurement(-max_driver_torque * sign)
self.assertTrue(self._tx(self._torque_cmd_msg((self.MAX_TORQUE - self.MAX_RATE_DOWN) * sign)))
self._set_prev_torque(self.MAX_TORQUE * sign)
self._reset_torque_driver_measurement(-max_driver_torque * sign)
self.assertTrue(self._tx(self._torque_cmd_msg(0)))
self._set_prev_torque(self.MAX_TORQUE * sign)
self._reset_torque_driver_measurement(-max_driver_torque * sign)
self.assertFalse(self._tx(self._torque_cmd_msg((self.MAX_TORQUE - self.MAX_RATE_DOWN + 1) * sign)))
def test_realtime_limits(self):
self.safety.set_controls_allowed(True)
for sign in [-1, 1]:
self.safety.init_tests()
self._set_prev_torque(0)
self._reset_torque_driver_measurement(0)
for t in np.arange(0, self.MAX_RT_DELTA, 1):
t *= sign
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1))))
self._set_prev_torque(0)
for t in np.arange(0, self.MAX_RT_DELTA, 1):
t *= sign
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
# Increase timer to update rt_torque_last
self.safety.set_timer(self.RT_INTERVAL + 1)
self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA - 1))))
self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1))))
def test_reset_driver_torque_measurements(self):
# Tests that the driver torque measurement sample_t is reset on safety mode init
for t in np.linspace(-self.MAX_TORQUE, self.MAX_TORQUE, MAX_SAMPLE_VALS):
self.assertTrue(self._rx(self._torque_driver_msg(t)))
self.assertNotEqual(self.safety.get_torque_driver_min(), 0)
self.assertNotEqual(self.safety.get_torque_driver_max(), 0)
self._reset_safety_hooks()
self.assertEqual(self.safety.get_torque_driver_min(), 0)
self.assertEqual(self.safety.get_torque_driver_max(), 0)
class MotorTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC):
MAX_TORQUE_ERROR = 0
TORQUE_MEAS_TOLERANCE = 0
@classmethod
def setUpClass(cls):
if cls.__name__ == "MotorTorqueSteeringSafetyTest":
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _torque_meas_msg(self, torque):
pass
def _set_prev_torque(self, t):
super()._set_prev_torque(t)
self.safety.set_torque_meas(t, t)
def test_torque_absolute_limits(self):
for controls_allowed in [True, False]:
for torque in np.arange(-self.MAX_TORQUE - 1000, self.MAX_TORQUE + 1000, self.MAX_RATE_UP):
self.safety.set_controls_allowed(controls_allowed)
self.safety.set_rt_torque_last(torque)
self.safety.set_torque_meas(torque, torque)
self.safety.set_desired_torque_last(torque - self.MAX_RATE_UP)
if controls_allowed:
send = (-self.MAX_TORQUE <= torque <= self.MAX_TORQUE)
else:
send = torque == 0
self.assertEqual(send, self._tx(self._torque_cmd_msg(torque)))
def test_non_realtime_limit_down(self):
self.safety.set_controls_allowed(True)
torque_meas = self.MAX_TORQUE - self.MAX_TORQUE_ERROR - 50
self.safety.set_rt_torque_last(self.MAX_TORQUE)
self.safety.set_torque_meas(torque_meas, torque_meas)
self.safety.set_desired_torque_last(self.MAX_TORQUE)
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE - self.MAX_RATE_DOWN)))
self.safety.set_rt_torque_last(self.MAX_TORQUE)
self.safety.set_torque_meas(torque_meas, torque_meas)
self.safety.set_desired_torque_last(self.MAX_TORQUE)
self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE - self.MAX_RATE_DOWN + 1)))
def test_exceed_torque_sensor(self):
self.safety.set_controls_allowed(True)
for sign in [-1, 1]:
self._set_prev_torque(0)
for t in np.arange(0, self.MAX_TORQUE_ERROR + 2, 2): # step needs to be smaller than MAX_TORQUE_ERROR
t *= sign
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_TORQUE_ERROR + 2))))
def test_realtime_limit_up(self):
self.safety.set_controls_allowed(True)
for sign in [-1, 1]:
self.safety.init_tests()
self._set_prev_torque(0)
for t in np.arange(0, self.MAX_RT_DELTA + 1, 1):
t *= sign
self.safety.set_torque_meas(t, t)
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1))))
self._set_prev_torque(0)
for t in np.arange(0, self.MAX_RT_DELTA + 1, 1):
t *= sign
self.safety.set_torque_meas(t, t)
self.assertTrue(self._tx(self._torque_cmd_msg(t)))
# Increase timer to update rt_torque_last
self.safety.set_timer(self.RT_INTERVAL + 1)
self.assertTrue(self._tx(self._torque_cmd_msg(sign * self.MAX_RT_DELTA)))
self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1))))
def test_torque_measurements(self):
trq = 50
for t in [trq, -trq, 0, 0, 0, 0]:
self._rx(self._torque_meas_msg(t))
max_range = range(trq, trq + self.TORQUE_MEAS_TOLERANCE + 1)
min_range = range(-(trq + self.TORQUE_MEAS_TOLERANCE), -trq + 1)
self.assertTrue(self.safety.get_torque_meas_min() in min_range)
self.assertTrue(self.safety.get_torque_meas_max() in max_range)
max_range = range(self.TORQUE_MEAS_TOLERANCE + 1)
min_range = range(-(trq + self.TORQUE_MEAS_TOLERANCE), -trq + 1)
self._rx(self._torque_meas_msg(0))
self.assertTrue(self.safety.get_torque_meas_min() in min_range)
self.assertTrue(self.safety.get_torque_meas_max() in max_range)
max_range = range(self.TORQUE_MEAS_TOLERANCE + 1)
min_range = range(-self.TORQUE_MEAS_TOLERANCE, 0 + 1)
self._rx(self._torque_meas_msg(0))
self.assertTrue(self.safety.get_torque_meas_min() in min_range)
self.assertTrue(self.safety.get_torque_meas_max() in max_range)
def test_reset_torque_measurements(self):
# Tests that the torque measurement sample_t is reset on safety mode init
for t in np.linspace(-self.MAX_TORQUE, self.MAX_TORQUE, MAX_SAMPLE_VALS):
self.assertTrue(self._rx(self._torque_meas_msg(t)))
self.assertNotEqual(self.safety.get_torque_meas_min(), 0)
self.assertNotEqual(self.safety.get_torque_meas_max(), 0)
self._reset_safety_hooks()
self.assertEqual(self.safety.get_torque_meas_min(), 0)
self.assertEqual(self.safety.get_torque_meas_max(), 0)
class AngleSteeringSafetyTest(PandaSafetyTestBase):
DEG_TO_CAN: float
ANGLE_RATE_BP: list[float]
ANGLE_RATE_UP: list[float] # windup limit
ANGLE_RATE_DOWN: list[float] # unwind limit
@classmethod
def setUpClass(cls):
if cls.__name__ == "AngleSteeringSafetyTest":
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _speed_msg(self, speed):
pass
@abc.abstractmethod
def _angle_cmd_msg(self, angle: float, enabled: bool):
pass
@abc.abstractmethod
def _angle_meas_msg(self, angle: float):
pass
def _set_prev_desired_angle(self, t):
t = round(t * self.DEG_TO_CAN)
self.safety.set_desired_angle_last(t)
def _reset_angle_measurement(self, angle):
for _ in range(MAX_SAMPLE_VALS):
self._rx(self._angle_meas_msg(angle))
def _reset_speed_measurement(self, speed):
for _ in range(MAX_SAMPLE_VALS):
self._rx(self._speed_msg(speed))
def test_vehicle_speed_measurements(self):
self._common_measurement_test(self._speed_msg, 0, 80, VEHICLE_SPEED_FACTOR, self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max)
def test_steering_angle_measurements(self, max_angle=300):
self._common_measurement_test(self._angle_meas_msg, -max_angle, max_angle, self.DEG_TO_CAN, self.safety.get_angle_meas_min, self.safety.get_angle_meas_max)
def test_angle_cmd_when_enabled(self, max_angle=300):
# when controls are allowed, angle cmd rate limit is enforced
speeds = [0., 1., 5., 10., 15., 50.]
angles = np.concatenate((np.arange(-max_angle, max_angle, 5), [0]))
for a in angles:
for s in speeds:
max_delta_up = np.interp(s, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP)
max_delta_down = np.interp(s, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN)
# first test against false positives
self._reset_angle_measurement(a)
self._reset_speed_measurement(s)
self._set_prev_desired_angle(a)
self.safety.set_controls_allowed(1)
# Stay within limits
# Up
self.assertTrue(self._tx(self._angle_cmd_msg(a + sign_of(a) * max_delta_up, True)))
self.assertTrue(self.safety.get_controls_allowed())
# Don't change
self.assertTrue(self._tx(self._angle_cmd_msg(a, True)))
self.assertTrue(self.safety.get_controls_allowed())
# Down
self.assertTrue(self._tx(self._angle_cmd_msg(a - sign_of(a) * max_delta_down, True)))
self.assertTrue(self.safety.get_controls_allowed())
# Inject too high rates
# Up
self.assertFalse(self._tx(self._angle_cmd_msg(a + sign_of(a) * (max_delta_up + 1.1), True)))
# Don't change
self.safety.set_controls_allowed(1)
self._set_prev_desired_angle(a)
self.assertTrue(self.safety.get_controls_allowed())
self.assertTrue(self._tx(self._angle_cmd_msg(a, True)))
self.assertTrue(self.safety.get_controls_allowed())
# Down
self.assertFalse(self._tx(self._angle_cmd_msg(a - sign_of(a) * (max_delta_down + 1.1), True)))
# Check desired steer should be the same as steer angle when controls are off
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._angle_cmd_msg(a, False)))
def test_angle_cmd_when_disabled(self):
# Tests that only angles close to the meas are allowed while
# steer actuation bit is 0, regardless of controls allowed.
for controls_allowed in (True, False):
self.safety.set_controls_allowed(controls_allowed)
for steer_control_enabled in (True, False):
for angle_meas in np.arange(-90, 91, 10):
self._reset_angle_measurement(angle_meas)
for angle_cmd in np.arange(-90, 91, 10):
self._set_prev_desired_angle(angle_cmd)
# controls_allowed is checked if actuation bit is 1, else the angle must be close to meas (inactive)
should_tx = controls_allowed if steer_control_enabled else angle_cmd == angle_meas
self.assertEqual(should_tx, self._tx(self._angle_cmd_msg(angle_cmd, steer_control_enabled)))
class PandaSafetyTest(PandaSafetyTestBase):
TX_MSGS: list[list[int]] | None = None
SCANNED_ADDRS = [*range(0x800), # Entire 11-bit CAN address space
*range(0x18DA00F1, 0x18DB00F1, 0x100), # 29-bit UDS physical addressing
*range(0x18DB00F1, 0x18DC00F1, 0x100), # 29-bit UDS functional addressing
*range(0x3300, 0x3400)] # Honda
FWD_BLACKLISTED_ADDRS: dict[int, list[int]] = {} # {bus: [addr]}
FWD_BUS_LOOKUP: dict[int, int] = {}
@classmethod
def setUpClass(cls):
if cls.__name__ == "PandaSafetyTest" or cls.__name__.endswith('Base'):
cls.safety = None
raise unittest.SkipTest
# ***** standard tests for all safety modes *****
def test_tx_msg_in_scanned_range(self):
# the relay malfunction, fwd hook, and spam can tests don't exhaustively
# scan the entire 29-bit address space, only some known important ranges
# make sure SCANNED_ADDRS stays up to date with car port TX_MSGS; new
# model ports should expand the range if needed
for msg in self.TX_MSGS:
self.assertTrue(msg[0] in self.SCANNED_ADDRS, f"{msg[0]=:#x}")
def test_fwd_hook(self):
# some safety modes don't forward anything, while others blacklist msgs
for bus in range(3):
for addr in self.SCANNED_ADDRS:
# assume len 8
fwd_bus = self.FWD_BUS_LOOKUP.get(bus, -1)
if bus in self.FWD_BLACKLISTED_ADDRS and addr in self.FWD_BLACKLISTED_ADDRS[bus]:
fwd_bus = -1
self.assertEqual(fwd_bus, self.safety.safety_fwd_hook(bus, addr), f"{addr=:#x} from {bus=} to {fwd_bus=}")
def test_spam_can_buses(self):
for bus in range(4):
for addr in self.SCANNED_ADDRS:
if [addr, bus] not in self.TX_MSGS:
self.assertFalse(self._tx(make_msg(bus, addr, 8)), f"allowed TX {addr=} {bus=}")
def test_default_controls_not_allowed(self):
self.assertFalse(self.safety.get_controls_allowed())
def test_manually_enable_controls_allowed(self):
self.safety.set_controls_allowed(1)
self.assertTrue(self.safety.get_controls_allowed())
self.safety.set_controls_allowed(0)
self.assertFalse(self.safety.get_controls_allowed())
def test_tx_hook_on_wrong_safety_mode(self):
files = os.listdir(os.path.dirname(os.path.realpath(__file__)))
test_files = [f for f in files if f.startswith("test_") and f.endswith(".py")]
current_test = self.__class__.__name__
all_tx = []
for tf in test_files:
test = importlib.import_module("opendbc.safety.tests."+tf[:-3])
for attr in dir(test):
if attr.startswith("Test") and attr != current_test:
tc = getattr(test, attr)
tx = tc.TX_MSGS
if tx is not None and not attr.endswith('Base'):
# No point in comparing different Tesla safety modes
if 'Tesla' in attr and 'Tesla' in current_test:
continue
# No point in comparing to ALLOUTPUT which allows all messages
if attr.startswith('TestAllOutput'):
continue
if attr.startswith('TestToyota') and current_test.startswith('TestToyota'):
continue
if attr.startswith('TestSubaruGen') and current_test.startswith('TestSubaruGen'):
continue
if attr.startswith('TestSubaruPreglobal') and current_test.startswith('TestSubaruPreglobal'):
continue
if {attr, current_test}.issubset({'TestVolkswagenPqSafety', 'TestVolkswagenPqStockSafety', 'TestVolkswagenPqLongSafety'}):
continue
if {attr, current_test}.issubset({'TestGmCameraSafety', 'TestGmCameraLongitudinalSafety'}):
continue
if attr.startswith('TestFord') and current_test.startswith('TestFord'):
continue
if attr.startswith('TestHyundaiCanfd') and current_test.startswith('TestHyundaiCanfd'):
continue
if {attr, current_test}.issubset({'TestVolkswagenMqbSafety', 'TestVolkswagenMqbStockSafety', 'TestVolkswagenMqbLongSafety'}):
continue
# overlapping TX addrs, but they're not actuating messages for either car
if attr == 'TestHyundaiCanfdHDA2LongEV' and current_test.startswith('TestToyota'):
tx = list(filter(lambda m: m[0] not in [0x160, ], tx))
# Volkswagen MQB longitudinal actuating message overlaps with the Subaru lateral actuating message
if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestSubaru'):
tx = list(filter(lambda m: m[0] not in [0x122, ], tx))
# Volkswagen MQB and Honda Nidec ACC HUD messages overlap
if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestHondaNidec'):
tx = list(filter(lambda m: m[0] not in [0x30c, ], tx))
# Volkswagen MQB and Honda Bosch Radarless ACC HUD messages overlap
if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestHondaBoschRadarless'):
tx = list(filter(lambda m: m[0] not in [0x30c, ], tx))
# TODO: Temporary, should be fixed in panda firmware, safety_honda.h
if attr.startswith('TestHonda'):
# exceptions for common msgs across different hondas
tx = list(filter(lambda m: m[0] not in [0x1FA, 0x30C, 0x33D, 0x33DB], tx))
all_tx.append([[m[0], m[1], attr] for m in tx])
# make sure we got all the msgs
self.assertTrue(len(all_tx) >= len(test_files)-1)
for tx_msgs in all_tx:
for addr, bus, test_name in tx_msgs:
msg = make_msg(bus, addr)
self.safety.set_controls_allowed(1)
# TODO: this should be blocked
if current_test in ["TestNissanSafety", "TestNissanSafetyAltEpsBus", "TestNissanLeafSafety"] and [addr, bus] in self.TX_MSGS:
continue
self.assertFalse(self._tx(msg), f"transmit of {addr=:#x} {bus=} from {test_name} during {current_test} was allowed")
@add_regen_tests
class PandaCarSafetyTest(PandaSafetyTest):
STANDSTILL_THRESHOLD: float | None = None
GAS_PRESSED_THRESHOLD = 0
RELAY_MALFUNCTION_ADDRS: dict[int, tuple[int, ...]] | None = None
@classmethod
def setUpClass(cls):
if cls.__name__ == "PandaCarSafetyTest" or cls.__name__.endswith('Base'):
cls.safety = None
raise unittest.SkipTest
@abc.abstractmethod
def _user_brake_msg(self, brake):
pass
def _user_regen_msg(self, regen):
pass
@abc.abstractmethod
def _speed_msg(self, speed):
pass
# Safety modes can override if vehicle_moving is driven by a different message
def _vehicle_moving_msg(self, speed: float):
return self._speed_msg(speed)
@abc.abstractmethod
def _user_gas_msg(self, gas):
pass
@abc.abstractmethod
def _pcm_status_msg(self, enable):
pass
# ***** standard tests for all car-specific safety modes *****
def test_relay_malfunction(self):
# each car has an addr that is used to detect relay malfunction
# if that addr is seen on specified bus, triggers the relay malfunction
# protection logic: both tx_hook and fwd_hook are expected to return failure
self.assertFalse(self.safety.get_relay_malfunction())
for bus in range(3):
for addr in self.SCANNED_ADDRS:
self.safety.set_relay_malfunction(False)
self._rx(make_msg(bus, addr, 8))
should_relay_malfunction = addr in self.RELAY_MALFUNCTION_ADDRS.get(bus, ())
self.assertEqual(should_relay_malfunction, self.safety.get_relay_malfunction(), (bus, addr))
# test relay malfunction protection logic
self.safety.set_relay_malfunction(True)
for bus in range(3):
for addr in self.SCANNED_ADDRS:
self.assertFalse(self._tx(make_msg(bus, addr, 8)))
self.assertEqual(-1, self.safety.safety_fwd_hook(bus, addr))
def test_prev_gas(self):
self.assertFalse(self.safety.get_gas_pressed_prev())
for pressed in [self.GAS_PRESSED_THRESHOLD + 1, 0]:
self._rx(self._user_gas_msg(pressed))
self.assertEqual(bool(pressed), self.safety.get_gas_pressed_prev())
def test_allow_engage_with_gas_pressed(self):
self._rx(self._user_gas_msg(1))
self.safety.set_controls_allowed(True)
self._rx(self._user_gas_msg(1))
self.assertTrue(self.safety.get_controls_allowed())
self._rx(self._user_gas_msg(1))
self.assertTrue(self.safety.get_controls_allowed())
def test_disengage_on_gas(self):
self._rx(self._user_gas_msg(0))
self.safety.set_controls_allowed(True)
self._rx(self._user_gas_msg(self.GAS_PRESSED_THRESHOLD + 1))
self.assertFalse(self.safety.get_controls_allowed())
def test_alternative_experience_no_disengage_on_gas(self):
self._rx(self._user_gas_msg(0))
self.safety.set_controls_allowed(True)
self.safety.set_alternative_experience(ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS)
self._rx(self._user_gas_msg(self.GAS_PRESSED_THRESHOLD + 1))
# Test we allow lateral, but not longitudinal
self.assertTrue(self.safety.get_controls_allowed())
self.assertFalse(self.safety.get_longitudinal_allowed())
# Make sure we can re-gain longitudinal actuation
self._rx(self._user_gas_msg(0))
self.assertTrue(self.safety.get_longitudinal_allowed())
def test_prev_user_brake(self, _user_brake_msg=None, get_brake_pressed_prev=None):
if _user_brake_msg is None:
_user_brake_msg = self._user_brake_msg
get_brake_pressed_prev = self.safety.get_brake_pressed_prev
self.assertFalse(get_brake_pressed_prev())
for pressed in [True, False]:
self._rx(_user_brake_msg(not pressed))
self.assertEqual(not pressed, get_brake_pressed_prev())
self._rx(_user_brake_msg(pressed))
self.assertEqual(pressed, get_brake_pressed_prev())
def test_enable_control_allowed_from_cruise(self):
self._rx(self._pcm_status_msg(False))
self.assertFalse(self.safety.get_controls_allowed())
self._rx(self._pcm_status_msg(True))
self.assertTrue(self.safety.get_controls_allowed())
def test_disable_control_allowed_from_cruise(self):
self.safety.set_controls_allowed(1)
self._rx(self._pcm_status_msg(False))
self.assertFalse(self.safety.get_controls_allowed())
def test_cruise_engaged_prev(self):
for engaged in [True, False]:
self._rx(self._pcm_status_msg(engaged))
self.assertEqual(engaged, self.safety.get_cruise_engaged_prev())
self._rx(self._pcm_status_msg(not engaged))
self.assertEqual(not engaged, self.safety.get_cruise_engaged_prev())
def test_allow_user_brake_at_zero_speed(self, _user_brake_msg=None, get_brake_pressed_prev=None):
if _user_brake_msg is None:
_user_brake_msg = self._user_brake_msg
# Brake was already pressed
self._rx(self._vehicle_moving_msg(0))
self._rx(_user_brake_msg(1))
self.safety.set_controls_allowed(1)
self._rx(_user_brake_msg(1))
self.assertTrue(self.safety.get_controls_allowed())
self.assertTrue(self.safety.get_longitudinal_allowed())
self._rx(_user_brake_msg(0))
self.assertTrue(self.safety.get_controls_allowed())
self.assertTrue(self.safety.get_longitudinal_allowed())
# rising edge of brake should disengage
self._rx(_user_brake_msg(1))
self.assertFalse(self.safety.get_controls_allowed())
self.assertFalse(self.safety.get_longitudinal_allowed())
self._rx(_user_brake_msg(0)) # reset no brakes
def test_not_allow_user_brake_when_moving(self, _user_brake_msg=None, get_brake_pressed_prev=None):
if _user_brake_msg is None:
_user_brake_msg = self._user_brake_msg
# Brake was already pressed
self._rx(_user_brake_msg(1))
self.safety.set_controls_allowed(1)
self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD))
self._rx(_user_brake_msg(1))
self.assertTrue(self.safety.get_controls_allowed())
self.assertTrue(self.safety.get_longitudinal_allowed())
self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD + 1))
self._rx(_user_brake_msg(1))
self.assertFalse(self.safety.get_controls_allowed())
self.assertFalse(self.safety.get_longitudinal_allowed())
self._rx(self._vehicle_moving_msg(0))
def test_vehicle_moving(self):
self.assertFalse(self.safety.get_vehicle_moving())
# not moving
self._rx(self._vehicle_moving_msg(0))
self.assertFalse(self.safety.get_vehicle_moving())
# speed is at threshold
self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD))
self.assertFalse(self.safety.get_vehicle_moving())
# past threshold
self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD + 1))
self.assertTrue(self.safety.get_vehicle_moving())
def test_safety_tick(self):
self.safety.set_timer(int(2e6))
self.safety.set_controls_allowed(True)
self.safety.safety_tick_current_safety_config()
self.assertFalse(self.safety.get_controls_allowed())
self.assertFalse(self.safety.safety_config_valid())

View File

@@ -0,0 +1,157 @@
import unittest
import opendbc.safety.tests.common as common
from opendbc.safety.tests.libsafety import libsafety_py
from opendbc.safety.tests.common import make_msg
class Buttons:
NONE = 0
RESUME = 1
SET = 2
CANCEL = 4
PREV_BUTTON_SAMPLES = 8
ENABLE_BUTTONS = (Buttons.RESUME, Buttons.SET, Buttons.CANCEL)
class HyundaiButtonBase:
# pylint: disable=no-member,abstract-method
BUTTONS_TX_BUS = 0 # tx on this bus, rx on 0
SCC_BUS = 0 # rx on this bus
def test_button_sends(self):
"""
Only RES and CANCEL buttons are allowed
- RES allowed while controls allowed
- CANCEL allowed while cruise is enabled
"""
self.safety.set_controls_allowed(0)
self.assertFalse(self._tx(self._button_msg(Buttons.RESUME, bus=self.BUTTONS_TX_BUS)))
self.assertFalse(self._tx(self._button_msg(Buttons.SET, bus=self.BUTTONS_TX_BUS)))
self.safety.set_controls_allowed(1)
self.assertTrue(self._tx(self._button_msg(Buttons.RESUME, bus=self.BUTTONS_TX_BUS)))
self.assertFalse(self._tx(self._button_msg(Buttons.SET, bus=self.BUTTONS_TX_BUS)))
for enabled in (True, False):
self._rx(self._pcm_status_msg(enabled))
self.assertEqual(enabled, self._tx(self._button_msg(Buttons.CANCEL, bus=self.BUTTONS_TX_BUS)))
def test_enable_control_allowed_from_cruise(self):
"""
Hyundai non-longitudinal only enables on PCM rising edge and recent button press. Tests PCM enabling with:
- disallowed: No buttons
- disallowed: Buttons that don't enable cruise
- allowed: Buttons that do enable cruise
- allowed: Main button with all above combinations
"""
for main_button in (0, 1):
for btn in range(8):
for _ in range(PREV_BUTTON_SAMPLES): # reset
self._rx(self._button_msg(Buttons.NONE))
self._rx(self._pcm_status_msg(False))
self.assertFalse(self.safety.get_controls_allowed())
self._rx(self._button_msg(btn, main_button=main_button))
self._rx(self._pcm_status_msg(True))
controls_allowed = btn in ENABLE_BUTTONS or main_button
self.assertEqual(controls_allowed, self.safety.get_controls_allowed())
def test_sampling_cruise_buttons(self):
"""
Test that we allow controls on recent button press, but not as button leaves sliding window
"""
self._rx(self._button_msg(Buttons.SET))
for i in range(2 * PREV_BUTTON_SAMPLES):
self._rx(self._pcm_status_msg(False))
self.assertFalse(self.safety.get_controls_allowed())
self._rx(self._pcm_status_msg(True))
controls_allowed = i < PREV_BUTTON_SAMPLES
self.assertEqual(controls_allowed, self.safety.get_controls_allowed())
self._rx(self._button_msg(Buttons.NONE))
class HyundaiLongitudinalBase(common.LongitudinalAccelSafetyTest):
# pylint: disable=no-member,abstract-method
DISABLED_ECU_UDS_MSG: tuple[int, int]
DISABLED_ECU_ACTUATION_MSG: tuple[int, int]
@classmethod
def setUpClass(cls):
if cls.__name__ == "HyundaiLongitudinalBase":
cls.safety = None
raise unittest.SkipTest
# override these tests from PandaCarSafetyTest, hyundai longitudinal uses button enable
def test_disable_control_allowed_from_cruise(self):
pass
def test_enable_control_allowed_from_cruise(self):
pass
def test_sampling_cruise_buttons(self):
pass
def test_cruise_engaged_prev(self):
pass
def test_button_sends(self):
pass
def _pcm_status_msg(self, enable):
raise Exception
def _accel_msg(self, accel, aeb_req=False, aeb_decel=0):
raise NotImplementedError
def test_set_resume_buttons(self):
"""
SET and RESUME enter controls allowed on their falling edge.
"""
for btn_prev in range(8):
for btn_cur in range(8):
self._rx(self._button_msg(Buttons.NONE))
self.safety.set_controls_allowed(0)
for _ in range(10):
self._rx(self._button_msg(btn_prev))
self.assertFalse(self.safety.get_controls_allowed())
# should enter controls allowed on falling edge and not transitioning to cancel
should_enable = btn_cur != btn_prev and \
btn_cur != Buttons.CANCEL and \
btn_prev in (Buttons.RESUME, Buttons.SET)
self._rx(self._button_msg(btn_cur))
self.assertEqual(should_enable, self.safety.get_controls_allowed())
def test_cancel_button(self):
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(Buttons.CANCEL))
self.assertFalse(self.safety.get_controls_allowed())
def test_tester_present_allowed(self):
"""
Ensure tester present diagnostic message is allowed to keep ECU knocked out
for longitudinal control.
"""
addr, bus = self.DISABLED_ECU_UDS_MSG
tester_present = libsafety_py.make_CANPacket(addr, bus, b"\x02\x3E\x80\x00\x00\x00\x00\x00")
self.assertTrue(self._tx(tester_present))
not_tester_present = libsafety_py.make_CANPacket(addr, bus, b"\x03\xAA\xAA\x00\x00\x00\x00\x00")
self.assertFalse(self._tx(not_tester_present))
def test_disabled_ecu_alive(self):
"""
If the ECU knockout failed, make sure the relay malfunction is shown
"""
addr, bus = self.DISABLED_ECU_ACTUATION_MSG
self.assertFalse(self.safety.get_relay_malfunction())
self._rx(make_msg(bus, addr, 8))
self.assertTrue(self.safety.get_relay_malfunction())

View File

@@ -0,0 +1,11 @@
#!/usr/bin/env bash
set -e
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
cd $DIR
if ! command -v "mull-runner-17" > /dev/null 2>&1; then
sudo apt-get update && sudo apt-get install -y curl clang-17
curl -1sLf 'https://dl.cloudsmith.io/public/mull-project/mull-stable/setup.deb.sh' | sudo -E bash
sudo apt-get update && sudo apt-get install -y mull-17
fi

View File

@@ -0,0 +1,54 @@
import platform
CC = 'gcc'
system = platform.system()
if system == 'Darwin':
# gcc installed by homebrew has version suffix (e.g. gcc-12) in order to be
# distinguishable from system one - which acts as a symlink to clang
CC += '-13'
env = Environment(
CC=CC,
CFLAGS=[
'-nostdlib',
'-fno-builtin',
'-std=gnu11',
'-Wfatal-errors',
'-Wno-pointer-to-int-cast',
],
CPPPATH=[".", "../../board/", "../../"],
)
if system == "Darwin":
env.PrependENVPath('PATH', '/opt/homebrew/bin')
if GetOption('mutation'):
env['CC'] = 'clang-17'
flags = [
'-fprofile-instr-generate',
'-fcoverage-mapping',
'-fpass-plugin=/usr/lib/mull-ir-frontend-17',
'-g',
'-grecord-command-line',
]
env['CFLAGS'] += flags
env['LINKFLAGS'] += flags
if GetOption('ubsan'):
flags = [
"-fsanitize=undefined",
"-fno-sanitize-recover=undefined",
]
env['CFLAGS'] += flags
env['LINKFLAGS'] += flags
safety = env.SharedObject("safety.os", "safety.c")
libsafety = env.SharedLibrary("libsafety.so", [safety])
if GetOption('coverage'):
env.Append(
CFLAGS=["-fprofile-arcs", "-ftest-coverage", "-fprofile-abs-path",],
LIBS=["gcov"],
)
# GCC note file is generated by compiler, ensure we build it, and allow scons to clean it up
AlwaysBuild(safety)
env.SideEffect("safety.gcno", safety)

View File

@@ -0,0 +1,75 @@
import os
from cffi import FFI
from typing import Protocol
from opendbc.safety import LEN_TO_DLC
from opendbc.safety.tests.libsafety.safety_helpers import PandaSafety, setup_safety_helpers
libsafety_dir = os.path.dirname(os.path.abspath(__file__))
libsafety_fn = os.path.join(libsafety_dir, "libsafety.so")
ffi = FFI()
ffi.cdef("""
typedef struct {
unsigned char fd : 1;
unsigned char bus : 3;
unsigned char data_len_code : 4;
unsigned char rejected : 1;
unsigned char returned : 1;
unsigned char extended : 1;
unsigned int addr : 29;
unsigned char checksum;
unsigned char data[64];
} CANPacket_t;
""", packed=True)
ffi.cdef("""
bool safety_rx_hook(CANPacket_t *to_send);
bool safety_tx_hook(CANPacket_t *to_push);
int safety_fwd_hook(int bus_num, int addr);
int set_safety_hooks(uint16_t mode, uint16_t param);
""")
ffi.cdef("""
void can_set_checksum(CANPacket_t *packet);
""")
setup_safety_helpers(ffi)
class CANPacket:
reserved: int
bus: int
data_len_code: int
rejected: int
returned: int
extended: int
addr: int
data: list[int]
class Panda(PandaSafety, Protocol):
# CAN
def can_set_checksum(self, p: CANPacket) -> None: ...
# safety
def safety_rx_hook(self, to_send: CANPacket) -> int: ...
def safety_tx_hook(self, to_push: CANPacket) -> int: ...
def safety_fwd_hook(self, bus_num: int, addr: int) -> int: ...
def set_safety_hooks(self, mode: int, param: int) -> int: ...
libsafety: Panda = ffi.dlopen(libsafety_fn)
# helpers
def make_CANPacket(addr: int, bus: int, dat):
ret = ffi.new('CANPacket_t *')
ret[0].extended = 1 if addr >= 0x800 else 0
ret[0].addr = addr
ret[0].data_len_code = LEN_TO_DLC[len(dat)]
ret[0].bus = bus
ret[0].data = bytes(dat)
libsafety.can_set_checksum(ret)
return ret

View File

@@ -0,0 +1,13 @@
#include <stdbool.h>
#include "fake_stm.h"
#include "can.h"
//int safety_tx_hook(CANPacket_t *to_send) { return 1; }
#include "faults.h"
#include "safety.h"
#include "drivers/can_common.h"
// libsafety stuff
#include "safety_helpers.h"

View File

@@ -0,0 +1,187 @@
void safety_tick_current_safety_config() {
safety_tick(&current_safety_config);
}
bool safety_config_valid() {
if (current_safety_config.rx_checks_len <= 0) {
printf("missing RX checks\n");
return false;
}
for (int i = 0; i < current_safety_config.rx_checks_len; i++) {
const RxCheck addr = current_safety_config.rx_checks[i];
bool valid = addr.status.msg_seen && !addr.status.lagging && addr.status.valid_checksum && (addr.status.wrong_counters < MAX_WRONG_COUNTERS) && addr.status.valid_quality_flag;
if (!valid) {
// printf("i %d seen %d lagging %d valid checksum %d wrong counters %d valid quality flag %d\n", i, addr.status.msg_seen, addr.status.lagging, addr.status.valid_checksum, addr.status.wrong_counters, addr.status.valid_quality_flag);
return false;
}
}
return true;
}
void set_controls_allowed(bool c){
controls_allowed = c;
}
void set_alternative_experience(int mode){
alternative_experience = mode;
}
void set_relay_malfunction(bool c){
relay_malfunction = c;
}
bool get_controls_allowed(void){
return controls_allowed;
}
int get_alternative_experience(void){
return alternative_experience;
}
bool get_relay_malfunction(void){
return relay_malfunction;
}
bool get_gas_pressed_prev(void){
return gas_pressed_prev;
}
void set_gas_pressed_prev(bool c){
gas_pressed_prev = c;
}
bool get_brake_pressed_prev(void){
return brake_pressed_prev;
}
bool get_regen_braking_prev(void){
return regen_braking_prev;
}
bool get_cruise_engaged_prev(void){
return cruise_engaged_prev;
}
void set_cruise_engaged_prev(bool engaged){
cruise_engaged_prev = engaged;
}
bool get_vehicle_moving(void){
return vehicle_moving;
}
bool get_acc_main_on(void){
return acc_main_on;
}
int get_vehicle_speed_min(void){
return vehicle_speed.min;
}
int get_vehicle_speed_max(void){
return vehicle_speed.max;
}
int get_vehicle_speed_last(void){
return vehicle_speed.values[0];
}
int get_current_safety_mode(void){
return current_safety_mode;
}
int get_current_safety_param(void){
return current_safety_param;
}
void set_timer(uint32_t t){
timer.CNT = t;
}
void set_torque_meas(int min, int max){
torque_meas.min = min;
torque_meas.max = max;
}
int get_torque_meas_min(void){
return torque_meas.min;
}
int get_torque_meas_max(void){
return torque_meas.max;
}
void set_torque_driver(int min, int max){
torque_driver.min = min;
torque_driver.max = max;
}
int get_torque_driver_min(void){
return torque_driver.min;
}
int get_torque_driver_max(void){
return torque_driver.max;
}
void set_rt_torque_last(int t){
rt_torque_last = t;
}
void set_desired_torque_last(int t){
desired_torque_last = t;
}
void set_desired_angle_last(int t){
desired_angle_last = t;
}
int get_desired_angle_last(void){
return desired_angle_last;
}
void set_angle_meas(int min, int max){
angle_meas.min = min;
angle_meas.max = max;
}
int get_angle_meas_min(void){
return angle_meas.min;
}
int get_angle_meas_max(void){
return angle_meas.max;
}
// ***** car specific helpers *****
void set_honda_alt_brake_msg(bool c){
honda_alt_brake_msg = c;
}
void set_honda_bosch_long(bool c){
honda_bosch_long = c;
}
int get_honda_hw(void) {
return honda_hw;
}
void set_honda_fwd_brake(bool c){
honda_fwd_brake = c;
}
bool get_honda_fwd_brake(void){
return honda_fwd_brake;
}
void init_tests(void){
safety_mode_cnt = 2U; // avoid ignoring relay_malfunction logic
alternative_experience = 0;
set_timer(0);
ts_steer_req_mismatch_last = 0;
valid_steer_req_count = 0;
invalid_steer_req_count = 0;
}

View File

@@ -0,0 +1,104 @@
# panda safety helpers, from safety_helpers.c
from typing import Protocol
def setup_safety_helpers(ffi):
ffi.cdef("""
void set_controls_allowed(bool c);
bool get_controls_allowed(void);
bool get_longitudinal_allowed(void);
void set_alternative_experience(int mode);
int get_alternative_experience(void);
void set_relay_malfunction(bool c);
bool get_relay_malfunction(void);
bool get_gas_pressed_prev(void);
void set_gas_pressed_prev(bool);
bool get_brake_pressed_prev(void);
bool get_regen_braking_prev(void);
bool get_acc_main_on(void);
int get_vehicle_speed_min(void);
int get_vehicle_speed_max(void);
int get_vehicle_speed_last(void);
int get_current_safety_mode(void);
int get_current_safety_param(void);
void set_torque_meas(int min, int max);
int get_torque_meas_min(void);
int get_torque_meas_max(void);
void set_torque_driver(int min, int max);
int get_torque_driver_min(void);
int get_torque_driver_max(void);
void set_desired_torque_last(int t);
void set_rt_torque_last(int t);
void set_desired_angle_last(int t);
int get_desired_angle_last();
void set_angle_meas(int min, int max);
int get_angle_meas_min(void);
int get_angle_meas_max(void);
bool get_cruise_engaged_prev(void);
void set_cruise_engaged_prev(bool engaged);
bool get_vehicle_moving(void);
void set_timer(uint32_t t);
void safety_tick_current_safety_config();
bool safety_config_valid();
void init_tests(void);
void set_honda_fwd_brake(bool c);
bool get_honda_fwd_brake(void);
void set_honda_alt_brake_msg(bool c);
void set_honda_bosch_long(bool c);
int get_honda_hw(void);
""")
class PandaSafety(Protocol):
def set_controls_allowed(self, c: bool) -> None: ...
def get_controls_allowed(self) -> bool: ...
def get_longitudinal_allowed(self) -> bool: ...
def set_alternative_experience(self, mode: int) -> None: ...
def get_alternative_experience(self) -> int: ...
def set_relay_malfunction(self, c: bool) -> None: ...
def get_relay_malfunction(self) -> bool: ...
def get_gas_pressed_prev(self) -> bool: ...
def set_gas_pressed_prev(self, c: bool) -> None: ...
def get_brake_pressed_prev(self) -> bool: ...
def get_regen_braking_prev(self) -> bool: ...
def get_acc_main_on(self) -> bool: ...
def get_vehicle_speed_min(self) -> int: ...
def get_vehicle_speed_max(self) -> int: ...
def get_vehicle_speed_last(self) -> int: ...
def get_current_safety_mode(self) -> int: ...
def get_current_safety_param(self) -> int: ...
def set_torque_meas(self, min: int, max: int) -> None: ... # noqa: A002
def get_torque_meas_min(self) -> int: ...
def get_torque_meas_max(self) -> int: ...
def set_torque_driver(self, min: int, max: int) -> None: ... # noqa: A002
def get_torque_driver_min(self) -> int: ...
def get_torque_driver_max(self) -> int: ...
def set_desired_torque_last(self, t: int) -> None: ...
def set_rt_torque_last(self, t: int) -> None: ...
def set_desired_angle_last(self, t: int) -> None: ...
def get_desired_angle_last(self) -> int: ...
def set_angle_meas(self, min: int, max: int) -> None: ... # noqa: A002
def get_angle_meas_min(self) -> int: ...
def get_angle_meas_max(self) -> int: ...
def get_cruise_engaged_prev(self) -> bool: ...
def set_cruise_engaged_prev(self, enabled: bool) -> None: ...
def get_vehicle_moving(self) -> bool: ...
def set_timer(self, t: int) -> None: ...
def safety_tick_current_safety_config(self) -> None: ...
def safety_config_valid(self) -> bool: ...
def init_tests(self) -> None: ...
def set_honda_fwd_brake(self, c: bool) -> None: ...
def get_honda_fwd_brake(self) -> bool: ...
def set_honda_alt_brake_msg(self, c: bool) -> None: ...
def set_honda_bosch_long(self, c: bool) -> None: ...
def get_honda_hw(self) -> int: ...

5
opendbc/safety/tests/misra/.gitignore vendored Normal file
View File

@@ -0,0 +1,5 @@
*.pdf
*.txt
.output.log
new_table
cppcheck/

View File

@@ -0,0 +1,911 @@
Cppcheck checkers list from test_misra.sh:
TEST variant options:
--enable=all --disable=unusedFunction -DPANDA --addon=misra -DSTM32F4 -DSTM32F413xx /opendbc/safety/main.c
Critical errors
---------------
No critical errors encountered.
Note: There might still have been non-critical bailouts which might lead to false negatives.
Open source checkers
--------------------
Yes Check64BitPortability::pointerassignment
Yes CheckAssert::assertWithSideEffects
Yes CheckAutoVariables::assignFunctionArg
Yes CheckAutoVariables::autoVariables
Yes CheckAutoVariables::checkVarLifetime
No CheckBool::checkAssignBoolToFloat require:style,c++
Yes CheckBool::checkAssignBoolToPointer
No CheckBool::checkBitwiseOnBoolean require:style,inconclusive
Yes CheckBool::checkComparisonOfBoolExpressionWithInt
No CheckBool::checkComparisonOfBoolWithBool require:style,c++
No CheckBool::checkComparisonOfBoolWithInt require:warning,c++
No CheckBool::checkComparisonOfFuncReturningBool require:style,c++
Yes CheckBool::checkIncrementBoolean
Yes CheckBool::pointerArithBool
Yes CheckBool::returnValueOfFunctionReturningBool
No CheckBoost::checkBoostForeachModification
Yes CheckBufferOverrun::analyseWholeProgram
Yes CheckBufferOverrun::argumentSize
Yes CheckBufferOverrun::arrayIndex
Yes CheckBufferOverrun::arrayIndexThenCheck
Yes CheckBufferOverrun::bufferOverflow
Yes CheckBufferOverrun::negativeArraySize
Yes CheckBufferOverrun::objectIndex
Yes CheckBufferOverrun::pointerArithmetic
No CheckBufferOverrun::stringNotZeroTerminated require:warning,inconclusive
Yes CheckClass::analyseWholeProgram
No CheckClass::checkConst require:style,inconclusive
No CheckClass::checkConstructors require:style,warning
No CheckClass::checkCopyConstructors require:warning
No CheckClass::checkDuplInheritedMembers require:warning
No CheckClass::checkExplicitConstructors require:style
No CheckClass::checkMemset
No CheckClass::checkMissingOverride require:style,c++03
No CheckClass::checkReturnByReference require:performance
No CheckClass::checkSelfInitialization
No CheckClass::checkThisUseAfterFree require:warning
No CheckClass::checkUnsafeClassRefMember require:warning,safeChecks
No CheckClass::checkUselessOverride require:style
No CheckClass::checkVirtualFunctionCallInConstructor require:warning
No CheckClass::initializationListUsage require:performance
No CheckClass::initializerListOrder require:style,inconclusive
No CheckClass::operatorEqRetRefThis require:style
No CheckClass::operatorEqToSelf require:warning
No CheckClass::privateFunctions require:style
No CheckClass::thisSubtraction require:warning
No CheckClass::virtualDestructor
Yes CheckCondition::alwaysTrueFalse
Yes CheckCondition::assignIf
Yes CheckCondition::checkAssignmentInCondition
Yes CheckCondition::checkBadBitmaskCheck
Yes CheckCondition::checkCompareValueOutOfTypeRange
Yes CheckCondition::checkDuplicateConditionalAssign
Yes CheckCondition::checkIncorrectLogicOperator
Yes CheckCondition::checkInvalidTestForOverflow
Yes CheckCondition::checkModuloAlwaysTrueFalse
Yes CheckCondition::checkPointerAdditionResultNotNull
Yes CheckCondition::clarifyCondition
Yes CheckCondition::comparison
Yes CheckCondition::duplicateCondition
Yes CheckCondition::multiCondition
Yes CheckCondition::multiCondition2
No CheckExceptionSafety::checkCatchExceptionByValue require:style
No CheckExceptionSafety::checkRethrowCopy require:style
No CheckExceptionSafety::deallocThrow require:warning
No CheckExceptionSafety::destructors require:warning
No CheckExceptionSafety::nothrowThrows
No CheckExceptionSafety::rethrowNoCurrentException
No CheckExceptionSafety::unhandledExceptionSpecification require:style,inconclusive
Yes CheckFunctions::checkIgnoredReturnValue
Yes CheckFunctions::checkMathFunctions
Yes CheckFunctions::checkMissingReturn
Yes CheckFunctions::checkProhibitedFunctions
Yes CheckFunctions::invalidFunctionUsage
Yes CheckFunctions::memsetInvalid2ndParam
Yes CheckFunctions::memsetZeroBytes
No CheckFunctions::returnLocalStdMove require:performance,c++11
Yes CheckFunctions::useStandardLibrary
No CheckIO::checkCoutCerrMisusage require:c
Yes CheckIO::checkFileUsage
Yes CheckIO::checkWrongPrintfScanfArguments
Yes CheckIO::invalidScanf
Yes CheckLeakAutoVar::check
No CheckMemoryLeakInClass::check
Yes CheckMemoryLeakInFunction::checkReallocUsage
Yes CheckMemoryLeakNoVar::check
No CheckMemoryLeakNoVar::checkForUnsafeArgAlloc
Yes CheckMemoryLeakStructMember::check
Yes CheckNullPointer::analyseWholeProgram
Yes CheckNullPointer::arithmetic
Yes CheckNullPointer::nullConstantDereference
Yes CheckNullPointer::nullPointer
No CheckOther::checkAccessOfMovedVariable require:c++11,warning
Yes CheckOther::checkCastIntToCharAndBack
Yes CheckOther::checkCharVariable
Yes CheckOther::checkComparePointers
Yes CheckOther::checkComparisonFunctionIsAlwaysTrueOrFalse
Yes CheckOther::checkConstPointer
No CheckOther::checkConstVariable require:style,c++
No CheckOther::checkDuplicateBranch require:style,inconclusive
Yes CheckOther::checkDuplicateExpression
Yes CheckOther::checkEvaluationOrder
Yes CheckOther::checkFuncArgNamesDifferent
No CheckOther::checkIncompleteArrayFill require:warning,portability,inconclusive
Yes CheckOther::checkIncompleteStatement
No CheckOther::checkInterlockedDecrement require:windows-platform
Yes CheckOther::checkInvalidFree
Yes CheckOther::checkKnownArgument
Yes CheckOther::checkKnownPointerToBool
No CheckOther::checkMisusedScopedObject require:style,c++
Yes CheckOther::checkModuloOfOne
Yes CheckOther::checkNanInArithmeticExpression
Yes CheckOther::checkNegativeBitwiseShift
Yes CheckOther::checkOverlappingWrite
No CheckOther::checkPassByReference require:performance,c++
Yes CheckOther::checkRedundantAssignment
No CheckOther::checkRedundantCopy require:c++,performance,inconclusive
Yes CheckOther::checkRedundantPointerOp
Yes CheckOther::checkShadowVariables
Yes CheckOther::checkSignOfUnsignedVariable
No CheckOther::checkSuspiciousCaseInSwitch require:warning,inconclusive
No CheckOther::checkSuspiciousSemicolon require:warning,inconclusive
Yes CheckOther::checkUnreachableCode
Yes CheckOther::checkUnusedLabel
Yes CheckOther::checkVarFuncNullUB
Yes CheckOther::checkVariableScope
Yes CheckOther::checkZeroDivision
Yes CheckOther::clarifyCalculation
Yes CheckOther::clarifyStatement
Yes CheckOther::invalidPointerCast
Yes CheckOther::redundantBitwiseOperationInSwitch
Yes CheckOther::suspiciousFloatingPointCast
No CheckOther::warningOldStylePointerCast require:style,c++
No CheckPostfixOperator::postfixOperator require:performance
Yes CheckSizeof::checkSizeofForArrayParameter
Yes CheckSizeof::checkSizeofForNumericParameter
Yes CheckSizeof::checkSizeofForPointerSize
Yes CheckSizeof::sizeofCalculation
Yes CheckSizeof::sizeofFunction
Yes CheckSizeof::sizeofVoid
Yes CheckSizeof::sizeofsizeof
No CheckSizeof::suspiciousSizeofCalculation require:warning,inconclusive
No CheckStl::checkDereferenceInvalidIterator require:warning
No CheckStl::checkDereferenceInvalidIterator2
No CheckStl::checkFindInsert require:performance
No CheckStl::checkMutexes require:warning
No CheckStl::erase
No CheckStl::eraseIteratorOutOfBounds
No CheckStl::if_find require:warning,performance
No CheckStl::invalidContainer
No CheckStl::iterators
No CheckStl::knownEmptyContainer require:style
No CheckStl::misMatchingContainerIterator
No CheckStl::misMatchingContainers
No CheckStl::missingComparison require:warning
No CheckStl::negativeIndex
No CheckStl::outOfBounds
No CheckStl::outOfBoundsIndexExpression
No CheckStl::redundantCondition require:style
No CheckStl::size require:performance,c++03
No CheckStl::stlBoundaries
No CheckStl::stlOutOfBounds
No CheckStl::string_c_str
No CheckStl::useStlAlgorithm require:style
No CheckStl::uselessCalls require:performance,warning
Yes CheckString::checkAlwaysTrueOrFalseStringCompare
Yes CheckString::checkIncorrectStringCompare
Yes CheckString::checkSuspiciousStringCompare
Yes CheckString::overlappingStrcmp
Yes CheckString::sprintfOverlappingData
Yes CheckString::strPlusChar
Yes CheckString::stringLiteralWrite
Yes CheckType::checkFloatToIntegerOverflow
Yes CheckType::checkIntegerOverflow
Yes CheckType::checkLongCast
Yes CheckType::checkSignConversion
Yes CheckType::checkTooBigBitwiseShift
Yes CheckUninitVar::check
Yes CheckUninitVar::valueFlowUninit
No CheckUnusedFunctions::check require:unusedFunction
Yes CheckUnusedVar::checkFunctionVariableUsage
Yes CheckUnusedVar::checkStructMemberUsage
Yes CheckVaarg::va_list_usage
Yes CheckVaarg::va_start_argument
Premium checkers
----------------
Not available, Cppcheck Premium is not used
Autosar
-------
Not available, Cppcheck Premium is not used
Cert C
------
Not available, Cppcheck Premium is not used
Cert C++
--------
Not available, Cppcheck Premium is not used
Misra C 2012
------------
No Misra C 2012: Dir 1.1
No Misra C 2012: Dir 2.1
No Misra C 2012: Dir 3.1
No Misra C 2012: Dir 4.1
No Misra C 2012: Dir 4.2
No Misra C 2012: Dir 4.3
No Misra C 2012: Dir 4.4
No Misra C 2012: Dir 4.5
No Misra C 2012: Dir 4.6 amendment:3
No Misra C 2012: Dir 4.7
No Misra C 2012: Dir 4.8
No Misra C 2012: Dir 4.9 amendment:3
No Misra C 2012: Dir 4.10
No Misra C 2012: Dir 4.11 amendment:3
No Misra C 2012: Dir 4.12
No Misra C 2012: Dir 4.13
No Misra C 2012: Dir 4.14 amendment:2
No Misra C 2012: Dir 4.15 amendment:3
No Misra C 2012: Dir 5.1 amendment:4
No Misra C 2012: Dir 5.2 amendment:4
No Misra C 2012: Dir 5.3 amendment:4
Yes Misra C 2012: 1.1
Yes Misra C 2012: 1.2
Yes Misra C 2012: 1.3
Yes Misra C 2012: 1.4 amendment:2
No Misra C 2012: 1.5 amendment:3 require:premium
Yes Misra C 2012: 2.1
Yes Misra C 2012: 2.2
Yes Misra C 2012: 2.3
Yes Misra C 2012: 2.4
Yes Misra C 2012: 2.5
Yes Misra C 2012: 2.6
Yes Misra C 2012: 2.7
Yes Misra C 2012: 2.8
Yes Misra C 2012: 3.1
Yes Misra C 2012: 3.2
Yes Misra C 2012: 4.1
Yes Misra C 2012: 4.2
Yes Misra C 2012: 5.1
Yes Misra C 2012: 5.2
Yes Misra C 2012: 5.3
Yes Misra C 2012: 5.4
Yes Misra C 2012: 5.5
Yes Misra C 2012: 5.6
Yes Misra C 2012: 5.7
Yes Misra C 2012: 5.8
Yes Misra C 2012: 5.9
Yes Misra C 2012: 6.1
Yes Misra C 2012: 6.2
No Misra C 2012: 6.3
Yes Misra C 2012: 7.1
Yes Misra C 2012: 7.2
Yes Misra C 2012: 7.3
Yes Misra C 2012: 7.4
No Misra C 2012: 7.5
No Misra C 2012: 7.6
Yes Misra C 2012: 8.1
Yes Misra C 2012: 8.2
No Misra C 2012: 8.3
Yes Misra C 2012: 8.4
Yes Misra C 2012: 8.5
Yes Misra C 2012: 8.6
Yes Misra C 2012: 8.7
Yes Misra C 2012: 8.8
Yes Misra C 2012: 8.9
Yes Misra C 2012: 8.10
Yes Misra C 2012: 8.11
Yes Misra C 2012: 8.12
Yes Misra C 2012: 8.13
Yes Misra C 2012: 8.14
No Misra C 2012: 8.15
No Misra C 2012: 8.16
No Misra C 2012: 8.17
Yes Misra C 2012: 9.1
Yes Misra C 2012: 9.2
Yes Misra C 2012: 9.3
Yes Misra C 2012: 9.4
Yes Misra C 2012: 9.5
No Misra C 2012: 9.6
No Misra C 2012: 9.7
Yes Misra C 2012: 10.1
Yes Misra C 2012: 10.2
Yes Misra C 2012: 10.3
Yes Misra C 2012: 10.4
Yes Misra C 2012: 10.5
Yes Misra C 2012: 10.6
Yes Misra C 2012: 10.7
Yes Misra C 2012: 10.8
Yes Misra C 2012: 11.1
Yes Misra C 2012: 11.2
Yes Misra C 2012: 11.3
Yes Misra C 2012: 11.4
Yes Misra C 2012: 11.5
Yes Misra C 2012: 11.6
Yes Misra C 2012: 11.7
Yes Misra C 2012: 11.8
Yes Misra C 2012: 11.9
No Misra C 2012: 11.10
Yes Misra C 2012: 12.1
Yes Misra C 2012: 12.2
Yes Misra C 2012: 12.3
Yes Misra C 2012: 12.4
Yes Misra C 2012: 12.5 amendment:1
No Misra C 2012: 12.6 amendment:4 require:premium
Yes Misra C 2012: 13.1
No Misra C 2012: 13.2
Yes Misra C 2012: 13.3
Yes Misra C 2012: 13.4
Yes Misra C 2012: 13.5
Yes Misra C 2012: 13.6
Yes Misra C 2012: 14.1
Yes Misra C 2012: 14.2
Yes Misra C 2012: 14.3
Yes Misra C 2012: 14.4
Yes Misra C 2012: 15.1
Yes Misra C 2012: 15.2
Yes Misra C 2012: 15.3
Yes Misra C 2012: 15.4
Yes Misra C 2012: 15.5
Yes Misra C 2012: 15.6
Yes Misra C 2012: 15.7
Yes Misra C 2012: 16.1
Yes Misra C 2012: 16.2
Yes Misra C 2012: 16.3
Yes Misra C 2012: 16.4
Yes Misra C 2012: 16.5
Yes Misra C 2012: 16.6
Yes Misra C 2012: 16.7
Yes Misra C 2012: 17.1
Yes Misra C 2012: 17.2
Yes Misra C 2012: 17.3
No Misra C 2012: 17.4
Yes Misra C 2012: 17.5
Yes Misra C 2012: 17.6
Yes Misra C 2012: 17.7
Yes Misra C 2012: 17.8
No Misra C 2012: 17.9
No Misra C 2012: 17.10
No Misra C 2012: 17.11
No Misra C 2012: 17.12
No Misra C 2012: 17.13
Yes Misra C 2012: 18.1
Yes Misra C 2012: 18.2
Yes Misra C 2012: 18.3
Yes Misra C 2012: 18.4
Yes Misra C 2012: 18.5
Yes Misra C 2012: 18.6
Yes Misra C 2012: 18.7
Yes Misra C 2012: 18.8
No Misra C 2012: 18.9
No Misra C 2012: 18.10
Yes Misra C 2012: 19.1
Yes Misra C 2012: 19.2
Yes Misra C 2012: 20.1
Yes Misra C 2012: 20.2
Yes Misra C 2012: 20.3
Yes Misra C 2012: 20.4
Yes Misra C 2012: 20.5
Yes Misra C 2012: 20.6
Yes Misra C 2012: 20.7
Yes Misra C 2012: 20.8
Yes Misra C 2012: 20.9
Yes Misra C 2012: 20.10
Yes Misra C 2012: 20.11
Yes Misra C 2012: 20.12
Yes Misra C 2012: 20.13
Yes Misra C 2012: 20.14
Yes Misra C 2012: 21.1
Yes Misra C 2012: 21.2
Yes Misra C 2012: 21.3
Yes Misra C 2012: 21.4
Yes Misra C 2012: 21.5
Yes Misra C 2012: 21.6
Yes Misra C 2012: 21.7
Yes Misra C 2012: 21.8
Yes Misra C 2012: 21.9
Yes Misra C 2012: 21.10
Yes Misra C 2012: 21.11
Yes Misra C 2012: 21.12
Yes Misra C 2012: 21.13 amendment:1
Yes Misra C 2012: 21.14 amendment:1
Yes Misra C 2012: 21.15 amendment:1
Yes Misra C 2012: 21.16 amendment:1
Yes Misra C 2012: 21.17 amendment:1
Yes Misra C 2012: 21.18 amendment:1
Yes Misra C 2012: 21.19 amendment:1
Yes Misra C 2012: 21.20 amendment:1
Yes Misra C 2012: 21.21 amendment:3
No Misra C 2012: 21.22 amendment:3 require:premium
No Misra C 2012: 21.23 amendment:3 require:premium
No Misra C 2012: 21.24 amendment:3 require:premium
No Misra C 2012: 21.25 amendment:4 require:premium
No Misra C 2012: 21.26 amendment:4 require:premium
Yes Misra C 2012: 22.1
Yes Misra C 2012: 22.2
Yes Misra C 2012: 22.3
Yes Misra C 2012: 22.4
Yes Misra C 2012: 22.5
Yes Misra C 2012: 22.6
Yes Misra C 2012: 22.7 amendment:1
Yes Misra C 2012: 22.8 amendment:1
Yes Misra C 2012: 22.9 amendment:1
Yes Misra C 2012: 22.10 amendment:1
No Misra C 2012: 22.11 amendment:4 require:premium
No Misra C 2012: 22.12 amendment:4 require:premium
No Misra C 2012: 22.13 amendment:4 require:premium
No Misra C 2012: 22.14 amendment:4 require:premium
No Misra C 2012: 22.15 amendment:4 require:premium
No Misra C 2012: 22.16 amendment:4 require:premium
No Misra C 2012: 22.17 amendment:4 require:premium
No Misra C 2012: 22.18 amendment:4 require:premium
No Misra C 2012: 22.19 amendment:4 require:premium
No Misra C 2012: 22.20 amendment:4 require:premium
No Misra C 2012: 23.1 amendment:3 require:premium
No Misra C 2012: 23.2 amendment:3 require:premium
No Misra C 2012: 23.3 amendment:3 require:premium
No Misra C 2012: 23.4 amendment:3 require:premium
No Misra C 2012: 23.5 amendment:3 require:premium
No Misra C 2012: 23.6 amendment:3 require:premium
No Misra C 2012: 23.7 amendment:3 require:premium
No Misra C 2012: 23.8 amendment:3 require:premium
Misra C++ 2008
--------------
Not available, Cppcheck Premium is not used
Misra C++ 2023
--------------
Not available, Cppcheck Premium is not used
TEST variant options:
--enable=all --disable=unusedFunction -DPANDA --addon=misra -DSTM32H7 -DSTM32H725xx /opendbc/safety/main.c
Critical errors
---------------
No critical errors encountered.
Note: There might still have been non-critical bailouts which might lead to false negatives.
Open source checkers
--------------------
Yes Check64BitPortability::pointerassignment
Yes CheckAssert::assertWithSideEffects
Yes CheckAutoVariables::assignFunctionArg
Yes CheckAutoVariables::autoVariables
Yes CheckAutoVariables::checkVarLifetime
No CheckBool::checkAssignBoolToFloat require:style,c++
Yes CheckBool::checkAssignBoolToPointer
No CheckBool::checkBitwiseOnBoolean require:style,inconclusive
Yes CheckBool::checkComparisonOfBoolExpressionWithInt
No CheckBool::checkComparisonOfBoolWithBool require:style,c++
No CheckBool::checkComparisonOfBoolWithInt require:warning,c++
No CheckBool::checkComparisonOfFuncReturningBool require:style,c++
Yes CheckBool::checkIncrementBoolean
Yes CheckBool::pointerArithBool
Yes CheckBool::returnValueOfFunctionReturningBool
No CheckBoost::checkBoostForeachModification
Yes CheckBufferOverrun::analyseWholeProgram
Yes CheckBufferOverrun::argumentSize
Yes CheckBufferOverrun::arrayIndex
Yes CheckBufferOverrun::arrayIndexThenCheck
Yes CheckBufferOverrun::bufferOverflow
Yes CheckBufferOverrun::negativeArraySize
Yes CheckBufferOverrun::objectIndex
Yes CheckBufferOverrun::pointerArithmetic
No CheckBufferOverrun::stringNotZeroTerminated require:warning,inconclusive
Yes CheckClass::analyseWholeProgram
No CheckClass::checkConst require:style,inconclusive
No CheckClass::checkConstructors require:style,warning
No CheckClass::checkCopyConstructors require:warning
No CheckClass::checkDuplInheritedMembers require:warning
No CheckClass::checkExplicitConstructors require:style
No CheckClass::checkMemset
No CheckClass::checkMissingOverride require:style,c++03
No CheckClass::checkReturnByReference require:performance
No CheckClass::checkSelfInitialization
No CheckClass::checkThisUseAfterFree require:warning
No CheckClass::checkUnsafeClassRefMember require:warning,safeChecks
No CheckClass::checkUselessOverride require:style
No CheckClass::checkVirtualFunctionCallInConstructor require:warning
No CheckClass::initializationListUsage require:performance
No CheckClass::initializerListOrder require:style,inconclusive
No CheckClass::operatorEqRetRefThis require:style
No CheckClass::operatorEqToSelf require:warning
No CheckClass::privateFunctions require:style
No CheckClass::thisSubtraction require:warning
No CheckClass::virtualDestructor
Yes CheckCondition::alwaysTrueFalse
Yes CheckCondition::assignIf
Yes CheckCondition::checkAssignmentInCondition
Yes CheckCondition::checkBadBitmaskCheck
Yes CheckCondition::checkCompareValueOutOfTypeRange
Yes CheckCondition::checkDuplicateConditionalAssign
Yes CheckCondition::checkIncorrectLogicOperator
Yes CheckCondition::checkInvalidTestForOverflow
Yes CheckCondition::checkModuloAlwaysTrueFalse
Yes CheckCondition::checkPointerAdditionResultNotNull
Yes CheckCondition::clarifyCondition
Yes CheckCondition::comparison
Yes CheckCondition::duplicateCondition
Yes CheckCondition::multiCondition
Yes CheckCondition::multiCondition2
No CheckExceptionSafety::checkCatchExceptionByValue require:style
No CheckExceptionSafety::checkRethrowCopy require:style
No CheckExceptionSafety::deallocThrow require:warning
No CheckExceptionSafety::destructors require:warning
No CheckExceptionSafety::nothrowThrows
No CheckExceptionSafety::rethrowNoCurrentException
No CheckExceptionSafety::unhandledExceptionSpecification require:style,inconclusive
Yes CheckFunctions::checkIgnoredReturnValue
Yes CheckFunctions::checkMathFunctions
Yes CheckFunctions::checkMissingReturn
Yes CheckFunctions::checkProhibitedFunctions
Yes CheckFunctions::invalidFunctionUsage
Yes CheckFunctions::memsetInvalid2ndParam
Yes CheckFunctions::memsetZeroBytes
No CheckFunctions::returnLocalStdMove require:performance,c++11
Yes CheckFunctions::useStandardLibrary
No CheckIO::checkCoutCerrMisusage require:c
Yes CheckIO::checkFileUsage
Yes CheckIO::checkWrongPrintfScanfArguments
Yes CheckIO::invalidScanf
Yes CheckLeakAutoVar::check
No CheckMemoryLeakInClass::check
Yes CheckMemoryLeakInFunction::checkReallocUsage
Yes CheckMemoryLeakNoVar::check
No CheckMemoryLeakNoVar::checkForUnsafeArgAlloc
Yes CheckMemoryLeakStructMember::check
Yes CheckNullPointer::analyseWholeProgram
Yes CheckNullPointer::arithmetic
Yes CheckNullPointer::nullConstantDereference
Yes CheckNullPointer::nullPointer
No CheckOther::checkAccessOfMovedVariable require:c++11,warning
Yes CheckOther::checkCastIntToCharAndBack
Yes CheckOther::checkCharVariable
Yes CheckOther::checkComparePointers
Yes CheckOther::checkComparisonFunctionIsAlwaysTrueOrFalse
Yes CheckOther::checkConstPointer
No CheckOther::checkConstVariable require:style,c++
No CheckOther::checkDuplicateBranch require:style,inconclusive
Yes CheckOther::checkDuplicateExpression
Yes CheckOther::checkEvaluationOrder
Yes CheckOther::checkFuncArgNamesDifferent
No CheckOther::checkIncompleteArrayFill require:warning,portability,inconclusive
Yes CheckOther::checkIncompleteStatement
No CheckOther::checkInterlockedDecrement require:windows-platform
Yes CheckOther::checkInvalidFree
Yes CheckOther::checkKnownArgument
Yes CheckOther::checkKnownPointerToBool
No CheckOther::checkMisusedScopedObject require:style,c++
Yes CheckOther::checkModuloOfOne
Yes CheckOther::checkNanInArithmeticExpression
Yes CheckOther::checkNegativeBitwiseShift
Yes CheckOther::checkOverlappingWrite
No CheckOther::checkPassByReference require:performance,c++
Yes CheckOther::checkRedundantAssignment
No CheckOther::checkRedundantCopy require:c++,performance,inconclusive
Yes CheckOther::checkRedundantPointerOp
Yes CheckOther::checkShadowVariables
Yes CheckOther::checkSignOfUnsignedVariable
No CheckOther::checkSuspiciousCaseInSwitch require:warning,inconclusive
No CheckOther::checkSuspiciousSemicolon require:warning,inconclusive
Yes CheckOther::checkUnreachableCode
Yes CheckOther::checkUnusedLabel
Yes CheckOther::checkVarFuncNullUB
Yes CheckOther::checkVariableScope
Yes CheckOther::checkZeroDivision
Yes CheckOther::clarifyCalculation
Yes CheckOther::clarifyStatement
Yes CheckOther::invalidPointerCast
Yes CheckOther::redundantBitwiseOperationInSwitch
Yes CheckOther::suspiciousFloatingPointCast
No CheckOther::warningOldStylePointerCast require:style,c++
No CheckPostfixOperator::postfixOperator require:performance
Yes CheckSizeof::checkSizeofForArrayParameter
Yes CheckSizeof::checkSizeofForNumericParameter
Yes CheckSizeof::checkSizeofForPointerSize
Yes CheckSizeof::sizeofCalculation
Yes CheckSizeof::sizeofFunction
Yes CheckSizeof::sizeofVoid
Yes CheckSizeof::sizeofsizeof
No CheckSizeof::suspiciousSizeofCalculation require:warning,inconclusive
No CheckStl::checkDereferenceInvalidIterator require:warning
No CheckStl::checkDereferenceInvalidIterator2
No CheckStl::checkFindInsert require:performance
No CheckStl::checkMutexes require:warning
No CheckStl::erase
No CheckStl::eraseIteratorOutOfBounds
No CheckStl::if_find require:warning,performance
No CheckStl::invalidContainer
No CheckStl::iterators
No CheckStl::knownEmptyContainer require:style
No CheckStl::misMatchingContainerIterator
No CheckStl::misMatchingContainers
No CheckStl::missingComparison require:warning
No CheckStl::negativeIndex
No CheckStl::outOfBounds
No CheckStl::outOfBoundsIndexExpression
No CheckStl::redundantCondition require:style
No CheckStl::size require:performance,c++03
No CheckStl::stlBoundaries
No CheckStl::stlOutOfBounds
No CheckStl::string_c_str
No CheckStl::useStlAlgorithm require:style
No CheckStl::uselessCalls require:performance,warning
Yes CheckString::checkAlwaysTrueOrFalseStringCompare
Yes CheckString::checkIncorrectStringCompare
Yes CheckString::checkSuspiciousStringCompare
Yes CheckString::overlappingStrcmp
Yes CheckString::sprintfOverlappingData
Yes CheckString::strPlusChar
Yes CheckString::stringLiteralWrite
Yes CheckType::checkFloatToIntegerOverflow
Yes CheckType::checkIntegerOverflow
Yes CheckType::checkLongCast
Yes CheckType::checkSignConversion
Yes CheckType::checkTooBigBitwiseShift
Yes CheckUninitVar::check
Yes CheckUninitVar::valueFlowUninit
No CheckUnusedFunctions::check require:unusedFunction
Yes CheckUnusedVar::checkFunctionVariableUsage
Yes CheckUnusedVar::checkStructMemberUsage
Yes CheckVaarg::va_list_usage
Yes CheckVaarg::va_start_argument
Premium checkers
----------------
Not available, Cppcheck Premium is not used
Autosar
-------
Not available, Cppcheck Premium is not used
Cert C
------
Not available, Cppcheck Premium is not used
Cert C++
--------
Not available, Cppcheck Premium is not used
Misra C 2012
------------
No Misra C 2012: Dir 1.1
No Misra C 2012: Dir 2.1
No Misra C 2012: Dir 3.1
No Misra C 2012: Dir 4.1
No Misra C 2012: Dir 4.2
No Misra C 2012: Dir 4.3
No Misra C 2012: Dir 4.4
No Misra C 2012: Dir 4.5
No Misra C 2012: Dir 4.6 amendment:3
No Misra C 2012: Dir 4.7
No Misra C 2012: Dir 4.8
No Misra C 2012: Dir 4.9 amendment:3
No Misra C 2012: Dir 4.10
No Misra C 2012: Dir 4.11 amendment:3
No Misra C 2012: Dir 4.12
No Misra C 2012: Dir 4.13
No Misra C 2012: Dir 4.14 amendment:2
No Misra C 2012: Dir 4.15 amendment:3
No Misra C 2012: Dir 5.1 amendment:4
No Misra C 2012: Dir 5.2 amendment:4
No Misra C 2012: Dir 5.3 amendment:4
Yes Misra C 2012: 1.1
Yes Misra C 2012: 1.2
Yes Misra C 2012: 1.3
Yes Misra C 2012: 1.4 amendment:2
No Misra C 2012: 1.5 amendment:3 require:premium
Yes Misra C 2012: 2.1
Yes Misra C 2012: 2.2
Yes Misra C 2012: 2.3
Yes Misra C 2012: 2.4
Yes Misra C 2012: 2.5
Yes Misra C 2012: 2.6
Yes Misra C 2012: 2.7
Yes Misra C 2012: 2.8
Yes Misra C 2012: 3.1
Yes Misra C 2012: 3.2
Yes Misra C 2012: 4.1
Yes Misra C 2012: 4.2
Yes Misra C 2012: 5.1
Yes Misra C 2012: 5.2
Yes Misra C 2012: 5.3
Yes Misra C 2012: 5.4
Yes Misra C 2012: 5.5
Yes Misra C 2012: 5.6
Yes Misra C 2012: 5.7
Yes Misra C 2012: 5.8
Yes Misra C 2012: 5.9
Yes Misra C 2012: 6.1
Yes Misra C 2012: 6.2
No Misra C 2012: 6.3
Yes Misra C 2012: 7.1
Yes Misra C 2012: 7.2
Yes Misra C 2012: 7.3
Yes Misra C 2012: 7.4
No Misra C 2012: 7.5
No Misra C 2012: 7.6
Yes Misra C 2012: 8.1
Yes Misra C 2012: 8.2
No Misra C 2012: 8.3
Yes Misra C 2012: 8.4
Yes Misra C 2012: 8.5
Yes Misra C 2012: 8.6
Yes Misra C 2012: 8.7
Yes Misra C 2012: 8.8
Yes Misra C 2012: 8.9
Yes Misra C 2012: 8.10
Yes Misra C 2012: 8.11
Yes Misra C 2012: 8.12
Yes Misra C 2012: 8.13
Yes Misra C 2012: 8.14
No Misra C 2012: 8.15
No Misra C 2012: 8.16
No Misra C 2012: 8.17
Yes Misra C 2012: 9.1
Yes Misra C 2012: 9.2
Yes Misra C 2012: 9.3
Yes Misra C 2012: 9.4
Yes Misra C 2012: 9.5
No Misra C 2012: 9.6
No Misra C 2012: 9.7
Yes Misra C 2012: 10.1
Yes Misra C 2012: 10.2
Yes Misra C 2012: 10.3
Yes Misra C 2012: 10.4
Yes Misra C 2012: 10.5
Yes Misra C 2012: 10.6
Yes Misra C 2012: 10.7
Yes Misra C 2012: 10.8
Yes Misra C 2012: 11.1
Yes Misra C 2012: 11.2
Yes Misra C 2012: 11.3
Yes Misra C 2012: 11.4
Yes Misra C 2012: 11.5
Yes Misra C 2012: 11.6
Yes Misra C 2012: 11.7
Yes Misra C 2012: 11.8
Yes Misra C 2012: 11.9
No Misra C 2012: 11.10
Yes Misra C 2012: 12.1
Yes Misra C 2012: 12.2
Yes Misra C 2012: 12.3
Yes Misra C 2012: 12.4
Yes Misra C 2012: 12.5 amendment:1
No Misra C 2012: 12.6 amendment:4 require:premium
Yes Misra C 2012: 13.1
No Misra C 2012: 13.2
Yes Misra C 2012: 13.3
Yes Misra C 2012: 13.4
Yes Misra C 2012: 13.5
Yes Misra C 2012: 13.6
Yes Misra C 2012: 14.1
Yes Misra C 2012: 14.2
Yes Misra C 2012: 14.3
Yes Misra C 2012: 14.4
Yes Misra C 2012: 15.1
Yes Misra C 2012: 15.2
Yes Misra C 2012: 15.3
Yes Misra C 2012: 15.4
Yes Misra C 2012: 15.5
Yes Misra C 2012: 15.6
Yes Misra C 2012: 15.7
Yes Misra C 2012: 16.1
Yes Misra C 2012: 16.2
Yes Misra C 2012: 16.3
Yes Misra C 2012: 16.4
Yes Misra C 2012: 16.5
Yes Misra C 2012: 16.6
Yes Misra C 2012: 16.7
Yes Misra C 2012: 17.1
Yes Misra C 2012: 17.2
Yes Misra C 2012: 17.3
No Misra C 2012: 17.4
Yes Misra C 2012: 17.5
Yes Misra C 2012: 17.6
Yes Misra C 2012: 17.7
Yes Misra C 2012: 17.8
No Misra C 2012: 17.9
No Misra C 2012: 17.10
No Misra C 2012: 17.11
No Misra C 2012: 17.12
No Misra C 2012: 17.13
Yes Misra C 2012: 18.1
Yes Misra C 2012: 18.2
Yes Misra C 2012: 18.3
Yes Misra C 2012: 18.4
Yes Misra C 2012: 18.5
Yes Misra C 2012: 18.6
Yes Misra C 2012: 18.7
Yes Misra C 2012: 18.8
No Misra C 2012: 18.9
No Misra C 2012: 18.10
Yes Misra C 2012: 19.1
Yes Misra C 2012: 19.2
Yes Misra C 2012: 20.1
Yes Misra C 2012: 20.2
Yes Misra C 2012: 20.3
Yes Misra C 2012: 20.4
Yes Misra C 2012: 20.5
Yes Misra C 2012: 20.6
Yes Misra C 2012: 20.7
Yes Misra C 2012: 20.8
Yes Misra C 2012: 20.9
Yes Misra C 2012: 20.10
Yes Misra C 2012: 20.11
Yes Misra C 2012: 20.12
Yes Misra C 2012: 20.13
Yes Misra C 2012: 20.14
Yes Misra C 2012: 21.1
Yes Misra C 2012: 21.2
Yes Misra C 2012: 21.3
Yes Misra C 2012: 21.4
Yes Misra C 2012: 21.5
Yes Misra C 2012: 21.6
Yes Misra C 2012: 21.7
Yes Misra C 2012: 21.8
Yes Misra C 2012: 21.9
Yes Misra C 2012: 21.10
Yes Misra C 2012: 21.11
Yes Misra C 2012: 21.12
Yes Misra C 2012: 21.13 amendment:1
Yes Misra C 2012: 21.14 amendment:1
Yes Misra C 2012: 21.15 amendment:1
Yes Misra C 2012: 21.16 amendment:1
Yes Misra C 2012: 21.17 amendment:1
Yes Misra C 2012: 21.18 amendment:1
Yes Misra C 2012: 21.19 amendment:1
Yes Misra C 2012: 21.20 amendment:1
Yes Misra C 2012: 21.21 amendment:3
No Misra C 2012: 21.22 amendment:3 require:premium
No Misra C 2012: 21.23 amendment:3 require:premium
No Misra C 2012: 21.24 amendment:3 require:premium
No Misra C 2012: 21.25 amendment:4 require:premium
No Misra C 2012: 21.26 amendment:4 require:premium
Yes Misra C 2012: 22.1
Yes Misra C 2012: 22.2
Yes Misra C 2012: 22.3
Yes Misra C 2012: 22.4
Yes Misra C 2012: 22.5
Yes Misra C 2012: 22.6
Yes Misra C 2012: 22.7 amendment:1
Yes Misra C 2012: 22.8 amendment:1
Yes Misra C 2012: 22.9 amendment:1
Yes Misra C 2012: 22.10 amendment:1
No Misra C 2012: 22.11 amendment:4 require:premium
No Misra C 2012: 22.12 amendment:4 require:premium
No Misra C 2012: 22.13 amendment:4 require:premium
No Misra C 2012: 22.14 amendment:4 require:premium
No Misra C 2012: 22.15 amendment:4 require:premium
No Misra C 2012: 22.16 amendment:4 require:premium
No Misra C 2012: 22.17 amendment:4 require:premium
No Misra C 2012: 22.18 amendment:4 require:premium
No Misra C 2012: 22.19 amendment:4 require:premium
No Misra C 2012: 22.20 amendment:4 require:premium
No Misra C 2012: 23.1 amendment:3 require:premium
No Misra C 2012: 23.2 amendment:3 require:premium
No Misra C 2012: 23.3 amendment:3 require:premium
No Misra C 2012: 23.4 amendment:3 require:premium
No Misra C 2012: 23.5 amendment:3 require:premium
No Misra C 2012: 23.6 amendment:3 require:premium
No Misra C 2012: 23.7 amendment:3 require:premium
No Misra C 2012: 23.8 amendment:3 require:premium
Misra C++ 2008
--------------
Not available, Cppcheck Premium is not used
Misra C++ 2023
--------------
Not available, Cppcheck Premium is not used

View File

@@ -0,0 +1,156 @@
1.1
1.2 X (Addon)
1.3 X (Cppcheck)
2.1 X (Cppcheck)
2.2 X (Addon)
2.3 X (Addon)
2.4 X (Addon)
2.5 X (Addon)
2.6 X (Cppcheck)
2.7 X (Addon)
3.1 X (Addon)
3.2 X (Addon)
4.1 X (Addon)
4.2 X (Addon)
5.1 X (Addon)
5.2 X (Addon)
5.3 X (Cppcheck)
5.4 X (Addon)
5.5 X (Addon)
5.6 X (Addon)
5.7 X (Addon)
5.8 X (Addon)
5.9 X (Addon)
6.1 X (Addon)
6.2 X (Addon)
7.1 X (Addon)
7.2 X (Addon)
7.3 X (Addon)
7.4 X (Addon)
8.1 X (Addon)
8.2 X (Addon)
8.3 X (Cppcheck)
8.4 X (Addon)
8.5 X (Addon)
8.6 X (Addon)
8.7 X (Addon)
8.8 X (Addon)
8.9 X (Addon)
8.10 X (Addon)
8.11 X (Addon)
8.12 X (Addon)
8.13 X (Cppcheck)
8.14 X (Addon)
9.1 X (Cppcheck)
9.2 X (Addon)
9.3 X (Addon)
9.4 X (Addon)
9.5 X (Addon)
10.1 X (Addon)
10.2 X (Addon)
10.3 X (Addon)
10.4 X (Addon)
10.5 X (Addon)
10.6 X (Addon)
10.7 X (Addon)
10.8 X (Addon)
11.1 X (Addon)
11.2 X (Addon)
11.3 X (Addon)
11.4 X (Addon)
11.5 X (Addon)
11.6 X (Addon)
11.7 X (Addon)
11.8 X (Addon)
11.9 X (Addon)
12.1 X (Addon)
12.2 X (Addon)
12.3 X (Addon)
12.4 X (Addon)
13.1 X (Addon)
13.2 X (Cppcheck)
13.3 X (Addon)
13.4 X (Addon)
13.5 X (Addon)
13.6 X (Addon)
14.1 X (Addon)
14.2 X (Addon)
14.3 X (Cppcheck)
14.4 X (Addon)
15.1 X (Addon)
15.2 X (Addon)
15.3 X (Addon)
15.4 X (Addon)
15.5 X (Addon)
15.6 X (Addon)
15.7 X (Addon)
16.1 X (Addon)
16.2 X (Addon)
16.3 X (Addon)
16.4 X (Addon)
16.5 X (Addon)
16.6 X (Addon)
16.7 X (Addon)
17.1 X (Addon)
17.2 X (Addon)
17.3 X (Addon)
17.4 X (Cppcheck)
17.5 X (Cppcheck)
17.6 X (Addon)
17.7 X (Addon)
17.8 X (Addon)
18.1 X (Cppcheck)
18.2 X (Cppcheck)
18.3 X (Cppcheck)
18.4 X (Addon)
18.5 X (Addon)
18.6 X (Cppcheck)
18.7 X (Addon)
18.8 X (Addon)
19.1 X (Cppcheck)
19.2 X (Addon)
20.1 X (Addon)
20.2 X (Addon)
20.3 X (Addon)
20.4 X (Addon)
20.5 X (Addon)
20.6 X (Cppcheck)
20.7 X (Addon)
20.8 X (Addon)
20.9 X (Addon)
20.10 X (Addon)
20.11 X (Addon)
20.12 X (Addon)
20.13 X (Addon)
20.14 X (Addon)
21.1 X (Addon)
21.2 X (Addon)
21.3 X (Addon)
21.4 X (Addon)
21.5 X (Addon)
21.6 X (Addon)
21.7 X (Addon)
21.8 X (Addon)
21.9 X (Addon)
21.10 X (Addon)
21.11 X (Addon)
21.12 X (Addon)
21.13 X (Cppcheck)
21.14 X (Addon)
21.15 X (Addon)
21.16 X (Addon)
21.17 X (Cppcheck)
21.18 X (Cppcheck)
21.19 X (Addon)
21.20 X (Addon)
21.21 X (Addon)
22.1 X (Cppcheck)
22.2 X (Cppcheck)
22.3 X (Cppcheck)
22.4 X (Cppcheck)
22.5 X (Addon)
22.6 X (Cppcheck)
22.7 X (Addon)
22.8 X (Addon)
22.9 X (Addon)
22.10 X (Addon)

View File

@@ -0,0 +1,18 @@
#!/usr/bin/env bash
set -e
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
: "${CPPCHECK_DIR:=$DIR/cppcheck/}"
if [ ! -d "$CPPCHECK_DIR" ]; then
git clone https://github.com/danmar/cppcheck.git $CPPCHECK_DIR
fi
cd $CPPCHECK_DIR
VERS="2.16.0"
git fetch --all --tags --force
git checkout $VERS
#make clean
make MATCHCOMPILTER=yes CXXFLAGS="-O2" -j8

View File

@@ -0,0 +1,21 @@
# Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well
misra-c2012-11.4
# Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well
misra-c2012-11.5
# Advisory: as stated in the Misra document, use of goto statements in accordance to 15.2 and 15.3 is ok
misra-c2012-15.1
# Advisory: union types can be used
misra-c2012-19.2
# Advisory: The # and ## preprocessor operators should not be used
misra-c2012-20.10
# needed since not all of these suppressions are applicable to all builds
unmatchedSuppression
# All interrupt handlers are defined, including ones we don't use
unusedFunction:*/interrupt_handlers*.h
# all of the below suppressions are from new checks introduced after updating
# cppcheck from 2.5 -> 2.13. they are listed here to separate the update from
# fixing the violations and all are intended to be removed soon after
misra-c2012-2.5 # unused macros. a few legit, rest aren't common between F4/H7 builds. should we do this in the unusedFunction pass?

View File

@@ -0,0 +1,86 @@
#!/usr/bin/env bash
set -e
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
cd $DIR
source ../../../../setup.sh
GREEN="\e[1;32m"
YELLOW="\e[1;33m"
RED="\e[1;31m"
NC='\033[0m'
: "${CPPCHECK_DIR:=$DIR/cppcheck/}"
# install cppcheck if missing
if [ -z "${SKIP_CPPCHECK_INSTALL}" ]; then
$DIR/install.sh
fi
# ensure checked in coverage table is up to date
if [ -z "$SKIP_TABLES_DIFF" ]; then
python3 $CPPCHECK_DIR/addons/misra.py -generate-table > coverage_table
if ! git diff --quiet coverage_table; then
echo -e "${YELLOW}MISRA coverage table doesn't match. Update and commit:${NC}"
exit 3
fi
fi
cd $BASEDIR
if [ -z "${SKIP_BUILD}" ]; then
scons -j8
fi
CHECKLIST=$DIR/checkers.txt
echo "Cppcheck checkers list from test_misra.sh:" > $CHECKLIST
cppcheck() {
# get all gcc defines: arm-none-eabi-gcc -dM -E - < /dev/null
COMMON_DEFINES="-D__GNUC__=9 -UCMSIS_NVIC_VIRTUAL -UCMSIS_VECTAB_VIRTUAL"
# note that cppcheck build cache results in inconsistent results as of v2.13.0
OUTPUT=$DIR/.output.log
echo -e "\n\n\n\n\nTEST variant options:" >> $CHECKLIST
echo -e ""${@//$BASEDIR/}"\n\n" >> $CHECKLIST # (absolute path removed)
$CPPCHECK_DIR/cppcheck --inline-suppr -I $BASEDIR/opendbc/safety/ \
-I $BASEDIR/opendbc/safety/safety/ -I $BASEDIR/opendbc/safety/board/ \
-I "$(arm-none-eabi-gcc -print-file-name=include)" \
--suppressions-list=$DIR/suppressions.txt --suppress=*:*inc/* \
--suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive --safety \
--platform=arm32-wchar_t4 $COMMON_DEFINES --checkers-report=$CHECKLIST.tmp \
--std=c11 "$@" 2>&1 | tee $OUTPUT
cat $CHECKLIST.tmp >> $CHECKLIST
rm $CHECKLIST.tmp
# cppcheck bug: some MISRA errors won't result in the error exit code,
# so check the output (https://trac.cppcheck.net/ticket/12440#no1)
if grep -e "misra violation" -e "error" -e "style: " $OUTPUT > /dev/null; then
printf "${RED}** FAILED: MISRA violations found!${NC}\n"
exit 1
fi
}
PANDA_OPTS="--enable=all --disable=unusedFunction -DPANDA --addon=misra"
printf "\n${GREEN}** PANDA F4 CODE **${NC}\n"
cppcheck $PANDA_OPTS -DSTM32F4 -DSTM32F413xx $BASEDIR/opendbc/safety/main.c
printf "\n${GREEN}** PANDA H7 CODE **${NC}\n"
cppcheck $PANDA_OPTS -DSTM32H7 -DSTM32H725xx $BASEDIR/opendbc/safety/main.c
# unused needs to run globally
#printf "\n${GREEN}** UNUSED ALL CODE **${NC}\n"
#cppcheck --enable=unusedFunction --quiet $BASEDIR/opendbc/safety/board/
printf "\n${GREEN}Success!${NC} took $SECONDS seconds\n"
# ensure list of checkers is up to date
cd $DIR
if [ -z "$SKIP_TABLES_DIFF" ] && ! git diff --quiet $CHECKLIST; then
echo -e "\n${YELLOW}WARNING: Cppcheck checkers.txt report has changed. Review and commit...${NC}"
exit 4
fi

View File

@@ -0,0 +1,69 @@
#!/usr/bin/env python3
import os
import glob
import pytest
import shutil
import subprocess
import tempfile
import random
HERE = os.path.abspath(os.path.dirname(__file__))
ROOT = os.path.join(HERE, "../../../../")
IGNORED_PATHS = (
'opendbc/safety/tests/',
'opendbc/safety/board/',
)
mutations = [
# default
(None, None, False),
# general safety
("opendbc/safety/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('opendbc/safety/**', 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) > 20, files
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):
with tempfile.TemporaryDirectory() as tmp:
shutil.copytree(ROOT, tmp, dirs_exist_ok=True)
shutil.rmtree(os.path.join(tmp, '.venv'), ignore_errors=True)
# apply patch
if fn is not None:
r = os.system(f"cd {tmp} && sed -i '{patch}' {fn}")
assert r == 0
# run test
r = subprocess.run("SKIP_TABLES_DIFF=1 SKIP_BUILD=1 opendbc/safety/tests/misra/test_misra.sh", cwd=tmp, shell=True)
failed = r.returncode != 0
assert failed == should_fail

View File

@@ -0,0 +1,22 @@
#!/usr/bin/env bash
set -e
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
cd $DIR
$DIR/install_mull.sh
GIT_REF="${GIT_REF:-origin/master}"
GIT_ROOT=$(git rev-parse --show-toplevel)
MULL_OPS="mutators: [cxx_increment, cxx_decrement, cxx_comparison, cxx_boundary, cxx_bitwise_assignment, cxx_bitwise, cxx_arithmetic_assignment, cxx_arithmetic, cxx_remove_negation]"
echo -e "$MULL_OPS" > $GIT_ROOT/mull.yml
scons --mutation -j$(nproc) -D
echo -e "timeout: 10000\ngitDiffRef: $GIT_REF\ngitProjectRoot: $GIT_ROOT" >> $GIT_ROOT/mull.yml
SAFETY_MODELS=$(find * | grep "^test_.*\.py")
for safety_model in ${SAFETY_MODELS[@]}; do
echo ""
echo ""
echo -e "Testing mutations on : $safety_model"
mull-runner-17 --ld-search-path /lib/x86_64-linux-gnu/ ./libsafety/libsafety.so -test-program=./$safety_model
done

36
opendbc/safety/tests/test.sh Executable file
View File

@@ -0,0 +1,36 @@
#!/usr/bin/env bash
set -e
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
cd $DIR
source ../../../setup.sh
# reset coverage data and generate gcc note file
rm -f ./libsafety/*.gcda
if [ "$1" == "--ubsan" ]; then
scons -j$(nproc) -D --coverage --ubsan
else
scons -j$(nproc) -D --coverage
fi
# run safety tests and generate coverage data
pytest test_*.py
# generate and open report
if [ "$1" == "--report" ]; then
geninfo ./libsafety/ -o coverage.info
genhtml coverage.info -o coverage-out
sensible-browser coverage-out/index.html
fi
# test coverage
GCOV_OUTPUT=$(gcov -n ./libsafety/safety.c)
INCOMPLETE_COVERAGE=$(echo "$GCOV_OUTPUT" | paste -s -d' \n' | grep -E "File.*(\/safety\/safety_.*)|(safety)\.h" | grep -v "100.00%" || true)
if [ -n "$INCOMPLETE_COVERAGE" ]; then
echo "FAILED: Some files have less than 100% coverage:"
echo "$INCOMPLETE_COVERAGE"
exit 1
else
echo "SUCCESS: All checked files have 100% coverage!"
fi

View File

@@ -0,0 +1,70 @@
#!/usr/bin/env python3
import unittest
import opendbc.safety.tests.common as common
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
from opendbc.safety.tests.common import CANPackerPanda
class TestBody(common.PandaSafetyTest):
TX_MSGS = [[0x250, 0], [0x251, 0], [0x350, 0], [0x351, 0],
[0x1, 0], [0x1, 1], [0x1, 2], [0x1, 3]]
def setUp(self):
self.packer = CANPackerPanda("comma_body")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_BODY, 0)
self.safety.init_tests()
def _motors_data_msg(self, speed_l, speed_r):
values = {"SPEED_L": speed_l, "SPEED_R": speed_r}
return self.packer.make_can_msg_panda("MOTORS_DATA", 0, values)
def _torque_cmd_msg(self, torque_l, torque_r):
values = {"TORQUE_L": torque_l, "TORQUE_R": torque_r}
return self.packer.make_can_msg_panda("TORQUE_CMD", 0, values)
def _knee_torque_cmd_msg(self, torque_l, torque_r):
values = {"TORQUE_L": torque_l, "TORQUE_R": torque_r}
return self.packer.make_can_msg_panda("KNEE_TORQUE_CMD", 0, values)
def _max_motor_rpm_cmd_msg(self, max_rpm_l, max_rpm_r):
values = {"MAX_RPM_L": max_rpm_l, "MAX_RPM_R": max_rpm_r}
return self.packer.make_can_msg_panda("MAX_MOTOR_RPM_CMD", 0, values)
def test_rx_hook(self):
self.assertFalse(self.safety.get_controls_allowed())
self.assertFalse(self.safety.get_vehicle_moving())
# controls allowed when we get MOTORS_DATA message
self.assertTrue(self._rx(self._torque_cmd_msg(0, 0)))
self.assertTrue(self.safety.get_vehicle_moving()) # always moving
self.assertFalse(self.safety.get_controls_allowed())
self.assertTrue(self._rx(self._motors_data_msg(0, 0)))
self.assertTrue(self.safety.get_vehicle_moving()) # always moving
self.assertTrue(self.safety.get_controls_allowed())
def test_tx_hook(self):
self.assertFalse(self._tx(self._torque_cmd_msg(0, 0)))
self.assertFalse(self._tx(self._knee_torque_cmd_msg(0, 0)))
self.safety.set_controls_allowed(True)
self.assertTrue(self._tx(self._torque_cmd_msg(0, 0)))
self.assertTrue(self._tx(self._knee_torque_cmd_msg(0, 0)))
def test_can_flasher(self):
# CAN flasher always allowed
self.safety.set_controls_allowed(False)
self.assertTrue(self._tx(common.make_msg(0, 0x1, 8)))
# 0xdeadfaceU enters CAN flashing mode for base & knee
for addr in (0x250, 0x350):
self.assertTrue(self._tx(common.make_msg(0, addr, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0\x0a')))
self.assertFalse(self._tx(common.make_msg(0, addr, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0'))) # not correct data/len
self.assertFalse(self._tx(common.make_msg(0, addr + 1, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0\x0a'))) # wrong address
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,127 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.chrysler.values import ChryslerSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSafetyTest):
TX_MSGS = [[0x23B, 0], [0x292, 0], [0x2A6, 0]]
STANDSTILL_THRESHOLD = 0
RELAY_MALFUNCTION_ADDRS = {0: (0x292,)}
FWD_BLACKLISTED_ADDRS = {2: [0x292, 0x2A6]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
MAX_RATE_UP = 3
MAX_RATE_DOWN = 3
MAX_TORQUE = 261
MAX_RT_DELTA = 112
RT_INTERVAL = 250000
MAX_TORQUE_ERROR = 80
LKAS_ACTIVE_VALUE = 1
DAS_BUS = 0
def setUp(self):
self.packer = CANPackerPanda("chrysler_pacifica_2017_hybrid_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_CHRYSLER, 0)
self.safety.init_tests()
def _button_msg(self, cancel=False, resume=False):
values = {"ACC_Cancel": cancel, "ACC_Resume": resume}
return self.packer.make_can_msg_panda("CRUISE_BUTTONS", self.DAS_BUS, values)
def _pcm_status_msg(self, enable):
values = {"ACC_ACTIVE": enable}
return self.packer.make_can_msg_panda("DAS_3", self.DAS_BUS, values)
def _speed_msg(self, speed):
values = {"SPEED_LEFT": speed, "SPEED_RIGHT": speed}
return self.packer.make_can_msg_panda("SPEED_1", 0, values)
def _user_gas_msg(self, gas):
values = {"Accelerator_Position": gas}
return self.packer.make_can_msg_panda("ECM_5", 0, values)
def _user_brake_msg(self, brake):
values = {"Brake_Pedal_State": 1 if brake else 0}
return self.packer.make_can_msg_panda("ESP_1", 0, values)
def _torque_meas_msg(self, torque):
values = {"EPS_TORQUE_MOTOR": torque}
return self.packer.make_can_msg_panda("EPS_2", 0, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"STEERING_TORQUE": torque, "LKAS_CONTROL_BIT": self.LKAS_ACTIVE_VALUE if steer_req else 0}
return self.packer.make_can_msg_panda("LKAS_COMMAND", 0, values)
def test_buttons(self):
for controls_allowed in (True, False):
self.safety.set_controls_allowed(controls_allowed)
# resume only while controls allowed
self.assertEqual(controls_allowed, self._tx(self._button_msg(resume=True)))
# can always cancel
self.assertTrue(self._tx(self._button_msg(cancel=True)))
# only one button at a time
self.assertFalse(self._tx(self._button_msg(cancel=True, resume=True)))
self.assertFalse(self._tx(self._button_msg(cancel=False, resume=False)))
class TestChryslerRamDTSafety(TestChryslerSafety):
TX_MSGS = [[0xB1, 2], [0xA6, 0], [0xFA, 0]]
RELAY_MALFUNCTION_ADDRS = {0: (0xA6,)}
FWD_BLACKLISTED_ADDRS = {2: [0xA6, 0xFA]}
MAX_RATE_UP = 6
MAX_RATE_DOWN = 6
MAX_TORQUE = 350
DAS_BUS = 2
LKAS_ACTIVE_VALUE = 2
def setUp(self):
self.packer = CANPackerPanda("chrysler_ram_dt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_CHRYSLER, ChryslerSafetyFlags.FLAG_CHRYSLER_RAM_DT)
self.safety.init_tests()
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]]
RELAY_MALFUNCTION_ADDRS = {0: (0x276,)}
FWD_BLACKLISTED_ADDRS = {2: [0x275, 0x276]}
MAX_TORQUE = 361
MAX_RATE_UP = 14
MAX_RATE_DOWN = 14
MAX_RT_DELTA = 182
DAS_BUS = 2
LKAS_ACTIVE_VALUE = 2
def setUp(self):
self.packer = CANPackerPanda("chrysler_ram_hd_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_CHRYSLER, ChryslerSafetyFlags.FLAG_CHRYSLER_RAM_HD)
self.safety.init_tests()
def _speed_msg(self, speed):
values = {"Vehicle_Speed": speed}
return self.packer.make_can_msg_panda("ESP_8", 0, values)
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,73 @@
#!/usr/bin/env python3
import unittest
import opendbc.safety.tests.common as common
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
class TestDefaultRxHookBase(common.PandaSafetyTest):
def test_rx_hook(self):
# default rx hook allows all msgs
for bus in range(4):
for addr in self.SCANNED_ADDRS:
self.assertTrue(self._rx(common.make_msg(bus, addr, 8)), f"failed RX {addr=}")
class TestNoOutput(TestDefaultRxHookBase):
TX_MSGS = []
def setUp(self):
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_NOOUTPUT, 0)
self.safety.init_tests()
class TestSilent(TestNoOutput):
"""SILENT uses same hooks as NOOUTPUT"""
def setUp(self):
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_SILENT, 0)
self.safety.init_tests()
class TestAllOutput(TestDefaultRxHookBase):
# Allow all messages
TX_MSGS = [[addr, bus] for addr in common.PandaSafetyTest.SCANNED_ADDRS
for bus in range(4)]
def setUp(self):
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_ALLOUTPUT, 0)
self.safety.init_tests()
def test_spam_can_buses(self):
# asserts tx allowed for all scanned addrs
for bus in range(4):
for addr in self.SCANNED_ADDRS:
should_tx = [addr, bus] in self.TX_MSGS
self.assertEqual(should_tx, self._tx(common.make_msg(bus, addr, 8)), f"allowed TX {addr=} {bus=}")
def test_default_controls_not_allowed(self):
# controls always allowed
self.assertTrue(self.safety.get_controls_allowed())
def test_tx_hook_on_wrong_safety_mode(self):
# No point, since we allow all messages
pass
class TestAllOutputPassthrough(TestAllOutput):
FWD_BLACKLISTED_ADDRS = {}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
def setUp(self):
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_ALLOUTPUT, 1)
self.safety.init_tests()
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,48 @@
#!/usr/bin/env python3
import unittest
import opendbc.safety.tests.common as common
from opendbc.safety import Safety, DLC_TO_LEN
from opendbc.safety.tests.libsafety import libsafety_py
from opendbc.safety.tests.test_defaults import TestDefaultRxHookBase
GM_CAMERA_DIAG_ADDR = 0x24B
class TestElm327(TestDefaultRxHookBase):
TX_MSGS = [[addr, bus] for addr in [GM_CAMERA_DIAG_ADDR, *range(0x600, 0x800),
*range(0x18DA00F1, 0x18DB00F1, 0x100), # 29-bit UDS physical addressing
*[0x18DB33F1], # 29-bit UDS functional address
] for bus in range(4)]
def setUp(self):
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_ELM327, 0)
self.safety.init_tests()
def test_tx_hook(self):
# ensure we can transmit arbitrary data on allowed addresses
for bus in range(4):
for addr in self.SCANNED_ADDRS:
should_tx = [addr, bus] in self.TX_MSGS
self.assertEqual(should_tx, self._tx(common.make_msg(bus, addr, 8)))
# ELM only allows 8 byte UDS/KWP messages under ISO 15765-4
for msg_len in DLC_TO_LEN:
should_tx = msg_len == 8
self.assertEqual(should_tx, self._tx(common.make_msg(0, 0x700, msg_len)))
# TODO: perform this check for all addresses
# 4 to 15 are reserved ISO-TP frame types (https://en.wikipedia.org/wiki/ISO_15765-2)
for byte in range(0xff):
should_tx = (byte >> 4) <= 3
self.assertEqual(should_tx, self._tx(common.make_msg(0, GM_CAMERA_DIAG_ADDR, dat=bytes([byte] * 8))))
def test_tx_hook_on_wrong_safety_mode(self):
# No point, since we allow many diagnostic addresses
pass
if __name__ == "__main__":
unittest.main()

466
opendbc/safety/tests/test_ford.py Executable file
View File

@@ -0,0 +1,466 @@
#!/usr/bin/env python3
import numpy as np
import random
import unittest
import opendbc.safety.tests.common as common
from opendbc.car.ford.values import FordSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
from opendbc.safety.tests.common import CANPackerPanda
MSG_EngBrakeData = 0x165 # RX from PCM, for driver brake pedal and cruise state
MSG_EngVehicleSpThrottle = 0x204 # RX from PCM, for driver throttle input
MSG_BrakeSysFeatures = 0x415 # RX from ABS, for vehicle speed
MSG_EngVehicleSpThrottle2 = 0x202 # RX from PCM, for second vehicle speed
MSG_Yaw_Data_FD1 = 0x91 # RX from RCM, for yaw rate
MSG_Steering_Data_FD1 = 0x083 # TX by OP, various driver switches and LKAS/CC buttons
MSG_ACCDATA = 0x186 # TX by OP, ACC controls
MSG_ACCDATA_3 = 0x18A # TX by OP, ACC/TJA user interface
MSG_Lane_Assist_Data1 = 0x3CA # TX by OP, Lane Keep Assist
MSG_LateralMotionControl = 0x3D3 # TX by OP, Lateral Control message
MSG_LateralMotionControl2 = 0x3D6 # TX by OP, alternate Lateral Control message
MSG_IPMA_Data = 0x3D8 # TX by OP, IPMA and LKAS user interface
def checksum(msg):
addr, dat, bus = msg
ret = bytearray(dat)
if addr == MSG_Yaw_Data_FD1:
chksum = dat[0] + dat[1] # VehRol_W_Actl
chksum += dat[2] + dat[3] # VehYaw_W_Actl
chksum += dat[5] # VehRollYaw_No_Cnt
chksum += dat[6] >> 6 # VehRolWActl_D_Qf
chksum += (dat[6] >> 4) & 0x3 # VehYawWActl_D_Qf
chksum = 0xff - (chksum & 0xff)
ret[4] = chksum
elif addr == MSG_BrakeSysFeatures:
chksum = dat[0] + dat[1] # Veh_V_ActlBrk
chksum += (dat[2] >> 2) & 0xf # VehVActlBrk_No_Cnt
chksum += dat[2] >> 6 # VehVActlBrk_D_Qf
chksum = 0xff - (chksum & 0xff)
ret[3] = chksum
elif addr == MSG_EngVehicleSpThrottle2:
chksum = (dat[2] >> 3) & 0xf # VehVActlEng_No_Cnt
chksum += (dat[4] >> 5) & 0x3 # VehVActlEng_D_Qf
chksum += dat[6] + dat[7] # Veh_V_ActlEng
chksum = 0xff - (chksum & 0xff)
ret[1] = chksum
return addr, ret, bus
class Buttons:
CANCEL = 0
RESUME = 1
TJA_TOGGLE = 2
# Ford safety has four different configurations tested here:
# * CAN with openpilot longitudinal
# * CAN FD with stock longitudinal
# * CAN FD with openpilot longitudinal
class TestFordSafetyBase(common.PandaCarSafetyTest):
STANDSTILL_THRESHOLD = 1
RELAY_MALFUNCTION_ADDRS = {0: (MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl,
MSG_LateralMotionControl2, MSG_IPMA_Data)}
FWD_BLACKLISTED_ADDRS = {2: [MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl,
MSG_LateralMotionControl2, MSG_IPMA_Data]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
# Max allowed delta between car speeds
MAX_SPEED_DELTA = 2.0 # m/s
STEER_MESSAGE = 0
# Curvature control limits
DEG_TO_CAN = 50000 # 1 / (2e-5) rad to can
MAX_CURVATURE = 0.02
MAX_CURVATURE_ERROR = 0.002
CURVATURE_ERROR_MIN_SPEED = 10.0 # m/s
ANGLE_RATE_BP = [5., 25., 25.]
ANGLE_RATE_UP = [0.00045, 0.0001, 0.0001] # windup limit
ANGLE_RATE_DOWN = [0.00045, 0.00015, 0.00015] # unwind limit
cnt_speed = 0
cnt_speed_2 = 0
cnt_yaw_rate = 0
packer: CANPackerPanda
safety: libsafety_py.Panda
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestFordSafetyBase":
raise unittest.SkipTest
def _set_prev_desired_angle(self, t):
t = round(t * self.DEG_TO_CAN)
self.safety.set_desired_angle_last(t)
def _reset_curvature_measurement(self, curvature, speed):
for _ in range(6):
self._rx(self._speed_msg(speed))
self._rx(self._yaw_rate_msg(curvature, speed))
# Driver brake pedal
def _user_brake_msg(self, brake: bool):
# brake pedal and cruise state share same message, so we have to send
# the other signal too
enable = self.safety.get_controls_allowed()
values = {
"BpedDrvAppl_D_Actl": 2 if brake else 1,
"CcStat_D_Actl": 5 if enable else 0,
}
return self.packer.make_can_msg_panda("EngBrakeData", 0, values)
# ABS vehicle speed
def _speed_msg(self, speed: float, quality_flag=True):
values = {"Veh_V_ActlBrk": speed * 3.6, "VehVActlBrk_D_Qf": 3 if quality_flag else 0, "VehVActlBrk_No_Cnt": self.cnt_speed % 16}
self.__class__.cnt_speed += 1
return self.packer.make_can_msg_panda("BrakeSysFeatures", 0, values, fix_checksum=checksum)
# PCM vehicle speed
def _speed_msg_2(self, speed: float, quality_flag=True):
values = {"Veh_V_ActlEng": speed * 3.6, "VehVActlEng_D_Qf": 3 if quality_flag else 0, "VehVActlEng_No_Cnt": self.cnt_speed_2 % 16}
self.__class__.cnt_speed_2 += 1
return self.packer.make_can_msg_panda("EngVehicleSpThrottle2", 0, values, fix_checksum=checksum)
# Standstill state
def _vehicle_moving_msg(self, speed: float):
values = {"VehStop_D_Stat": 1 if speed <= self.STANDSTILL_THRESHOLD else random.choice((0, 2, 3))}
return self.packer.make_can_msg_panda("DesiredTorqBrk", 0, values)
# Current curvature
def _yaw_rate_msg(self, curvature: float, speed: float, quality_flag=True):
values = {"VehYaw_W_Actl": curvature * speed, "VehYawWActl_D_Qf": 3 if quality_flag else 0,
"VehRollYaw_No_Cnt": self.cnt_yaw_rate % 256}
self.__class__.cnt_yaw_rate += 1
return self.packer.make_can_msg_panda("Yaw_Data_FD1", 0, values, fix_checksum=checksum)
# Drive throttle input
def _user_gas_msg(self, gas: float):
values = {"ApedPos_Pc_ActlArb": gas}
return self.packer.make_can_msg_panda("EngVehicleSpThrottle", 0, values)
# Cruise status
def _pcm_status_msg(self, enable: bool):
# brake pedal and cruise state share same message, so we have to send
# the other signal too
brake = self.safety.get_brake_pressed_prev()
values = {
"BpedDrvAppl_D_Actl": 2 if brake else 1,
"CcStat_D_Actl": 5 if enable else 0,
}
return self.packer.make_can_msg_panda("EngBrakeData", 0, values)
# LKAS command
def _lkas_command_msg(self, action: int):
values = {
"LkaActvStats_D2_Req": action,
}
return self.packer.make_can_msg_panda("Lane_Assist_Data1", 0, values)
# LCA command
def _lat_ctl_msg(self, enabled: bool, path_offset: float, path_angle: float, curvature: float, curvature_rate: float):
if self.STEER_MESSAGE == MSG_LateralMotionControl:
values = {
"LatCtl_D_Rq": 1 if enabled else 0,
"LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter
"LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians
"LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2
"LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter
}
return self.packer.make_can_msg_panda("LateralMotionControl", 0, values)
elif self.STEER_MESSAGE == MSG_LateralMotionControl2:
values = {
"LatCtl_D2_Rq": 1 if enabled else 0,
"LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter
"LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians
"LatCtlCrv_NoRate2_Actl": curvature_rate, # Curvature rate [-0.001024|0.001023] 1/meter^2
"LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter
}
return self.packer.make_can_msg_panda("LateralMotionControl2", 0, values)
# Cruise control buttons
def _acc_button_msg(self, button: int, bus: int):
values = {
"CcAslButtnCnclPress": 1 if button == Buttons.CANCEL else 0,
"CcAsllButtnResPress": 1 if button == Buttons.RESUME else 0,
"TjaButtnOnOffPress": 1 if button == Buttons.TJA_TOGGLE else 0,
}
return self.packer.make_can_msg_panda("Steering_Data_FD1", bus, values)
def test_rx_hook(self):
# checksum, counter, and quality flag checks
for quality_flag in [True, False]:
for msg in ["speed", "speed_2", "yaw"]:
self.safety.set_controls_allowed(True)
# send multiple times to verify counter checks
for _ in range(10):
if msg == "speed":
to_push = self._speed_msg(0, quality_flag=quality_flag)
elif msg == "speed_2":
to_push = self._speed_msg_2(0, quality_flag=quality_flag)
elif msg == "yaw":
to_push = self._yaw_rate_msg(0, 0, quality_flag=quality_flag)
self.assertEqual(quality_flag, self._rx(to_push))
self.assertEqual(quality_flag, self.safety.get_controls_allowed())
# Mess with checksum to make it fail, checksum is not checked for 2nd speed
to_push[0].data[3] = 0 # Speed checksum & half of yaw signal
should_rx = msg == "speed_2" and quality_flag
self.assertEqual(should_rx, self._rx(to_push))
self.assertEqual(should_rx, self.safety.get_controls_allowed())
def test_rx_hook_speed_mismatch(self):
# Ford relies on speed for driver curvature limiting, so it checks two sources
for speed in np.arange(0, 40, 0.5):
for speed_delta in np.arange(-5, 5, 0.1):
speed_2 = round(max(speed + speed_delta, 0), 1)
# Set controls allowed in between rx since first message can reset it
self._rx(self._speed_msg(speed))
self.safety.set_controls_allowed(True)
self._rx(self._speed_msg_2(speed_2))
within_delta = abs(speed - speed_2) <= self.MAX_SPEED_DELTA
self.assertEqual(self.safety.get_controls_allowed(), within_delta)
def test_angle_measurements(self):
"""Tests rx hook correctly parses the curvature measurement from the vehicle speed and yaw rate"""
for speed in np.arange(0.5, 40, 0.5):
for curvature in np.arange(0, self.MAX_CURVATURE * 2, 2e-3):
self._rx(self._speed_msg(speed))
for c in (curvature, -curvature, 0, 0, 0, 0):
self._rx(self._yaw_rate_msg(c, speed))
self.assertEqual(self.safety.get_angle_meas_min(), round(-curvature * self.DEG_TO_CAN))
self.assertEqual(self.safety.get_angle_meas_max(), round(curvature * self.DEG_TO_CAN))
self._rx(self._yaw_rate_msg(0, speed))
self.assertEqual(self.safety.get_angle_meas_min(), round(-curvature * self.DEG_TO_CAN))
self.assertEqual(self.safety.get_angle_meas_max(), 0)
self._rx(self._yaw_rate_msg(0, speed))
self.assertEqual(self.safety.get_angle_meas_min(), 0)
self.assertEqual(self.safety.get_angle_meas_max(), 0)
def test_steer_allowed(self):
path_offsets = np.arange(-5.12, 5.11, 1).round()
path_angles = np.arange(-0.5, 0.5235, 0.1).round(1)
curvature_rates = np.arange(-0.001024, 0.00102375, 0.001).round(3)
curvatures = np.arange(-0.02, 0.02094, 0.01).round(2)
for speed in (self.CURVATURE_ERROR_MIN_SPEED - 1,
self.CURVATURE_ERROR_MIN_SPEED + 1):
for controls_allowed in (True, False):
for steer_control_enabled in (True, False):
for path_offset in path_offsets:
for path_angle in path_angles:
for curvature_rate in curvature_rates:
for curvature in curvatures:
self.safety.set_controls_allowed(controls_allowed)
self._set_prev_desired_angle(curvature)
self._reset_curvature_measurement(curvature, speed)
should_tx = path_offset == 0 and path_angle == 0 and curvature_rate == 0
# when request bit is 0, only allow curvature of 0 since the signal range
# is not large enough to enforce it tracking measured
should_tx = should_tx and (controls_allowed if steer_control_enabled else curvature == 0)
with self.subTest(controls_allowed=controls_allowed, steer_control_enabled=steer_control_enabled,
path_offset=path_offset, path_angle=path_angle, curvature_rate=curvature_rate,
curvature=curvature):
self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(steer_control_enabled, path_offset, path_angle, curvature, curvature_rate)))
def test_curvature_rate_limit_up(self):
"""
When the curvature error is exceeded, commanded curvature must start moving towards meas respecting rate limits.
Since panda allows higher rate limits to avoid false positives, we need to allow a lower rate to move towards meas.
"""
self.safety.set_controls_allowed(True)
small_curvature = 2 / self.DEG_TO_CAN # significant small amount of curvature to cross boundary
for speed in np.arange(0, 40, 0.5):
limit_command = speed > self.CURVATURE_ERROR_MIN_SPEED
max_delta_up = np.interp(speed - 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP)
max_delta_up_lower = np.interp(speed + 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP)
cases = [
(not limit_command, 0),
(not limit_command, max_delta_up_lower - small_curvature),
(True, max_delta_up_lower),
(True, max_delta_up),
(False, max_delta_up + small_curvature),
]
for sign in (-1, 1):
self._reset_curvature_measurement(sign * (self.MAX_CURVATURE_ERROR + 1e-3), speed)
for should_tx, curvature in cases:
self._set_prev_desired_angle(sign * small_curvature)
self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(True, 0, 0, sign * (small_curvature + curvature), 0)))
def test_curvature_rate_limit_down(self):
self.safety.set_controls_allowed(True)
small_curvature = 2 / self.DEG_TO_CAN # significant small amount of curvature to cross boundary
for speed in np.arange(0, 40, 0.5):
limit_command = speed > self.CURVATURE_ERROR_MIN_SPEED
max_delta_down = np.interp(speed - 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN)
max_delta_down_lower = np.interp(speed + 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN)
cases = [
(not limit_command, self.MAX_CURVATURE),
(not limit_command, self.MAX_CURVATURE - max_delta_down_lower + small_curvature),
(True, self.MAX_CURVATURE - max_delta_down_lower),
(True, self.MAX_CURVATURE - max_delta_down),
(False, self.MAX_CURVATURE - max_delta_down - small_curvature),
]
for sign in (-1, 1):
self._reset_curvature_measurement(sign * (self.MAX_CURVATURE - self.MAX_CURVATURE_ERROR - 1e-3), speed)
for should_tx, curvature in cases:
self._set_prev_desired_angle(sign * self.MAX_CURVATURE)
self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(True, 0, 0, sign * curvature, 0)))
def test_prevent_lkas_action(self):
self.safety.set_controls_allowed(1)
self.assertFalse(self._tx(self._lkas_command_msg(1)))
self.safety.set_controls_allowed(0)
self.assertFalse(self._tx(self._lkas_command_msg(1)))
def test_acc_buttons(self):
for allowed in (0, 1):
self.safety.set_controls_allowed(allowed)
for enabled in (True, False):
self._rx(self._pcm_status_msg(enabled))
self.assertTrue(self._tx(self._acc_button_msg(Buttons.TJA_TOGGLE, 2)))
for allowed in (0, 1):
self.safety.set_controls_allowed(allowed)
for bus in (0, 2):
self.assertEqual(allowed, self._tx(self._acc_button_msg(Buttons.RESUME, bus)))
for enabled in (True, False):
self._rx(self._pcm_status_msg(enabled))
for bus in (0, 2):
self.assertEqual(enabled, self._tx(self._acc_button_msg(Buttons.CANCEL, bus)))
class TestFordCANFDStockSafety(TestFordSafetyBase):
STEER_MESSAGE = MSG_LateralMotionControl2
TX_MSGS = [
[MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0],
[MSG_LateralMotionControl2, 0], [MSG_IPMA_Data, 0],
]
def setUp(self):
self.packer = CANPackerPanda("ford_lincoln_base_pt")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_FORD, FordSafetyFlags.FLAG_FORD_CANFD)
self.safety.init_tests()
class TestFordLongitudinalSafetyBase(TestFordSafetyBase):
RELAY_MALFUNCTION_ADDRS = {0: (MSG_ACCDATA, MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl,
MSG_LateralMotionControl2, MSG_IPMA_Data)}
FWD_BLACKLISTED_ADDRS = {2: [MSG_ACCDATA, MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl,
MSG_LateralMotionControl2, MSG_IPMA_Data]}
MAX_ACCEL = 2.0 # accel is used for brakes, but openpilot can set positive values
MIN_ACCEL = -3.5
INACTIVE_ACCEL = 0.0
MAX_GAS = 2.0
MIN_GAS = -0.5
INACTIVE_GAS = -5.0
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestFordLongitudinalSafetyBase":
raise unittest.SkipTest
# ACC command
def _acc_command_msg(self, gas: float, brake: float, brake_actuation: bool, cmbb_deny: bool = False):
values = {
"AccPrpl_A_Rq": gas, # [-5|5.23] m/s^2
"AccPrpl_A_Pred": gas, # [-5|5.23] m/s^2
"AccBrkTot_A_Rq": brake, # [-20|11.9449] m/s^2
"AccBrkPrchg_B_Rq": 1 if brake_actuation else 0, # Pre-charge brake request: 0=No, 1=Yes
"AccBrkDecel_B_Rq": 1 if brake_actuation else 0, # Deceleration request: 0=Inactive, 1=Active
"CmbbDeny_B_Actl": 1 if cmbb_deny else 0, # [0|1] deny AEB actuation
}
return self.packer.make_can_msg_panda("ACCDATA", 0, values)
def test_stock_aeb(self):
# Test that CmbbDeny_B_Actl is never 1, it prevents the ABS module from actuating AEB requests from ACCDATA_2
for controls_allowed in (True, False):
self.safety.set_controls_allowed(controls_allowed)
for cmbb_deny in (True, False):
should_tx = not cmbb_deny
self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.INACTIVE_GAS, self.INACTIVE_ACCEL, controls_allowed, cmbb_deny)))
should_tx = controls_allowed and not cmbb_deny
self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.MAX_GAS, self.MAX_ACCEL, controls_allowed, cmbb_deny)))
def test_gas_safety_check(self):
for controls_allowed in (True, False):
self.safety.set_controls_allowed(controls_allowed)
for gas in np.concatenate((np.arange(self.MIN_GAS - 2, self.MAX_GAS + 2, 0.05), [self.INACTIVE_GAS])):
gas = round(gas, 2) # floats might not hit exact boundary conditions without rounding
should_tx = (controls_allowed and self.MIN_GAS <= gas <= self.MAX_GAS) or gas == self.INACTIVE_GAS
self.assertEqual(should_tx, self._tx(self._acc_command_msg(gas, self.INACTIVE_ACCEL, controls_allowed)))
def test_brake_safety_check(self):
for controls_allowed in (True, False):
self.safety.set_controls_allowed(controls_allowed)
for brake_actuation in (True, False):
for brake in np.arange(self.MIN_ACCEL - 2, self.MAX_ACCEL + 2, 0.05):
brake = round(brake, 2) # floats might not hit exact boundary conditions without rounding
should_tx = (controls_allowed and self.MIN_ACCEL <= brake <= self.MAX_ACCEL) or brake == self.INACTIVE_ACCEL
should_tx = should_tx and (controls_allowed or not brake_actuation)
self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.INACTIVE_GAS, brake, brake_actuation)))
class TestFordLongitudinalSafety(TestFordLongitudinalSafetyBase):
STEER_MESSAGE = MSG_LateralMotionControl
TX_MSGS = [
[MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA, 0], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0],
[MSG_LateralMotionControl, 0], [MSG_IPMA_Data, 0],
]
def setUp(self):
self.packer = CANPackerPanda("ford_lincoln_base_pt")
self.safety = libsafety_py.libsafety
# Make sure we enforce long safety even without long flag for CAN
self.safety.set_safety_hooks(Safety.SAFETY_FORD, 0)
self.safety.init_tests()
class TestFordCANFDLongitudinalSafety(TestFordLongitudinalSafetyBase):
STEER_MESSAGE = MSG_LateralMotionControl2
TX_MSGS = [
[MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA, 0], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0],
[MSG_LateralMotionControl2, 0], [MSG_IPMA_Data, 0],
]
def setUp(self):
self.packer = CANPackerPanda("ford_lincoln_base_pt")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_FORD, FordSafetyFlags.FLAG_FORD_LONG_CONTROL | FordSafetyFlags.FLAG_FORD_CANFD)
self.safety.init_tests()
if __name__ == "__main__":
unittest.main()

229
opendbc/safety/tests/test_gm.py Executable file
View File

@@ -0,0 +1,229 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.gm.values import GMSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
class Buttons:
UNPRESS = 1
RES_ACCEL = 2
DECEL_SET = 3
CANCEL = 6
class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeSafetyTest):
# pylint: disable=no-member,abstract-method
RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB)} # ASCMLKASteeringCmd, ASCMGasRegenCmd
MAX_POSSIBLE_BRAKE = 2 ** 12
MAX_BRAKE = 400
MAX_POSSIBLE_GAS = 2 ** 12
PCM_CRUISE = False # openpilot can control the PCM state if longitudinal
def _send_brake_msg(self, brake):
values = {"FrictionBrakeCmd": -brake}
return self.packer_chassis.make_can_msg_panda("EBCMFrictionBrakeCmd", self.BRAKE_BUS, values)
def _send_gas_msg(self, gas):
values = {"GasRegenCmd": gas}
return self.packer.make_can_msg_panda("ASCMGasRegenCmd", 0, values)
# override these tests from PandaCarSafetyTest, GM longitudinal uses button enable
def _pcm_status_msg(self, enable):
raise NotImplementedError
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 test_set_resume_buttons(self):
"""
SET and RESUME enter controls allowed on their falling and rising edges, respectively.
"""
for btn_prev in range(8):
for btn_cur in range(8):
with self.subTest(btn_prev=btn_prev, btn_cur=btn_cur):
self._rx(self._button_msg(btn_prev))
self.safety.set_controls_allowed(0)
for _ in range(10):
self._rx(self._button_msg(btn_cur))
should_enable = btn_cur != Buttons.DECEL_SET and btn_prev == Buttons.DECEL_SET
should_enable = should_enable or (btn_cur == Buttons.RES_ACCEL and btn_prev != Buttons.RES_ACCEL)
should_enable = should_enable and btn_cur != Buttons.CANCEL
self.assertEqual(should_enable, self.safety.get_controls_allowed())
def test_cancel_button(self):
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(Buttons.CANCEL))
self.assertFalse(self.safety.get_controls_allowed())
class TestGmSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest):
STANDSTILL_THRESHOLD = 10 * 0.0311
# Ensures ASCM is off on ASCM cars, and relay is not malfunctioning for camera-ACC cars
RELAY_MALFUNCTION_ADDRS = {0: (0x180,)} # ASCMLKASteeringCmd
BUTTONS_BUS = 0 # rx or tx
BRAKE_BUS = 0 # tx only
MAX_RATE_UP = 10
MAX_RATE_DOWN = 15
MAX_TORQUE = 300
MAX_RT_DELTA = 128
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 65
DRIVER_TORQUE_FACTOR = 4
PCM_CRUISE = True # openpilot is tied to the PCM state if not longitudinal
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestGmSafetyBase":
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def setUp(self):
self.packer = CANPackerPanda("gm_global_a_powertrain_generated")
self.packer_chassis = CANPackerPanda("gm_global_a_chassis")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_GM, 0)
self.safety.init_tests()
def _pcm_status_msg(self, enable):
if self.PCM_CRUISE:
values = {"CruiseState": enable}
return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values)
else:
raise NotImplementedError
def _speed_msg(self, speed):
values = {"%sWheelSpd" % s: speed for s in ["RL", "RR"]}
return self.packer.make_can_msg_panda("EBCMWheelSpdRear", 0, values)
def _user_brake_msg(self, brake):
# GM safety has a brake threshold of 8
values = {"BrakePedalPos": 8 if brake else 0}
return self.packer.make_can_msg_panda("ECMAcceleratorPos", 0, values)
def _user_regen_msg(self, regen):
values = {"RegenPaddle": 2 if regen else 0}
return self.packer.make_can_msg_panda("EBCMRegenPaddle", 0, values)
def _user_gas_msg(self, gas):
values = {"AcceleratorPedal2": 1 if gas else 0}
if self.PCM_CRUISE:
# Fill CruiseState with expected value if the safety mode reads cruise state from gas msg
values["CruiseState"] = self.safety.get_controls_allowed()
return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values)
def _torque_driver_msg(self, torque):
# Safety tests assume driver torque is an int, use DBC factor
values = {"LKADriverAppldTrq": torque * 0.01}
return self.packer.make_can_msg_panda("PSCMStatus", 0, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"LKASteeringCmd": torque, "LKASteeringCmdActive": steer_req}
return self.packer.make_can_msg_panda("ASCMLKASteeringCmd", 0, values)
def _button_msg(self, buttons):
values = {"ACCButtons": buttons}
return self.packer.make_can_msg_panda("ASCMSteeringButton", self.BUTTONS_BUS, values)
class TestGmAscmSafety(GmLongitudinalBase, TestGmSafetyBase):
TX_MSGS = [[0x180, 0], [0x409, 0], [0x40A, 0], [0x2CB, 0], [0x370, 0], # pt bus
[0xA1, 1], [0x306, 1], [0x308, 1], [0x310, 1], # obs bus
[0x315, 2]] # ch bus
FWD_BLACKLISTED_ADDRS: dict[int, list[int]] = {}
FWD_BUS_LOOKUP: dict[int, int] = {}
BRAKE_BUS = 2
MAX_GAS = 3072
MIN_GAS = 1404 # maximum regen
INACTIVE_GAS = 1404
def setUp(self):
self.packer = CANPackerPanda("gm_global_a_powertrain_generated")
self.packer_chassis = CANPackerPanda("gm_global_a_chassis")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_GM, 0)
self.safety.init_tests()
class TestGmCameraSafetyBase(TestGmSafetyBase):
FWD_BUS_LOOKUP = {0: 2, 2: 0}
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestGmCameraSafetyBase":
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def _user_brake_msg(self, brake):
values = {"BrakePressed": brake}
return self.packer.make_can_msg_panda("ECMEngineStatus", 0, values)
class TestGmCameraSafety(TestGmCameraSafetyBase):
TX_MSGS = [[0x180, 0], # pt bus
[0x184, 2]] # camera bus
FWD_BLACKLISTED_ADDRS = {2: [0x180], 0: [0x184]} # block LKAS message and PSCMStatus
BUTTONS_BUS = 2 # tx only
def setUp(self):
self.packer = CANPackerPanda("gm_global_a_powertrain_generated")
self.packer_chassis = CANPackerPanda("gm_global_a_chassis")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_GM, GMSafetyFlags.FLAG_GM_HW_CAM)
self.safety.init_tests()
def test_buttons(self):
# Only CANCEL button is allowed while cruise is enabled
self.safety.set_controls_allowed(0)
for btn in range(8):
self.assertFalse(self._tx(self._button_msg(btn)))
self.safety.set_controls_allowed(1)
for btn in range(8):
self.assertFalse(self._tx(self._button_msg(btn)))
for enabled in (True, False):
self._rx(self._pcm_status_msg(enabled))
self.assertEqual(enabled, self._tx(self._button_msg(Buttons.CANCEL)))
class TestGmCameraLongitudinalSafety(GmLongitudinalBase, TestGmCameraSafetyBase):
TX_MSGS = [[0x180, 0], [0x315, 0], [0x2CB, 0], [0x370, 0], # pt bus
[0x184, 2]] # camera bus
FWD_BLACKLISTED_ADDRS = {2: [0x180, 0x2CB, 0x370, 0x315], 0: [0x184]} # block LKAS, ACC messages and PSCMStatus
BUTTONS_BUS = 0 # rx only
MAX_GAS = 3400
MIN_GAS = 1514 # maximum regen
INACTIVE_GAS = 1554
def setUp(self):
self.packer = CANPackerPanda("gm_global_a_powertrain_generated")
self.packer_chassis = CANPackerPanda("gm_global_a_chassis")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_GM, GMSafetyFlags.FLAG_GM_HW_CAM | GMSafetyFlags.FLAG_GM_HW_CAM_LONG)
self.safety.init_tests()
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,575 @@
#!/usr/bin/env python3
import unittest
import numpy as np
from opendbc.car.honda.values import HondaSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda, MAX_WRONG_COUNTERS
HONDA_N_COMMON_TX_MSGS = [[0xE4, 0], [0x194, 0], [0x1FA, 0], [0x30C, 0], [0x33D, 0]]
class Btn:
NONE = 0
MAIN = 1
CANCEL = 2
SET = 3
RESUME = 4
HONDA_NIDEC = 0
HONDA_BOSCH = 1
# Honda safety has several different configurations tested here:
# * Nidec
# * normal (PCM-enable)
# * alt SCM messages (PCM-enable)
# * Bosch
# * Bosch with Longitudinal Support
# * Bosch Radarless
# * Bosch Radarless with Longitudinal Support
class HondaButtonEnableBase(common.PandaCarSafetyTest):
# pylint: disable=no-member,abstract-method
# override these inherited tests since we're using 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 test_buttons_with_main_off(self):
for btn in (Btn.SET, Btn.RESUME, Btn.CANCEL):
self.safety.set_controls_allowed(1)
self._rx(self._acc_state_msg(False))
self._rx(self._button_msg(btn, main_on=False))
self.assertFalse(self.safety.get_controls_allowed())
def test_set_resume_buttons(self):
"""
Both SET and RES should enter controls allowed on their falling edge.
"""
for main_on in (True, False):
self._rx(self._acc_state_msg(main_on))
for btn_prev in range(8):
for btn_cur in range(8):
self._rx(self._button_msg(Btn.NONE))
self.safety.set_controls_allowed(0)
for _ in range(10):
self._rx(self._button_msg(btn_prev))
self.assertFalse(self.safety.get_controls_allowed())
# should enter controls allowed on falling edge and not transitioning to cancel or main
should_enable = (main_on and
btn_cur != btn_prev and
btn_prev in (Btn.RESUME, Btn.SET) and
btn_cur not in (Btn.CANCEL, Btn.MAIN))
self._rx(self._button_msg(btn_cur, main_on=main_on))
self.assertEqual(should_enable, self.safety.get_controls_allowed(), msg=f"{main_on=} {btn_prev=} {btn_cur=}")
def test_main_cancel_buttons(self):
"""
Both MAIN and CANCEL should exit controls immediately.
"""
for btn in (Btn.MAIN, Btn.CANCEL):
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(btn, main_on=True))
self.assertFalse(self.safety.get_controls_allowed())
def test_disengage_on_main(self):
self.safety.set_controls_allowed(1)
self._rx(self._acc_state_msg(True))
self.assertTrue(self.safety.get_controls_allowed())
self._rx(self._acc_state_msg(False))
self.assertFalse(self.safety.get_controls_allowed())
def test_rx_hook(self):
# TODO: move this test to common
# checksum checks
for msg in ["btn", "gas", "speed"]:
self.safety.set_controls_allowed(1)
if msg == "btn":
to_push = self._button_msg(Btn.SET)
if msg == "gas":
to_push = self._user_gas_msg(0)
if msg == "speed":
to_push = self._speed_msg(0)
self.assertTrue(self._rx(to_push))
if msg != "btn":
to_push[0].data[4] = 0 # invalidate checksum
to_push[0].data[5] = 0
to_push[0].data[6] = 0
to_push[0].data[7] = 0
self.assertFalse(self._rx(to_push))
self.assertFalse(self.safety.get_controls_allowed())
# counter
# reset wrong_counters to zero by sending valid messages
for i in range(MAX_WRONG_COUNTERS + 1):
self.__class__.cnt_speed += 1
self.__class__.cnt_button += 1
self.__class__.cnt_powertrain_data += 1
if i < MAX_WRONG_COUNTERS:
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(Btn.SET))
self._rx(self._speed_msg(0))
self._rx(self._user_gas_msg(0))
else:
self.assertFalse(self._rx(self._button_msg(Btn.SET)))
self.assertFalse(self._rx(self._speed_msg(0)))
self.assertFalse(self._rx(self._user_gas_msg(0)))
self.assertFalse(self.safety.get_controls_allowed())
# restore counters for future tests with a couple of good messages
for _ in range(2):
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(Btn.SET, main_on=True))
self._rx(self._speed_msg(0))
self._rx(self._user_gas_msg(0))
self._rx(self._button_msg(Btn.SET, main_on=True))
self.assertTrue(self.safety.get_controls_allowed())
class HondaPcmEnableBase(common.PandaCarSafetyTest):
# pylint: disable=no-member,abstract-method
def test_buttons(self):
"""
Buttons should only cancel in this configuration,
since our state is tied to the PCM's cruise state.
"""
for controls_allowed in (True, False):
for main_on in (True, False):
# not a valid state
if controls_allowed and not main_on:
continue
for btn in (Btn.SET, Btn.RESUME, Btn.CANCEL):
self.safety.set_controls_allowed(controls_allowed)
self._rx(self._acc_state_msg(main_on))
# btn + none for falling edge
self._rx(self._button_msg(btn, main_on=main_on))
self._rx(self._button_msg(Btn.NONE, main_on=main_on))
if btn == Btn.CANCEL:
self.assertFalse(self.safety.get_controls_allowed())
else:
self.assertEqual(controls_allowed, self.safety.get_controls_allowed())
class HondaBase(common.PandaCarSafetyTest):
MAX_BRAKE = 255
PT_BUS: int | None = None # must be set when inherited
STEER_BUS: int | None = None # must be set when inherited
BUTTONS_BUS: int | None = None # must be set when inherited, tx on this bus, rx on PT_BUS
STANDSTILL_THRESHOLD = 0
RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x194)} # STEERING_CONTROL
FWD_BUS_LOOKUP = {0: 2, 2: 0}
cnt_speed = 0
cnt_button = 0
cnt_brake = 0
cnt_powertrain_data = 0
cnt_acc_state = 0
@classmethod
def setUpClass(cls):
if cls.__name__.endswith("Base"):
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def _powertrain_data_msg(self, cruise_on=None, brake_pressed=None, gas_pressed=None):
# preserve the state
if cruise_on is None:
# or'd with controls allowed since the tests use it to "enable" cruise
cruise_on = self.safety.get_cruise_engaged_prev() or self.safety.get_controls_allowed()
if brake_pressed is None:
brake_pressed = self.safety.get_brake_pressed_prev()
if gas_pressed is None:
gas_pressed = self.safety.get_gas_pressed_prev()
values = {
"ACC_STATUS": cruise_on,
"BRAKE_PRESSED": brake_pressed,
"PEDAL_GAS": gas_pressed,
"COUNTER": self.cnt_powertrain_data % 4
}
self.__class__.cnt_powertrain_data += 1
return self.packer.make_can_msg_panda("POWERTRAIN_DATA", self.PT_BUS, values)
def _pcm_status_msg(self, enable):
return self._powertrain_data_msg(cruise_on=enable)
def _speed_msg(self, speed):
values = {"XMISSION_SPEED": speed, "COUNTER": self.cnt_speed % 4}
self.__class__.cnt_speed += 1
return self.packer.make_can_msg_panda("ENGINE_DATA", self.PT_BUS, values)
def _acc_state_msg(self, main_on):
values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4}
self.__class__.cnt_acc_state += 1
return self.packer.make_can_msg_panda("SCM_FEEDBACK", self.PT_BUS, values)
def _button_msg(self, buttons, main_on=False, bus=None):
bus = self.PT_BUS if bus is None else bus
values = {"CRUISE_BUTTONS": buttons, "COUNTER": self.cnt_button % 4}
self.__class__.cnt_button += 1
return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values)
def _user_brake_msg(self, brake):
return self._powertrain_data_msg(brake_pressed=brake)
def _user_gas_msg(self, gas):
return self._powertrain_data_msg(gas_pressed=gas)
def _send_steer_msg(self, steer):
values = {"STEER_TORQUE": steer}
return self.packer.make_can_msg_panda("STEERING_CONTROL", self.STEER_BUS, values)
def _send_brake_msg(self, brake):
# must be implemented when inherited
raise NotImplementedError
def test_disengage_on_brake(self):
self.safety.set_controls_allowed(1)
self._rx(self._user_brake_msg(1))
self.assertFalse(self.safety.get_controls_allowed())
def test_steer_safety_check(self):
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._send_steer_msg(0x0000)))
self.assertFalse(self._tx(self._send_steer_msg(0x1000)))
# ********************* Honda Nidec **********************
class TestHondaNidecSafetyBase(HondaBase):
TX_MSGS = HONDA_N_COMMON_TX_MSGS
FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x194, 0x33D, 0x30C]}
PT_BUS = 0
STEER_BUS = 0
BUTTONS_BUS = 0
MAX_GAS = 198
def setUp(self):
self.packer = CANPackerPanda("honda_civic_touring_2016_can_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_NIDEC, 0)
self.safety.init_tests()
def _send_brake_msg(self, brake, aeb_req=0, bus=0):
values = {"COMPUTER_BRAKE": brake, "AEB_REQ_1": aeb_req}
return self.packer.make_can_msg_panda("BRAKE_COMMAND", bus, values)
def _rx_brake_msg(self, brake, aeb_req=0):
return self._send_brake_msg(brake, aeb_req, bus=2)
def _send_acc_hud_msg(self, pcm_gas, pcm_speed):
# Used to control ACC on Nidec without pedal
values = {"PCM_GAS": pcm_gas, "PCM_SPEED": pcm_speed}
return self.packer.make_can_msg_panda("ACC_HUD", 0, values)
def test_acc_hud_safety_check(self):
for controls_allowed in [True, False]:
self.safety.set_controls_allowed(controls_allowed)
for pcm_gas in range(255):
for pcm_speed in range(100):
send = (controls_allowed and pcm_gas <= self.MAX_GAS) or (pcm_gas == 0 and pcm_speed == 0)
self.assertEqual(send, self._tx(self._send_acc_hud_msg(pcm_gas, pcm_speed)))
def test_fwd_hook(self):
# normal operation, not forwarding AEB
self.FWD_BLACKLISTED_ADDRS[2].append(0x1FA)
self.safety.set_honda_fwd_brake(False)
super().test_fwd_hook()
# forwarding AEB brake signal
self.FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x194, 0x33D, 0x30C]}
self.safety.set_honda_fwd_brake(True)
super().test_fwd_hook()
def test_honda_fwd_brake_latching(self):
# Shouldn't fwd stock Honda requesting brake without AEB
self.assertTrue(self._rx(self._rx_brake_msg(self.MAX_BRAKE, aeb_req=0)))
self.assertFalse(self.safety.get_honda_fwd_brake())
# Now allow controls and request some brake
openpilot_brake = round(self.MAX_BRAKE / 2.0)
self.safety.set_controls_allowed(True)
self.assertTrue(self._tx(self._send_brake_msg(openpilot_brake)))
# Still shouldn't fwd stock Honda brake until it's more than openpilot's
for stock_honda_brake in range(self.MAX_BRAKE + 1):
self.assertTrue(self._rx(self._rx_brake_msg(stock_honda_brake, aeb_req=1)))
should_fwd_brake = stock_honda_brake >= openpilot_brake
self.assertEqual(should_fwd_brake, self.safety.get_honda_fwd_brake())
# Shouldn't stop fwding until AEB event is over
for stock_honda_brake in range(self.MAX_BRAKE + 1)[::-1]:
self.assertTrue(self._rx(self._rx_brake_msg(stock_honda_brake, aeb_req=1)))
self.assertTrue(self.safety.get_honda_fwd_brake())
self.assertTrue(self._rx(self._rx_brake_msg(0, aeb_req=0)))
self.assertFalse(self.safety.get_honda_fwd_brake())
def test_brake_safety_check(self):
for fwd_brake in [False, True]:
self.safety.set_honda_fwd_brake(fwd_brake)
for brake in np.arange(0, self.MAX_BRAKE + 10, 1):
for controls_allowed in [True, False]:
self.safety.set_controls_allowed(controls_allowed)
if fwd_brake:
send = False # block openpilot brake msg when fwd'ing stock msg
elif controls_allowed:
send = self.MAX_BRAKE >= brake >= 0
else:
send = brake == 0
self.assertEqual(send, self._tx(self._send_brake_msg(brake)))
class TestHondaNidecPcmSafety(HondaPcmEnableBase, TestHondaNidecSafetyBase):
"""
Covers the Honda Nidec safety mode
"""
# Nidec doesn't disengage on falling edge of cruise. See comment in safety_honda.h
def test_disable_control_allowed_from_cruise(self):
pass
class TestHondaNidecPcmAltSafety(TestHondaNidecPcmSafety):
"""
Covers the Honda Nidec safety mode with alt SCM messages
"""
def setUp(self):
self.packer = CANPackerPanda("acura_ilx_2016_can_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_NIDEC, HondaSafetyFlags.FLAG_HONDA_NIDEC_ALT)
self.safety.init_tests()
def _acc_state_msg(self, main_on):
values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4}
self.__class__.cnt_acc_state += 1
return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values)
def _button_msg(self, buttons, main_on=False, bus=None):
bus = self.PT_BUS if bus is None else bus
values = {"CRUISE_BUTTONS": buttons, "MAIN_ON": main_on, "COUNTER": self.cnt_button % 4}
self.__class__.cnt_button += 1
return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values)
# ********************* Honda Bosch **********************
class TestHondaBoschSafetyBase(HondaBase):
PT_BUS = 1
STEER_BUS = 0
BUTTONS_BUS = 1
TX_MSGS = [[0xE4, 0], [0xE5, 0], [0x296, 1], [0x33D, 0], [0x33DA, 0], [0x33DB, 0]]
FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]}
def setUp(self):
self.packer = CANPackerPanda("honda_accord_2018_can_generated")
self.safety = libsafety_py.libsafety
def _alt_brake_msg(self, brake):
values = {"BRAKE_PRESSED": brake, "COUNTER": self.cnt_brake % 4}
self.__class__.cnt_brake += 1
return self.packer.make_can_msg_panda("BRAKE_MODULE", self.PT_BUS, values)
def _send_brake_msg(self, brake):
pass
def test_alt_disengage_on_brake(self):
self.safety.set_honda_alt_brake_msg(1)
self.safety.set_controls_allowed(1)
self._rx(self._alt_brake_msg(1))
self.assertFalse(self.safety.get_controls_allowed())
self.safety.set_honda_alt_brake_msg(0)
self.safety.set_controls_allowed(1)
self._rx(self._alt_brake_msg(1))
self.assertTrue(self.safety.get_controls_allowed())
def test_spam_cancel_safety_check(self):
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._button_msg(Btn.CANCEL, bus=self.BUTTONS_BUS)))
self.assertFalse(self._tx(self._button_msg(Btn.RESUME, bus=self.BUTTONS_BUS)))
self.assertFalse(self._tx(self._button_msg(Btn.SET, bus=self.BUTTONS_BUS)))
# do not block resume if we are engaged already
self.safety.set_controls_allowed(1)
self.assertTrue(self._tx(self._button_msg(Btn.RESUME, bus=self.BUTTONS_BUS)))
class TestHondaBoschAltBrakeSafetyBase(TestHondaBoschSafetyBase):
"""
Base Bosch safety test class with an alternate brake message
"""
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, HondaSafetyFlags.FLAG_HONDA_ALT_BRAKE)
self.safety.init_tests()
def _user_brake_msg(self, brake):
return self._alt_brake_msg(brake)
def test_alt_brake_rx_hook(self):
self.safety.set_honda_alt_brake_msg(1)
self.safety.set_controls_allowed(1)
to_push = self._alt_brake_msg(0)
self.assertTrue(self._rx(to_push))
to_push[0].data[2] = to_push[0].data[2] & 0xF0 # invalidate checksum
self.assertFalse(self._rx(to_push))
self.assertFalse(self.safety.get_controls_allowed())
class TestHondaBoschSafety(HondaPcmEnableBase, TestHondaBoschSafetyBase):
"""
Covers the Honda Bosch safety mode with stock longitudinal
"""
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, 0)
self.safety.init_tests()
class TestHondaBoschAltBrakeSafety(HondaPcmEnableBase, TestHondaBoschAltBrakeSafetyBase):
"""
Covers the Honda Bosch safety mode with stock longitudinal and an alternate brake message
"""
class TestHondaBoschLongSafety(HondaButtonEnableBase, TestHondaBoschSafetyBase):
"""
Covers the Honda Bosch safety mode with longitudinal control
"""
NO_GAS = -30000
MAX_GAS = 2000
MAX_ACCEL = 2.0 # accel is used for brakes, but openpilot can set positive values
MIN_ACCEL = -3.5
STEER_BUS = 1
TX_MSGS = [[0xE4, 1], [0x1DF, 1], [0x1EF, 1], [0x1FA, 1], [0x30C, 1], [0x33D, 1], [0x33DA, 1], [0x33DB, 1], [0x39F, 1], [0x18DAB0F1, 1]]
FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]}
# 0x1DF is to test that radar is disabled
RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x194), 1: (0x1DF,)} # STEERING_CONTROL, ACC_CONTROL
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, HondaSafetyFlags.FLAG_HONDA_BOSCH_LONG)
self.safety.init_tests()
def _send_gas_brake_msg(self, gas, accel):
values = {
"GAS_COMMAND": gas,
"ACCEL_COMMAND": accel,
"BRAKE_REQUEST": accel < 0,
}
return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values)
# Longitudinal doesn't need to send buttons
def test_spam_cancel_safety_check(self):
pass
def test_diagnostics(self):
tester_present = libsafety_py.make_CANPacket(0x18DAB0F1, self.PT_BUS, b"\x02\x3E\x80\x00\x00\x00\x00\x00")
self.assertTrue(self._tx(tester_present))
not_tester_present = libsafety_py.make_CANPacket(0x18DAB0F1, self.PT_BUS, b"\x03\xAA\xAA\x00\x00\x00\x00\x00")
self.assertFalse(self._tx(not_tester_present))
def test_gas_safety_check(self):
for controls_allowed in [True, False]:
for gas in np.arange(self.NO_GAS, self.MAX_GAS + 2000, 100):
accel = 0 if gas < 0 else gas / 1000
self.safety.set_controls_allowed(controls_allowed)
send = (controls_allowed and 0 <= gas <= self.MAX_GAS) or gas == self.NO_GAS
self.assertEqual(send, self._tx(self._send_gas_brake_msg(gas, accel)), (controls_allowed, gas, accel))
def test_brake_safety_check(self):
for controls_allowed in [True, False]:
for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.01):
accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding
self.safety.set_controls_allowed(controls_allowed)
send = self.MIN_ACCEL <= accel <= self.MAX_ACCEL if controls_allowed else accel == 0
self.assertEqual(send, self._tx(self._send_gas_brake_msg(self.NO_GAS, accel)), (controls_allowed, accel))
class TestHondaBoschRadarlessSafetyBase(TestHondaBoschSafetyBase):
"""Base class for radarless Honda Bosch"""
PT_BUS = 0
STEER_BUS = 0
BUTTONS_BUS = 2 # camera controls ACC, need to send buttons on bus 2
TX_MSGS = [[0xE4, 0], [0x296, 2], [0x33D, 0]]
FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]}
def setUp(self):
self.packer = CANPackerPanda("honda_civic_ex_2022_can_generated")
self.safety = libsafety_py.libsafety
class TestHondaBoschRadarlessSafety(HondaPcmEnableBase, TestHondaBoschRadarlessSafetyBase):
"""
Covers the Honda Bosch Radarless safety mode with stock longitudinal
"""
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, HondaSafetyFlags.FLAG_HONDA_RADARLESS)
self.safety.init_tests()
class TestHondaBoschRadarlessAltBrakeSafety(HondaPcmEnableBase, TestHondaBoschRadarlessSafetyBase, TestHondaBoschAltBrakeSafetyBase):
"""
Covers the Honda Bosch Radarless safety mode with stock longitudinal and an alternate brake message
"""
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, HondaSafetyFlags.FLAG_HONDA_RADARLESS | HondaSafetyFlags.FLAG_HONDA_ALT_BRAKE)
self.safety.init_tests()
class TestHondaBoschRadarlessLongSafety(common.LongitudinalAccelSafetyTest, HondaButtonEnableBase,
TestHondaBoschRadarlessSafetyBase):
"""
Covers the Honda Bosch Radarless safety mode with longitudinal control
"""
TX_MSGS = [[0xE4, 0], [0x33D, 0], [0x1C8, 0], [0x30C, 0]]
FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB, 0x1C8, 0x30C]}
def setUp(self):
super().setUp()
self.safety.set_safety_hooks(Safety.SAFETY_HONDA_BOSCH, HondaSafetyFlags.FLAG_HONDA_RADARLESS | HondaSafetyFlags.FLAG_HONDA_BOSCH_LONG)
self.safety.init_tests()
def _accel_msg(self, accel):
values = {
"ACCEL_COMMAND": accel,
}
return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values)
# Longitudinal doesn't need to send buttons
def test_spam_cancel_safety_check(self):
pass
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,218 @@
#!/usr/bin/env python3
import random
import unittest
from opendbc.car.hyundai.values import HyundaiSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
from opendbc.safety.tests.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase
# 4 bit checkusm used in some hyundai messages
# lives outside the can packer because we never send this msg
def checksum(msg):
addr, dat, bus = msg
chksum = 0
if addr == 0x386:
for i, b in enumerate(dat):
for j in range(8):
# exclude checksum and counter bits
if (i != 1 or j < 6) and (i != 3 or j < 6) and (i != 5 or j < 6) and (i != 7 or j < 6):
bit = (b >> j) & 1
else:
bit = 0
chksum += bit
chksum = (chksum ^ 9) & 0xF
ret = bytearray(dat)
ret[5] |= (chksum & 0x3) << 6
ret[7] |= (chksum & 0xc) << 4
else:
for i, b in enumerate(dat):
if addr in [0x260, 0x421] and i == 7:
b &= 0x0F if addr == 0x421 else 0xF0
elif addr == 0x394 and i == 6:
b &= 0xF0
elif addr == 0x394 and i == 7:
continue
chksum += sum(divmod(b, 16))
chksum = (16 - chksum) % 16
ret = bytearray(dat)
ret[6 if addr == 0x394 else 7] |= chksum << (4 if addr == 0x421 else 0)
return addr, ret, bus
class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest):
TX_MSGS = [[0x340, 0], [0x4F1, 0], [0x485, 0]]
STANDSTILL_THRESHOLD = 12 # 0.375 kph
RELAY_MALFUNCTION_ADDRS = {0: (0x340,)} # LKAS11
FWD_BLACKLISTED_ADDRS = {2: [0x340, 0x485]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
MAX_RATE_UP = 3
MAX_RATE_DOWN = 7
MAX_TORQUE = 384
MAX_RT_DELTA = 112
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 50
DRIVER_TORQUE_FACTOR = 2
# Safety around steering req bit
MIN_VALID_STEERING_FRAMES = 89
MAX_INVALID_STEERING_FRAMES = 2
MIN_VALID_STEERING_RT_INTERVAL = 810000 # a ~10% buffer, can send steer up to 110Hz
cnt_gas = 0
cnt_speed = 0
cnt_brake = 0
cnt_cruise = 0
cnt_button = 0
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI, 0)
self.safety.init_tests()
def _button_msg(self, buttons, main_button=0, bus=0):
values = {"CF_Clu_CruiseSwState": buttons, "CF_Clu_CruiseSwMain": main_button, "CF_Clu_AliveCnt1": self.cnt_button}
self.__class__.cnt_button += 1
return self.packer.make_can_msg_panda("CLU11", bus, values)
def _user_gas_msg(self, gas):
values = {"CF_Ems_AclAct": gas, "AliveCounter": self.cnt_gas % 4}
self.__class__.cnt_gas += 1
return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum)
def _user_brake_msg(self, brake):
values = {"DriverOverride": 2 if brake else random.choice((0, 1, 3)),
"AliveCounterTCS": self.cnt_brake % 8}
self.__class__.cnt_brake += 1
return self.packer.make_can_msg_panda("TCS13", 0, values, fix_checksum=checksum)
def _speed_msg(self, speed):
# panda safety doesn't scale, so undo the scaling
values = {"WHL_SPD_%s" % s: speed * 0.03125 for s in ["FL", "FR", "RL", "RR"]}
values["WHL_SPD_AliveCounter_LSB"] = (self.cnt_speed % 16) & 0x3
values["WHL_SPD_AliveCounter_MSB"] = (self.cnt_speed % 16) >> 2
self.__class__.cnt_speed += 1
return self.packer.make_can_msg_panda("WHL_SPD11", 0, values, fix_checksum=checksum)
def _pcm_status_msg(self, enable):
values = {"ACCMode": enable, "CR_VSM_Alive": self.cnt_cruise % 16}
self.__class__.cnt_cruise += 1
return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values, fix_checksum=checksum)
def _torque_driver_msg(self, torque):
values = {"CR_Mdps_StrColTq": torque}
return self.packer.make_can_msg_panda("MDPS12", 0, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"CR_Lkas_StrToqReq": torque, "CF_Lkas_ActToi": steer_req}
return self.packer.make_can_msg_panda("LKAS11", 0, values)
class TestHyundaiSafetyAltLimits(TestHyundaiSafety):
MAX_RATE_UP = 2
MAX_RATE_DOWN = 3
MAX_TORQUE = 270
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI, HyundaiSafetyFlags.FLAG_HYUNDAI_ALT_LIMITS)
self.safety.init_tests()
class TestHyundaiSafetyCameraSCC(TestHyundaiSafety):
BUTTONS_TX_BUS = 2 # tx on 2, rx on 0
SCC_BUS = 2 # rx on 2
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI, HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC)
self.safety.init_tests()
class TestHyundaiLegacySafety(TestHyundaiSafety):
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_LEGACY, 0)
self.safety.init_tests()
class TestHyundaiLegacySafetyEV(TestHyundaiSafety):
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_LEGACY, 1)
self.safety.init_tests()
def _user_gas_msg(self, gas):
values = {"Accel_Pedal_Pos": gas}
return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum)
class TestHyundaiLegacySafetyHEV(TestHyundaiSafety):
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_LEGACY, 2)
self.safety.init_tests()
def _user_gas_msg(self, gas):
values = {"CR_Vcu_AccPedDep_Pos": gas}
return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum)
class TestHyundaiLongitudinalSafety(HyundaiLongitudinalBase, TestHyundaiSafety):
TX_MSGS = [[0x340, 0], [0x4F1, 0], [0x485, 0], [0x420, 0], [0x421, 0], [0x50A, 0], [0x389, 0], [0x4A2, 0], [0x38D, 0], [0x483, 0], [0x7D0, 0]]
RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x421)} # LKAS11, SCC12
DISABLED_ECU_UDS_MSG = (0x7D0, 0)
DISABLED_ECU_ACTUATION_MSG = (0x421, 0)
def setUp(self):
self.packer = CANPackerPanda("hyundai_kia_generic")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI, HyundaiSafetyFlags.FLAG_HYUNDAI_LONG)
self.safety.init_tests()
def _accel_msg(self, accel, aeb_req=False, aeb_decel=0):
values = {
"aReqRaw": accel,
"aReqValue": accel,
"AEB_CmdAct": int(aeb_req),
"CR_VSM_DecCmd": aeb_decel,
}
return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values)
def _fca11_msg(self, idx=0, vsm_aeb_req=False, fca_aeb_req=False, aeb_decel=0):
values = {
"CR_FCA_Alive": idx % 0xF,
"FCA_Status": 2,
"CR_VSM_DecCmd": aeb_decel,
"CF_VSM_DecCmdAct": int(vsm_aeb_req),
"FCA_CmdAct": int(fca_aeb_req),
}
return self.packer.make_can_msg_panda("FCA11", 0, values)
def test_no_aeb_fca11(self):
self.assertTrue(self._tx(self._fca11_msg()))
self.assertFalse(self._tx(self._fca11_msg(vsm_aeb_req=True)))
self.assertFalse(self._tx(self._fca11_msg(fca_aeb_req=True)))
self.assertFalse(self._tx(self._fca11_msg(aeb_decel=1.0)))
def test_no_aeb_scc12(self):
self.assertTrue(self._tx(self._accel_msg(0)))
self.assertFalse(self._tx(self._accel_msg(0, aeb_req=True)))
self.assertFalse(self._tx(self._accel_msg(0, aeb_decel=1.0)))
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,283 @@
#!/usr/bin/env python3
from parameterized import parameterized_class
import unittest
from opendbc.car.hyundai.values import HyundaiSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
from opendbc.safety.tests.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase
class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest):
TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]]
STANDSTILL_THRESHOLD = 12 # 0.375 kph
FWD_BLACKLISTED_ADDRS = {2: [0x50, 0x2a4]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
MAX_RATE_UP = 2
MAX_RATE_DOWN = 3
MAX_TORQUE = 270
MAX_RT_DELTA = 112
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 250
DRIVER_TORQUE_FACTOR = 2
# Safety around steering req bit
MIN_VALID_STEERING_FRAMES = 89
MAX_INVALID_STEERING_FRAMES = 2
MIN_VALID_STEERING_RT_INTERVAL = 810000 # a ~10% buffer, can send steer up to 110Hz
PT_BUS = 0
SCC_BUS = 2
STEER_BUS = 0
STEER_MSG = ""
GAS_MSG = ("", "")
BUTTONS_TX_BUS = 1
@classmethod
def setUpClass(cls):
super().setUpClass()
if cls.__name__ == "TestHyundaiCanfdBase":
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def _torque_driver_msg(self, torque):
values = {"STEERING_COL_TORQUE": torque}
return self.packer.make_can_msg_panda("MDPS", self.PT_BUS, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"TORQUE_REQUEST": torque, "STEER_REQ": steer_req}
return self.packer.make_can_msg_panda(self.STEER_MSG, self.STEER_BUS, values)
def _speed_msg(self, speed):
values = {f"WHEEL_SPEED_{i}": speed * 0.03125 for i in range(1, 5)}
return self.packer.make_can_msg_panda("WHEEL_SPEEDS", self.PT_BUS, values)
def _user_brake_msg(self, brake):
values = {"DriverBraking": brake}
return self.packer.make_can_msg_panda("TCS", self.PT_BUS, values)
def _user_gas_msg(self, gas):
values = {self.GAS_MSG[1]: gas}
return self.packer.make_can_msg_panda(self.GAS_MSG[0], self.PT_BUS, values)
def _pcm_status_msg(self, enable):
values = {"ACCMode": 1 if enable else 0}
return self.packer.make_can_msg_panda("SCC_CONTROL", self.SCC_BUS, values)
def _button_msg(self, buttons, main_button=0, bus=None):
if bus is None:
bus = self.PT_BUS
values = {
"CRUISE_BUTTONS": buttons,
"ADAPTIVE_CRUISE_MAIN_BTN": main_button,
}
return self.packer.make_can_msg_panda("CRUISE_BUTTONS", bus, values)
class TestHyundaiCanfdHDA1Base(TestHyundaiCanfdBase):
TX_MSGS = [[0x12A, 0], [0x1A0, 1], [0x1CF, 0], [0x1E0, 0]]
RELAY_MALFUNCTION_ADDRS = {0: (0x12A,)} # LFA
FWD_BLACKLISTED_ADDRS = {2: [0x12A, 0x1E0]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
STEER_MSG = "LFA"
BUTTONS_TX_BUS = 2
SAFETY_PARAM: int
@classmethod
def setUpClass(cls):
super().setUpClass()
if cls.__name__ in ("TestHyundaiCanfdHDA1", "TestHyundaiCanfdHDA1AltButtons"):
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, self.SAFETY_PARAM)
self.safety.init_tests()
@parameterized_class([
# Radar SCC, test with long flag to ensure flag is not respected until it is supported
{"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
{"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
{"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_HYBRID_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
# Camera SCC
{"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
{"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
{"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_HYBRID_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
])
class TestHyundaiCanfdHDA1(TestHyundaiCanfdHDA1Base):
pass
@parameterized_class([
# Radar SCC, test with long flag to ensure flag is not respected until it is supported
{"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
{"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
{"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_HYBRID_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
# Camera SCC
{"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
{"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
{"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_HYBRID_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC},
])
class TestHyundaiCanfdHDA1AltButtons(TestHyundaiCanfdHDA1Base):
SAFETY_PARAM: int
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, HyundaiSafetyFlags.FLAG_HYUNDAI_CANFD_ALT_BUTTONS | self.SAFETY_PARAM)
self.safety.init_tests()
def _button_msg(self, buttons, main_button=0, bus=1):
values = {
"CRUISE_BUTTONS": buttons,
"ADAPTIVE_CRUISE_MAIN_BTN": main_button,
}
return self.packer.make_can_msg_panda("CRUISE_BUTTONS_ALT", self.PT_BUS, values)
def test_button_sends(self):
"""
No button send allowed with alt buttons.
"""
for enabled in (True, False):
for btn in range(8):
self.safety.set_controls_allowed(enabled)
self.assertFalse(self._tx(self._button_msg(btn)))
class TestHyundaiCanfdHDA2EV(TestHyundaiCanfdBase):
TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]]
RELAY_MALFUNCTION_ADDRS = {0: (0x50,)} # LKAS
FWD_BLACKLISTED_ADDRS = {2: [0x50, 0x2a4]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
PT_BUS = 1
SCC_BUS = 1
STEER_MSG = "LKAS"
GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL")
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, HyundaiSafetyFlags.FLAG_HYUNDAI_CANFD_HDA2 | HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS)
self.safety.init_tests()
# TODO: Handle ICE and HEV configurations once we see cars that use the new messages
class TestHyundaiCanfdHDA2EVAltSteering(TestHyundaiCanfdBase):
TX_MSGS = [[0x110, 0], [0x1CF, 1], [0x362, 0]]
RELAY_MALFUNCTION_ADDRS = {0: (0x110,)} # LKAS_ALT
FWD_BLACKLISTED_ADDRS = {2: [0x110, 0x362]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
PT_BUS = 1
SCC_BUS = 1
STEER_MSG = "LKAS_ALT"
GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL")
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, HyundaiSafetyFlags.FLAG_HYUNDAI_CANFD_HDA2 | HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS |
HyundaiSafetyFlags.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING)
self.safety.init_tests()
class TestHyundaiCanfdHDA2LongEV(HyundaiLongitudinalBase, TestHyundaiCanfdHDA2EV):
TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0], [0x51, 0], [0x730, 1], [0x12a, 1], [0x160, 1],
[0x1e0, 1], [0x1a0, 1], [0x1ea, 1], [0x200, 1], [0x345, 1], [0x1da, 1]]
RELAY_MALFUNCTION_ADDRS = {0: (0x50,), 1: (0x1a0,)} # LKAS, SCC_CONTROL
DISABLED_ECU_UDS_MSG = (0x730, 1)
DISABLED_ECU_ACTUATION_MSG = (0x1a0, 1)
STEER_MSG = "LFA"
GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL")
STEER_BUS = 1
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, HyundaiSafetyFlags.FLAG_HYUNDAI_CANFD_HDA2 |
HyundaiSafetyFlags.FLAG_HYUNDAI_LONG | HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS)
self.safety.init_tests()
def _accel_msg(self, accel, aeb_req=False, aeb_decel=0):
values = {
"aReqRaw": accel,
"aReqValue": accel,
}
return self.packer.make_can_msg_panda("SCC_CONTROL", 1, values)
# Tests HDA1 longitudinal for ICE, hybrid, EV
@parameterized_class([
# Camera SCC is the only supported configuration for HDA1 longitudinal, TODO: allow radar SCC
{"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_LONG},
{"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_LONG | HyundaiSafetyFlags.FLAG_HYUNDAI_EV_GAS},
{"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SAFETY_PARAM": HyundaiSafetyFlags.FLAG_HYUNDAI_LONG | HyundaiSafetyFlags.FLAG_HYUNDAI_HYBRID_GAS},
])
class TestHyundaiCanfdHDA1Long(HyundaiLongitudinalBase, TestHyundaiCanfdHDA1Base):
FWD_BLACKLISTED_ADDRS = {2: [0x12a, 0x1e0, 0x1a0]}
RELAY_MALFUNCTION_ADDRS = {0: (0x12A, 0x1a0)} # LFA, SCC_CONTROL
DISABLED_ECU_UDS_MSG = (0x730, 1)
DISABLED_ECU_ACTUATION_MSG = (0x1a0, 0)
STEER_MSG = "LFA"
STEER_BUS = 0
SCC_BUS = 2
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestHyundaiCanfdHDA1Long":
cls.safety = None
raise unittest.SkipTest
def setUp(self):
self.packer = CANPackerPanda("hyundai_canfd")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_HYUNDAI_CANFD, HyundaiSafetyFlags.FLAG_HYUNDAI_CAMERA_SCC | self.SAFETY_PARAM)
self.safety.init_tests()
def _accel_msg(self, accel, aeb_req=False, aeb_decel=0):
values = {
"aReqRaw": accel,
"aReqValue": accel,
}
return self.packer.make_can_msg_panda("SCC_CONTROL", 0, values)
# no knockout
def test_tester_present_allowed(self):
pass
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,86 @@
#!/usr/bin/env python3
import unittest
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest):
TX_MSGS = [[0x243, 0], [0x09d, 0], [0x440, 0]]
STANDSTILL_THRESHOLD = .1
RELAY_MALFUNCTION_ADDRS = {0: (0x243,)}
FWD_BLACKLISTED_ADDRS = {2: [0x243, 0x440]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
MAX_RATE_UP = 10
MAX_RATE_DOWN = 25
MAX_TORQUE = 800
MAX_RT_DELTA = 300
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 15
DRIVER_TORQUE_FACTOR = 1
# Mazda actually does not set any bit when requesting torque
NO_STEER_REQ_BIT = True
def setUp(self):
self.packer = CANPackerPanda("mazda_2017")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_MAZDA, 0)
self.safety.init_tests()
def _torque_meas_msg(self, torque):
values = {"STEER_TORQUE_MOTOR": torque}
return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values)
def _torque_driver_msg(self, torque):
values = {"STEER_TORQUE_SENSOR": torque}
return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"LKAS_REQUEST": torque}
return self.packer.make_can_msg_panda("CAM_LKAS", 0, values)
def _speed_msg(self, speed):
values = {"SPEED": speed}
return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values)
def _user_brake_msg(self, brake):
values = {"BRAKE_ON": brake}
return self.packer.make_can_msg_panda("PEDALS", 0, values)
def _user_gas_msg(self, gas):
values = {"PEDAL_GAS": gas}
return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values)
def _pcm_status_msg(self, enable):
values = {"CRZ_ACTIVE": enable}
return self.packer.make_can_msg_panda("CRZ_CTRL", 0, values)
def _button_msg(self, resume=False, cancel=False):
values = {
"CAN_OFF": cancel,
"CAN_OFF_INV": (cancel + 1) % 2,
"RES": resume,
"RES_INV": (resume + 1) % 2,
}
return self.packer.make_can_msg_panda("CRZ_BTNS", 0, values)
def test_buttons(self):
# only cancel allows while controls not allowed
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._button_msg(cancel=True)))
self.assertFalse(self._tx(self._button_msg(resume=True)))
# do not block resume if we are engaged already
self.safety.set_controls_allowed(1)
self.assertTrue(self._tx(self._button_msg(cancel=True)))
self.assertTrue(self._tx(self._button_msg(resume=True)))
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,119 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.nissan.values import NissanSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
class TestNissanSafety(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest):
TX_MSGS = [[0x169, 0], [0x2b1, 0], [0x4cc, 0], [0x20b, 2], [0x280, 2]]
STANDSTILL_THRESHOLD = 0
GAS_PRESSED_THRESHOLD = 3
RELAY_MALFUNCTION_ADDRS = {0: (0x169,)}
FWD_BLACKLISTED_ADDRS = {0: [0x280], 2: [0x169, 0x2b1, 0x4cc]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
EPS_BUS = 0
CRUISE_BUS = 2
# Angle control limits
DEG_TO_CAN = 100
ANGLE_RATE_BP = [0., 5., 15.]
ANGLE_RATE_UP = [5., .8, .15] # windup limit
ANGLE_RATE_DOWN = [5., 3.5, .4] # unwind limit
def setUp(self):
self.packer = CANPackerPanda("nissan_x_trail_2017_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_NISSAN, 0)
self.safety.init_tests()
def _angle_cmd_msg(self, angle: float, enabled: bool):
values = {"DESIRED_ANGLE": angle, "LKA_ACTIVE": 1 if enabled else 0}
return self.packer.make_can_msg_panda("LKAS", 0, values)
def _angle_meas_msg(self, angle: float):
values = {"STEER_ANGLE": angle}
return self.packer.make_can_msg_panda("STEER_ANGLE_SENSOR", self.EPS_BUS, values)
def _pcm_status_msg(self, enable):
values = {"CRUISE_ENABLED": enable}
return self.packer.make_can_msg_panda("CRUISE_STATE", self.CRUISE_BUS, values)
def _speed_msg(self, speed):
values = {"WHEEL_SPEED_%s" % s: speed * 3.6 for s in ["RR", "RL"]}
return self.packer.make_can_msg_panda("WHEEL_SPEEDS_REAR", self.EPS_BUS, values)
def _user_brake_msg(self, brake):
values = {"USER_BRAKE_PRESSED": brake}
return self.packer.make_can_msg_panda("DOORS_LIGHTS", self.EPS_BUS, values)
def _user_gas_msg(self, gas):
values = {"GAS_PEDAL": gas}
return self.packer.make_can_msg_panda("GAS_PEDAL", self.EPS_BUS, values)
def _acc_button_cmd(self, cancel=0, propilot=0, flw_dist=0, _set=0, res=0):
no_button = not any([cancel, propilot, flw_dist, _set, res])
values = {"CANCEL_BUTTON": cancel, "PROPILOT_BUTTON": propilot,
"FOLLOW_DISTANCE_BUTTON": flw_dist, "SET_BUTTON": _set,
"RES_BUTTON": res, "NO_BUTTON_PRESSED": no_button}
return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 2, values)
def test_acc_buttons(self):
btns = [
("cancel", True),
("propilot", False),
("flw_dist", False),
("_set", False),
("res", False),
(None, False),
]
for controls_allowed in (True, False):
for btn, should_tx in btns:
self.safety.set_controls_allowed(controls_allowed)
args = {} if btn is None else {btn: 1}
tx = self._tx(self._acc_button_cmd(**args))
self.assertEqual(tx, should_tx)
class TestNissanSafetyAltEpsBus(TestNissanSafety):
"""Altima uses different buses"""
EPS_BUS = 1
CRUISE_BUS = 1
def setUp(self):
self.packer = CANPackerPanda("nissan_x_trail_2017_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_NISSAN, NissanSafetyFlags.FLAG_NISSAN_ALT_EPS_BUS)
self.safety.init_tests()
class TestNissanLeafSafety(TestNissanSafety):
def setUp(self):
self.packer = CANPackerPanda("nissan_leaf_2018_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_NISSAN, 0)
self.safety.init_tests()
def _user_brake_msg(self, brake):
values = {"USER_BRAKE_PRESSED": brake}
return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values)
def _user_gas_msg(self, gas):
values = {"GAS_PEDAL": gas}
return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values)
# TODO: leaf should use its own safety param
def test_acc_buttons(self):
pass
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,230 @@
#!/usr/bin/env python3
import enum
import unittest
from opendbc.car.subaru.values import SubaruSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
from functools import partial
class SubaruMsg(enum.IntEnum):
Brake_Status = 0x13c
CruiseControl = 0x240
Throttle = 0x40
Steering_Torque = 0x119
Wheel_Speeds = 0x13a
ES_LKAS = 0x122
ES_LKAS_ANGLE = 0x124
ES_Brake = 0x220
ES_Distance = 0x221
ES_Status = 0x222
ES_DashStatus = 0x321
ES_LKAS_State = 0x322
ES_Infotainment = 0x323
ES_UDS_Request = 0x787
ES_HighBeamAssist = 0x121
ES_STATIC_1 = 0x22a
ES_STATIC_2 = 0x325
SUBARU_MAIN_BUS = 0
SUBARU_ALT_BUS = 1
SUBARU_CAM_BUS = 2
def lkas_tx_msgs(alt_bus, lkas_msg=SubaruMsg.ES_LKAS):
return [[lkas_msg, SUBARU_MAIN_BUS],
[SubaruMsg.ES_Distance, alt_bus],
[SubaruMsg.ES_DashStatus, SUBARU_MAIN_BUS],
[SubaruMsg.ES_LKAS_State, SUBARU_MAIN_BUS],
[SubaruMsg.ES_Infotainment, SUBARU_MAIN_BUS]]
def long_tx_msgs(alt_bus):
return [[SubaruMsg.ES_Brake, alt_bus],
[SubaruMsg.ES_Status, alt_bus]]
def gen2_long_additional_tx_msgs():
return [[SubaruMsg.ES_UDS_Request, SUBARU_CAM_BUS],
[SubaruMsg.ES_HighBeamAssist, SUBARU_MAIN_BUS],
[SubaruMsg.ES_STATIC_1, SUBARU_MAIN_BUS],
[SubaruMsg.ES_STATIC_2, SUBARU_MAIN_BUS]]
def fwd_blacklisted_addr(lkas_msg=SubaruMsg.ES_LKAS):
return {SUBARU_CAM_BUS: [lkas_msg, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment]}
class TestSubaruSafetyBase(common.PandaCarSafetyTest):
FLAGS = 0
STANDSTILL_THRESHOLD = 0 # kph
RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS,)}
FWD_BUS_LOOKUP = {SUBARU_MAIN_BUS: SUBARU_CAM_BUS, SUBARU_CAM_BUS: SUBARU_MAIN_BUS}
FWD_BLACKLISTED_ADDRS = fwd_blacklisted_addr()
MAX_RT_DELTA = 940
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 60
DRIVER_TORQUE_FACTOR = 50
ALT_MAIN_BUS = SUBARU_MAIN_BUS
ALT_CAM_BUS = SUBARU_CAM_BUS
DEG_TO_CAN = 100
INACTIVE_GAS = 1818
def setUp(self):
self.packer = CANPackerPanda("subaru_global_2017_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_SUBARU, self.FLAGS)
self.safety.init_tests()
def _set_prev_torque(self, t):
self.safety.set_desired_torque_last(t)
self.safety.set_rt_torque_last(t)
def _torque_driver_msg(self, torque):
values = {"Steer_Torque_Sensor": torque}
return self.packer.make_can_msg_panda("Steering_Torque", 0, values)
def _speed_msg(self, speed):
values = {s: speed for s in ["FR", "FL", "RR", "RL"]}
return self.packer.make_can_msg_panda("Wheel_Speeds", self.ALT_MAIN_BUS, values)
def _angle_meas_msg(self, angle):
values = {"Steering_Angle": angle}
return self.packer.make_can_msg_panda("Steering_Torque", 0, values)
def _user_brake_msg(self, brake):
values = {"Brake": brake}
return self.packer.make_can_msg_panda("Brake_Status", self.ALT_MAIN_BUS, values)
def _user_gas_msg(self, gas):
values = {"Throttle_Pedal": gas}
return self.packer.make_can_msg_panda("Throttle", 0, values)
def _pcm_status_msg(self, enable):
values = {"Cruise_Activated": enable}
return self.packer.make_can_msg_panda("CruiseControl", self.ALT_MAIN_BUS, values)
class TestSubaruStockLongitudinalSafetyBase(TestSubaruSafetyBase):
def _cancel_msg(self, cancel, cruise_throttle=0):
values = {"Cruise_Cancel": cancel, "Cruise_Throttle": cruise_throttle}
return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values)
def test_cancel_message(self):
# test that we can only send the cancel message (ES_Distance) with inactive throttle (1818) and Cruise_Cancel=1
for cancel in [True, False]:
self._generic_limit_safety_check(partial(self._cancel_msg, cancel), self.INACTIVE_GAS, self.INACTIVE_GAS, 0, 2**12, 1, self.INACTIVE_GAS, cancel)
class TestSubaruLongitudinalSafetyBase(TestSubaruSafetyBase, common.LongitudinalGasBrakeSafetyTest):
MIN_GAS = 808
MAX_GAS = 3400
INACTIVE_GAS = 1818
MAX_POSSIBLE_GAS = 2**13
MIN_BRAKE = 0
MAX_BRAKE = 600
MAX_POSSIBLE_BRAKE = 2**16
MIN_RPM = 0
MAX_RPM = 3600
MAX_POSSIBLE_RPM = 2**13
FWD_BLACKLISTED_ADDRS = {2: [SubaruMsg.ES_LKAS, SubaruMsg.ES_Brake, SubaruMsg.ES_Distance,
SubaruMsg.ES_Status, SubaruMsg.ES_DashStatus,
SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment]}
def test_rpm_safety_check(self):
self._generic_limit_safety_check(self._send_rpm_msg, self.MIN_RPM, self.MAX_RPM, 0, self.MAX_POSSIBLE_RPM, 1)
def _send_brake_msg(self, brake):
values = {"Brake_Pressure": brake}
return self.packer.make_can_msg_panda("ES_Brake", self.ALT_MAIN_BUS, values)
def _send_gas_msg(self, gas):
values = {"Cruise_Throttle": gas}
return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values)
def _send_rpm_msg(self, rpm):
values = {"Cruise_RPM": rpm}
return self.packer.make_can_msg_panda("ES_Status", self.ALT_MAIN_BUS, values)
class TestSubaruTorqueSafetyBase(TestSubaruSafetyBase, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest):
MAX_RATE_UP = 50
MAX_RATE_DOWN = 70
MAX_TORQUE = 2047
# Safety around steering req bit
MIN_VALID_STEERING_FRAMES = 7
MAX_INVALID_STEERING_FRAMES = 1
MIN_VALID_STEERING_RT_INTERVAL = 144000
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"LKAS_Output": torque, "LKAS_Request": steer_req}
return self.packer.make_can_msg_panda("ES_LKAS", SUBARU_MAIN_BUS, values)
class TestSubaruGen1TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruTorqueSafetyBase):
FLAGS = 0
TX_MSGS = lkas_tx_msgs(SUBARU_MAIN_BUS)
class TestSubaruGen2TorqueSafetyBase(TestSubaruTorqueSafetyBase):
ALT_MAIN_BUS = SUBARU_ALT_BUS
ALT_CAM_BUS = SUBARU_ALT_BUS
MAX_RATE_UP = 40
MAX_RATE_DOWN = 40
MAX_TORQUE = 1000
class TestSubaruGen2TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase):
FLAGS = SubaruSafetyFlags.FLAG_SUBARU_GEN2
TX_MSGS = lkas_tx_msgs(SUBARU_ALT_BUS)
class TestSubaruGen1LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruTorqueSafetyBase):
FLAGS = SubaruSafetyFlags.FLAG_SUBARU_LONG
TX_MSGS = lkas_tx_msgs(SUBARU_MAIN_BUS) + long_tx_msgs(SUBARU_MAIN_BUS)
class TestSubaruGen2LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase):
FLAGS = SubaruSafetyFlags.FLAG_SUBARU_LONG | SubaruSafetyFlags.FLAG_SUBARU_GEN2
TX_MSGS = lkas_tx_msgs(SUBARU_ALT_BUS) + long_tx_msgs(SUBARU_ALT_BUS) + gen2_long_additional_tx_msgs()
def _rdbi_msg(self, did: int):
return b'\x03\x22' + did.to_bytes(2) + b'\x00\x00\x00\x00'
def _es_uds_msg(self, msg: bytes):
return libsafety_py.make_CANPacket(SubaruMsg.ES_UDS_Request, 2, msg)
def test_es_uds_message(self):
tester_present = b'\x02\x3E\x80\x00\x00\x00\x00\x00'
not_tester_present = b"\x03\xAA\xAA\x00\x00\x00\x00\x00"
button_did = 0x1130
# Tester present is allowed for gen2 long to keep eyesight disabled
self.assertTrue(self._tx(self._es_uds_msg(tester_present)))
# Non-Tester present is not allowed
self.assertFalse(self._tx(self._es_uds_msg(not_tester_present)))
# Only button_did is allowed to be read via UDS
for did in range(0xFFFF):
should_tx = (did == button_did)
self.assertEqual(self._tx(self._es_uds_msg(self._rdbi_msg(did))), should_tx)
# any other msg is not allowed
for sid in range(0xFF):
msg = b'\x03' + sid.to_bytes(1) + b'\x00' * 6
self.assertFalse(self._tx(self._es_uds_msg(msg)))
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,72 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.subaru.values import SubaruSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest):
FLAGS = 0
DBC = "subaru_outback_2015_generated"
TX_MSGS = [[0x161, 0], [0x164, 0]]
STANDSTILL_THRESHOLD = 0 # kph
RELAY_MALFUNCTION_ADDRS = {0: (0x164,)}
FWD_BLACKLISTED_ADDRS = {2: [0x161, 0x164]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
MAX_RATE_UP = 50
MAX_RATE_DOWN = 70
MAX_TORQUE = 2047
MAX_RT_DELTA = 940
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 75
DRIVER_TORQUE_FACTOR = 10
def setUp(self):
self.packer = CANPackerPanda(self.DBC)
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_SUBARU_PREGLOBAL, self.FLAGS)
self.safety.init_tests()
def _set_prev_torque(self, t):
self.safety.set_desired_torque_last(t)
self.safety.set_rt_torque_last(t)
def _torque_driver_msg(self, torque):
values = {"Steer_Torque_Sensor": torque}
return self.packer.make_can_msg_panda("Steering_Torque", 0, values)
def _speed_msg(self, speed):
# subaru safety doesn't use the scaled value, so undo the scaling
values = {s: speed*0.0592 for s in ["FR", "FL", "RR", "RL"]}
return self.packer.make_can_msg_panda("Wheel_Speeds", 0, values)
def _user_brake_msg(self, brake):
values = {"Brake_Pedal": brake}
return self.packer.make_can_msg_panda("Brake_Pedal", 0, values)
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"LKAS_Command": torque, "LKAS_Active": steer_req}
return self.packer.make_can_msg_panda("ES_LKAS", 0, values)
def _user_gas_msg(self, gas):
values = {"Throttle_Pedal": gas}
return self.packer.make_can_msg_panda("Throttle", 0, values)
def _pcm_status_msg(self, enable):
values = {"Cruise_Activated": enable}
return self.packer.make_can_msg_panda("CruiseControl", 0, values)
class TestSubaruPreglobalReversedDriverTorqueSafety(TestSubaruPreglobalSafety):
FLAGS = SubaruSafetyFlags.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE
DBC = "subaru_outback_2019_generated"
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,169 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.tesla.values import TeslaSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
MSG_DAS_steeringControl = 0x488
MSG_APS_eacMonitor = 0x27d
MSG_DAS_Control = 0x2b9
class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest, common.LongitudinalAccelSafetyTest):
RELAY_MALFUNCTION_ADDRS = {0: (MSG_DAS_steeringControl, MSG_APS_eacMonitor)}
FWD_BLACKLISTED_ADDRS = {2: [MSG_DAS_steeringControl, MSG_APS_eacMonitor]}
TX_MSGS = [[MSG_DAS_steeringControl, 0], [MSG_APS_eacMonitor, 0], [MSG_DAS_Control, 0]]
STANDSTILL_THRESHOLD = 0.1
GAS_PRESSED_THRESHOLD = 3
FWD_BUS_LOOKUP = {0: 2, 2: 0}
# Angle control limits
DEG_TO_CAN = 10
ANGLE_RATE_BP = [0., 5., 15.]
ANGLE_RATE_UP = [10., 1.6, .3] # windup limit
ANGLE_RATE_DOWN = [10., 7.0, .8] # unwind limit
# Long control limits
MAX_ACCEL = 2.0
MIN_ACCEL = -3.48
INACTIVE_ACCEL = 0.0
packer: CANPackerPanda
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestTeslaSafetyBase":
raise unittest.SkipTest
def _angle_cmd_msg(self, angle: float, enabled: bool):
values = {"DAS_steeringAngleRequest": angle, "DAS_steeringControlType": 1 if enabled else 0}
return self.packer.make_can_msg_panda("DAS_steeringControl", 0, values)
def _angle_meas_msg(self, angle: float):
values = {"EPAS3S_internalSAS": angle}
return self.packer.make_can_msg_panda("EPAS3S_sysStatus", 0, values)
def _user_brake_msg(self, brake):
values = {"IBST_driverBrakeApply": 2 if brake else 1}
return self.packer.make_can_msg_panda("IBST_status", 0, values)
def _speed_msg(self, speed):
values = {"DI_vehicleSpeed": speed * 3.6}
return self.packer.make_can_msg_panda("DI_speed", 0, values)
def _vehicle_moving_msg(self, speed: float):
values = {"DI_cruiseState": 3 if speed <= self.STANDSTILL_THRESHOLD else 2}
return self.packer.make_can_msg_panda("DI_state", 0, values)
def _user_gas_msg(self, gas):
values = {"DI_accelPedalPos": gas}
return self.packer.make_can_msg_panda("DI_systemStatus", 0, values)
def _pcm_status_msg(self, enable):
values = {"DI_cruiseState": 2 if enable else 0}
return self.packer.make_can_msg_panda("DI_state", 0, values)
def _long_control_msg(self, set_speed, acc_val=0, jerk_limits=(0, 0), accel_limits=(0, 0), aeb_event=0, bus=0):
values = {
"DAS_setSpeed": set_speed,
"DAS_accState": acc_val,
"DAS_aebEvent": aeb_event,
"DAS_jerkMin": jerk_limits[0],
"DAS_jerkMax": jerk_limits[1],
"DAS_accelMin": accel_limits[0],
"DAS_accelMax": accel_limits[1],
}
return self.packer.make_can_msg_panda("DAS_control", bus, values)
def _accel_msg(self, accel: float):
# For common.LongitudinalAccelSafetyTest
return self._long_control_msg(10, accel_limits=(accel, max(accel, 0)))
def test_vehicle_speed_measurements(self):
# OVERRIDDEN: 79.1667 is the max speed in m/s
self._common_measurement_test(self._speed_msg, 0, 285 / 3.6, common.VEHICLE_SPEED_FACTOR,
self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max)
class TestTeslaStockSafety(TestTeslaSafetyBase):
def setUp(self):
self.packer = CANPackerPanda("tesla_model3_party")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TESLA, 0)
self.safety.init_tests()
def test_accel_actuation_limits(self, stock_longitudinal=True):
super().test_accel_actuation_limits(stock_longitudinal)
def test_cancel(self):
for accval in range(16):
self.safety.set_controls_allowed(True)
should_tx = accval == 13 # ACC_CANCEL_GENERIC_SILENT
self.assertFalse(self._tx(self._long_control_msg(0, acc_val=accval, accel_limits=(self.MIN_ACCEL, self.MAX_ACCEL))))
self.assertEqual(should_tx, self._tx(self._long_control_msg(0, acc_val=accval)))
def test_no_aeb(self):
for aeb_event in range(4):
self.assertEqual(self._tx(self._long_control_msg(10, acc_val=13, aeb_event=aeb_event)), aeb_event == 0)
class TestTeslaLongitudinalSafety(TestTeslaSafetyBase):
RELAY_MALFUNCTION_ADDRS = {0: (MSG_DAS_steeringControl, MSG_APS_eacMonitor, MSG_DAS_Control)}
FWD_BLACKLISTED_ADDRS = {2: [MSG_DAS_steeringControl, MSG_APS_eacMonitor, MSG_DAS_Control]}
def setUp(self):
self.packer = CANPackerPanda("tesla_model3_party")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TESLA, TeslaSafetyFlags.FLAG_TESLA_LONG_CONTROL)
self.safety.init_tests()
def test_no_aeb(self):
for aeb_event in range(4):
self.assertEqual(self._tx(self._long_control_msg(10, aeb_event=aeb_event)), aeb_event == 0)
def test_stock_aeb_passthrough(self):
no_aeb_msg = self._long_control_msg(10, aeb_event=0)
no_aeb_msg_cam = self._long_control_msg(10, aeb_event=0, bus=2)
aeb_msg_cam = self._long_control_msg(10, aeb_event=1, bus=2)
# stock system sends no AEB -> no forwarding, and OP is allowed to TX
self.assertEqual(1, self._rx(no_aeb_msg_cam))
self.assertEqual(-1, self.safety.safety_fwd_hook(2, no_aeb_msg_cam.addr))
self.assertTrue(self._tx(no_aeb_msg))
# stock system sends AEB -> forwarding, and OP is not allowed to TX
self.assertEqual(1, self._rx(aeb_msg_cam))
self.assertEqual(0, self.safety.safety_fwd_hook(2, aeb_msg_cam.addr))
self.assertFalse(self._tx(no_aeb_msg))
def test_prevent_reverse(self):
# Note: Tesla can reverse while at a standstill if both accel_min and accel_max are negative.
self.safety.set_controls_allowed(True)
# accel_min and accel_max are positive
self.assertTrue(self._tx(self._long_control_msg(set_speed=10, accel_limits=(1.1, 0.8))))
self.assertTrue(self._tx(self._long_control_msg(set_speed=0, accel_limits=(1.1, 0.8))))
# accel_min and accel_max are both zero
self.assertTrue(self._tx(self._long_control_msg(set_speed=10, accel_limits=(0, 0))))
self.assertTrue(self._tx(self._long_control_msg(set_speed=0, accel_limits=(0, 0))))
# accel_min and accel_max have opposing signs
self.assertTrue(self._tx(self._long_control_msg(set_speed=10, accel_limits=(-0.8, 1.3))))
self.assertTrue(self._tx(self._long_control_msg(set_speed=0, accel_limits=(0.8, -1.3))))
self.assertTrue(self._tx(self._long_control_msg(set_speed=0, accel_limits=(0, -1.3))))
# accel_min and accel_max are negative
self.assertFalse(self._tx(self._long_control_msg(set_speed=10, accel_limits=(-1.1, -0.6))))
self.assertFalse(self._tx(self._long_control_msg(set_speed=0, accel_limits=(-0.6, -1.1))))
self.assertFalse(self._tx(self._long_control_msg(set_speed=0, accel_limits=(-0.1, -0.1))))
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,364 @@
#!/usr/bin/env python3
import numpy as np
import random
import unittest
import itertools
from opendbc.car.toyota.values import ToyotaSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
TOYOTA_COMMON_TX_MSGS = [[0x2E4, 0], [0x191, 0], [0x412, 0], [0x343, 0], [0x1D2, 0]] # LKAS + LTA + ACC & PCM cancel cmds
TOYOTA_SECOC_TX_MSGS = [[0x131, 0]] + TOYOTA_COMMON_TX_MSGS
TOYOTA_COMMON_LONG_TX_MSGS = [[0x283, 0], [0x2E6, 0], [0x2E7, 0], [0x33E, 0], [0x344, 0], [0x365, 0], [0x366, 0], [0x4CB, 0], # DSU bus 0
[0x128, 1], [0x141, 1], [0x160, 1], [0x161, 1], [0x470, 1], # DSU bus 1
[0x411, 0], # PCS_HUD
[0x750, 0]] # radar diagnostic address
class TestToyotaSafetyBase(common.PandaCarSafetyTest, common.LongitudinalAccelSafetyTest):
TX_MSGS = TOYOTA_COMMON_TX_MSGS + TOYOTA_COMMON_LONG_TX_MSGS
STANDSTILL_THRESHOLD = 0 # kph
RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x343)}
FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191, 0x343]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
EPS_SCALE = 73
packer: CANPackerPanda
safety: libsafety_py.Panda
@classmethod
def setUpClass(cls):
if cls.__name__.endswith("Base"):
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def _torque_meas_msg(self, torque: int, driver_torque: int | None = None):
values = {"STEER_TORQUE_EPS": (torque / self.EPS_SCALE) * 100.}
if driver_torque is not None:
values["STEER_TORQUE_DRIVER"] = driver_torque
return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values)
# Both torque and angle safety modes test with each other's steering commands
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"STEER_TORQUE_CMD": torque, "STEER_REQUEST": steer_req}
return self.packer.make_can_msg_panda("STEERING_LKA", 0, values)
def _angle_meas_msg(self, angle: float, steer_angle_initializing: bool = False):
# This creates a steering torque angle message. Not set on all platforms,
# relative to init angle on some older TSS2 platforms. Only to be used with LTA
values = {"STEER_ANGLE": angle, "STEER_ANGLE_INITIALIZING": int(steer_angle_initializing)}
return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values)
def _angle_cmd_msg(self, angle: float, enabled: bool):
return self._lta_msg(int(enabled), int(enabled), angle, torque_wind_down=100 if enabled else 0)
def _lta_msg(self, req, req2, angle_cmd, torque_wind_down=100):
values = {"STEER_REQUEST": req, "STEER_REQUEST_2": req2, "STEER_ANGLE_CMD": angle_cmd, "TORQUE_WIND_DOWN": torque_wind_down}
return self.packer.make_can_msg_panda("STEERING_LTA", 0, values)
def _accel_msg(self, accel, cancel_req=0):
values = {"ACCEL_CMD": accel, "CANCEL_REQ": cancel_req}
return self.packer.make_can_msg_panda("ACC_CONTROL", 0, values)
def _speed_msg(self, speed):
values = {("WHEEL_SPEED_%s" % n): speed * 3.6 for n in ["FR", "FL", "RR", "RL"]}
return self.packer.make_can_msg_panda("WHEEL_SPEEDS", 0, values)
def _user_brake_msg(self, brake):
values = {"BRAKE_PRESSED": brake}
return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values)
def _user_gas_msg(self, gas):
cruise_active = self.safety.get_controls_allowed()
values = {"GAS_RELEASED": not gas, "CRUISE_ACTIVE": cruise_active}
return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values)
def _pcm_status_msg(self, enable):
values = {"CRUISE_ACTIVE": enable}
return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values)
def test_diagnostics(self, stock_longitudinal: bool = False):
for should_tx, msg in ((False, b"\x6D\x02\x3E\x00\x00\x00\x00\x00"), # fwdCamera tester present
(False, b"\x0F\x03\xAA\xAA\x00\x00\x00\x00"), # non-tester present
(True, b"\x0F\x02\x3E\x00\x00\x00\x00\x00")):
tester_present = libsafety_py.make_CANPacket(0x750, 0, msg)
self.assertEqual(should_tx and not stock_longitudinal, self._tx(tester_present))
def test_block_aeb(self, stock_longitudinal: bool = False):
for controls_allowed in (True, False):
for bad in (True, False):
for _ in range(10):
self.safety.set_controls_allowed(controls_allowed)
dat = [random.randint(1, 255) for _ in range(7)]
if not bad:
dat = [0]*6 + dat[-1:]
msg = libsafety_py.make_CANPacket(0x283, 0, bytes(dat))
self.assertEqual(not bad and not stock_longitudinal, self._tx(msg))
# Only allow LTA msgs with no actuation
def test_lta_steer_cmd(self):
for engaged, req, req2, torque_wind_down, angle in itertools.product([True, False],
[0, 1], [0, 1],
[0, 50, 100],
np.linspace(-20, 20, 5)):
self.safety.set_controls_allowed(engaged)
should_tx = not req and not req2 and angle == 0 and torque_wind_down == 0
self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down)),
f"{req=} {req2=} {angle=} {torque_wind_down=}")
def test_rx_hook(self):
# checksum checks
for msg in ["trq", "pcm"]:
self.safety.set_controls_allowed(1)
if msg == "trq":
to_push = self._torque_meas_msg(0)
if msg == "pcm":
to_push = self._pcm_status_msg(True)
self.assertTrue(self._rx(to_push))
to_push[0].data[4] = 0
to_push[0].data[5] = 0
to_push[0].data[6] = 0
to_push[0].data[7] = 0
self.assertFalse(self._rx(to_push))
self.assertFalse(self.safety.get_controls_allowed())
class TestToyotaSafetyTorque(TestToyotaSafetyBase, common.MotorTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest):
MAX_RATE_UP = 15
MAX_RATE_DOWN = 25
MAX_TORQUE = 1500
MAX_RT_DELTA = 450
RT_INTERVAL = 250000
MAX_TORQUE_ERROR = 350
TORQUE_MEAS_TOLERANCE = 1 # toyota safety adds one to be conservative for rounding
# Safety around steering req bit
MIN_VALID_STEERING_FRAMES = 18
MAX_INVALID_STEERING_FRAMES = 1
MIN_VALID_STEERING_RT_INTERVAL = 170000 # a ~10% buffer, can send steer up to 110Hz
def setUp(self):
self.packer = CANPackerPanda("toyota_nodsu_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE)
self.safety.init_tests()
class TestToyotaSafetyAngle(TestToyotaSafetyBase, common.AngleSteeringSafetyTest):
# Angle control limits
DEG_TO_CAN = 17.452007 # 1 / 0.0573 deg to can
ANGLE_RATE_BP = [5., 25., 25.]
ANGLE_RATE_UP = [0.3, 0.15, 0.15] # windup limit
ANGLE_RATE_DOWN = [0.36, 0.26, 0.26] # unwind limit
MAX_LTA_ANGLE = 94.9461 # PCS faults if commanding above this, deg
MAX_MEAS_TORQUE = 1500 # max allowed measured EPS torque before wind down
MAX_LTA_DRIVER_TORQUE = 150 # max allowed driver torque before wind down
def setUp(self):
self.packer = CANPackerPanda("toyota_nodsu_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE | ToyotaSafetyFlags.FLAG_TOYOTA_LTA)
self.safety.init_tests()
# Only allow LKA msgs with no actuation
def test_lka_steer_cmd(self):
for engaged, steer_req, torque in itertools.product([True, False],
[0, 1],
np.linspace(-1500, 1500, 7)):
self.safety.set_controls_allowed(engaged)
torque = int(torque)
self.safety.set_rt_torque_last(torque)
self.safety.set_torque_meas(torque, torque)
self.safety.set_desired_torque_last(torque)
should_tx = not steer_req and torque == 0
self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(torque, steer_req)))
def test_lta_steer_cmd(self):
"""
Tests the LTA steering command message
controls_allowed:
* STEER_REQUEST and STEER_REQUEST_2 do not mismatch
* TORQUE_WIND_DOWN is only set to 0 or 100 when STEER_REQUEST and STEER_REQUEST_2 are both 1
* Full torque messages are blocked if either EPS torque or driver torque is above the threshold
not controls_allowed:
* STEER_REQUEST, STEER_REQUEST_2, and TORQUE_WIND_DOWN are all 0
"""
for controls_allowed in (True, False):
for angle in np.arange(-90, 90, 1):
self.safety.set_controls_allowed(controls_allowed)
self._reset_angle_measurement(angle)
self._set_prev_desired_angle(angle)
self.assertTrue(self._tx(self._lta_msg(0, 0, angle, 0)))
if controls_allowed:
# Test the two steer request bits and TORQUE_WIND_DOWN torque wind down signal
for req, req2, torque_wind_down in itertools.product([0, 1], [0, 1], [0, 50, 100]):
mismatch = not (req or req2) and torque_wind_down != 0
should_tx = req == req2 and (torque_wind_down in (0, 100)) and not mismatch
self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down)))
# Test max EPS torque and driver override thresholds
cases = itertools.product(
(0, self.MAX_MEAS_TORQUE - 1, self.MAX_MEAS_TORQUE, self.MAX_MEAS_TORQUE + 1, self.MAX_MEAS_TORQUE * 2),
(0, self.MAX_LTA_DRIVER_TORQUE - 1, self.MAX_LTA_DRIVER_TORQUE, self.MAX_LTA_DRIVER_TORQUE + 1, self.MAX_LTA_DRIVER_TORQUE * 2)
)
for eps_torque, driver_torque in cases:
for sign in (-1, 1):
for _ in range(6):
self._rx(self._torque_meas_msg(sign * eps_torque, sign * driver_torque))
# Toyota adds 1 to EPS torque since it is rounded after EPS factor
should_tx = (eps_torque - 1) <= self.MAX_MEAS_TORQUE and driver_torque <= self.MAX_LTA_DRIVER_TORQUE
self.assertEqual(should_tx, self._tx(self._lta_msg(1, 1, angle, 100)))
self.assertTrue(self._tx(self._lta_msg(1, 1, angle, 0))) # should tx if we wind down torque
else:
# Controls not allowed
for req, req2, torque_wind_down in itertools.product([0, 1], [0, 1], [0, 50, 100]):
should_tx = not (req or req2) and torque_wind_down == 0
self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down)))
def test_steering_angle_measurements(self, max_angle=None):
# Measurement test tests max angle + 0.5 which will fail
super().test_steering_angle_measurements(max_angle=self.MAX_LTA_ANGLE - 0.5)
def test_angle_cmd_when_enabled(self, max_angle=None):
super().test_angle_cmd_when_enabled(max_angle=self.MAX_LTA_ANGLE)
def test_angle_measurements(self):
"""
* Tests angle meas quality flag dictates whether angle measurement is parsed, and if rx is valid
* Tests rx hook correctly clips the angle measurement, since it is to be compared to LTA cmd when inactive
"""
for steer_angle_initializing in (True, False):
for angle in np.arange(0, self.MAX_LTA_ANGLE * 2, 1):
# If init flag is set, do not rx or parse any angle measurements
for a in (angle, -angle, 0, 0, 0, 0):
self.assertEqual(not steer_angle_initializing,
self._rx(self._angle_meas_msg(a, steer_angle_initializing)))
final_angle = (0 if steer_angle_initializing else
round(min(angle, self.MAX_LTA_ANGLE) * self.DEG_TO_CAN))
self.assertEqual(self.safety.get_angle_meas_min(), -final_angle)
self.assertEqual(self.safety.get_angle_meas_max(), final_angle)
self._rx(self._angle_meas_msg(0))
self.assertEqual(self.safety.get_angle_meas_min(), -final_angle)
self.assertEqual(self.safety.get_angle_meas_max(), 0)
self._rx(self._angle_meas_msg(0))
self.assertEqual(self.safety.get_angle_meas_min(), 0)
self.assertEqual(self.safety.get_angle_meas_max(), 0)
class TestToyotaAltBrakeSafety(TestToyotaSafetyTorque):
def setUp(self):
self.packer = CANPackerPanda("toyota_new_mc_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE | ToyotaSafetyFlags.FLAG_TOYOTA_ALT_BRAKE)
self.safety.init_tests()
def _user_brake_msg(self, brake):
values = {"BRAKE_PRESSED": brake}
return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values)
# No LTA message in the DBC
def test_lta_steer_cmd(self):
pass
class TestToyotaStockLongitudinalBase(TestToyotaSafetyBase):
TX_MSGS = TOYOTA_COMMON_TX_MSGS
# Base addresses minus ACC_CONTROL (0x343)
RELAY_MALFUNCTION_ADDRS = {0: (0x2E4,)}
FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191]}
def test_diagnostics(self, stock_longitudinal: bool = True):
super().test_diagnostics(stock_longitudinal=stock_longitudinal)
def test_block_aeb(self, stock_longitudinal: bool = True):
super().test_block_aeb(stock_longitudinal=stock_longitudinal)
def test_accel_actuation_limits(self, stock_longitudinal=True):
super().test_accel_actuation_limits(stock_longitudinal=stock_longitudinal)
def test_acc_cancel(self):
"""
Regardless of controls allowed, never allow ACC_CONTROL if cancel bit isn't set
"""
for controls_allowed in [True, False]:
self.safety.set_controls_allowed(controls_allowed)
for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.1):
self.assertFalse(self._tx(self._accel_msg(accel)))
should_tx = np.isclose(accel, 0, atol=0.0001)
self.assertEqual(should_tx, self._tx(self._accel_msg(accel, cancel_req=1)))
class TestToyotaStockLongitudinalTorque(TestToyotaStockLongitudinalBase, TestToyotaSafetyTorque):
def setUp(self):
self.packer = CANPackerPanda("toyota_nodsu_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE | ToyotaSafetyFlags.FLAG_TOYOTA_STOCK_LONGITUDINAL)
self.safety.init_tests()
class TestToyotaStockLongitudinalAngle(TestToyotaStockLongitudinalBase, TestToyotaSafetyAngle):
def setUp(self):
self.packer = CANPackerPanda("toyota_nodsu_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE | ToyotaSafetyFlags.FLAG_TOYOTA_STOCK_LONGITUDINAL | ToyotaSafetyFlags.FLAG_TOYOTA_LTA)
self.safety.init_tests()
class TestToyotaSecOcSafety(TestToyotaStockLongitudinalBase):
TX_MSGS = TOYOTA_SECOC_TX_MSGS
RELAY_MALFUNCTION_ADDRS = {0: (0x2E4,)}
FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191, 0x131]}
def setUp(self):
self.packer = CANPackerPanda("toyota_secoc_pt_generated")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_TOYOTA, self.EPS_SCALE | ToyotaSafetyFlags.FLAG_TOYOTA_STOCK_LONGITUDINAL | ToyotaSafetyFlags.FLAG_TOYOTA_SECOC)
self.safety.init_tests()
# This platform also has alternate brake and PCM messages, but same naming in the DBC, so same packers work
def _user_gas_msg(self, gas):
values = {"GAS_PEDAL_USER": gas}
return self.packer.make_can_msg_panda("GAS_PEDAL", 0, values)
# This platform sends both STEERING_LTA (same as other Toyota) and STEERING_LTA_2 (SecOC signed)
# STEERING_LTA is checked for no-actuation by the base class, STEERING_LTA_2 is checked for no-actuation below
def _lta_2_msg(self, req, req2, angle_cmd, torque_wind_down=100):
values = {"STEER_REQUEST": req, "STEER_REQUEST_2": req2, "STEER_ANGLE_CMD": angle_cmd}
return self.packer.make_can_msg_panda("STEERING_LTA_2", 0, values)
def test_lta_2_steer_cmd(self):
for engaged, req, req2, angle in itertools.product([True, False], [0, 1], [0, 1], np.linspace(-20, 20, 5)):
self.safety.set_controls_allowed(engaged)
should_tx = not req and not req2 and angle == 0
self.assertEqual(should_tx, self._tx(self._lta_2_msg(req, req2, angle)), f"{req=} {req2=} {angle=}")
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,226 @@
#!/usr/bin/env python3
import unittest
import numpy as np
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
from opendbc.car.volkswagen.values import VolkswagenSafetyFlags
MAX_ACCEL = 2.0
MIN_ACCEL = -3.5
MSG_ESP_19 = 0xB2 # RX from ABS, for wheel speeds
MSG_LH_EPS_03 = 0x9F # RX from EPS, for driver steering torque
MSG_ESP_05 = 0x106 # RX from ABS, for brake light state
MSG_TSK_06 = 0x120 # RX from ECU, for ACC status from drivetrain coordinator
MSG_MOTOR_20 = 0x121 # RX from ECU, for driver throttle input
MSG_ACC_06 = 0x122 # TX by OP, ACC control instructions to the drivetrain coordinator
MSG_HCA_01 = 0x126 # TX by OP, Heading Control Assist steering torque
MSG_GRA_ACC_01 = 0x12B # TX by OP, ACC control buttons for cancel/resume
MSG_ACC_07 = 0x12E # TX by OP, ACC control instructions to the drivetrain coordinator
MSG_ACC_02 = 0x30C # TX by OP, ACC HUD data to the instrument cluster
MSG_LDW_02 = 0x397 # TX by OP, Lane line recognition and text alerts
class TestVolkswagenMqbSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest):
STANDSTILL_THRESHOLD = 0
RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01,)}
MAX_RATE_UP = 4
MAX_RATE_DOWN = 10
MAX_TORQUE = 300
MAX_RT_DELTA = 75
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 80
DRIVER_TORQUE_FACTOR = 3
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestVolkswagenMqbSafety":
cls.packer = None
cls.safety = None
raise unittest.SkipTest
# Wheel speeds _esp_19_msg
def _speed_msg(self, speed):
values = {"ESP_%s_Radgeschw_02" % s: speed for s in ["HL", "HR", "VL", "VR"]}
return self.packer.make_can_msg_panda("ESP_19", 0, values)
# Driver brake pressure over threshold
def _esp_05_msg(self, brake):
values = {"ESP_Fahrer_bremst": brake}
return self.packer.make_can_msg_panda("ESP_05", 0, values)
# Brake pedal switch
def _motor_14_msg(self, brake):
values = {"MO_Fahrer_bremst": brake}
return self.packer.make_can_msg_panda("Motor_14", 0, values)
def _user_brake_msg(self, brake):
return self._motor_14_msg(brake)
# Driver throttle input
def _user_gas_msg(self, gas):
values = {"MO_Fahrpedalrohwert_01": gas}
return self.packer.make_can_msg_panda("Motor_20", 0, values)
# ACC engagement status
def _tsk_status_msg(self, enable, main_switch=True):
if main_switch:
tsk_status = 3 if enable else 2
else:
tsk_status = 0
values = {"TSK_Status": tsk_status}
return self.packer.make_can_msg_panda("TSK_06", 0, values)
def _pcm_status_msg(self, enable):
return self._tsk_status_msg(enable)
# Driver steering input torque
def _torque_driver_msg(self, torque):
values = {"EPS_Lenkmoment": abs(torque), "EPS_VZ_Lenkmoment": torque < 0}
return self.packer.make_can_msg_panda("LH_EPS_03", 0, values)
# openpilot steering output torque
def _torque_cmd_msg(self, torque, steer_req=1):
values = {"HCA_01_LM_Offset": abs(torque), "HCA_01_LM_OffSign": torque < 0, "HCA_01_Sendestatus": steer_req}
return self.packer.make_can_msg_panda("HCA_01", 0, values)
# Cruise control buttons
def _gra_acc_01_msg(self, cancel=0, resume=0, _set=0, bus=2):
values = {"GRA_Abbrechen": cancel, "GRA_Tip_Setzen": _set, "GRA_Tip_Wiederaufnahme": resume}
return self.packer.make_can_msg_panda("GRA_ACC_01", bus, values)
# Acceleration request to drivetrain coordinator
def _acc_06_msg(self, accel):
values = {"ACC_Sollbeschleunigung_02": accel}
return self.packer.make_can_msg_panda("ACC_06", 0, values)
# Acceleration request to drivetrain coordinator
def _acc_07_msg(self, accel, secondary_accel=3.02):
values = {"ACC_Sollbeschleunigung_02": accel, "ACC_Folgebeschl": secondary_accel}
return self.packer.make_can_msg_panda("ACC_07", 0, values)
# Verify brake_pressed is true if either the switch or pressure threshold signals are true
def test_redundant_brake_signals(self):
test_combinations = [(True, True, True), (True, True, False), (True, False, True), (False, False, False)]
for brake_pressed, motor_14_signal, esp_05_signal in test_combinations:
self._rx(self._motor_14_msg(False))
self._rx(self._esp_05_msg(False))
self.assertFalse(self.safety.get_brake_pressed_prev())
self._rx(self._motor_14_msg(motor_14_signal))
self._rx(self._esp_05_msg(esp_05_signal))
self.assertEqual(brake_pressed, self.safety.get_brake_pressed_prev(),
f"expected {brake_pressed=} with {motor_14_signal=} and {esp_05_signal=}")
def test_torque_measurements(self):
# TODO: make this test work with all cars
self._rx(self._torque_driver_msg(50))
self._rx(self._torque_driver_msg(-50))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self.assertEqual(-50, self.safety.get_torque_driver_min())
self.assertEqual(50, self.safety.get_torque_driver_max())
self._rx(self._torque_driver_msg(0))
self.assertEqual(0, self.safety.get_torque_driver_max())
self.assertEqual(-50, self.safety.get_torque_driver_min())
self._rx(self._torque_driver_msg(0))
self.assertEqual(0, self.safety.get_torque_driver_max())
self.assertEqual(0, self.safety.get_torque_driver_min())
class TestVolkswagenMqbStockSafety(TestVolkswagenMqbSafety):
TX_MSGS = [[MSG_HCA_01, 0], [MSG_LDW_02, 0], [MSG_LH_EPS_03, 2], [MSG_GRA_ACC_01, 0], [MSG_GRA_ACC_01, 2]]
FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
def setUp(self):
self.packer = CANPackerPanda("vw_mqb_2010")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_VOLKSWAGEN_MQB, 0)
self.safety.init_tests()
def test_spam_cancel_safety_check(self):
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._gra_acc_01_msg(cancel=1)))
self.assertFalse(self._tx(self._gra_acc_01_msg(resume=1)))
self.assertFalse(self._tx(self._gra_acc_01_msg(_set=1)))
# do not block resume if we are engaged already
self.safety.set_controls_allowed(1)
self.assertTrue(self._tx(self._gra_acc_01_msg(resume=1)))
class TestVolkswagenMqbLongSafety(TestVolkswagenMqbSafety):
TX_MSGS = [[MSG_HCA_01, 0], [MSG_LDW_02, 0], [MSG_LH_EPS_03, 2], [MSG_ACC_02, 0], [MSG_ACC_06, 0], [MSG_ACC_07, 0]]
FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02, MSG_ACC_02, MSG_ACC_06, MSG_ACC_07]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
INACTIVE_ACCEL = 3.01
def setUp(self):
self.packer = CANPackerPanda("vw_mqb_2010")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_VOLKSWAGEN_MQB, VolkswagenSafetyFlags.FLAG_VOLKSWAGEN_LONG_CONTROL)
self.safety.init_tests()
# stock cruise controls are entirely bypassed under openpilot longitudinal control
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 test_set_and_resume_buttons(self):
for button in ["set", "resume"]:
# ACC main switch must be on, engage on falling edge
self.safety.set_controls_allowed(0)
self._rx(self._tsk_status_msg(False, main_switch=False))
self._rx(self._gra_acc_01_msg(_set=(button == "set"), resume=(button == "resume"), bus=0))
self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} with main switch off")
self._rx(self._tsk_status_msg(False, main_switch=True))
self._rx(self._gra_acc_01_msg(_set=(button == "set"), resume=(button == "resume"), bus=0))
self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} rising edge")
self._rx(self._gra_acc_01_msg(bus=0))
self.assertTrue(self.safety.get_controls_allowed(), f"controls not allowed on {button} falling edge")
def test_cancel_button(self):
# Disable on rising edge of cancel button
self._rx(self._tsk_status_msg(False, main_switch=True))
self.safety.set_controls_allowed(1)
self._rx(self._gra_acc_01_msg(cancel=True, bus=0))
self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after cancel")
def test_main_switch(self):
# Disable as soon as main switch turns off
self._rx(self._tsk_status_msg(False, main_switch=True))
self.safety.set_controls_allowed(1)
self._rx(self._tsk_status_msg(False, main_switch=False))
self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after ACC main switch off")
def test_accel_safety_check(self):
for controls_allowed in [True, False]:
# enforce we don't skip over 0 or inactive accel
for accel in np.concatenate((np.arange(MIN_ACCEL - 2, MAX_ACCEL + 2, 0.03), [0, self.INACTIVE_ACCEL])):
accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding
is_inactive_accel = accel == self.INACTIVE_ACCEL
send = (controls_allowed and MIN_ACCEL <= accel <= MAX_ACCEL) or is_inactive_accel
self.safety.set_controls_allowed(controls_allowed)
# primary accel request used by ECU
self.assertEqual(send, self._tx(self._acc_06_msg(accel)), (controls_allowed, accel))
# additional accel request used by ABS/ESP
self.assertEqual(send, self._tx(self._acc_07_msg(accel)), (controls_allowed, accel))
# ensure the optional secondary accel field remains inactive for now
self.assertEqual(is_inactive_accel, self._tx(self._acc_07_msg(accel, secondary_accel=accel)), (controls_allowed, accel))
if __name__ == "__main__":
unittest.main()

View File

@@ -0,0 +1,201 @@
#!/usr/bin/env python3
import unittest
from opendbc.car.volkswagen.values import VolkswagenSafetyFlags
from opendbc.safety import Safety
from opendbc.safety.tests.libsafety import libsafety_py
import opendbc.safety.tests.common as common
from opendbc.safety.tests.common import CANPackerPanda
MSG_LENKHILFE_3 = 0x0D0 # RX from EPS, for steering angle and driver steering torque
MSG_HCA_1 = 0x0D2 # TX by OP, Heading Control Assist steering torque
MSG_BREMSE_1 = 0x1A0 # RX from ABS, for ego speed
MSG_MOTOR_2 = 0x288 # RX from ECU, for CC state and brake switch state
MSG_ACC_SYSTEM = 0x368 # TX by OP, longitudinal acceleration controls
MSG_MOTOR_3 = 0x380 # RX from ECU, for driver throttle input
MSG_GRA_NEU = 0x38A # TX by OP, ACC control buttons for cancel/resume
MSG_MOTOR_5 = 0x480 # RX from ECU, for ACC main switch state
MSG_ACC_GRA_ANZEIGE = 0x56A # TX by OP, ACC HUD
MSG_LDW_1 = 0x5BE # TX by OP, Lane line recognition and text alerts
class TestVolkswagenPqSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest):
cruise_engaged = False
STANDSTILL_THRESHOLD = 0
RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1,)}
MAX_RATE_UP = 6
MAX_RATE_DOWN = 10
MAX_TORQUE = 300
MAX_RT_DELTA = 113
RT_INTERVAL = 250000
DRIVER_TORQUE_ALLOWANCE = 80
DRIVER_TORQUE_FACTOR = 3
@classmethod
def setUpClass(cls):
if cls.__name__ == "TestVolkswagenPqSafety":
cls.packer = None
cls.safety = None
raise unittest.SkipTest
def _set_prev_torque(self, t):
self.safety.set_desired_torque_last(t)
self.safety.set_rt_torque_last(t)
# Ego speed (Bremse_1)
def _speed_msg(self, speed):
values = {"Geschwindigkeit_neu__Bremse_1_": speed}
return self.packer.make_can_msg_panda("Bremse_1", 0, values)
# Brake light switch (shared message Motor_2)
def _user_brake_msg(self, brake):
# since this signal is used for engagement status, preserve current state
return self._motor_2_msg(brake_pressed=brake, cruise_engaged=self.safety.get_controls_allowed())
# ACC engaged status (shared message Motor_2)
def _pcm_status_msg(self, enable):
self.__class__.cruise_engaged = enable
return self._motor_2_msg(cruise_engaged=enable)
# Acceleration request to drivetrain coordinator
def _accel_msg(self, accel):
values = {"ACS_Sollbeschl": accel}
return self.packer.make_can_msg_panda("ACC_System", 0, values)
# Driver steering input torque
def _torque_driver_msg(self, torque):
values = {"LH3_LM": abs(torque), "LH3_LMSign": torque < 0}
return self.packer.make_can_msg_panda("Lenkhilfe_3", 0, values)
# openpilot steering output torque
def _torque_cmd_msg(self, torque, steer_req=1, hca_status=5):
values = {"LM_Offset": abs(torque), "LM_OffSign": torque < 0, "HCA_Status": hca_status if steer_req else 3}
return self.packer.make_can_msg_panda("HCA_1", 0, values)
# ACC engagement and brake light switch status
# Called indirectly for compatibility with common.py tests
def _motor_2_msg(self, brake_pressed=False, cruise_engaged=False):
values = {"Bremslichtschalter": brake_pressed,
"GRA_Status": cruise_engaged}
return self.packer.make_can_msg_panda("Motor_2", 0, values)
# ACC main switch status
def _motor_5_msg(self, main_switch=False):
values = {"GRA_Hauptschalter": main_switch}
return self.packer.make_can_msg_panda("Motor_5", 0, values)
# Driver throttle input (Motor_3)
def _user_gas_msg(self, gas):
values = {"Fahrpedal_Rohsignal": gas}
return self.packer.make_can_msg_panda("Motor_3", 0, values)
# Cruise control buttons (GRA_Neu)
def _button_msg(self, _set=False, resume=False, cancel=False, bus=2):
values = {"GRA_Neu_Setzen": _set, "GRA_Recall": resume, "GRA_Abbrechen": cancel}
return self.packer.make_can_msg_panda("GRA_Neu", bus, values)
def test_torque_measurements(self):
# TODO: make this test work with all cars
self._rx(self._torque_driver_msg(50))
self._rx(self._torque_driver_msg(-50))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self._rx(self._torque_driver_msg(0))
self.assertEqual(-50, self.safety.get_torque_driver_min())
self.assertEqual(50, self.safety.get_torque_driver_max())
self._rx(self._torque_driver_msg(0))
self.assertEqual(0, self.safety.get_torque_driver_max())
self.assertEqual(-50, self.safety.get_torque_driver_min())
self._rx(self._torque_driver_msg(0))
self.assertEqual(0, self.safety.get_torque_driver_max())
self.assertEqual(0, self.safety.get_torque_driver_min())
class TestVolkswagenPqStockSafety(TestVolkswagenPqSafety):
# Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
TX_MSGS = [[MSG_HCA_1, 0], [MSG_GRA_NEU, 0], [MSG_GRA_NEU, 2], [MSG_LDW_1, 0]]
FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
def setUp(self):
self.packer = CANPackerPanda("vw_golf_mk4")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_VOLKSWAGEN_PQ, 0)
self.safety.init_tests()
def test_spam_cancel_safety_check(self):
self.safety.set_controls_allowed(0)
self.assertTrue(self._tx(self._button_msg(cancel=True)))
self.assertFalse(self._tx(self._button_msg(resume=True)))
self.assertFalse(self._tx(self._button_msg(_set=True)))
# do not block resume if we are engaged already
self.safety.set_controls_allowed(1)
self.assertTrue(self._tx(self._button_msg(resume=True)))
class TestVolkswagenPqLongSafety(TestVolkswagenPqSafety, common.LongitudinalAccelSafetyTest):
TX_MSGS = [[MSG_HCA_1, 0], [MSG_LDW_1, 0], [MSG_ACC_SYSTEM, 0], [MSG_ACC_GRA_ANZEIGE, 0]]
FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1, MSG_ACC_SYSTEM, MSG_ACC_GRA_ANZEIGE]}
FWD_BUS_LOOKUP = {0: 2, 2: 0}
INACTIVE_ACCEL = 3.01
def setUp(self):
self.packer = CANPackerPanda("vw_golf_mk4")
self.safety = libsafety_py.libsafety
self.safety.set_safety_hooks(Safety.SAFETY_VOLKSWAGEN_PQ, VolkswagenSafetyFlags.FLAG_VOLKSWAGEN_LONG_CONTROL)
self.safety.init_tests()
# stock cruise controls are entirely bypassed under openpilot longitudinal control
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 test_set_and_resume_buttons(self):
for button in ["set", "resume"]:
# ACC main switch must be on, engage on falling edge
self.safety.set_controls_allowed(0)
self._rx(self._motor_5_msg(main_switch=False))
self._rx(self._button_msg(_set=(button == "set"), resume=(button == "resume"), bus=0))
self._rx(self._button_msg(bus=0))
self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} with main switch off")
self._rx(self._motor_5_msg(main_switch=True))
self._rx(self._button_msg(_set=(button == "set"), resume=(button == "resume"), bus=0))
self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} rising edge")
self._rx(self._button_msg(bus=0))
self.assertTrue(self.safety.get_controls_allowed(), f"controls not allowed on {button} falling edge")
def test_cancel_button(self):
# Disable on rising edge of cancel button
self._rx(self._motor_5_msg(main_switch=True))
self.safety.set_controls_allowed(1)
self._rx(self._button_msg(cancel=True, bus=0))
self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after cancel")
def test_main_switch(self):
# Disable as soon as main switch turns off
self._rx(self._motor_5_msg(main_switch=True))
self.safety.set_controls_allowed(1)
self._rx(self._motor_5_msg(main_switch=False))
self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after ACC main switch off")
def test_torque_cmd_enable_variants(self):
# The EPS rack accepts either 5 or 7 for an enabled status, with different low speed tuning behavior
self.safety.set_controls_allowed(1)
for enabled_status in (5, 7):
self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP, steer_req=1, hca_status=enabled_status)),
f"torque cmd rejected with {enabled_status=}")
if __name__ == "__main__":
unittest.main()

View File

@@ -24,9 +24,12 @@ dependencies = [
[project.optional-dependencies]
testing = [
"cffi",
"ruff",
"pytest",
"pytest-coverage",
"pytest-mock",
"pytest-randomly",
"pytest-xdist",
"pytest-subtests",
"hypothesis==6.47.*",
@@ -112,4 +115,5 @@ flake8-implicit-str-concat.allow-multiline=false
[tool.ruff.lint.flake8-tidy-imports.banned-api]
"pytest.main".msg = "pytest.main requires special handling that is easy to mess up!"
"unittest".msg = "Use pytest"
# TODO: re-enable when all tests are converted to pytest
#"unittest".msg = "Use pytest"

View File

@@ -15,7 +15,7 @@ scons -j8
ruff check .
# *** test ***
pytest -n8
pytest -n8 --ignore opendbc/safety
# *** all done ***
GREEN='\033[0;32m'