From 0ba412d52e21628ffcb91b60ad960605abeadc8b Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Thu, 31 Oct 2019 17:02:31 -0700 Subject: [PATCH] Squashed 'panda/' changes from 30c7ca8a5..256d274e7 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 256d274e7 Fix Mac installation instruction per: https://github.com/commaai/panda/pull/308/files bfd8ff1b1 Update cppcheck commit with more coverage b143a1cf9 Fixed Misra complaint 606f1d913 Fixed RTC on non-uno boards, second try. Cannot work when there is no xtal. 933c75770 Fix RTC on non-uno boards (#311) 48d0d0c78 VW button spam: fix safety and add tests (#306) 6cccf969a Fan and IR at 0 when in power savings mode (#309) 05373282a board get_sdk scripts were left on python2 de18a7ef1 bump version after uno merge 1965817d3 Changed default values for testing a12a148d5 Uno (#274) 7d29dc5a2 bump panda version. We really need a better way 40075321d VW: stricter limits to comply with comma safety policy e2e2be92c add safety mode to health packet 101238c7f turned on VW ignition based CAN logic a0d8d5dae fix misra 5.3: check_ignition is intended as check_started and can't be used twice ea636de61 made check_ignition function to both look at ignition_line and ignition_can 1102e6965 make ignition logic common for all cars (#303) 3a110c6f6 bump version after CMSIS core upgrade 55dfa5230 Update core to CMSIS 5.6 release (#251) ee864907c fix linter 2 f410b110d fix linter 55957d6e4 proper python3 exception inheritance 6ba0f47b5 fix linter errors 5c49fe050 Merge pull request #145 from gregjhogan/uds 0f361999b timeout is float 396d6aad5 safety_replay only installs few extra requirements 25af7d301 Misra also need python 3 env 7434c5ce2 centralize requirements for tests a0c37c70a coverage not needed in linter reqs fce38a91d Linter python (#299) 62e2f5caa update cppcheck commit 711810d2f more uds debug 4454e3a6b better CAN comm abstraction 6b1f28f57 fix more encoding and some bytes cleanup (#300) 43adad311 fix WARNING_INDICATOR_REQUESTED name 9c857da37 0x b64d6fa5d typing 768fdf7e1 bytes() > chr().encode() 1be15ea93 custom errors from thread 68da8315f more python3 eb358e81c uds lib example 4f288586d updates for python3 932745f62 support tx flow control for chunked messages b1c371292 add timeout param cdf2f626b bug fixes b1a319577 fix rx message filtering bug 80fb6a6fa convert uds lib to class 59cd2b47f handle separation time in microseconds 4429600d8 fix separation time parsing c641e66f7 fix typo 48b8dcc6f fix flow control delay scale 78f413d88 flow control delay 33a5167d9 bug fixes 8ee89a091 multi-frame tx 5e89a9c72 clear rx buffer and numeric error ids 966230063 fix remaining size calculation 01ef1fae3 zero pad messages before sending 1ddc9735d uds can communication dca176e71 syntax errors 95be4811e SERVICE_TYPE enum 98e73b51d more UDS message type implementation c1c5b0356 uds lib 162f4853d fix chr to bytes conversions (#298) 4972376de Update VW regression test to follow Comma safety index refactoring (#296) f9053f5df more Python 3 fixes, attempting to fix jenkins wifi regresison test (#295) 2f9e07628 Panda safety code for Volkswagen, Audi, SEAT, and Škoda (#293) git-subtree-dir: panda git-subtree-split: 256d274e760ce00d4e5ff5e0d9b86d0fb5924568 old-commit-hash: 22023ebd586de9239e6795e71c81f40c267597e3 --- .circleci/config.yml | 15 + Jenkinsfile | 15 + README.md | 2 + UPDATING.md | 12 +- VERSION | 2 +- __init__.py | 2 +- board/README.md | 1 + board/board.h | 33 +- board/board_declarations.h | 15 + board/boards/black.h | 24 +- board/boards/common.h | 6 +- board/boards/grey.h | 5 +- board/boards/pedal.h | 16 + board/boards/uno.h | 247 +++++++ board/boards/white.h | 23 +- board/bootstub.c | 1 + board/drivers/can.h | 40 +- board/drivers/fan.h | 36 + board/drivers/pwm.h | 55 ++ board/drivers/rtc.h | 108 +++ board/get_sdk.sh | 2 +- board/get_sdk_mac.sh | 2 +- board/inc/cmsis_compiler.h | 3 + board/inc/cmsis_gcc.h | 4 +- board/inc/cmsis_version.h | 3 + board/inc/core_cm3.h | 4 +- board/inc/core_cm4.h | 4 +- board/inc/core_cmFunc.h | 3 - board/inc/core_cmInstr.h | 3 - board/inc/core_cmSimd.h | 3 - board/inc/mpu_armv7.h | 3 + board/main.c | 147 ++-- board/power_saving.h | 15 +- board/safety.h | 11 +- board/safety/safety_cadillac.h | 12 - board/safety/safety_chrysler.h | 1 - board/safety/safety_defaults.h | 6 - board/safety/safety_elm327.h | 1 - board/safety/safety_ford.h | 1 - board/safety/safety_gm.h | 36 - board/safety/safety_gm_ascm.h | 1 - board/safety/safety_honda.h | 8 +- board/safety/safety_hyundai.h | 1 - board/safety/safety_mazda.h | 1 - board/safety/safety_subaru.h | 1 - board/safety/safety_tesla.h | 16 - board/safety/safety_toyota.h | 1 - board/safety/safety_toyota_ipas.h | 1 - board/safety/safety_volkswagen.h | 167 +++++ board/safety_declarations.h | 3 - board/tools/enter_download_mode.py | 2 +- crypto/getcertheader.py | 1 - examples/can_bit_transition.py | 2 - examples/can_unique.py | 2 - examples/eps_read_software_ids.py | 59 ++ examples/get_panda_password.py | 1 + examples/query_vin_and_stats.py | 11 +- examples/tesla_tester.py | 4 +- python/__init__.py | 58 +- python/dfu.py | 4 +- python/esptool.py | 14 +- python/isotp.py | 18 +- python/serial.py | 5 +- python/uds.py | 770 +++++++++++++++++++++ python/update.py | 1 - requirements.txt | 10 +- setup.py | 2 +- tests/automated/0_builds.py | 1 - tests/automated/1_program.py | 4 +- tests/automated/2_usb_to_can.py | 4 +- tests/automated/3_wifi.py | 2 - tests/automated/4_wifi_functionality.py | 2 - tests/automated/5_wifi_udp.py | 2 +- tests/automated/6_two_panda.py | 2 +- tests/automated/helpers.py | 11 +- tests/black_loopback_test.py | 13 +- tests/black_white_loopback_test.py | 7 +- tests/black_white_relay_endurance.py | 19 +- tests/black_white_relay_test.py | 17 +- tests/elm_car_simulator.py | 6 +- tests/elm_wifi.py | 62 +- tests/fan_test.py | 17 + tests/gmbitbang/recv.py | 7 +- tests/gmbitbang/rigol.py | 1 + tests/gps_stability_test.py | 42 +- tests/ir_test.py | 17 + tests/language/Dockerfile | 1 - tests/language/test_language.py | 2 +- tests/linter_python/.pylintrc | 585 ++++++++++++++++ tests/linter_python/Dockerfile | 19 + tests/linter_python/flake8_panda.sh | 8 + tests/linter_python/pylint_panda.sh | 11 + tests/location_listener.py | 2 +- tests/loopback_test.py | 2 +- tests/misra/Dockerfile | 19 +- tests/misra/coverage_table | 8 +- tests/misra/suppressions.txt | 2 + tests/misra/test_misra.sh | 2 +- tests/pedal/enter_canloader.py | 1 - tests/rtc_test.py | 13 + tests/safety/Dockerfile | 5 +- tests/safety/libpandasafety_py.py | 7 + tests/safety/requirements.txt | 4 - tests/safety/test.c | 54 +- tests/safety/test.sh | 3 +- tests/safety/test_cadillac.py | 2 +- tests/safety/test_chrysler.py | 4 +- tests/safety/test_gm.py | 2 +- tests/safety/test_honda.py | 6 +- tests/safety/test_honda_bosch.py | 16 +- tests/safety/test_hyundai.py | 2 +- tests/safety/test_subaru.py | 2 +- tests/safety/test_toyota.py | 2 +- tests/safety/test_toyota_ipas.py | 6 +- tests/safety/test_volkswagen.py | 247 +++++++ tests/safety_replay/Dockerfile | 6 +- tests/safety_replay/replay_drive.py | 7 +- tests/safety_replay/requirements.txt | 8 - tests/safety_replay/requirements_extra.txt | 4 + tests/safety_replay/test_safety_replay.py | 2 +- tests/spam_can.py | 3 +- tests/throughput_test.py | 2 +- tests/tucan_loopback.py | 8 +- 123 files changed, 2974 insertions(+), 425 deletions(-) create mode 100644 board/boards/uno.h create mode 100644 board/drivers/fan.h create mode 100644 board/drivers/pwm.h create mode 100644 board/drivers/rtc.h create mode 100644 board/inc/cmsis_compiler.h create mode 100644 board/inc/cmsis_version.h delete mode 100644 board/inc/core_cmFunc.h delete mode 100644 board/inc/core_cmInstr.h delete mode 100644 board/inc/core_cmSimd.h create mode 100644 board/inc/mpu_armv7.h create mode 100644 board/safety/safety_volkswagen.h create mode 100755 examples/eps_read_software_ids.py create mode 100644 python/uds.py create mode 100755 tests/fan_test.py create mode 100755 tests/ir_test.py create mode 100644 tests/linter_python/.pylintrc create mode 100644 tests/linter_python/Dockerfile create mode 100755 tests/linter_python/flake8_panda.sh create mode 100755 tests/linter_python/pylint_panda.sh create mode 100755 tests/rtc_test.py delete mode 100644 tests/safety/requirements.txt create mode 100644 tests/safety/test_volkswagen.py delete mode 100644 tests/safety_replay/requirements.txt create mode 100644 tests/safety_replay/requirements_extra.txt diff --git a/.circleci/config.yml b/.circleci/config.yml index 6348ff0f55..58fc1d13bc 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -92,6 +92,20 @@ jobs: command: | docker run language_check /bin/bash -c "cd /panda/tests/language; ./test_language.py" + linter_python: + machine: + docker_layer_caching: true + steps: + - checkout + - run: + name: Build image + command: "docker build -t linter_python -f tests/linter_python/Dockerfile ." + - run: + name: Run linter python test + command: | + docker run linter_python /bin/bash -c "cd /panda/tests/linter_python; PYTHONPATH=/ ./flake8_panda.sh" + docker run linter_python /bin/bash -c "cd /panda/tests/linter_python; PYTHONPATH=/ ./pylint_panda.sh" + workflows: version: 2 main: @@ -101,3 +115,4 @@ workflows: - build - safety_replay - language_check + - linter_python diff --git a/Jenkinsfile b/Jenkinsfile index 7f147a2fe9..204b5beb3d 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -46,6 +46,21 @@ pipeline { } } } +/* + stage('Test Dev Build (WIFI)') { + steps { + lock(resource: "Pandas", inversePrecedence: true, quantity: 1){ + timeout(time: 60, unit: 'MINUTES') { + script { + sh "docker run --name ${env.DOCKER_NAME} --privileged --volume /dev/bus/usb:/dev/bus/usb --volume /var/run/dbus:/var/run/dbus --net host ${env.DOCKER_IMAGE_TAG} bash -c 'cd /tmp/panda; ./run_automated_tests.sh'" + sh "docker cp ${env.DOCKER_NAME}:/tmp/panda/nosetests.xml test_results_dev.xml" + sh "docker rm ${env.DOCKER_NAME}" + } + } + } + } + } +*/ } post { failure { diff --git a/README.md b/README.md index 7c9bd68bf7..634db4c120 100644 --- a/README.md +++ b/README.md @@ -108,6 +108,8 @@ to ensure that the behavior remains unchanged. * compiling the code in various configuration and flashing it both through USB and WiFi. * Receiving, sending and forwarding CAN messages on all buses, over USB and WiFi. +In addition, we run [Pylint](https://www.pylint.org/) and [Flake8](https://github.com/PyCQA/flake8) linters on all python files within the panda repo. + Hardware ------ diff --git a/UPDATING.md b/UPDATING.md index 100acc6bab..ab60f88ac8 100644 --- a/UPDATING.md +++ b/UPDATING.md @@ -1,9 +1,9 @@ # Updating your panda -Panda should update automatically via the [Chffr](http://chffr.comma.ai/) app ([apple](https://itunes.apple.com/us/app/chffr-dash-cam-that-remembers/id1146683979) and [android](https://play.google.com/store/apps/details?id=ai.comma.chffr)) +Panda should update automatically via the [openpilot](http://openpilot.comma.ai/). -If it doesn't however, you can use the following commands on linux or Mac OSX - `sudo pip install --upgrade pandacan` -` PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` - -(You'll need to have `pip` and `sudo` installed.) +On Linux or Mac OSX, you can manually update it using: +``` +sudo pip install --upgrade pandacan` +PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` +``` diff --git a/VERSION b/VERSION index 01558e339a..4279ff22f4 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -v1.5.3 \ No newline at end of file +v1.5.9 \ No newline at end of file diff --git a/__init__.py b/__init__.py index b802cf5a59..5374d5a9ab 100644 --- a/__init__.py +++ b/__init__.py @@ -1 +1 @@ -from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial +from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial # noqa: F401 diff --git a/board/README.md b/board/README.md index 5fe2e4b238..7151bfbf93 100644 --- a/board/README.md +++ b/board/README.md @@ -4,6 +4,7 @@ Dependencies **Mac** ``` +xcode-select --install ./get_sdk_mac.sh ``` diff --git a/board/board.h b/board/board.h index 154f32132e..5629a841d3 100644 --- a/board/board.h +++ b/board/board.h @@ -7,9 +7,12 @@ // ///// Board definition and detection ///// // #include "drivers/harness.h" #ifdef PANDA + #include "drivers/fan.h" + #include "drivers/rtc.h" #include "boards/white.h" #include "boards/grey.h" #include "boards/black.h" + #include "boards/uno.h" #else #include "boards/pedal.h" #endif @@ -23,6 +26,9 @@ void detect_board_type(void) { } else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K hw_type = HW_TYPE_GREY_PANDA; current_board = &board_grey; + } else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { + hw_type = HW_TYPE_UNO; + current_board = &board_uno; } else { hw_type = HW_TYPE_BLACK_PANDA; current_board = &board_black; @@ -31,7 +37,7 @@ void detect_board_type(void) { #ifdef PEDAL hw_type = HW_TYPE_PEDAL; current_board = &board_pedal; - #else + #else hw_type = HW_TYPE_UNKNOWN; puts("Hardware type is UNKNOWN!\n"); #endif @@ -60,6 +66,27 @@ void detect_configuration(void) { } // ///// Board functions ///// // +// TODO: Make these config options in the board struct bool board_has_gps(void) { - return ((hw_type == HW_TYPE_GREY_PANDA) || (hw_type == HW_TYPE_BLACK_PANDA)); -} \ No newline at end of file + return ((hw_type == HW_TYPE_GREY_PANDA) || (hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); +} + +bool board_has_gmlan(void) { + return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); +} + +bool board_has_obd(void) { + return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); +} + +bool board_has_lin(void) { + return ((hw_type == HW_TYPE_WHITE_PANDA) || (hw_type == HW_TYPE_GREY_PANDA)); +} + +bool board_has_rtc(void) { + return (hw_type == HW_TYPE_UNO); +} + +bool board_has_relay(void) { + return ((hw_type == HW_TYPE_BLACK_PANDA) || (hw_type == HW_TYPE_UNO)); +} diff --git a/board/board_declarations.h b/board/board_declarations.h index 21eb140c3e..2fd3976a0d 100644 --- a/board/board_declarations.h +++ b/board/board_declarations.h @@ -8,6 +8,9 @@ typedef void (*board_set_esp_gps_mode)(uint8_t mode); typedef void (*board_set_can_mode)(uint8_t mode); typedef void (*board_usb_power_mode_tick)(uint64_t tcnt); typedef bool (*board_check_ignition)(void); +typedef uint32_t (*board_read_current)(void); +typedef void (*board_set_ir_power)(uint8_t percentage); +typedef void (*board_set_fan_power)(uint8_t percentage); struct board { const char *board_type; @@ -21,6 +24,9 @@ struct board { board_set_can_mode set_can_mode; board_usb_power_mode_tick usb_power_mode_tick; board_check_ignition check_ignition; + board_read_current read_current; + board_set_ir_power set_ir_power; + board_set_fan_power set_fan_power; }; // ******************* Definitions ******************** @@ -30,6 +36,7 @@ struct board { #define HW_TYPE_GREY_PANDA 2U #define HW_TYPE_BLACK_PANDA 3U #define HW_TYPE_PEDAL 4U +#define HW_TYPE_UNO 5U // LED colors #define LED_RED 0U @@ -55,3 +62,11 @@ struct board { // ********************* Globals ********************** uint8_t usb_power_mode = USB_POWER_NONE; + +// ************ Board function prototypes ************* +bool board_has_gps(void); +bool board_has_gmlan(void); +bool board_has_obd(void); +bool board_has_lin(void); +bool board_has_rtc(void); +bool board_has_relay(void); \ No newline at end of file diff --git a/board/boards/black.h b/board/boards/black.h index c6078e3b56..f033e82b23 100644 --- a/board/boards/black.h +++ b/board/boards/black.h @@ -23,7 +23,8 @@ void black_enable_can_transciever(uint8_t transciever, bool enabled) { } void black_enable_can_transcievers(bool enabled) { - for(uint8_t i=1U; i<=4U; i++){ + uint8_t t1 = enabled ? 1U : 2U; // leave transciever 1 enabled to detect CAN ignition + for(uint8_t i=t1; i<=4U; i++) { black_enable_can_transciever(i, enabled); } } @@ -132,6 +133,19 @@ bool black_check_ignition(void){ return harness_check_ignition(); } +uint32_t black_read_current(void){ + // No current sense on black panda + return 0U; +} + +void black_set_ir_power(uint8_t percentage){ + UNUSED(percentage); +} + +void black_set_fan_power(uint8_t percentage){ + UNUSED(percentage); +} + void black_init(void) { common_init_gpio(); @@ -153,9 +167,6 @@ void black_init(void) { set_gpio_output(GPIOC, 10, 1); set_gpio_output(GPIOC, 11, 1); - // C8: FAN aka TIM3_CH3 - set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); - // Turn on GPS load switch. black_set_gps_load_switch(true); @@ -213,5 +224,8 @@ const board board_black = { .set_esp_gps_mode = black_set_esp_gps_mode, .set_can_mode = black_set_can_mode, .usb_power_mode_tick = black_usb_power_mode_tick, - .check_ignition = black_check_ignition + .check_ignition = black_check_ignition, + .read_current = black_read_current, + .set_fan_power = black_set_fan_power, + .set_ir_power = black_set_ir_power }; diff --git a/board/boards/common.h b/board/boards/common.h index d176e4eaf5..e33b2a2f04 100644 --- a/board/boards/common.h +++ b/board/boards/common.h @@ -58,16 +58,18 @@ void peripherals_init(void){ #endif RCC->APB1ENR |= RCC_APB1ENR_DACEN; RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; // main counter - RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; // slow loop and pedal - RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; // gmlan_alt + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; // pedal and fan PWM + RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; // gmlan_alt and IR PWM //RCC->APB1ENR |= RCC_APB1ENR_TIM5EN; //RCC->APB1ENR |= RCC_APB1ENR_TIM6EN; + RCC->APB1ENR |= RCC_APB1ENR_PWREN; // for RTC config RCC->APB2ENR |= RCC_APB2ENR_USART1EN; RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; //RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; + RCC->APB2ENR |= RCC_APB2ENR_TIM9EN; // slow loop } // Detection with internal pullup diff --git a/board/boards/grey.h b/board/boards/grey.h index 1927b54591..1a39bce07f 100644 --- a/board/boards/grey.h +++ b/board/boards/grey.h @@ -14,5 +14,8 @@ const board board_grey = { .set_esp_gps_mode = white_set_esp_gps_mode, .set_can_mode = white_set_can_mode, .usb_power_mode_tick = white_usb_power_mode_tick, - .check_ignition = white_check_ignition + .check_ignition = white_check_ignition, + .read_current = white_read_current, + .set_fan_power = white_set_fan_power, + .set_ir_power = white_set_ir_power }; \ No newline at end of file diff --git a/board/boards/pedal.h b/board/boards/pedal.h index 9209a33ba7..02612d3f09 100644 --- a/board/boards/pedal.h +++ b/board/boards/pedal.h @@ -60,6 +60,19 @@ bool pedal_check_ignition(void){ return false; } +uint32_t pedal_read_current(void){ + // No current sense on pedal + return 0U; +} + +void pedal_set_ir_power(uint8_t percentage){ + UNUSED(percentage); +} + +void pedal_set_fan_power(uint8_t percentage){ + UNUSED(percentage); +} + void pedal_init(void) { common_init_gpio(); @@ -93,4 +106,7 @@ const board board_pedal = { .set_can_mode = pedal_set_can_mode, .usb_power_mode_tick = pedal_usb_power_mode_tick, .check_ignition = pedal_check_ignition, + .read_current = pedal_read_current, + .set_fan_power = pedal_set_fan_power, + .set_ir_power = pedal_set_ir_power }; \ No newline at end of file diff --git a/board/boards/uno.h b/board/boards/uno.h new file mode 100644 index 0000000000..f5765c226f --- /dev/null +++ b/board/boards/uno.h @@ -0,0 +1,247 @@ +// ///////////// // +// Uno + Harness // +// ///////////// // + +void uno_enable_can_transciever(uint8_t transciever, bool enabled) { + switch (transciever){ + case 1U: + set_gpio_output(GPIOC, 1, !enabled); + break; + case 2U: + set_gpio_output(GPIOC, 13, !enabled); + break; + case 3U: + set_gpio_output(GPIOA, 0, !enabled); + break; + case 4U: + set_gpio_output(GPIOB, 10, !enabled); + break; + default: + puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); + break; + } +} + +void uno_enable_can_transcievers(bool enabled) { + for(uint8_t i=1U; i<=4U; i++){ + uno_enable_can_transciever(i, enabled); + } +} + +void uno_set_led(uint8_t color, bool enabled) { + switch (color){ + case LED_RED: + set_gpio_output(GPIOC, 9, !enabled); + break; + case LED_GREEN: + set_gpio_output(GPIOC, 7, !enabled); + break; + case LED_BLUE: + set_gpio_output(GPIOC, 6, !enabled); + break; + default: + break; + } +} + +void uno_set_gps_load_switch(bool enabled) { + set_gpio_output(GPIOC, 12, enabled); +} + +void uno_set_usb_power_mode(uint8_t mode) { + UNUSED(mode); + puts("Setting USB mode makes no sense on UNO\n"); +} + +void uno_set_esp_gps_mode(uint8_t mode) { + switch (mode) { + case ESP_GPS_DISABLED: + // GPS OFF + set_gpio_output(GPIOB, 1, 0); + set_gpio_output(GPIOC, 5, 0); + uno_set_gps_load_switch(false); + break; + case ESP_GPS_ENABLED: + // GPS ON + set_gpio_output(GPIOB, 1, 1); + set_gpio_output(GPIOC, 5, 1); + uno_set_gps_load_switch(true); + break; + case ESP_GPS_BOOTMODE: + set_gpio_output(GPIOB, 1, 1); + set_gpio_output(GPIOC, 5, 0); + uno_set_gps_load_switch(true); + break; + default: + puts("Invalid ESP/GPS mode\n"); + break; + } +} + +void uno_set_can_mode(uint8_t mode){ + switch (mode) { + case CAN_MODE_NORMAL: + case CAN_MODE_OBD_CAN2: + if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(car_harness_status == HARNESS_STATUS_NORMAL)) { + // B12,B13: disable OBD mode + set_gpio_mode(GPIOB, 12, MODE_INPUT); + set_gpio_mode(GPIOB, 13, MODE_INPUT); + + // B5,B6: normal CAN2 mode + set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); + set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); + } else { + // B5,B6: disable normal CAN2 mode + set_gpio_mode(GPIOB, 5, MODE_INPUT); + set_gpio_mode(GPIOB, 6, MODE_INPUT); + + // B12,B13: OBD mode + set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); + set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); + } + break; + default: + puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); + break; + } +} + +void uno_set_bootkick(bool enabled){ + set_gpio_output(GPIOB, 14, !enabled); +} + +void uno_usb_power_mode_tick(uint64_t tcnt){ + if(tcnt == 3U){ + uno_set_bootkick(false); + } +} + +bool uno_check_ignition(void){ + // ignition is checked through harness + return harness_check_ignition(); +} + +void uno_set_usb_switch(bool phone){ + set_gpio_output(GPIOB, 3, phone); +} + +void uno_set_ir_power(uint8_t percentage){ + pwm_set(TIM4, 2, percentage); +} + +void uno_set_fan_power(uint8_t percentage){ + // Enable fan power only if percentage is non-zero. + set_gpio_output(GPIOA, 1, (percentage != 0U)); + fan_set_power(percentage); +} + +uint32_t uno_read_current(void){ + // No current sense on Uno + return 0U; +} + +void uno_init(void) { + common_init_gpio(); + + // A8,A15: normal CAN3 mode + set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); + set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); + + // C0: OBD_SBU1 (orientation detection) + // C3: OBD_SBU2 (orientation detection) + set_gpio_mode(GPIOC, 0, MODE_ANALOG); + set_gpio_mode(GPIOC, 3, MODE_ANALOG); + + // C10: OBD_SBU1_RELAY (harness relay driving output) + // C11: OBD_SBU2_RELAY (harness relay driving output) + set_gpio_mode(GPIOC, 10, MODE_OUTPUT); + set_gpio_mode(GPIOC, 11, MODE_OUTPUT); + set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output(GPIOC, 10, 1); + set_gpio_output(GPIOC, 11, 1); + + // C8: FAN PWM aka TIM3_CH3 + set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); + + // Turn on GPS load switch. + uno_set_gps_load_switch(true); + + // Turn on phone regulator + set_gpio_output(GPIOB, 4, 1); + + // Initialize IR PWM and set to 0% + set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); + pwm_init(TIM4, 2); + uno_set_ir_power(0U); + + // Initialize fan and set to 0% + fan_init(); + uno_set_fan_power(0U); + + // Initialize harness + harness_init(); + + // Initialize RTC + rtc_init(); + + // Enable CAN transcievers + uno_enable_can_transcievers(true); + + // Disable LEDs + uno_set_led(LED_RED, false); + uno_set_led(LED_GREEN, false); + uno_set_led(LED_BLUE, false); + + // Set normal CAN mode + uno_set_can_mode(CAN_MODE_NORMAL); + + // flip CAN0 and CAN2 if we are flipped + if (car_harness_status == HARNESS_STATUS_NORMAL) { + can_flip_buses(0, 2); + } + + // init multiplexer + can_set_obd(car_harness_status, false); + + // Switch to phone usb mode if harness connection is powered by less than 7V + if(adc_get_voltage() < 7000U){ + uno_set_usb_switch(true); + } else { + uno_set_usb_switch(false); + } + + // Bootkick phone + uno_set_bootkick(true); +} + +const harness_configuration uno_harness_config = { + .has_harness = true, + .GPIO_SBU1 = GPIOC, + .GPIO_SBU2 = GPIOC, + .GPIO_relay_normal = GPIOC, + .GPIO_relay_flipped = GPIOC, + .pin_SBU1 = 0, + .pin_SBU2 = 3, + .pin_relay_normal = 10, + .pin_relay_flipped = 11, + .adc_channel_SBU1 = 10, + .adc_channel_SBU2 = 13 +}; + +const board board_uno = { + .board_type = "Uno", + .harness_config = &uno_harness_config, + .init = uno_init, + .enable_can_transciever = uno_enable_can_transciever, + .enable_can_transcievers = uno_enable_can_transcievers, + .set_led = uno_set_led, + .set_usb_power_mode = uno_set_usb_power_mode, + .set_esp_gps_mode = uno_set_esp_gps_mode, + .set_can_mode = uno_set_can_mode, + .usb_power_mode_tick = uno_usb_power_mode_tick, + .check_ignition = uno_check_ignition, + .read_current = uno_read_current, + .set_fan_power = uno_set_fan_power, + .set_ir_power = uno_set_ir_power +}; diff --git a/board/boards/white.h b/board/boards/white.h index 241f1b91bc..899ba8d4fe 100644 --- a/board/boards/white.h +++ b/board/boards/white.h @@ -20,8 +20,10 @@ void white_enable_can_transciever(uint8_t transciever, bool enabled) { } void white_enable_can_transcievers(bool enabled) { - for(uint8_t i=1; i<=3U; i++) + uint8_t t1 = enabled ? 1U : 2U; // leave transciever 1 enabled to detect CAN ignition + for(uint8_t i=t1; i<=3U; i++) { white_enable_can_transciever(i, enabled); + } } void white_set_led(uint8_t color, bool enabled) { @@ -150,6 +152,10 @@ void white_set_can_mode(uint8_t mode){ } } +uint32_t white_read_current(void){ + return adc_get(ADCCHAN_CURRENT); +} + uint64_t marker = 0; void white_usb_power_mode_tick(uint64_t tcnt){ @@ -158,7 +164,7 @@ void white_usb_power_mode_tick(uint64_t tcnt){ #define CURRENT_THRESHOLD 0xF00U #define CLICKS 5U // 5 seconds to switch modes - uint32_t current = adc_get(ADCCHAN_CURRENT); + uint32_t current = white_read_current(); // ~0x9a = 500 ma // puth(current); puts("\n"); @@ -217,6 +223,14 @@ void white_usb_power_mode_tick(uint64_t tcnt){ #endif } +void white_set_ir_power(uint8_t percentage){ + UNUSED(percentage); +} + +void white_set_fan_power(uint8_t percentage){ + UNUSED(percentage); +} + bool white_check_ignition(void){ // ignition is on PA1 return !get_gpio_input(GPIOA, 1); @@ -315,5 +329,8 @@ const board board_white = { .set_esp_gps_mode = white_set_esp_gps_mode, .set_can_mode = white_set_can_mode, .usb_power_mode_tick = white_usb_power_mode_tick, - .check_ignition = white_check_ignition + .check_ignition = white_check_ignition, + .read_current = white_read_current, + .set_fan_power = white_set_fan_power, + .set_ir_power = white_set_ir_power }; diff --git a/board/bootstub.c b/board/bootstub.c index 51ce6695db..8ada20c738 100644 --- a/board/bootstub.c +++ b/board/bootstub.c @@ -33,6 +33,7 @@ const board *current_board; #include "drivers/clock.h" #include "drivers/llgpio.h" #include "drivers/adc.h" +#include "drivers/pwm.h" #include "board.h" diff --git a/board/drivers/can.h b/board/drivers/can.h index c45a3fe8d1..c9bf2d2543 100644 --- a/board/drivers/can.h +++ b/board/drivers/can.h @@ -30,6 +30,9 @@ void can_init_all(void); void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number); bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem); +// Ignition detected from CAN meessages +bool ignition_can = false; + // end API #define ALL_CAN_SILENT 0xFF @@ -173,7 +176,7 @@ void can_flip_buses(uint8_t bus1, uint8_t bus2){ // TODO: Cleanup with new abstraction void can_set_gmlan(uint8_t bus) { - if(hw_type != HW_TYPE_BLACK_PANDA){ + if(board_has_gmlan()){ // first, disable GMLAN on prev bus uint8_t prev_bus = can_num_lookup[3]; if (bus != prev_bus) { @@ -226,7 +229,7 @@ void can_set_obd(uint8_t harness_orientation, bool obd){ } else { puts("setting CAN2 to be normal\n"); } - if(hw_type == HW_TYPE_BLACK_PANDA){ + if(board_has_obd()){ if(obd != (bool)(harness_orientation == HARNESS_STATUS_NORMAL)){ // B5,B6: disable normal mode set_gpio_mode(GPIOB, 5, MODE_INPUT); @@ -243,7 +246,7 @@ void can_set_obd(uint8_t harness_orientation, bool obd){ set_gpio_mode(GPIOB, 13, MODE_INPUT); } } else { - puts("OBD CAN not available on non-black panda\n"); + puts("OBD CAN not available on this board\n"); } } @@ -332,6 +335,36 @@ void process_can(uint8_t can_number) { } } +void ignition_can_hook(CAN_FIFOMailBox_TypeDef *to_push) { + + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); + int len = GET_LEN(to_push); + + if (bus == 0) { + // GM exception + if ((addr == 0x1F1) && (len == 8)) { + //Bit 5 is ignition "on" + ignition_can = (GET_BYTE(to_push, 0) & 0x20) != 0; + } + // Tesla exception + if ((addr == 0x348) && (len == 8)) { + // GTW_status + ignition_can = (GET_BYTE(to_push, 0) & 0x1) != 0; + } + // Cadillac exception + if ((addr == 0x160) && (len == 5)) { + // this message isn't all zeros when ignition is on + ignition_can = GET_BYTES_04(to_push) != 0; + } + // VW exception + if ((addr == 0x3C0) && (len == 4)) { + // VW Terminal 15 (ignition-on) state + ignition_can = (GET_BYTE(to_push, 2) & 0x2) != 0; + } + } +} + // CAN receive handlers // blink blue when we are receiving CAN messages void can_rx(uint8_t can_number) { @@ -365,6 +398,7 @@ void can_rx(uint8_t can_number) { } safety_rx_hook(&to_push); + ignition_can_hook(&to_push); current_board->set_led(LED_BLUE, true); can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; diff --git a/board/drivers/fan.h b/board/drivers/fan.h new file mode 100644 index 0000000000..d7326ec0b3 --- /dev/null +++ b/board/drivers/fan.h @@ -0,0 +1,36 @@ +void fan_init(void){ + // Init PWM speed control + pwm_init(TIM3, 3); + + // Init TACH interrupt + SYSCFG->EXTICR[0] = SYSCFG_EXTICR1_EXTI2_PD; + EXTI->IMR |= (1U << 2); + EXTI->RTSR |= (1U << 2); + EXTI->FTSR |= (1U << 2); + NVIC_EnableIRQ(EXTI2_IRQn); +} + +void fan_set_power(uint8_t percentage){ + pwm_set(TIM3, 3, percentage); +} + +uint16_t fan_tach_counter = 0U; +uint16_t fan_rpm = 0U; + +// Can be way more acurate than this, but this is probably good enough for our purposes. + +// Call this every second +void fan_tick(void){ + // 4 interrupts per rotation + fan_rpm = fan_tach_counter * 15U; + fan_tach_counter = 0U; +} + +// TACH interrupt handler +void EXTI2_IRQHandler(void) { + volatile unsigned int pr = EXTI->PR & (1U << 2); + if ((pr & (1U << 2)) != 0U) { + fan_tach_counter++; + } + EXTI->PR = (1U << 2); +} \ No newline at end of file diff --git a/board/drivers/pwm.h b/board/drivers/pwm.h new file mode 100644 index 0000000000..d2e1652c1c --- /dev/null +++ b/board/drivers/pwm.h @@ -0,0 +1,55 @@ +#define PWM_COUNTER_OVERFLOW 2000U // To get ~50kHz + +void pwm_init(TIM_TypeDef *TIM, uint8_t channel){ + // Enable timer and auto-reload + TIM->CR1 = TIM_CR1_CEN | TIM_CR1_ARPE; + + // Set channel as PWM mode 1 and enable output + switch(channel){ + case 1U: + TIM->CCMR1 |= (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE); + TIM->CCER |= TIM_CCER_CC1E; + break; + case 2U: + TIM->CCMR1 |= (TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE); + TIM->CCER |= TIM_CCER_CC2E; + break; + case 3U: + TIM->CCMR2 |= (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE); + TIM->CCER |= TIM_CCER_CC3E; + break; + case 4U: + TIM->CCMR2 |= (TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4PE); + TIM->CCER |= TIM_CCER_CC4E; + break; + default: + break; + } + + // Set max counter value + TIM->ARR = PWM_COUNTER_OVERFLOW; + + // Update registers and clear counter + TIM->EGR |= TIM_EGR_UG; +} + +// TODO: Implement for 32-bit timers +void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){ + uint16_t comp_value = (((uint16_t) percentage * PWM_COUNTER_OVERFLOW) / 100U); + switch(channel){ + case 1U: + TIM->CCR1 = comp_value; + break; + case 2U: + TIM->CCR2 = comp_value; + break; + case 3U: + TIM->CCR3 = comp_value; + break; + case 4U: + TIM->CCR4 = comp_value; + break; + default: + break; + } +} \ No newline at end of file diff --git a/board/drivers/rtc.h b/board/drivers/rtc.h new file mode 100644 index 0000000000..9cf113a02e --- /dev/null +++ b/board/drivers/rtc.h @@ -0,0 +1,108 @@ +#define RCC_BDCR_OPTIONS (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) +#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) + +#define YEAR_OFFSET 2000U + +typedef struct __attribute__((packed)) timestamp_t { + uint16_t year; + uint8_t month; + uint8_t day; + uint8_t weekday; + uint8_t hour; + uint8_t minute; + uint8_t second; +} timestamp_t; + +uint8_t to_bcd(uint16_t value){ + return (((value / 10U) & 0x0FU) << 4U) | ((value % 10U) & 0x0FU); +} + +uint16_t from_bcd(uint8_t value){ + return (((value & 0xF0U) >> 4U) * 10U) + (value & 0x0FU); +} + +void rtc_init(void){ + if(board_has_rtc()){ + // Initialize RTC module and clock if not done already. + if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ + puts("Initializing RTC\n"); + // Reset backup domain + RCC->BDCR |= RCC_BDCR_BDRST; + + // Disable write protection + PWR->CR |= PWR_CR_DBP; + + // Clear backup domain reset + RCC->BDCR &= ~(RCC_BDCR_BDRST); + + // Set RTC options + RCC->BDCR = RCC_BDCR_OPTIONS | (RCC->BDCR & (~RCC_BDCR_MASK)); + + // Enable write protection + PWR->CR &= ~(PWR_CR_DBP); + } + } +} + +void rtc_set_time(timestamp_t time){ + if(board_has_rtc()){ + puts("Setting RTC time\n"); + + // Disable write protection + PWR->CR |= PWR_CR_DBP; + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + // Enable initialization mode + RTC->ISR |= RTC_ISR_INIT; + while((RTC->ISR & RTC_ISR_INITF) == 0){} + + // Set time + RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); + RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); + + // Set options + RTC->CR = 0U; + + // Disable initalization mode + RTC->ISR &= ~(RTC_ISR_INIT); + + // Wait for synchronization + while((RTC->ISR & RTC_ISR_RSF) == 0){} + + // Re-enable write protection + RTC->WPR = 0x00; + PWR->CR &= ~(PWR_CR_DBP); + } +} + +timestamp_t rtc_get_time(void){ + timestamp_t result; + // Init with zero values in case there is no RTC running + result.year = 0U; + result.month = 0U; + result.day = 0U; + result.weekday = 0U; + result.hour = 0U; + result.minute = 0U; + result.second = 0U; + + if(board_has_rtc()){ + // Wait until the register sync flag is set + while((RTC->ISR & RTC_ISR_RSF) == 0){} + + // Read time and date registers. Since our HSE > 7*LSE, this should be fine. + uint32_t time = RTC->TR; + uint32_t date = RTC->DR; + + // Parse values + result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; + result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); + result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); + result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); + result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); + result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); + result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); + } + return result; +} \ No newline at end of file diff --git a/board/get_sdk.sh b/board/get_sdk.sh index 7b8d1f9154..3a009a5a13 100755 --- a/board/get_sdk.sh +++ b/board/get_sdk.sh @@ -1,3 +1,3 @@ #!/bin/bash sudo apt-get install gcc-arm-none-eabi python-pip -sudo pip2 install libusb1 pycrypto requests +sudo pip install libusb1 pycrypto requests diff --git a/board/get_sdk_mac.sh b/board/get_sdk_mac.sh index a6f641dce1..a0a919f7d8 100755 --- a/board/get_sdk_mac.sh +++ b/board/get_sdk_mac.sh @@ -2,4 +2,4 @@ # Need formula for gcc brew tap ArmMbed/homebrew-formulae brew install python dfu-util arm-none-eabi-gcc -pip2 install libusb1 pycrypto requests +pip install --user libusb1 pycrypto requests diff --git a/board/inc/cmsis_compiler.h b/board/inc/cmsis_compiler.h new file mode 100644 index 0000000000..28cbb46207 --- /dev/null +++ b/board/inc/cmsis_compiler.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3eeeb716701baca7c9aec136ada74ac29fa5731d188c1728f66b13e54a69ab64 +size 9482 diff --git a/board/inc/cmsis_gcc.h b/board/inc/cmsis_gcc.h index 94e69eedf9..a4f77ec5e6 100644 --- a/board/inc/cmsis_gcc.h +++ b/board/inc/cmsis_gcc.h @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:6c7e75d09887cb3035f18bc6f4fdbd7392a50379cd556315deb3bcb762d99078 -size 40062 +oid sha256:9bf43ac370e82ed7c9cc9a9fb5b624276fa03d15f96103550c7ab3b043f048f2 +size 62628 diff --git a/board/inc/cmsis_version.h b/board/inc/cmsis_version.h new file mode 100644 index 0000000000..f0827be44f --- /dev/null +++ b/board/inc/cmsis_version.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d649eaa2fb1c421add02950ab9c111ccabb8be27197f3d37e03f03357e817ff8 +size 1677 diff --git a/board/inc/core_cm3.h b/board/inc/core_cm3.h index 2ec8c848a9..655f489e03 100644 --- a/board/inc/core_cm3.h +++ b/board/inc/core_cm3.h @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:03a80f17ff18c5d0e3b234009f98698cd402b8ea972df687a6cfafd8b8a78654 -size 102146 +oid sha256:01793bb15ec31729c8d1d4422a2e86ce5e0728b6a8834b94f08ea46c4c43b3b5 +size 109421 diff --git a/board/inc/core_cm4.h b/board/inc/core_cm4.h index f3a7ca0e48..8c23dc1850 100644 --- a/board/inc/core_cm4.h +++ b/board/inc/core_cm4.h @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:83c5d601dd5640a863fe4dc43cd228b46239bbf9f07b51102bf0c1c8f235cdfa -size 112561 +oid sha256:dd13b2caea9d4490a5d49cdb86fbfa3e0d7b01343dc0ad8560c10a924626320e +size 120868 diff --git a/board/inc/core_cmFunc.h b/board/inc/core_cmFunc.h deleted file mode 100644 index 6f4be85719..0000000000 --- a/board/inc/core_cmFunc.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1fdd226d82bde2a90231ba47a59377158b8907e4cada2a6215f32dcf13ab35cd -size 3533 diff --git a/board/inc/core_cmInstr.h b/board/inc/core_cmInstr.h deleted file mode 100644 index 226e8a75e5..0000000000 --- a/board/inc/core_cmInstr.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c9b8e36d05097da5d493f197aa7f81ce517f4532536925b568ccbd6e2c01eb8a -size 3549 diff --git a/board/inc/core_cmSimd.h b/board/inc/core_cmSimd.h deleted file mode 100644 index fbec148892..0000000000 --- a/board/inc/core_cmSimd.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5d338d36730ccbd138126078e17f69c308a015f0a88d85bd639af072e527d53d -size 3566 diff --git a/board/inc/mpu_armv7.h b/board/inc/mpu_armv7.h new file mode 100644 index 0000000000..599b59d2af --- /dev/null +++ b/board/inc/mpu_armv7.h @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:16660b4b9af5c288949272e55dfc463fd704acd7bbbe34f0fa6acbdea2d41c22 +size 11691 diff --git a/board/main.c b/board/main.c index df134e046b..3bcae876e2 100644 --- a/board/main.c +++ b/board/main.c @@ -13,6 +13,7 @@ #include "drivers/llcan.h" #include "drivers/llgpio.h" #include "drivers/adc.h" +#include "drivers/pwm.h" #include "board.h" @@ -35,6 +36,10 @@ // ********************* Serial debugging ********************* +bool check_started(void) { + return current_board->check_ignition() || ignition_can; +} + void debug_ring_callback(uart_ring *ring) { char rcv; while (getc(ring, &rcv)) { @@ -80,10 +85,10 @@ void started_interrupt_handler(uint8_t interrupt_line) { #ifdef EON // set power savings mode here if on EON build - int power_save_state = current_board->check_ignition() ? POWER_SAVE_STATUS_DISABLED : POWER_SAVE_STATUS_ENABLED; + int power_save_state = check_started() ? POWER_SAVE_STATUS_DISABLED : POWER_SAVE_STATUS_ENABLED; set_power_save_state(power_save_state); // set CDP usb power mode everytime that the car starts to make sure EON is charging - if (current_board->check_ignition()) { + if (check_started()) { current_board->set_usb_power_mode(USB_POWER_CDP); } #endif @@ -117,7 +122,7 @@ void set_safety_mode(uint16_t mode, int16_t param) { switch (mode) { case SAFETY_NOOUTPUT: set_intercept_relay(false); - if(hw_type == HW_TYPE_BLACK_PANDA){ + if(board_has_obd()){ current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_SILENT; @@ -125,7 +130,7 @@ void set_safety_mode(uint16_t mode, int16_t param) { case SAFETY_ELM327: set_intercept_relay(false); heartbeat_counter = 0U; - if(hw_type == HW_TYPE_BLACK_PANDA){ + if(board_has_obd()){ current_board->set_can_mode(CAN_MODE_OBD_CAN2); } can_silent = ALL_CAN_LIVE; @@ -133,19 +138,12 @@ void set_safety_mode(uint16_t mode, int16_t param) { default: set_intercept_relay(true); heartbeat_counter = 0U; - if(hw_type == HW_TYPE_BLACK_PANDA){ + if(board_has_obd()){ current_board->set_can_mode(CAN_MODE_NORMAL); } can_silent = ALL_CAN_LIVE; break; } - if (safety_ignition_hook() != -1) { - // if the ignition hook depends on something other than the started GPIO - // we have to disable power savings (fix for GM and Tesla) - set_power_save_state(POWER_SAVE_STATUS_DISABLED); - } else { - // power mode is already POWER_SAVE_STATUS_DISABLED and CAN TXs are active - } can_init_all(); } } @@ -159,30 +157,21 @@ int get_health_pkt(void *dat) { uint32_t can_send_errs_pkt; uint32_t can_fwd_errs_pkt; uint32_t gmlan_send_errs_pkt; - uint8_t started_pkt; + uint8_t ignition_line_pkt; + uint8_t ignition_can_pkt; uint8_t controls_allowed_pkt; uint8_t gas_interceptor_detected_pkt; uint8_t car_harness_status_pkt; uint8_t usb_power_mode_pkt; + uint8_t safety_mode_pkt; } *health = dat; health->voltage_pkt = adc_get_voltage(); + health->current_pkt = current_board->read_current(); - // No current sense on panda black - if(hw_type != HW_TYPE_BLACK_PANDA){ - health->current_pkt = adc_get(ADCCHAN_CURRENT); - } else { - health->current_pkt = 0; - } - - int safety_ignition = safety_ignition_hook(); - if (safety_ignition < 0) { - //Use the GPIO pin to determine ignition - health->started_pkt = (uint8_t)(current_board->check_ignition()); - } else { - //Current safety hooks want to determine ignition (ex: GM) - health->started_pkt = safety_ignition; - } + //Use the GPIO pin to determine ignition or use a CAN based logic + health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); + health->ignition_can_pkt = (uint8_t)(ignition_can); health->controls_allowed_pkt = controls_allowed; health->gas_interceptor_detected_pkt = gas_interceptor_detected; @@ -191,10 +180,17 @@ int get_health_pkt(void *dat) { health->gmlan_send_errs_pkt = gmlan_send_errs; health->car_harness_status_pkt = car_harness_status; health->usb_power_mode_pkt = usb_power_mode; + health->safety_mode_pkt = (uint8_t)(current_safety_mode); return sizeof(*health); } +int get_rtc_pkt(void *dat) { + timestamp_t t = rtc_get_time(); + (void)memcpy(dat, &t, sizeof(t)); + return sizeof(t); +} + int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { UNUSED(hardwired); CAN_FIFOMailBox_TypeDef *reply = (CAN_FIFOMailBox_TypeDef *)usbdata; @@ -247,7 +243,76 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) unsigned int resp_len = 0; uart_ring *ur = NULL; int i; + timestamp_t t; switch (setup->b.bRequest) { + // **** 0xa0: get rtc time + case 0xa0: + resp_len = get_rtc_pkt(resp); + break; + // **** 0xa1: set rtc year + case 0xa1: + t = rtc_get_time(); + t.year = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa2: set rtc month + case 0xa2: + t = rtc_get_time(); + t.month = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa3: set rtc day + case 0xa3: + t = rtc_get_time(); + t.day = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa4: set rtc weekday + case 0xa4: + t = rtc_get_time(); + t.weekday = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa5: set rtc hour + case 0xa5: + t = rtc_get_time(); + t.hour = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa6: set rtc minute + case 0xa6: + t = rtc_get_time(); + t.minute = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa7: set rtc second + case 0xa7: + t = rtc_get_time(); + t.second = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xb0: set IR power + case 0xb0: + if(power_save_status == POWER_SAVE_STATUS_DISABLED){ + current_board->set_ir_power(setup->b.wValue.w); + } else { + puts("Setting IR power not allowed in power saving mode\n"); + } + break; + // **** 0xb1: set fan power + case 0xb1: + if(power_save_status == POWER_SAVE_STATUS_DISABLED){ + current_board->set_fan_power(setup->b.wValue.w); + } else { + puts("Setting fan power not allowed in power saving mode\n"); + } + break; + // **** 0xb2: get fan rpm + case 0xb2: + resp[0] = (fan_rpm & 0x00FFU); + resp[1] = ((fan_rpm & 0xFF00U) >> 8U); + resp_len = 2; + break; // **** 0xc0: get CAN debug info case 0xc0: puts("can tx: "); puth(can_tx_cnt); @@ -335,7 +400,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode case 0xdb: - if(hw_type == HW_TYPE_BLACK_PANDA){ + if(board_has_obd()){ if (setup->b.wValue.w == 1U) { // Enable OBD CAN current_board->set_can_mode(CAN_MODE_OBD_CAN2); @@ -583,8 +648,8 @@ uint64_t tcnt = 0; // called once per second // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck -void TIM3_IRQHandler(void) { - if (TIM3->SR != 0) { +void TIM1_BRK_TIM9_IRQHandler(void) { + if (TIM9->SR != 0) { can_live = pending_can_live; current_board->usb_power_mode_tick(tcnt); @@ -602,6 +667,10 @@ void TIM3_IRQHandler(void) { puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); #endif + // Tick fan driver + fan_tick(); + //puts("Fan speed: "); puth((unsigned int) fan_rpm); puts("rpm\n"); + // set green LED to be controls allowed current_board->set_led(LED_GREEN, controls_allowed); @@ -616,7 +685,7 @@ void TIM3_IRQHandler(void) { // check heartbeat counter if we are running EON code. If the heartbeat has been gone for a while, go to NOOUTPUT safety mode. #ifdef EON - if (heartbeat_counter >= (current_board->check_ignition() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { + if (heartbeat_counter >= (check_started() ? EON_HEARTBEAT_IGNITION_CNT_ON : EON_HEARTBEAT_IGNITION_CNT_OFF)) { puts("EON hasn't sent a heartbeat for 0x"); puth(heartbeat_counter); puts(" seconds. Safety is set to NOOUTPUT mode.\n"); if(current_safety_mode != SAFETY_NOOUTPUT){ set_safety_mode(SAFETY_NOOUTPUT, 0U); @@ -627,7 +696,7 @@ void TIM3_IRQHandler(void) { // on to the next one tcnt += 1U; } - TIM3->SR = 0; + TIM9->SR = 0; } int main(void) { @@ -675,8 +744,7 @@ int main(void) { uart_init(&uart_ring_esp_gps, 115200); } - // there is no LIN on panda black - if(hw_type != HW_TYPE_BLACK_PANDA){ + if(board_has_lin()){ // enable LIN uart_init(&uart_ring_lin1, 10400); UART5->CR2 |= USART_CR2_LINEN; @@ -714,14 +782,13 @@ int main(void) { current_board->set_esp_gps_mode(ESP_GPS_DISABLED); } // only enter power save after the first cycle - /*if (current_board->check_ignition()) { + /*if (check_started()) { set_power_save_state(POWER_SAVE_STATUS_ENABLED); }*/ #endif - - // 48mhz / 65536 ~= 732 / 732 = 1 - timer_init(TIM3, 732); - NVIC_EnableIRQ(TIM3_IRQn); + // 1hz + timer_init(TIM9, 1464); + NVIC_EnableIRQ(TIM1_BRK_TIM9_IRQn); #ifdef DEBUG puts("DEBUG ENABLED\n"); diff --git a/board/power_saving.h b/board/power_saving.h index 0a926c119d..d397884f6e 100644 --- a/board/power_saving.h +++ b/board/power_saving.h @@ -25,7 +25,6 @@ void set_power_save_state(int state) { enable = true; } - // Switch CAN transcievers current_board->enable_can_transcievers(enable); // Switch EPS/GPS @@ -34,17 +33,25 @@ void set_power_save_state(int state) { } else { current_board->set_esp_gps_mode(ESP_GPS_DISABLED); } - - if(hw_type != HW_TYPE_BLACK_PANDA){ + + if(board_has_gmlan()){ // turn on GMLAN set_gpio_output(GPIOB, 14, enable); set_gpio_output(GPIOB, 15, enable); + } - // turn on LIN + if(board_has_lin()){ + // turn on LIN set_gpio_output(GPIOB, 7, enable); set_gpio_output(GPIOA, 14, enable); } + // Switch off IR and fan when in power saving + if(!enable){ + current_board->set_ir_power(0U); + current_board->set_fan_power(0U); + } + power_save_status = state; } } diff --git a/board/safety.h b/board/safety.h index ffdfebb454..c68eda2c4a 100644 --- a/board/safety.h +++ b/board/safety.h @@ -14,6 +14,7 @@ #include "safety/safety_chrysler.h" #include "safety/safety_subaru.h" #include "safety/safety_mazda.h" +#include "safety/safety_volkswagen.h" #include "safety/safety_elm327.h" // from cereal.car.CarParams.SafetyModel @@ -29,8 +30,8 @@ #define SAFETY_CHRYSLER 9U #define SAFETY_TESLA 10U #define SAFETY_SUBARU 11U -#define SAFETY_GM_PASSIVE 12U #define SAFETY_MAZDA 13U +#define SAFETY_VOLKSWAGEN 15U #define SAFETY_TOYOTA_IPAS 16U #define SAFETY_ALLOUTPUT 17U #define SAFETY_GM_ASCM 18U @@ -50,12 +51,6 @@ int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){ return current_hooks->tx_lin(lin_num, data, len); } -// -1 = Disabled (Use GPIO to determine ignition) -// 0 = Off (not started) -// 1 = On (started) -int safety_ignition_hook() { - return current_hooks->ignition(); -} int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { return current_hooks->fwd(bus_num, to_fwd); } @@ -78,8 +73,8 @@ const safety_hook_config safety_hook_registry[] = { {SAFETY_CHRYSLER, &chrysler_hooks}, {SAFETY_TESLA, &tesla_hooks}, {SAFETY_SUBARU, &subaru_hooks}, - {SAFETY_GM_PASSIVE, &gm_passive_hooks}, {SAFETY_MAZDA, &mazda_hooks}, + {SAFETY_VOLKSWAGEN, &volkswagen_hooks}, {SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, {SAFETY_ALLOUTPUT, &alloutput_hooks}, {SAFETY_GM_ASCM, &gm_ascm_hooks}, diff --git a/board/safety/safety_cadillac.h b/board/safety/safety_cadillac.h index ef63360955..4ae2045505 100644 --- a/board/safety/safety_cadillac.h +++ b/board/safety/safety_cadillac.h @@ -10,7 +10,6 @@ const int CADILLAC_MAX_RATE_DOWN = 5; const int CADILLAC_DRIVER_TORQUE_ALLOWANCE = 50; const int CADILLAC_DRIVER_TORQUE_FACTOR = 4; -bool cadillac_ign = 0; int cadillac_cruise_engaged_last = 0; int cadillac_rt_torque_last = 0; const int cadillac_torque_msgs_n = 4; @@ -35,11 +34,6 @@ static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { update_sample(&cadillac_torque_driver, torque_driver_new); } - // this message isn't all zeros when ignition is on - if ((addr == 0x160) && (bus == 0)) { - cadillac_ign = GET_BYTES_04(to_push) != 0; - } - // enter controls on rising edge of ACC, exit controls on ACC off if ((addr == 0x370) && (bus == 0)) { int cruise_engaged = GET_BYTE(to_push, 2) & 0x80; // bit 23 @@ -118,11 +112,6 @@ static int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { static void cadillac_init(int16_t param) { UNUSED(param); controls_allowed = 0; - cadillac_ign = 0; -} - -static int cadillac_ign_hook(void) { - return cadillac_ign; } const safety_hooks cadillac_hooks = { @@ -130,6 +119,5 @@ const safety_hooks cadillac_hooks = { .rx = cadillac_rx_hook, .tx = cadillac_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = cadillac_ign_hook, .fwd = default_fwd_hook, }; diff --git a/board/safety/safety_chrysler.h b/board/safety/safety_chrysler.h index e608785739..9b8fc36154 100644 --- a/board/safety/safety_chrysler.h +++ b/board/safety/safety_chrysler.h @@ -136,6 +136,5 @@ const safety_hooks chrysler_hooks = { .rx = chrysler_rx_hook, .tx = chrysler_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = chrysler_fwd_hook, }; diff --git a/board/safety/safety_defaults.h b/board/safety/safety_defaults.h index 9dc23b54b7..2743db96fe 100644 --- a/board/safety/safety_defaults.h +++ b/board/safety/safety_defaults.h @@ -2,10 +2,6 @@ void default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { UNUSED(to_push); } -int default_ign_hook(void) { - return -1; // use GPIO to determine ignition -} - // *** no output safety mode *** static void nooutput_init(int16_t param) { @@ -36,7 +32,6 @@ const safety_hooks nooutput_hooks = { .rx = default_rx_hook, .tx = nooutput_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = default_fwd_hook, }; @@ -64,6 +59,5 @@ const safety_hooks alloutput_hooks = { .rx = default_rx_hook, .tx = alloutput_tx_hook, .tx_lin = alloutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = default_fwd_hook, }; diff --git a/board/safety/safety_elm327.h b/board/safety/safety_elm327.h index bbad909f28..ce405b4767 100644 --- a/board/safety/safety_elm327.h +++ b/board/safety/safety_elm327.h @@ -38,6 +38,5 @@ const safety_hooks elm327_hooks = { .rx = default_rx_hook, .tx = elm327_tx_hook, .tx_lin = elm327_tx_lin_hook, - .ignition = default_ign_hook, .fwd = default_fwd_hook, }; diff --git a/board/safety/safety_ford.h b/board/safety/safety_ford.h index 0bb839f2f6..22fc604ff1 100644 --- a/board/safety/safety_ford.h +++ b/board/safety/safety_ford.h @@ -97,6 +97,5 @@ const safety_hooks ford_hooks = { .rx = ford_rx_hook, .tx = ford_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = default_fwd_hook, }; diff --git a/board/safety/safety_gm.h b/board/safety/safety_gm.h index ed8217fc02..452f70953d 100644 --- a/board/safety/safety_gm.h +++ b/board/safety/safety_gm.h @@ -24,7 +24,6 @@ int gm_gas_prev = 0; bool gm_moving = false; // silence everything if stock car control ECUs are still online bool gm_ascm_detected = 0; -bool gm_ignition_started = 0; int gm_rt_torque_last = 0; int gm_desired_torque_last = 0; uint32_t gm_ts_last = 0; @@ -41,13 +40,6 @@ static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { update_sample(&gm_torque_driver, torque_driver_new); } - if ((addr == 0x1F1) && (bus_number == 0)) { - //Bit 5 should be ignition "on" - //Backup plan is Bit 2 (accessory power) - bool ign = (GET_BYTE(to_push, 0) & 0x20) != 0; - gm_ignition_started = ign; - } - // sample speed, really only care if car is moving or not // rear left wheel speed if (addr == 842) { @@ -224,41 +216,13 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { static void gm_init(int16_t param) { UNUSED(param); controls_allowed = 0; - gm_ignition_started = 0; -} - -static int gm_ign_hook(void) { - return gm_ignition_started; } -// All sending is disallowed. -// The only difference from "no output" model -// is using GM ignition hook. - -static void gm_passive_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { - int bus_number = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if ((addr == 0x1F1) && (bus_number == 0)) { - bool ign = (GET_BYTE(to_push, 0) & 0x20) != 0; - gm_ignition_started = ign; - } -} const safety_hooks gm_hooks = { .init = gm_init, .rx = gm_rx_hook, .tx = gm_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = gm_ign_hook, - .fwd = default_fwd_hook, -}; - -const safety_hooks gm_passive_hooks = { - .init = gm_init, - .rx = gm_passive_rx_hook, - .tx = nooutput_tx_hook, - .tx_lin = nooutput_tx_lin_hook, - .ignition = gm_ign_hook, .fwd = default_fwd_hook, }; diff --git a/board/safety/safety_gm_ascm.h b/board/safety/safety_gm_ascm.h index 82f1db6ae5..36fd1d8f2a 100644 --- a/board/safety/safety_gm_ascm.h +++ b/board/safety/safety_gm_ascm.h @@ -39,7 +39,6 @@ const safety_hooks gm_ascm_hooks = { .rx = default_rx_hook, .tx = alloutput_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = gm_ascm_fwd_hook, }; diff --git a/board/safety/safety_honda.h b/board/safety/safety_honda.h index ebaa15642a..f59e288812 100644 --- a/board/safety/safety_honda.h +++ b/board/safety/safety_honda.h @@ -156,7 +156,7 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW // ensuring that only the cancel button press is sent (VAL 2) when controls are off. // This avoids unintended engagements while still allowing resume spam - int bus_pt = ((hw_type == HW_TYPE_BLACK_PANDA) && honda_bosch_hardware)? 1 : 0; + int bus_pt = ((board_has_relay()) && honda_bosch_hardware)? 1 : 0; if ((addr == 0x296) && honda_bosch_hardware && !current_controls_allowed && (bus == bus_pt)) { if (((GET_BYTE(to_send, 0) >> 5) & 0x7) != 2) { @@ -210,8 +210,8 @@ static int honda_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { int bus_fwd = -1; - int bus_rdr_cam = (hw_type == HW_TYPE_BLACK_PANDA) ? 2 : 1; // radar bus, camera side - int bus_rdr_car = (hw_type == HW_TYPE_BLACK_PANDA) ? 0 : 2; // radar bus, car side + int bus_rdr_cam = (board_has_relay()) ? 2 : 1; // radar bus, camera side + int bus_rdr_car = (board_has_relay()) ? 0 : 2; // radar bus, car side if (bus_num == bus_rdr_car) { bus_fwd = bus_rdr_cam; @@ -231,7 +231,6 @@ const safety_hooks honda_hooks = { .rx = honda_rx_hook, .tx = honda_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = honda_fwd_hook, }; @@ -240,6 +239,5 @@ const safety_hooks honda_bosch_hooks = { .rx = honda_rx_hook, .tx = honda_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = honda_bosch_fwd_hook, }; diff --git a/board/safety/safety_hyundai.h b/board/safety/safety_hyundai.h index aed30621f4..21796e4caa 100644 --- a/board/safety/safety_hyundai.h +++ b/board/safety/safety_hyundai.h @@ -155,6 +155,5 @@ const safety_hooks hyundai_hooks = { .rx = hyundai_rx_hook, .tx = hyundai_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = hyundai_fwd_hook, }; diff --git a/board/safety/safety_mazda.h b/board/safety/safety_mazda.h index 63fbcdfd6f..60d8b2bda9 100644 --- a/board/safety/safety_mazda.h +++ b/board/safety/safety_mazda.h @@ -164,6 +164,5 @@ const safety_hooks mazda_hooks = { .rx = mazda_rx_hook, .tx = mazda_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = mazda_fwd_hook, }; diff --git a/board/safety/safety_subaru.h b/board/safety/safety_subaru.h index 5b482973e6..c09b9d6225 100644 --- a/board/safety/safety_subaru.h +++ b/board/safety/safety_subaru.h @@ -124,6 +124,5 @@ const safety_hooks subaru_hooks = { .rx = subaru_rx_hook, .tx = subaru_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = subaru_fwd_hook, }; diff --git a/board/safety/safety_tesla.h b/board/safety/safety_tesla.h index 188b12ac48..2e5d20c622 100644 --- a/board/safety/safety_tesla.h +++ b/board/safety/safety_tesla.h @@ -39,9 +39,6 @@ int tesla_gas_prev = 0; int tesla_speed = 0; int eac_status = 0; -int tesla_ignition_started = 0; - - void set_gmlan_digital_output(int to_set); void reset_gmlan_switch_timeout(void); void gmlan_switch_init(int timeout_enable); @@ -66,13 +63,6 @@ static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { } } - // Detect drive rail on (ignition) (start recording) - if (addr == 0x348) { - // GTW_status - int drive_rail_on = GET_BYTE(to_push, 0) & 0x1; - tesla_ignition_started = drive_rail_on == 1; - } - // exit controls on brake press // DI_torque2::DI_brakePedal 0x118 if (addr == 0x118) { @@ -183,14 +173,9 @@ static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { static void tesla_init(int16_t param) { UNUSED(param); controls_allowed = 0; - tesla_ignition_started = 0; gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled } -static int tesla_ign_hook(void) { - return tesla_ignition_started; -} - static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { int bus_fwd = -1; @@ -224,6 +209,5 @@ const safety_hooks tesla_hooks = { .rx = tesla_rx_hook, .tx = tesla_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = tesla_ign_hook, .fwd = tesla_fwd_hook, }; diff --git a/board/safety/safety_toyota.h b/board/safety/safety_toyota.h index c1ce996058..134cc845c9 100644 --- a/board/safety/safety_toyota.h +++ b/board/safety/safety_toyota.h @@ -224,6 +224,5 @@ const safety_hooks toyota_hooks = { .rx = toyota_rx_hook, .tx = toyota_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = toyota_fwd_hook, }; diff --git a/board/safety/safety_toyota_ipas.h b/board/safety/safety_toyota_ipas.h index 3e3a3b3a24..d5833e45db 100644 --- a/board/safety/safety_toyota_ipas.h +++ b/board/safety/safety_toyota_ipas.h @@ -164,6 +164,5 @@ const safety_hooks toyota_ipas_hooks = { .rx = toyota_ipas_rx_hook, .tx = toyota_ipas_tx_hook, .tx_lin = nooutput_tx_lin_hook, - .ignition = default_ign_hook, .fwd = toyota_fwd_hook, }; diff --git a/board/safety/safety_volkswagen.h b/board/safety/safety_volkswagen.h new file mode 100644 index 0000000000..bb184cd91f --- /dev/null +++ b/board/safety/safety_volkswagen.h @@ -0,0 +1,167 @@ +const int VOLKSWAGEN_MAX_STEER = 250; // 2.5 Nm (EPS side max of 3.0Nm with fault if violated) +const int VOLKSWAGEN_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 +const uint32_t VOLKSWAGEN_RT_INTERVAL = 250000; // 250ms between real time checks +const int VOLKSWAGEN_MAX_RATE_UP = 4; // 2.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s) +const int VOLKSWAGEN_MAX_RATE_DOWN = 10; // 5.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s) +const int VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE = 80; +const int VOLKSWAGEN_DRIVER_TORQUE_FACTOR = 3; + +struct sample_t volkswagen_torque_driver; // last few driver torques measured +int volkswagen_rt_torque_last = 0; +int volkswagen_desired_torque_last = 0; +uint32_t volkswagen_ts_last = 0; +int volkswagen_gas_prev = 0; + +// Safety-relevant CAN messages for the Volkswagen MQB platform. +#define MSG_EPS_01 0x09F +#define MSG_MOTOR_20 0x121 +#define MSG_ACC_06 0x122 +#define MSG_HCA_01 0x126 +#define MSG_GRA_ACC_01 0x12B +#define MSG_LDW_02 0x397 +#define MSG_KLEMMEN_STATUS_01 0x3C0 + +static void volkswagen_init(int16_t param) { + UNUSED(param); // May use param in the future to indicate MQB vs PQ35/PQ46/NMS vs MLB, or wiring configuration. + controls_allowed = 0; +} + +static void volkswagen_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); + + // Update driver input torque samples from EPS_01.Driver_Strain for absolute torque, and EPS_01.Driver_Strain_VZ + // for the direction. + if ((bus == 0) && (addr == MSG_EPS_01)) { + int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1F) << 8); + int sign = (GET_BYTE(to_push, 6) & 0x80) >> 7; + if (sign == 1) { + torque_driver_new *= -1; + } + + update_sample(&volkswagen_torque_driver, torque_driver_new); + } + + // Monitor ACC_06.ACC_Status_ACC for stock ACC status. Because the current MQB port is lateral-only, OP's control + // allowed state is directly driven by stock ACC engagement. Permit the ACC message to come from either bus, in + // order to accommodate future camera-side integrations if needed. + if (addr == MSG_ACC_06) { + int acc_status = (GET_BYTE(to_push, 7) & 0x70) >> 4; + controls_allowed = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0; + } + + // exit controls on rising edge of gas press. Bits [12-20) + if (addr == MSG_MOTOR_20) { + int gas = (GET_BYTES_04(to_push) >> 12) & 0xFF; + if ((gas > 0) && (volkswagen_gas_prev == 0) && long_controls_allowed) { + controls_allowed = 0; + } + volkswagen_gas_prev = gas; + } +} + +static int volkswagen_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + int addr = GET_ADDR(to_send); + int bus = GET_BUS(to_send); + int tx = 1; + + // Safety check for HCA_01 Heading Control Assist torque. + if (addr == MSG_HCA_01) { + bool violation = false; + + int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x3F) << 8); + int sign = (GET_BYTE(to_send, 3) & 0x80) >> 7; + if (sign == 1) { + desired_torque *= -1; + } + + uint32_t ts = TIM2->CNT; + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, VOLKSWAGEN_MAX_STEER, -VOLKSWAGEN_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, volkswagen_desired_torque_last, &volkswagen_torque_driver, + VOLKSWAGEN_MAX_STEER, VOLKSWAGEN_MAX_RATE_UP, VOLKSWAGEN_MAX_RATE_DOWN, + VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_DRIVER_TORQUE_FACTOR); + volkswagen_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, volkswagen_rt_torque_last, VOLKSWAGEN_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, volkswagen_ts_last); + if (ts_elapsed > VOLKSWAGEN_RT_INTERVAL) { + volkswagen_rt_torque_last = desired_torque; + volkswagen_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = true; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + volkswagen_desired_torque_last = 0; + volkswagen_rt_torque_last = 0; + volkswagen_ts_last = ts; + } + + if (violation) { + tx = 0; + } + } + + // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. + // This avoids unintended engagements while still allowing resume spam + if ((bus == 2) && (addr == MSG_GRA_ACC_01) && !controls_allowed) { + // disallow resume and set: bits 16 and 19 + if ((GET_BYTE(to_send, 2) & 0x9) != 0) { + tx = 0; + } + } + + // 1 allows the message through + return tx; +} + +static int volkswagen_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + int addr = GET_ADDR(to_fwd); + int bus_fwd = -1; + + // NOTE: Will need refactoring for other bus layouts, such as no-forwarding at camera or J533 running-gear CAN + + switch (bus_num) { + case 0: + // Forward all traffic from J533 gateway to Extended CAN devices. + bus_fwd = 2; + break; + case 2: + if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { + // OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera. + bus_fwd = -1; + } else { + // Forward all remaining traffic from Extended CAN devices to J533 gateway. + bus_fwd = 0; + } + break; + default: + // No other buses should be in use; fallback to do-not-forward. + bus_fwd = -1; + break; + } + + return bus_fwd; +} + +const safety_hooks volkswagen_hooks = { + .init = volkswagen_init, + .rx = volkswagen_rx_hook, + .tx = volkswagen_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .fwd = volkswagen_fwd_hook, +}; diff --git a/board/safety_declarations.h b/board/safety_declarations.h index 7e0a54d73e..efa6a4e2b8 100644 --- a/board/safety_declarations.h +++ b/board/safety_declarations.h @@ -14,7 +14,6 @@ struct lookup_t { void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); -int safety_ignition_hook(void); 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); @@ -31,12 +30,10 @@ typedef void (*safety_hook_init)(int16_t param); typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push); typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send); typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); -typedef int (*ign_hook)(void); typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd); typedef struct { safety_hook_init init; - ign_hook ignition; rx_hook rx; tx_hook tx; tx_lin_hook tx_lin; diff --git a/board/tools/enter_download_mode.py b/board/tools/enter_download_mode.py index 3dd6545f4c..17d30dda11 100755 --- a/board/tools/enter_download_mode.py +++ b/board/tools/enter_download_mode.py @@ -11,7 +11,7 @@ def enter_download_mode(device): try: handle.controlWrite(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd1, 0, 0, b'') - except (usb1.USBErrorIO, usb1.USBErrorPipe) as e: + except (usb1.USBErrorIO, usb1.USBErrorPipe): print("Device download mode enabled.") time.sleep(1) else: diff --git a/crypto/getcertheader.py b/crypto/getcertheader.py index b323cd101d..bbbe475ef8 100755 --- a/crypto/getcertheader.py +++ b/crypto/getcertheader.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import sys -import struct from Crypto.PublicKey import RSA def egcd(a, b): diff --git a/examples/can_bit_transition.py b/examples/can_bit_transition.py index 1cd72a6831..aa4aa9df95 100755 --- a/examples/can_bit_transition.py +++ b/examples/can_bit_transition.py @@ -1,6 +1,4 @@ #!/usr/bin/env python3 - -import binascii import csv import sys diff --git a/examples/can_unique.py b/examples/can_unique.py index 05f24a7d91..fdd586c3d3 100755 --- a/examples/can_unique.py +++ b/examples/can_unique.py @@ -13,10 +13,8 @@ # 0,344,c000c00000000000 -import binascii import csv import sys -from panda import Panda class Message(): """Details about a specific message ID.""" diff --git a/examples/eps_read_software_ids.py b/examples/eps_read_software_ids.py new file mode 100755 index 0000000000..a3292207c7 --- /dev/null +++ b/examples/eps_read_software_ids.py @@ -0,0 +1,59 @@ +#!/usr/bin/env python3 +from panda import Panda +from panda.python.uds import UdsClient, NegativeResponseError, DATA_IDENTIFIER_TYPE + +if __name__ == "__main__": + address = 0x18da30f1 # Honda EPS + panda = Panda() + uds_client = UdsClient(panda, address, debug=False) + + print("tester present ...") + uds_client.tester_present() + + try: + print("") + print("read data by id: boot software id ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.BOOT_SOFTWARE_IDENTIFICATION) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) + + try: + print("") + print("read data by id: application software id ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) + + try: + print("") + print("read data by id: application data id ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) + + try: + print("") + print("read data by id: boot software fingerprint ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.BOOT_SOFTWARE_FINGERPRINT) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) + + try: + print("") + print("read data by id: application software fingerprint ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_FINGERPRINT) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) + + try: + print("") + print("read data by id: application data fingerprint ...") + data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_FINGERPRINT) + print(data.decode('utf-8')) + except NegativeResponseError as e: + print(e) diff --git a/examples/get_panda_password.py b/examples/get_panda_password.py index 13dacf2534..54cbe57ec3 100644 --- a/examples/get_panda_password.py +++ b/examples/get_panda_password.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import sys from panda import Panda def get_panda_password(): diff --git a/examples/query_vin_and_stats.py b/examples/query_vin_and_stats.py index 9a0df78ec1..f8b5d9b2eb 100755 --- a/examples/query_vin_and_stats.py +++ b/examples/query_vin_and_stats.py @@ -8,9 +8,10 @@ from panda.python.isotp import isotp_send, isotp_recv # 0x7e0 = Toyota # 0x18DB33F1 for Honda? + def get_current_data_for_pid(pid): # 01 xx = Show current data - isotp_send(panda, "\x01"+chr(pid), 0x7e0) + isotp_send(panda, b"\x01"+ bytes([pid]), 0x7e0) return isotp_recv(panda, 0x7e8) def get_supported_pids(): @@ -33,15 +34,15 @@ if __name__ == "__main__": panda.can_clear(0) # 09 02 = Get VIN - isotp_send(panda, "\x09\x02", 0x7df) + isotp_send(panda, b"\x09\x02", 0x7df) ret = isotp_recv(panda, 0x7e8) hexdump(ret) - print("VIN: %s" % ret[2:]) + print("VIN: %s" % "".join(map(chr, ret[:2]))) # 03 = get DTCS - isotp_send(panda, "\x03", 0x7e0) + isotp_send(panda, b"\x03", 0x7e0) dtcs = isotp_recv(panda, 0x7e8) - print("DTCs:", dtcs[2:].encode("hex")) + print("DTCs:", "".join(map(chr, dtcs[:2]))) supported_pids = get_supported_pids() print("Supported PIDs:",supported_pids) diff --git a/examples/tesla_tester.py b/examples/tesla_tester.py index 74f19f2552..9a77eb4edf 100644 --- a/examples/tesla_tester.py +++ b/examples/tesla_tester.py @@ -29,11 +29,11 @@ def tesla_tester(): # BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock: print("Unlocking Tesla...") - p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num) + p.can_send(0x248, b"\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num) #Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both) print("Opening Frunk...") - p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num) + p.can_send(0x248, b"\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num) #Back to safety... print("Disabling output on Panda...") diff --git a/python/__init__.py b/python/__init__.py index 565770918a..326128d3ec 100644 --- a/python/__init__.py +++ b/python/__init__.py @@ -1,5 +1,5 @@ # python library to interface with panda - +import datetime import binascii import struct import hashlib @@ -10,10 +10,10 @@ import time import traceback import subprocess from .dfu import PandaDFU -from .esptool import ESPROM, CesantaFlasher -from .flash_release import flash_release -from .update import ensure_st_up_to_date -from .serial import PandaSerial +from .esptool import ESPROM, CesantaFlasher # noqa: F401 +from .flash_release import flash_release # noqa: F401 +from .update import ensure_st_up_to_date # noqa: F401 +from .serial import PandaSerial # noqa: F401 from .isotp import isotp_send, isotp_recv __version__ = '0.0.9' @@ -27,10 +27,10 @@ def build_st(target, mkfile="Makefile"): from panda import BASEDIR cmd = 'cd %s && make -f %s clean && make -f %s %s >/dev/null' % (os.path.join(BASEDIR, "board"), mkfile, mkfile, target) try: - output = subprocess.check_output(cmd, stderr=subprocess.STDOUT, shell=True) - except subprocess.CalledProcessError as exception: - output = exception.output - returncode = exception.returncode + _ = subprocess.check_output(cmd, stderr=subprocess.STDOUT, shell=True) + except subprocess.CalledProcessError: + #output = exception.output + #returncode = exception.returncode raise def parse_can_buffer(dat): @@ -122,8 +122,8 @@ class Panda(object): SAFETY_CHRYSLER = 9 SAFETY_TESLA = 10 SAFETY_SUBARU = 11 - SAFETY_GM_PASSIVE = 12 SAFETY_MAZDA = 13 + SAFETY_VOLKSWAGEN = 15 SAFETY_TOYOTA_IPAS = 16 SAFETY_ALLOUTPUT = 17 SAFETY_GM_ASCM = 18 @@ -144,6 +144,7 @@ class Panda(object): HW_TYPE_GREY_PANDA = b'\x02' HW_TYPE_BLACK_PANDA = b'\x03' HW_TYPE_PEDAL = b'\x04' + HW_TYPE_UNO = b'\x05' def __init__(self, serial=None, claim=True): self._serial = serial @@ -382,11 +383,14 @@ class Panda(object): def is_black(self): return self.get_type() == Panda.HW_TYPE_BLACK_PANDA + def is_uno(self): + return self.get_type() == Panda.HW_TYPE_UNO + def get_serial(self): dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20) hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4] assert(hashsig == calc_hash) - return [dat[0:0x10], dat[0x10:0x10+10]] + return [dat[0:0x10].decode("utf8"), dat[0x10:0x10+10].decode("utf8")] def get_secret(self): return self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 1, 0, 0x10) @@ -557,7 +561,7 @@ class Panda(object): def kline_ll_recv(self, cnt, bus=2): echo = bytearray() while len(echo) != cnt: - ret = str(self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))) + ret = self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo)) if DEBUG and len(ret) > 0: print("kline recv: " + binascii.hexlify(ret)) echo += ret @@ -577,7 +581,7 @@ class Panda(object): ts = x[i:i+0xf] if DEBUG: print("kline send: " + binascii.hexlify(ts)) - self._handle.bulkWrite(2, chr(bus).encode()+ts) + self._handle.bulkWrite(2, bytes([bus]) + ts) echo = self.kline_ll_recv(len(ts), bus=bus) if echo != ts: print("**** ECHO ERROR %d ****" % i) @@ -592,3 +596,31 @@ class Panda(object): def send_heartbeat(self): self._handle.controlWrite(Panda.REQUEST_OUT, 0xf3, 0, 0, b'') + + # ******************* RTC ******************* + def set_datetime(self, dt): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa1, int(dt.year), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa2, int(dt.month), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa3, int(dt.day), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa4, int(dt.isoweekday()), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa5, int(dt.hour), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa6, int(dt.minute), 0, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xa7, int(dt.second), 0, b'') + + def get_datetime(self): + dat = self._handle.controlRead(Panda.REQUEST_IN, 0xa0, 0, 0, 8) + a = struct.unpack("HBBBBBB", dat) + return datetime.datetime(a[0], a[1], a[2], a[4], a[5], a[6]) + + # ******************* IR ******************* + def set_ir_power(self, percentage): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xb0, int(percentage), 0, b'') + + # ******************* Fan ****************** + def set_fan_power(self, percentage): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xb1, int(percentage), 0, b'') + + def get_fan_rpm(self): + dat = self._handle.controlRead(Panda.REQUEST_IN, 0xb2, 0, 0, 2) + a = struct.unpack("H", dat) + return a[0] \ No newline at end of file diff --git a/python/dfu.py b/python/dfu.py index bbab812b07..d9d619a822 100644 --- a/python/dfu.py +++ b/python/dfu.py @@ -1,8 +1,6 @@ - import os import usb1 import struct -import time import binascii # *** DFU mode *** @@ -116,6 +114,6 @@ class PandaDFU(object): self.status() try: self._handle.controlWrite(0x21, DFU_DNLOAD, 2, 0, b"") - stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) + _ = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) except Exception: pass diff --git a/python/esptool.py b/python/esptool.py index 941c3557c8..74e383eb08 100755 --- a/python/esptool.py +++ b/python/esptool.py @@ -29,7 +29,7 @@ import subprocess import sys import tempfile import time -import traceback +#import traceback import usb1 __version__ = "1.2" @@ -44,7 +44,7 @@ class FakePort(object): @property def baudrate(self): - return self._baudrate + return self.baudrate @baudrate.setter def baudrate(self, x): @@ -434,7 +434,7 @@ class BaseFirmwareImage(object): def write_v1_header(self, f, segments): f.write(struct.pack('>8)) + chr(len(x)&0xFF)).encode("utf8") + x[0:5] + ss = bytes([subaddr, 0x10 + (len(x) >> 8), len(x) & 0xFF]) + x[0:5] x = x[5:] else: - ss = (chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF)).encode("utf8") + x[0:6] + ss = bytes([0x10 + (len(x) >> 8), len(x) & 0xFF]) + x[0:6] x = x[6:] idx = 1 sends = [] while len(x) > 0: if subaddr: - sends.append((((chr(subaddr) + chr(0x20 + (idx&0xF))).encode('utf8') + x[0:6]).ljust(8, b"\x00"))) + sends.append(((bytes([subaddr, 0x20 + (idx & 0xF)]) + x[0:6]).ljust(8, b"\x00"))) x = x[6:] else: - sends.append(((chr(0x20 + (idx&0xF)).encode("utf8") + x[0:7]).ljust(8, b"\x00"))) + sends.append(((bytes([0x20 + (idx & 0xF)]) + x[0:7]).ljust(8, b"\x00"))) x = x[7:] idx += 1 @@ -107,7 +107,7 @@ def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None): else: msg = recv(panda, 1, addr, bus)[0] - if msg[0]&0xf0 == 0x10: + if msg[0] & 0xf0 == 0x10: # first tlen = ((msg[0] & 0xf) << 8) | msg[1] dat = msg[2:] @@ -122,7 +122,7 @@ def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None): assert mm[0] == (0x20 | (idx&0xF)) dat += mm[1:] idx += 1 - elif msg[0]&0xf0 == 0x00: + elif msg[0] & 0xf0 == 0x00: # single tlen = msg[0] & 0xf dat = msg[1:] diff --git a/python/serial.py b/python/serial.py index 72ab3de92b..4d900cf29f 100644 --- a/python/serial.py +++ b/python/serial.py @@ -19,10 +19,7 @@ class PandaSerial(object): def write(self, dat): #print "W: ", dat.encode("hex") #print ' pigeon_send("' + ''.join(map(lambda x: "\\x%02X" % ord(x), dat)) + '");' - if(isinstance(dat, bytes)): - return self.panda.serial_write(self.port, dat) - else: - return self.panda.serial_write(self.port, str.encode(dat)) + return self.panda.serial_write(self.port, dat) def close(self): pass diff --git a/python/uds.py b/python/uds.py new file mode 100644 index 0000000000..5f5ae53bfb --- /dev/null +++ b/python/uds.py @@ -0,0 +1,770 @@ +#!/usr/bin/env python3 +import time +import struct +from typing import NamedTuple, List +from enum import IntEnum +from queue import Queue, Empty +from threading import Thread +from binascii import hexlify + +class SERVICE_TYPE(IntEnum): + DIAGNOSTIC_SESSION_CONTROL = 0x10 + ECU_RESET = 0x11 + SECURITY_ACCESS = 0x27 + COMMUNICATION_CONTROL = 0x28 + TESTER_PRESENT = 0x3E + ACCESS_TIMING_PARAMETER = 0x83 + SECURED_DATA_TRANSMISSION = 0x84 + CONTROL_DTC_SETTING = 0x85 + RESPONSE_ON_EVENT = 0x86 + LINK_CONTROL = 0x87 + READ_DATA_BY_IDENTIFIER = 0x22 + READ_MEMORY_BY_ADDRESS = 0x23 + READ_SCALING_DATA_BY_IDENTIFIER = 0x24 + READ_DATA_BY_PERIODIC_IDENTIFIER = 0x2A + DYNAMICALLY_DEFINE_DATA_IDENTIFIER = 0x2C + WRITE_DATA_BY_IDENTIFIER = 0x2E + WRITE_MEMORY_BY_ADDRESS = 0x3D + CLEAR_DIAGNOSTIC_INFORMATION = 0x14 + READ_DTC_INFORMATION = 0x19 + INPUT_OUTPUT_CONTROL_BY_IDENTIFIER = 0x2F + ROUTINE_CONTROL = 0x31 + REQUEST_DOWNLOAD = 0x34 + REQUEST_UPLOAD = 0x35 + TRANSFER_DATA = 0x36 + REQUEST_TRANSFER_EXIT = 0x37 + +class SESSION_TYPE(IntEnum): + DEFAULT = 1 + PROGRAMMING = 2 + EXTENDED_DIAGNOSTIC = 3 + SAFETY_SYSTEM_DIAGNOSTIC = 4 + +class RESET_TYPE(IntEnum): + HARD = 1 + KEY_OFF_ON = 2 + SOFT = 3 + ENABLE_RAPID_POWER_SHUTDOWN = 4 + DISABLE_RAPID_POWER_SHUTDOWN = 5 + +class ACCESS_TYPE(IntEnum): + REQUEST_SEED = 1 + SEND_KEY = 2 + +class CONTROL_TYPE(IntEnum): + ENABLE_RX_ENABLE_TX = 0 + ENABLE_RX_DISABLE_TX = 1 + DISABLE_RX_ENABLE_TX = 2 + DISABLE_RX_DISABLE_TX = 3 + +class MESSAGE_TYPE(IntEnum): + NORMAL = 1 + NETWORK_MANAGEMENT = 2 + NORMAL_AND_NETWORK_MANAGEMENT = 3 + +class TIMING_PARAMETER_TYPE(IntEnum): + READ_EXTENDED_SET = 1 + SET_TO_DEFAULT_VALUES = 2 + READ_CURRENTLY_ACTIVE = 3 + SET_TO_GIVEN_VALUES = 4 + +class DTC_SETTING_TYPE(IntEnum): + ON = 1 + OFF = 2 + +class RESPONSE_EVENT_TYPE(IntEnum): + STOP_RESPONSE_ON_EVENT = 0 + ON_DTC_STATUS_CHANGE = 1 + ON_TIMER_INTERRUPT = 2 + ON_CHANGE_OF_DATA_IDENTIFIER = 3 + REPORT_ACTIVATED_EVENTS = 4 + START_RESPONSE_ON_EVENT = 5 + CLEAR_RESPONSE_ON_EVENT = 6 + ON_COMPARISON_OF_VALUES = 7 + +class LINK_CONTROL_TYPE(IntEnum): + VERIFY_BAUDRATE_TRANSITION_WITH_FIXED_BAUDRATE = 1 + VERIFY_BAUDRATE_TRANSITION_WITH_SPECIFIC_BAUDRATE = 2 + TRANSITION_BAUDRATE = 3 + +class BAUD_RATE_TYPE(IntEnum): + PC9600 = 1 + PC19200 = 2 + PC38400 = 3 + PC57600 = 4 + PC115200 = 5 + CAN125000 = 16 + CAN250000 = 17 + CAN500000 = 18 + CAN1000000 = 19 + +class DATA_IDENTIFIER_TYPE(IntEnum): + BOOT_SOFTWARE_IDENTIFICATION = 0xF180 + APPLICATION_SOFTWARE_IDENTIFICATION = 0xF181 + APPLICATION_DATA_IDENTIFICATION = 0xF182 + BOOT_SOFTWARE_FINGERPRINT = 0xF183 + APPLICATION_SOFTWARE_FINGERPRINT = 0xF184 + APPLICATION_DATA_FINGERPRINT = 0xF185 + ACTIVE_DIAGNOSTIC_SESSION = 0xF186 + VEHICLE_MANUFACTURER_SPARE_PART_NUMBER = 0xF187 + VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER = 0xF188 + VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER = 0xF189 + SYSTEM_SUPPLIER_IDENTIFIER = 0xF18A + ECU_MANUFACTURING_DATE = 0xF18B + ECU_SERIAL_NUMBER = 0xF18C + SUPPORTED_FUNCTIONAL_UNITS = 0xF18D + VEHICLE_MANUFACTURER_KIT_ASSEMBLY_PART_NUMBER = 0xF18E + VIN = 0xF190 + VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER = 0xF191 + SYSTEM_SUPPLIER_ECU_HARDWARE_NUMBER = 0xF192 + SYSTEM_SUPPLIER_ECU_HARDWARE_VERSION_NUMBER = 0xF193 + SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER = 0xF194 + SYSTEM_SUPPLIER_ECU_SOFTWARE_VERSION_NUMBER = 0xF195 + EXHAUST_REGULATION_OR_TYPE_APPROVAL_NUMBER = 0xF196 + SYSTEM_NAME_OR_ENGINE_TYPE = 0xF197 + REPAIR_SHOP_CODE_OR_TESTER_SERIAL_NUMBER = 0xF198 + PROGRAMMING_DATE = 0xF199 + CALIBRATION_REPAIR_SHOP_CODE_OR_CALIBRATION_EQUIPMENT_SERIAL_NUMBER = 0xF19A + CALIBRATION_DATE = 0xF19B + CALIBRATION_EQUIPMENT_SOFTWARE_NUMBER = 0xF19C + ECU_INSTALLATION_DATE = 0xF19D + ODX_FILE = 0xF19E + ENTITY = 0xF19F + +class TRANSMISSION_MODE_TYPE(IntEnum): + SEND_AT_SLOW_RATE = 1 + SEND_AT_MEDIUM_RATE = 2 + SEND_AT_FAST_RATE = 3 + STOP_SENDING = 4 + +class DYNAMIC_DEFINITION_TYPE(IntEnum): + DEFINE_BY_IDENTIFIER = 1 + DEFINE_BY_MEMORY_ADDRESS = 2 + CLEAR_DYNAMICALLY_DEFINED_DATA_IDENTIFIER = 3 + +class DynamicSourceDefinition(NamedTuple): + data_identifier: int + position: int + memory_size: int + memory_address: int + +class DTC_GROUP_TYPE(IntEnum): + EMISSIONS = 0x000000 + ALL = 0xFFFFFF + +class DTC_REPORT_TYPE(IntEnum): + NUMBER_OF_DTC_BY_STATUS_MASK = 0x01 + DTC_BY_STATUS_MASK = 0x02 + DTC_SNAPSHOT_IDENTIFICATION = 0x03 + DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER = 0x04 + DTC_SNAPSHOT_RECORD_BY_RECORD_NUMBER = 0x05 + DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER = 0x06 + NUMBER_OF_DTC_BY_SEVERITY_MASK_RECORD = 0x07 + DTC_BY_SEVERITY_MASK_RECORD = 0x08 + SEVERITY_INFORMATION_OF_DTC = 0x09 + SUPPORTED_DTC = 0x0A + FIRST_TEST_FAILED_DTC = 0x0B + FIRST_CONFIRMED_DTC = 0x0C + MOST_RECENT_TEST_FAILED_DTC = 0x0D + MOST_RECENT_CONFIRMED_DTC = 0x0E + MIRROR_MEMORY_DTC_BY_STATUS_MASK = 0x0F + MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER = 0x10 + NUMBER_OF_MIRROR_MEMORY_DTC_BY_STATUS_MASK = 0x11 + NUMBER_OF_EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK = 0x12 + EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK = 0x13 + DTC_FAULT_DETECTION_COUNTER = 0x14 + DTC_WITH_PERMANENT_STATUS = 0x15 + +class DTC_STATUS_MASK_TYPE(IntEnum): + TEST_FAILED = 0x01 + TEST_FAILED_THIS_OPERATION_CYCLE = 0x02 + PENDING_DTC = 0x04 + CONFIRMED_DTC = 0x08 + TEST_NOT_COMPLETED_SINCE_LAST_CLEAR = 0x10 + TEST_FAILED_SINCE_LAST_CLEAR = 0x20 + TEST_NOT_COMPLETED_THIS_OPERATION_CYCLE = 0x40 + WARNING_INDICATOR_REQUESTED = 0x80 + ALL = 0xFF + +class DTC_SEVERITY_MASK_TYPE(IntEnum): + MAINTENANCE_ONLY = 0x20 + CHECK_AT_NEXT_HALT = 0x40 + CHECK_IMMEDIATELY = 0x80 + ALL = 0xE0 + +class CONTROL_PARAMETER_TYPE(IntEnum): + RETURN_CONTROL_TO_ECU = 0 + RESET_TO_DEFAULT = 1 + FREEZE_CURRENT_STATE = 2 + SHORT_TERM_ADJUSTMENT = 3 + +class ROUTINE_CONTROL_TYPE(IntEnum): + START = 1 + STOP = 2 + REQUEST_RESULTS = 3 + +class ROUTINE_IDENTIFIER_TYPE(IntEnum): + ERASE_MEMORY = 0xFF00 + CHECK_PROGRAMMING_DEPENDENCIES = 0xFF01 + ERASE_MIRROR_MEMORY_DTCS = 0xFF02 + +class MessageTimeoutError(Exception): + pass + +class NegativeResponseError(Exception): + def __init__(self, message, service_id, error_code): + self.message = message + self.service_id = service_id + self.error_code = error_code + + def __str__(self): + return self.message + +class InvalidServiceIdError(Exception): + pass + +class InvalidSubFunctioneError(Exception): + pass + +_negative_response_codes = { + 0x00: 'positive response', + 0x10: 'general reject', + 0x11: 'service not supported', + 0x12: 'sub-function not supported', + 0x13: 'incorrect message length or invalid format', + 0x14: 'response too long', + 0x21: 'busy repeat request', + 0x22: 'conditions not correct', + 0x24: 'request sequence error', + 0x25: 'no response from subnet component', + 0x26: 'failure prevents execution of requested action', + 0x31: 'request out of range', + 0x33: 'security access denied', + 0x35: 'invalid key', + 0x36: 'exceed numebr of attempts', + 0x37: 'required time delay not expired', + 0x70: 'upload download not accepted', + 0x71: 'transfer data suspended', + 0x72: 'general programming failure', + 0x73: 'wrong block sequence counter', + 0x78: 'request correctly received - response pending', + 0x7e: 'sub-function not supported in active session', + 0x7f: 'service not supported in active session', + 0x81: 'rpm too high', + 0x82: 'rpm too low', + 0x83: 'engine is running', + 0x84: 'engine is not running', + 0x85: 'engine run time too low', + 0x86: 'temperature too high', + 0x87: 'temperature too low', + 0x88: 'vehicle speed too high', + 0x89: 'vehicle speed too low', + 0x8a: 'throttle/pedal too high', + 0x8b: 'throttle/pedal too low', + 0x8c: 'transmission not in neutral', + 0x8d: 'transmission not in gear', + 0x8f: 'brake switch(es) not closed', + 0x90: 'shifter lever not in park', + 0x91: 'torque converter clutch locked', + 0x92: 'voltage too high', + 0x93: 'voltage too low', +} + +class IsoTpMessage(): + def __init__(self, can_tx_queue: Queue, can_rx_queue: Queue, timeout: float, debug: bool=False): + self.can_tx_queue = can_tx_queue + self.can_rx_queue = can_rx_queue + self.timeout = timeout + self.debug = debug + + def send(self, dat: bytes) -> None: + self.tx_dat = dat + self.tx_len = len(dat) + self.tx_idx = 0 + self.tx_done = False + + if self.debug: print(f"ISO-TP: REQUEST - {hexlify(self.tx_dat)}") + self._tx_first_frame() + + def _tx_first_frame(self) -> None: + if self.tx_len < 8: + # single frame (send all bytes) + if self.debug: print("ISO-TP: TX - single frame") + msg = (bytes([self.tx_len]) + self.tx_dat).ljust(8, b"\x00") + self.tx_done = True + else: + # first frame (send first 6 bytes) + if self.debug: print("ISO-TP: TX - first frame") + msg = (struct.pack("!H", 0x1000 | self.tx_len) + self.tx_dat[:6]).ljust(8, b"\x00") + self.can_tx_queue.put(msg) + + def recv(self) -> bytes: + self.rx_dat = b"" + self.rx_len = 0 + self.rx_idx = 0 + self.rx_done = False + + try: + while True: + self._isotp_rx_next() + if self.tx_done and self.rx_done: + return self.rx_dat + except Empty: + raise MessageTimeoutError("timeout waiting for response") + finally: + if self.debug: print(f"ISO-TP: RESPONSE - {hexlify(self.rx_dat)}") + + def _isotp_rx_next(self) -> None: + rx_data = self.can_rx_queue.get(block=True, timeout=self.timeout) + + # single rx_frame + if rx_data[0] >> 4 == 0x0: + self.rx_len = rx_data[0] & 0xFF + self.rx_dat = rx_data[1:1+self.rx_len] + self.rx_idx = 0 + self.rx_done = True + if self.debug: print(f"ISO-TP: RX - single frame - idx={self.rx_idx} done={self.rx_done}") + return + + # first rx_frame + if rx_data[0] >> 4 == 0x1: + self.rx_len = ((rx_data[0] & 0x0F) << 8) + rx_data[1] + self.rx_dat = rx_data[2:] + self.rx_idx = 0 + self.rx_done = False + if self.debug: print(f"ISO-TP: RX - first frame - idx={self.rx_idx} done={self.rx_done}") + if self.debug: print(f"ISO-TP: TX - flow control continue") + # send flow control message (send all bytes) + msg = b"\x30\x00\x00".ljust(8, b"\x00") + self.can_tx_queue.put(msg) + return + + # consecutive rx frame + if rx_data[0] >> 4 == 0x2: + assert self.rx_done == False, "isotp - rx: consecutive frame with no active frame" + self.rx_idx += 1 + assert self.rx_idx & 0xF == rx_data[0] & 0xF, "isotp - rx: invalid consecutive frame index" + rx_size = self.rx_len - len(self.rx_dat) + self.rx_dat += rx_data[1:1+min(rx_size, 7)] + if self.rx_len == len(self.rx_dat): + self.rx_done = True + if self.debug: print(f"ISO-TP: RX - consecutive frame - idx={self.rx_idx} done={self.rx_done}") + return + + # flow control + if rx_data[0] >> 4 == 0x3: + assert self.tx_done == False, "isotp - rx: flow control with no active frame" + assert rx_data[0] != 0x32, "isotp - rx: flow-control overflow/abort" + assert rx_data[0] == 0x30 or rx_data[0] == 0x31, "isotp - rx: flow-control transfer state indicator invalid" + if rx_data[0] == 0x30: + if self.debug: print("ISO-TP: RX - flow control continue") + delay_ts = rx_data[2] & 0x7F + # scale is 1 milliseconds if first bit == 0, 100 micro seconds if first bit == 1 + delay_div = 1000. if rx_data[2] & 0x80 == 0 else 10000. + # first frame = 6 bytes, each consecutive frame = 7 bytes + start = 6 + self.tx_idx * 7 + count = rx_data[1] + end = start + count * 7 if count > 0 else self.tx_len + for i in range(start, end, 7): + if delay_ts > 0 and i > start: + delay_s = delay_ts / delay_div + if self.debug: print(f"ISO-TP: TX - delay - seconds={delay_s}") + time.sleep(delay_s) + self.tx_idx += 1 + # consecutive tx frames + msg = (bytes([0x20 | (self.tx_idx & 0xF)]) + self.tx_dat[i:i+7]).ljust(8, b"\x00") + self.can_tx_queue.put(msg) + if end >= self.tx_len: + self.tx_done = True + if self.debug: print(f"ISO-TP: TX - consecutive frame - idx={self.tx_idx} done={self.tx_done}") + elif rx_data[0] == 0x31: + # wait (do nothing until next flow control message) + if self.debug: print("ISO-TP: TX - flow control wait") + +class UdsClient(): + def __init__(self, panda, tx_addr: int, rx_addr: int=None, bus: int=0, timeout: float=10, debug: bool=False): + self.panda = panda + self.bus = bus + self.tx_addr = tx_addr + if rx_addr == None: + if tx_addr < 0xFFF8: + # standard 11 bit response addr (add 8) + self.rx_addr = tx_addr+8 + elif tx_addr > 0x10000000 and tx_addr < 0xFFFFFFFF: + # standard 29 bit response addr (flip last two bytes) + self.rx_addr = (tx_addr & 0xFFFF0000) + (tx_addr<<8 & 0xFF00) + (tx_addr>>8 & 0xFF) + else: + raise ValueError("invalid tx_addr: {}".format(tx_addr)) + + self.can_tx_queue = Queue() + self.can_rx_queue = Queue() + self.timeout = timeout + self.debug = debug + + self.can_thread = Thread(target=self._can_thread, args=(self.debug,)) + self.can_thread.daemon = True + self.can_thread.start() + + def _can_thread(self, debug: bool=False): + try: + # allow all output + self.panda.set_safety_mode(0x1337) + # clear tx buffer + self.panda.can_clear(self.bus) + # clear rx buffer + self.panda.can_clear(0xFFFF) + + while True: + # send + while not self.can_tx_queue.empty(): + msg = self.can_tx_queue.get(block=False) + if debug: print("CAN-TX: {} - {}".format(hex(self.tx_addr), hexlify(msg))) + self.panda.can_send(self.tx_addr, msg, self.bus) + + # receive + msgs = self.panda.can_recv() + for rx_addr, rx_ts, rx_data, rx_bus in msgs: + if rx_bus != self.bus or rx_addr != self.rx_addr or len(rx_data) == 0: + continue + if debug: print("CAN-RX: {} - {}".format(hex(self.rx_addr), hexlify(rx_data))) + self.can_rx_queue.put(rx_data) + else: + time.sleep(0.01) + finally: + self.panda.close() + + # generic uds request + def _uds_request(self, service_type: SERVICE_TYPE, subfunction: int=None, data: bytes=None) -> bytes: + req = bytes([service_type]) + if subfunction is not None: + req += bytes([subfunction]) + if data is not None: + req += data + + # send request, wait for response + isotp_msg = IsoTpMessage(self.can_tx_queue, self.can_rx_queue, self.timeout, self.debug) + isotp_msg.send(req) + while True: + resp = isotp_msg.recv() + resp_sid = resp[0] if len(resp) > 0 else None + + # negative response + if resp_sid == 0x7F: + service_id = resp[1] if len(resp) > 1 else -1 + try: + service_desc = SERVICE_TYPE(service_id).name + except Exception: + service_desc = 'NON_STANDARD_SERVICE' + error_code = resp[2] if len(resp) > 2 else -1 + try: + error_desc = _negative_response_codes[error_code] + except Exception: + error_desc = resp[3:] + # wait for another message if response pending + if error_code == 0x78: + if self.debug: print("UDS-RX: response pending") + continue + raise NegativeResponseError('{} - {}'.format(service_desc, error_desc), service_id, error_code) + + # positive response + if service_type+0x40 != resp_sid: + resp_sid_hex = hex(resp_sid) if resp_sid is not None else None + raise InvalidServiceIdError('invalid response service id: {}'.format(resp_sid_hex)) + + if subfunction is not None: + resp_sfn = resp[1] if len(resp) > 1 else None + if subfunction != resp_sfn: + resp_sfn_hex = hex(resp_sfn) if resp_sfn is not None else None + raise InvalidSubFunctioneError('invalid response subfunction: {}'.format(hex(resp_sfn_hex))) + + # return data (exclude service id and sub-function id) + return resp[(1 if subfunction is None else 2):] + + # services + def diagnostic_session_control(self, session_type: SESSION_TYPE): + self._uds_request(SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, subfunction=session_type) + + def ecu_reset(self, reset_type: RESET_TYPE): + resp = self._uds_request(SERVICE_TYPE.ECU_RESET, subfunction=reset_type) + power_down_time = None + if reset_type == RESET_TYPE.ENABLE_RAPID_POWER_SHUTDOWN: + power_down_time = resp[0] + return power_down_time + + def security_access(self, access_type: ACCESS_TYPE, security_key: bytes=None): + request_seed = access_type % 2 != 0 + if request_seed and security_key is not None: + raise ValueError('security_key not allowed') + if not request_seed and security_key is None: + raise ValueError('security_key is missing') + resp = self._uds_request(SERVICE_TYPE.SECURITY_ACCESS, subfunction=access_type, data=security_key) + if request_seed: + security_seed = resp + return security_seed + + def communication_control(self, control_type: CONTROL_TYPE, message_type: MESSAGE_TYPE): + data = bytes([message_type]) + self._uds_request(SERVICE_TYPE.COMMUNICATION_CONTROL, subfunction=control_type, data=data) + + def tester_present(self, ): + self._uds_request(SERVICE_TYPE.TESTER_PRESENT, subfunction=0x00) + + def access_timing_parameter(self, timing_parameter_type: TIMING_PARAMETER_TYPE, parameter_values: bytes=None): + write_custom_values = timing_parameter_type == TIMING_PARAMETER_TYPE.SET_TO_GIVEN_VALUES + read_values = ( + timing_parameter_type == TIMING_PARAMETER_TYPE.READ_CURRENTLY_ACTIVE or + timing_parameter_type == TIMING_PARAMETER_TYPE.READ_EXTENDED_SET + ) + if not write_custom_values and parameter_values is not None: + raise ValueError('parameter_values not allowed') + if write_custom_values and parameter_values is None: + raise ValueError('parameter_values is missing') + resp = self._uds_request(SERVICE_TYPE.ACCESS_TIMING_PARAMETER, subfunction=timing_parameter_type, data=parameter_values) + if read_values: + # TODO: parse response into values? + parameter_values = resp + return parameter_values + + def secured_data_transmission(self, data: bytes): + # TODO: split data into multiple input parameters? + resp = self._uds_request(SERVICE_TYPE.SECURED_DATA_TRANSMISSION, subfunction=None, data=data) + # TODO: parse response into multiple output values? + return resp + + def control_dtc_setting(self, dtc_setting_type: DTC_SETTING_TYPE): + self._uds_request(SERVICE_TYPE.CONTROL_DTC_SETTING, subfunction=dtc_setting_type) + + def response_on_event(self, response_event_type: RESPONSE_EVENT_TYPE, store_event: bool, window_time: int, event_type_record: int, service_response_record: int): + if store_event: + response_event_type |= 0x20 + # TODO: split record parameters into arrays + data = bytes([window_time, event_type_record, service_response_record]) + resp = self._uds_request(SERVICE_TYPE.RESPONSE_ON_EVENT, subfunction=response_event_type, data=data) + + if response_event_type == RESPONSE_EVENT_TYPE.REPORT_ACTIVATED_EVENTS: + return { + "num_of_activated_events": resp[0], + "data": resp[1:], # TODO: parse the reset of response + } + + return { + "num_of_identified_events": resp[0], + "event_window_time": resp[1], + "data": resp[2:], # TODO: parse the reset of response + } + + def link_control(self, link_control_type: LINK_CONTROL_TYPE, baud_rate_type: BAUD_RATE_TYPE=None): + if link_control_type == LINK_CONTROL_TYPE.VERIFY_BAUDRATE_TRANSITION_WITH_FIXED_BAUDRATE: + # baud_rate_type = BAUD_RATE_TYPE + data = bytes([baud_rate_type]) + elif link_control_type == LINK_CONTROL_TYPE.VERIFY_BAUDRATE_TRANSITION_WITH_SPECIFIC_BAUDRATE: + # baud_rate_type = custom value (3 bytes big-endian) + data = struct.pack('!I', baud_rate_type)[1:] + else: + data = None + self._uds_request(SERVICE_TYPE.LINK_CONTROL, subfunction=link_control_type, data=data) + + def read_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE): + # TODO: support list of identifiers + data = struct.pack('!H', data_identifier_type) + resp = self._uds_request(SERVICE_TYPE.READ_DATA_BY_IDENTIFIER, subfunction=None, data=data) + resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None + if resp_id != data_identifier_type: + raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) + return resp[2:] + + def read_memory_by_address(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=1): + if memory_address_bytes < 1 or memory_address_bytes > 4: + raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) + if memory_size_bytes < 1 or memory_size_bytes > 4: + raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) + data = bytes([memory_size_bytes<<4 | memory_address_bytes]) + + if memory_address >= 1<<(memory_address_bytes*8): + raise ValueError('invalid memory_address: {}'.format(memory_address)) + data += struct.pack('!I', memory_address)[4-memory_address_bytes:] + if memory_size >= 1<<(memory_size_bytes*8): + raise ValueError('invalid memory_size: {}'.format(memory_size)) + data += struct.pack('!I', memory_size)[4-memory_size_bytes:] + + resp = self._uds_request(SERVICE_TYPE.READ_MEMORY_BY_ADDRESS, subfunction=None, data=data) + return resp + + def read_scaling_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE): + data = struct.pack('!H', data_identifier_type) + resp = self._uds_request(SERVICE_TYPE.READ_SCALING_DATA_BY_IDENTIFIER, subfunction=None, data=data) + resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None + if resp_id != data_identifier_type: + raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) + return resp[2:] # TODO: parse the response + + def read_data_by_periodic_identifier(self, transmission_mode_type: TRANSMISSION_MODE_TYPE, periodic_data_identifier: int): + # TODO: support list of identifiers + data = bytes([transmission_mode_type, periodic_data_identifier]) + self._uds_request(SERVICE_TYPE.READ_DATA_BY_PERIODIC_IDENTIFIER, subfunction=None, data=data) + + def dynamically_define_data_identifier(self, dynamic_definition_type: DYNAMIC_DEFINITION_TYPE, dynamic_data_identifier: int, source_definitions: List[DynamicSourceDefinition], memory_address_bytes: int=4, memory_size_bytes: int=1): + if memory_address_bytes < 1 or memory_address_bytes > 4: + raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) + if memory_size_bytes < 1 or memory_size_bytes > 4: + raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) + + data = struct.pack('!H', dynamic_data_identifier) + if dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.DEFINE_BY_IDENTIFIER: + for s in source_definitions: + data += struct.pack('!H', s["data_identifier"]) + bytes([s["position"], s["memory_size"]]) + elif dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.DEFINE_BY_MEMORY_ADDRESS: + data += bytes([memory_size_bytes<<4 | memory_address_bytes]) + for s in source_definitions: + if s["memory_address"] >= 1<<(memory_address_bytes*8): + raise ValueError('invalid memory_address: {}'.format(s["memory_address"])) + data += struct.pack('!I', s["memory_address"])[4-memory_address_bytes:] + if s["memory_size"] >= 1<<(memory_size_bytes*8): + raise ValueError('invalid memory_size: {}'.format(s["memory_size"])) + data += struct.pack('!I', s["memory_size"])[4-memory_size_bytes:] + elif dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.CLEAR_DYNAMICALLY_DEFINED_DATA_IDENTIFIER: + pass + else: + raise ValueError('invalid dynamic identifier type: {}'.format(hex(dynamic_definition_type))) + self._uds_request(SERVICE_TYPE.DYNAMICALLY_DEFINE_DATA_IDENTIFIER, subfunction=dynamic_definition_type, data=data) + + def write_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE, data_record: bytes): + data = struct.pack('!H', data_identifier_type) + data_record + resp = self._uds_request(SERVICE_TYPE.WRITE_DATA_BY_IDENTIFIER, subfunction=None, data=data) + resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None + if resp_id != data_identifier_type: + raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) + + def write_memory_by_address(self, memory_address: int, memory_size: int, data_record: bytes, memory_address_bytes: int=4, memory_size_bytes: int=1): + if memory_address_bytes < 1 or memory_address_bytes > 4: + raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) + if memory_size_bytes < 1 or memory_size_bytes > 4: + raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) + data = bytes([memory_size_bytes<<4 | memory_address_bytes]) + + if memory_address >= 1<<(memory_address_bytes*8): + raise ValueError('invalid memory_address: {}'.format(memory_address)) + data += struct.pack('!I', memory_address)[4-memory_address_bytes:] + if memory_size >= 1<<(memory_size_bytes*8): + raise ValueError('invalid memory_size: {}'.format(memory_size)) + data += struct.pack('!I', memory_size)[4-memory_size_bytes:] + + data += data_record + self._uds_request(SERVICE_TYPE.WRITE_MEMORY_BY_ADDRESS, subfunction=0x00, data=data) + + def clear_diagnostic_information(self, dtc_group_type: DTC_GROUP_TYPE): + data = struct.pack('!I', dtc_group_type)[1:] # 3 bytes + self._uds_request(SERVICE_TYPE.CLEAR_DIAGNOSTIC_INFORMATION, subfunction=None, data=data) + + def read_dtc_information(self, dtc_report_type: DTC_REPORT_TYPE, dtc_status_mask_type: DTC_STATUS_MASK_TYPE=DTC_STATUS_MASK_TYPE.ALL, dtc_severity_mask_type: DTC_SEVERITY_MASK_TYPE=DTC_SEVERITY_MASK_TYPE.ALL, dtc_mask_record: int=0xFFFFFF, dtc_snapshot_record_num: int=0xFF, dtc_extended_record_num: int=0xFF): + data = b'' + # dtc_status_mask_type + if dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_DTC_BY_STATUS_MASK or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_BY_STATUS_MASK or \ + dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_BY_STATUS_MASK or \ + dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_MIRROR_MEMORY_DTC_BY_STATUS_MASK or \ + dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK or \ + dtc_report_type == DTC_REPORT_TYPE.EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK: + data += bytes([dtc_status_mask_type]) + # dtc_mask_record + if dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_IDENTIFICATION or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ + dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ + dtc_report_type == DTC_REPORT_TYPE.SEVERITY_INFORMATION_OF_DTC: + data += struct.pack('!I', dtc_mask_record)[1:] # 3 bytes + # dtc_snapshot_record_num + if dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_IDENTIFICATION or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_RECORD_NUMBER: + data += ord(dtc_snapshot_record_num) + # dtc_extended_record_num + if dtc_report_type == DTC_REPORT_TYPE.DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ + dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER: + data += bytes([dtc_extended_record_num]) + # dtc_severity_mask_type + if dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_DTC_BY_SEVERITY_MASK_RECORD or \ + dtc_report_type == DTC_REPORT_TYPE.DTC_BY_SEVERITY_MASK_RECORD: + data += bytes([dtc_severity_mask_type, dtc_status_mask_type]) + + resp = self._uds_request(SERVICE_TYPE.READ_DTC_INFORMATION, subfunction=dtc_report_type, data=data) + + # TODO: parse response + return resp + + def input_output_control_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE, control_parameter_type: CONTROL_PARAMETER_TYPE, control_option_record: bytes, control_enable_mask_record: bytes=b''): + data = struct.pack('!H', data_identifier_type) + bytes([control_parameter_type]) + control_option_record + control_enable_mask_record + resp = self._uds_request(SERVICE_TYPE.INPUT_OUTPUT_CONTROL_BY_IDENTIFIER, subfunction=None, data=data) + resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None + if resp_id != data_identifier_type: + raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) + return resp[2:] + + def routine_control(self, routine_control_type: ROUTINE_CONTROL_TYPE, routine_identifier_type: ROUTINE_IDENTIFIER_TYPE, routine_option_record: bytes=b''): + data = struct.pack('!H', routine_identifier_type) + routine_option_record + resp = self._uds_request(SERVICE_TYPE.ROUTINE_CONTROL, subfunction=routine_control_type, data=data) + resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None + if resp_id != routine_identifier_type: + raise ValueError('invalid response routine identifier: {}'.format(hex(resp_id))) + return resp[2:] + + def request_download(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=4, data_format: int=0x00): + data = bytes([data_format]) + + if memory_address_bytes < 1 or memory_address_bytes > 4: + raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) + if memory_size_bytes < 1 or memory_size_bytes > 4: + raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) + data += bytes([memory_size_bytes<<4 | memory_address_bytes]) + + if memory_address >= 1<<(memory_address_bytes*8): + raise ValueError('invalid memory_address: {}'.format(memory_address)) + data += struct.pack('!I', memory_address)[4-memory_address_bytes:] + if memory_size >= 1<<(memory_size_bytes*8): + raise ValueError('invalid memory_size: {}'.format(memory_size)) + data += struct.pack('!I', memory_size)[4-memory_size_bytes:] + + resp = self._uds_request(SERVICE_TYPE.REQUEST_DOWNLOAD, subfunction=None, data=data) + max_num_bytes_len = resp[0] >> 4 if len(resp) > 0 else None + if max_num_bytes_len >= 1 and max_num_bytes_len <= 4: + max_num_bytes = struct.unpack('!I', (b"\x00"*(4-max_num_bytes_len))+resp[1:max_num_bytes_len+1])[0] + else: + raise ValueError('invalid max_num_bytes_len: {}'.format(max_num_bytes_len)) + + return max_num_bytes # max number of bytes per transfer data request + + def request_upload(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=4, data_format: int=0x00): + data = bytes([data_format]) + + if memory_address_bytes < 1 or memory_address_bytes > 4: + raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) + if memory_size_bytes < 1 or memory_size_bytes > 4: + raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) + data += bytes([memory_size_bytes<<4 | memory_address_bytes]) + + if memory_address >= 1<<(memory_address_bytes*8): + raise ValueError('invalid memory_address: {}'.format(memory_address)) + data += struct.pack('!I', memory_address)[4-memory_address_bytes:] + if memory_size >= 1<<(memory_size_bytes*8): + raise ValueError('invalid memory_size: {}'.format(memory_size)) + data += struct.pack('!I', memory_size)[4-memory_size_bytes:] + + resp = self._uds_request(SERVICE_TYPE.REQUEST_UPLOAD, subfunction=None, data=data) + max_num_bytes_len = resp[0] >> 4 if len(resp) > 0 else None + if max_num_bytes_len >= 1 and max_num_bytes_len <= 4: + max_num_bytes = struct.unpack('!I', (b"\x00"*(4-max_num_bytes_len))+resp[1:max_num_bytes_len+1])[0] + else: + raise ValueError('invalid max_num_bytes_len: {}'.format(max_num_bytes_len)) + + return max_num_bytes # max number of bytes per transfer data request + + def transfer_data(self, block_sequence_count: int, data: bytes=b''): + data = bytes([block_sequence_count]) + data + resp = self._uds_request(SERVICE_TYPE.TRANSFER_DATA, subfunction=None, data=data) + resp_id = resp[0] if len(resp) > 0 else None + if resp_id != block_sequence_count: + raise ValueError('invalid block_sequence_count: {}'.format(resp_id)) + return resp[1:] + + def request_transfer_exit(self): + self._uds_request(SERVICE_TYPE.REQUEST_TRANSFER_EXIT, subfunction=None) diff --git a/python/update.py b/python/update.py index d72de11645..7d8d2c0402 100755 --- a/python/update.py +++ b/python/update.py @@ -12,7 +12,6 @@ def ensure_st_up_to_date(): panda = None panda_dfu = None - should_flash_recover = False while 1: # break on normal mode Panda diff --git a/requirements.txt b/requirements.txt index ad6b4c76e0..e7cf9931d5 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,11 @@ libusb1 == 1.6.6 -hexdump -pycrypto -tqdm +numpy==1.17.2 +hexdump>=3.3 +pycrypto==2.6.1 +tqdm>=4.14.0 nose parameterized requests +flake8==3.7.8 +pylint==2.4.2 +cffi==1.11.4 diff --git a/setup.py b/setup.py index 2acd9b9e16..f34905d7a2 100644 --- a/setup.py +++ b/setup.py @@ -13,7 +13,7 @@ import codecs import os import re -from setuptools import setup, Extension +from setuptools import setup here = os.path.abspath(os.path.dirname(__file__)) diff --git a/tests/automated/0_builds.py b/tests/automated/0_builds.py index df4186cce4..fa3a1125d4 100644 --- a/tests/automated/0_builds.py +++ b/tests/automated/0_builds.py @@ -1,4 +1,3 @@ -import os from panda import build_st def test_build_panda(): diff --git a/tests/automated/1_program.py b/tests/automated/1_program.py index 944db18d9a..538f18c0c7 100644 --- a/tests/automated/1_program.py +++ b/tests/automated/1_program.py @@ -1,6 +1,4 @@ -import os -from panda import Panda -from .helpers import panda_type_to_serial, test_white_and_grey, test_all_pandas, panda_connect_and_init +from .helpers import test_all_pandas, panda_connect_and_init @test_all_pandas @panda_connect_and_init diff --git a/tests/automated/2_usb_to_can.py b/tests/automated/2_usb_to_can.py index 645f686e15..32ef558cfc 100644 --- a/tests/automated/2_usb_to_can.py +++ b/tests/automated/2_usb_to_can.py @@ -1,5 +1,3 @@ - -import os import sys import time from panda import Panda @@ -180,6 +178,6 @@ def test_gmlan_bad_toggle(p): @test_all_pandas @panda_connect_and_init def test_serial_debug(p): - junk = p.serial_read(Panda.SERIAL_DEBUG) + _ = p.serial_read(Panda.SERIAL_DEBUG) # junk p.call_control_api(0xc0) assert(p.serial_read(Panda.SERIAL_DEBUG).startswith(b"can ")) diff --git a/tests/automated/3_wifi.py b/tests/automated/3_wifi.py index f57dbbd021..df66d6c0f3 100644 --- a/tests/automated/3_wifi.py +++ b/tests/automated/3_wifi.py @@ -1,5 +1,3 @@ - -import os import time from panda import Panda from .helpers import connect_wifi, test_white, test_all_pandas, panda_type_to_serial, panda_connect_and_init diff --git a/tests/automated/4_wifi_functionality.py b/tests/automated/4_wifi_functionality.py index 67cce4bf9c..ee349ddcbf 100644 --- a/tests/automated/4_wifi_functionality.py +++ b/tests/automated/4_wifi_functionality.py @@ -1,8 +1,6 @@ - import time from panda import Panda from .helpers import time_many_sends, connect_wifi, test_white, panda_type_to_serial -from nose.tools import timed, assert_equal, assert_less, assert_greater @test_white @panda_type_to_serial diff --git a/tests/automated/5_wifi_udp.py b/tests/automated/5_wifi_udp.py index 642d8f02a5..fd905aa895 100644 --- a/tests/automated/5_wifi_udp.py +++ b/tests/automated/5_wifi_udp.py @@ -3,7 +3,7 @@ import sys import time from .helpers import time_many_sends, connect_wifi, test_white, panda_type_to_serial from panda import Panda, PandaWifiStreaming -from nose.tools import timed, assert_equal, assert_less, assert_greater +from nose.tools import assert_less, assert_greater @test_white @panda_type_to_serial diff --git a/tests/automated/6_two_panda.py b/tests/automated/6_two_panda.py index 711b83fddf..f91403545f 100644 --- a/tests/automated/6_two_panda.py +++ b/tests/automated/6_two_panda.py @@ -171,7 +171,7 @@ def test_black_loopback(panda0, panda1): time.sleep(0.1) # check for receive - cans_echo = send_panda.can_recv() + _ = send_panda.can_recv() # cans echo cans_loop = recv_panda.can_recv() loop_buses = [] diff --git a/tests/automated/helpers.py b/tests/automated/helpers.py index f73a17dc04..2642e9156a 100644 --- a/tests/automated/helpers.py +++ b/tests/automated/helpers.py @@ -2,13 +2,12 @@ import os import sys import time import random -import binascii import subprocess import requests import _thread from functools import wraps from panda import Panda -from nose.tools import timed, assert_equal, assert_less, assert_greater +from nose.tools import assert_equal from parameterized import parameterized, param SPEED_NORMAL = 500 @@ -50,7 +49,7 @@ def connect_wifi(serial=None): FNULL = open(os.devnull, 'w') def _connect_wifi(dongle_id, pw, insecure_okay=False): - ssid = "panda-" + dongle_id.decode("utf8") + ssid = "panda-" + dongle_id r = subprocess.call(["ping", "-W", "4", "-c", "1", "192.168.0.10"], stdout=FNULL, stderr=subprocess.STDOUT) if not r: @@ -69,7 +68,7 @@ def _connect_wifi(dongle_id, pw, insecure_okay=False): if sys.platform == "darwin": os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw)) else: - wlan_interface = subprocess.check_output(["sh", "-c", "iw dev | awk '/Interface/ {print $2}'"]).strip() + wlan_interface = subprocess.check_output(["sh", "-c", "iw dev | awk '/Interface/ {print $2}'"]).strip().decode('utf8') cnt = 0 MAX_TRIES = 10 while cnt < MAX_TRIES: @@ -87,13 +86,13 @@ def _connect_wifi(dongle_id, pw, insecure_okay=False): if "-pair" in wifi_scan[0]: os.system("nmcli d wifi connect %s-pair" % (ssid)) connect_cnt = 0 - MAX_TRIES = 20 + MAX_TRIES = 100 while connect_cnt < MAX_TRIES: connect_cnt += 1 r = subprocess.call(["ping", "-W", "4", "-c", "1", "192.168.0.10"], stdout=FNULL, stderr=subprocess.STDOUT) if r: print("Waiting for panda to ping...") - time.sleep(0.1) + time.sleep(0.5) else: break if insecure_okay: diff --git a/tests/black_loopback_test.py b/tests/black_loopback_test.py index 0953cba4fa..5fe0c48077 100755 --- a/tests/black_loopback_test.py +++ b/tests/black_loopback_test.py @@ -11,9 +11,6 @@ import time import random import argparse -from hexdump import hexdump -from itertools import permutations - sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) from panda import Panda @@ -33,7 +30,7 @@ def run_test(sleep_duration): pandas[0] = Panda(pandas[0]) pandas[1] = Panda(pandas[1]) - # find out the hardware types + # find out the hardware types if not pandas[0].is_black() or not pandas[1].is_black(): print("Connect two black pandas to run this test!") assert False @@ -66,14 +63,14 @@ def run_test(sleep_duration): test_buses(pandas[0], pandas[1], test_array, sleep_duration) print("***************** TESTING (1 --> 0) *****************") test_buses(pandas[1], pandas[0], test_array, sleep_duration) - + def test_buses(send_panda, recv_panda, test_array, sleep_duration): for send_bus, send_obd, recv_obd, recv_buses in test_array: send_panda.send_heartbeat() recv_panda.send_heartbeat() print("\nSend bus:", send_bus, " Send OBD:", send_obd, " Recv OBD:", recv_obd) - + # set OBD on pandas send_panda.set_gmlan(True if send_obd else None) recv_panda.set_gmlan(True if recv_obd else None) @@ -92,7 +89,7 @@ def test_buses(send_panda, recv_panda, test_array, sleep_duration): time.sleep(0.1) # check for receive - cans_echo = send_panda.can_recv() + _ = send_panda.can_recv() # cans echo cans_loop = recv_panda.can_recv() loop_buses = [] @@ -101,7 +98,7 @@ def test_buses(send_panda, recv_panda, test_array, sleep_duration): loop_buses.append(loop[3]) if len(cans_loop) == 0: print(" No loop") - + # test loop buses recv_buses.sort() loop_buses.sort() diff --git a/tests/black_white_loopback_test.py b/tests/black_white_loopback_test.py index 7ad2107fa0..66c5e80f45 100755 --- a/tests/black_white_loopback_test.py +++ b/tests/black_white_loopback_test.py @@ -11,9 +11,6 @@ import time import random import argparse -from hexdump import hexdump -from itertools import permutations - sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) from panda import Panda @@ -118,10 +115,10 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): # check for receive if direction: - cans_echo = black_panda.can_recv() + _ = black_panda.can_recv() # can echo cans_loop = other_panda.can_recv() else: - cans_echo = other_panda.can_recv() + _ = other_panda.can_recv() # can echo cans_loop = black_panda.can_recv() loop_buses = [] diff --git a/tests/black_white_relay_endurance.py b/tests/black_white_relay_endurance.py index 3eaaa16555..6970966526 100755 --- a/tests/black_white_relay_endurance.py +++ b/tests/black_white_relay_endurance.py @@ -11,9 +11,6 @@ import time import random import argparse -from hexdump import hexdump -from itertools import permutations - sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) from panda import Panda @@ -42,7 +39,7 @@ def run_test(sleep_duration): black_panda = None other_panda = None - + # find out which one is black if pandas[0].is_black() and not pandas[1].is_black(): black_panda = pandas[0] @@ -69,7 +66,7 @@ def run_test(sleep_duration): test_buses(black_panda, other_panda, True, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (1, True, [0])], sleep_duration) test_buses(black_panda, other_panda, False, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (0, True, [0, 1])], sleep_duration) counter += 1 - + runtime = time.time() - start_time print("Number of cycles:", counter, "Non-zero bus errors:", nonzero_bus_errors, "Zero bus errors:", zero_bus_errors, "Content errors:", content_errors, "Runtime: ", runtime) @@ -80,7 +77,7 @@ def run_test(sleep_duration): black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) time.sleep(1) temp_start_time = time.time() - + def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): global nonzero_bus_errors, zero_bus_errors, content_errors @@ -94,7 +91,7 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): black_panda.send_heartbeat() other_panda.send_heartbeat() print("\ntest can: ", send_bus, " OBD: ", obd) - + # set OBD on black panda black_panda.set_gmlan(True if obd else None) @@ -109,7 +106,7 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): other_panda.can_clear(recv_bus) else: black_panda.can_clear(recv_bus) - + black_panda.can_recv() other_panda.can_recv() @@ -124,10 +121,10 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): # check for receive if direction: - cans_echo = black_panda.can_recv() + _ = black_panda.can_recv() # cans echo cans_loop = other_panda.can_recv() else: - cans_echo = other_panda.can_recv() + _ = other_panda.can_recv() # cans echo cans_loop = black_panda.can_recv() loop_buses = [] @@ -141,7 +138,7 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): print(" No loop") if not os.getenv("NOASSERT"): assert False - + # test loop buses recv_buses.sort() loop_buses.sort() diff --git a/tests/black_white_relay_test.py b/tests/black_white_relay_test.py index 65877dc29f..d80490f7d4 100755 --- a/tests/black_white_relay_test.py +++ b/tests/black_white_relay_test.py @@ -10,9 +10,6 @@ import time import random import argparse -from hexdump import hexdump -from itertools import permutations - sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) from panda import Panda @@ -46,7 +43,7 @@ def run_test(sleep_duration): black_panda = None other_panda = None - + if type0 == "\x03" and type1 != "\x03": black_panda = pandas[0] other_panda = pandas[1] @@ -86,15 +83,15 @@ def run_test(sleep_duration): assert False counter += 1 - print("Number of cycles:", counter, "Open errors:", open_errors, "Closed errors:", closed_errors, "Content errors:", content_errors) + print("Number of cycles:", counter, "Open errors:", open_errors, "Closed errors:", closed_errors, "Content errors:", content_errors) def test_buses(black_panda, other_panda, test_obj): global content_errors send_bus, obd, recv_buses = test_obj - + black_panda.send_heartbeat() other_panda.send_heartbeat() - + # Set OBD on send panda other_panda.set_gmlan(True if obd else None) @@ -103,7 +100,7 @@ def test_buses(black_panda, other_panda, test_obj): for recv_bus in recv_buses: black_panda.can_clear(recv_bus) - + black_panda.can_recv() other_panda.can_recv() @@ -114,7 +111,7 @@ def test_buses(black_panda, other_panda, test_obj): time.sleep(0.05) # check for receive - cans_echo = other_panda.can_recv() + _ = other_panda.can_recv() # can echo cans_loop = black_panda.can_recv() loop_buses = [] @@ -122,7 +119,7 @@ def test_buses(black_panda, other_panda, test_obj): if (loop[0] != at) or (loop[2] != st): content_errors += 1 loop_buses.append(loop[3]) - + # test loop buses recv_buses.sort() loop_buses.sort() diff --git a/tests/elm_car_simulator.py b/tests/elm_car_simulator.py index ffb309664e..01b79c8840 100755 --- a/tests/elm_car_simulator.py +++ b/tests/elm_car_simulator.py @@ -109,9 +109,9 @@ class ELMCarSimulator(): print(" LIN Reply (%x)" % to_addr, binascii.hexlify(msg)) PHYS_ADDR = 0x80 - FUNC_ADDR = 0xC0 + #FUNC_ADDR = 0xC0 RECV = 0xF1 - SEND = 0x33 # Car OBD Functional Address + #SEND = 0x33 # Car OBD Functional Address headers = struct.pack("BBB", PHYS_ADDR | len(msg), RECV, to_addr) if not self.__silent: print(" Sending LIN", binascii.hexlify(headers+msg), @@ -172,7 +172,7 @@ class ELMCarSimulator(): while not self.__stop: for address, ts, data, src in self.panda.can_recv(): - if self.__on and src is 0 and len(data) == 8 and data[0] >= 2: + if self.__on and src == 0 and len(data) == 8 and data[0] >= 2: if not self.__silent: print("Processing CAN message", src, hex(address), binascii.hexlify(data)) self.__can_process_msg(data[1], data[2], address, ts, data, src) diff --git a/tests/elm_wifi.py b/tests/elm_wifi.py index 6c4a334b73..b0645ea889 100644 --- a/tests/elm_wifi.py +++ b/tests/elm_wifi.py @@ -1,16 +1,14 @@ - import os import sys import time import socket import select -import pytest import struct sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) -from . import elm_car_simulator sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..", "..")) from panda import Panda +from panda.tests import elm_car_simulator def elm_connect(): s = socket.create_connection(("192.168.0.10", 35000)) @@ -234,35 +232,35 @@ def test_elm_send_lin_multiline_msg(): send_compare(s, b'0902\r', # headers OFF, Spaces ON b"BUS INIT: OK\r" - "49 02 01 00 00 00 31 \r" - "49 02 02 44 34 47 50 \r" - "49 02 03 30 30 52 35 \r" - "49 02 04 35 42 31 32 \r" - "49 02 05 33 34 35 36 \r\r>") + b"49 02 01 00 00 00 31 \r" + b"49 02 02 44 34 47 50 \r" + b"49 02 03 30 30 52 35 \r" + b"49 02 04 35 42 31 32 \r" + b"49 02 05 33 34 35 36 \r\r>") send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF send_compare(s, b'0902\r', # Headers OFF, Spaces OFF b"49020100000031\r" - "49020244344750\r" - "49020330305235\r" - "49020435423132\r" - "49020533343536\r\r>") + b"49020244344750\r" + b"49020330305235\r" + b"49020435423132\r" + b"49020533343536\r\r>") send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON send_compare(s, b'0902\r', # Headers ON, Spaces OFF b"87F1104902010000003105\r" - "87F11049020244344750E4\r" - "87F11049020330305235BD\r" - "87F11049020435423132B1\r" - "87F11049020533343536AA\r\r>") + b"87F11049020244344750E4\r" + b"87F11049020330305235BD\r" + b"87F11049020435423132B1\r" + b"87F11049020533343536AA\r\r>") send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces ON send_compare(s, b'0902\r', # Headers ON, Spaces ON b"87 F1 10 49 02 01 00 00 00 31 05 \r" - "87 F1 10 49 02 02 44 34 47 50 E4 \r" - "87 F1 10 49 02 03 30 30 52 35 BD \r" - "87 F1 10 49 02 04 35 42 31 32 B1 \r" - "87 F1 10 49 02 05 33 34 35 36 AA \r\r>") + b"87 F1 10 49 02 02 44 34 47 50 E4 \r" + b"87 F1 10 49 02 03 30 30 52 35 BD \r" + b"87 F1 10 49 02 04 35 42 31 32 B1 \r" + b"87 F1 10 49 02 05 33 34 35 36 AA \r\r>") finally: sim.stop() sim.join() @@ -322,7 +320,7 @@ def test_elm_panda_safety_mode_KWPFast(): def kline_send(p, x, bus=2): p.kline_drain(bus=bus) - p._handle.bulkWrite(2, chr(bus).encode()+x) + p._handle.bulkWrite(2, bytes([bus]) + x) return timed_recv_check(p, bus, x) def did_send(priority, toaddr, fromaddr, dat, bus=2, checkbyte=None): @@ -461,7 +459,7 @@ def test_elm_send_can_multimsg(): sim.can_add_extra_noise(b'\x03\x41\x0D\xFA', addr=0x7E9)# Inject message into the stream send_compare(s, b'010D\r', b"7E8 03 41 0D 53 \r" - "7E9 03 41 0D FA \r\r>") # Check it was ignored. + b"7E9 03 41 0D FA \r\r>") # Check it was ignored. finally: sim.stop() sim.join() @@ -503,28 +501,28 @@ def test_elm_send_can_multiline_msg(): send_compare(s, b'0902\r', # headers OFF, Spaces ON b"014 \r" - "0: 49 02 01 31 44 34 \r" - "1: 47 50 30 30 52 35 35 \r" - "2: 42 31 32 33 34 35 36 \r\r>") + b"0: 49 02 01 31 44 34 \r" + b"1: 47 50 30 30 52 35 35 \r" + b"2: 42 31 32 33 34 35 36 \r\r>") send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF send_compare(s, b'0902\r', # Headers OFF, Spaces OFF b"014\r" - "0:490201314434\r" - "1:47503030523535\r" - "2:42313233343536\r\r>") + b"0:490201314434\r" + b"1:47503030523535\r" + b"2:42313233343536\r\r>") send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON send_compare(s, b'0902\r', # Headers ON, Spaces OFF b"7E81014490201314434\r" - "7E82147503030523535\r" - "7E82242313233343536\r\r>") + b"7E82147503030523535\r" + b"7E82242313233343536\r\r>") send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces ON send_compare(s, b'0902\r', # Headers ON, Spaces ON b"7E8 10 14 49 02 01 31 44 34 \r" - "7E8 21 47 50 30 30 52 35 35 \r" - "7E8 22 42 31 32 33 34 35 36 \r\r>") + b"7E8 21 47 50 30 30 52 35 35 \r" + b"7E8 22 42 31 32 33 34 35 36 \r\r>") finally: sim.stop() sim.join() diff --git a/tests/fan_test.py b/tests/fan_test.py new file mode 100755 index 0000000000..7385698828 --- /dev/null +++ b/tests/fan_test.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python +import os +import sys +import time + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +power = 0 +if __name__ == "__main__": + p = Panda() + while True: + p.set_fan_power(power) + time.sleep(5) + print("Power: ", power, "RPM: ", str(p.get_fan_rpm())) + power += 10 + power %=100 diff --git a/tests/gmbitbang/recv.py b/tests/gmbitbang/recv.py index 92111ed7ec..3949c424d9 100755 --- a/tests/gmbitbang/recv.py +++ b/tests/gmbitbang/recv.py @@ -1,17 +1,16 @@ #!/usr/bin/env python3 -import time from panda import Panda p = Panda() p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) p.set_gmlan(bus=2) -#p.can_send(0xaaa, "\x00\x00", bus=3) +#p.can_send(0xaaa, b"\x00\x00", bus=3) last_add = None while 1: ret = p.can_recv() if len(ret) > 0: add = ret[0][0] - if last_add is not None and add != last_add+1: - print("MISS %d %d" % (last_add, add)) + if last_add is not None and add != last_add + 1: + print("MISS: ", last_add, add) last_add = add print(ret) diff --git a/tests/gmbitbang/rigol.py b/tests/gmbitbang/rigol.py index f2efb0340e..5fcdf243ec 100755 --- a/tests/gmbitbang/rigol.py +++ b/tests/gmbitbang/rigol.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +# pylint: skip-file import numpy as np import visa import matplotlib.pyplot as plt diff --git a/tests/gps_stability_test.py b/tests/gps_stability_test.py index c96aaf123b..529970e0f4 100755 --- a/tests/gps_stability_test.py +++ b/tests/gps_stability_test.py @@ -77,7 +77,7 @@ def init_gps(panda): # Upping baud rate print("Upping GPS baud rate") - msg = add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % GPS_BAUD)+"\r\n" + msg = str.encode(add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % GPS_BAUD)+"\r\n") ser.write(msg) time.sleep(1) # needs a wait for it to actually send @@ -86,24 +86,24 @@ def init_gps(panda): # Sending all config messages boardd sends print("Sending config") - ser.write("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") - ser.write("\xB5\x62\x06\x3E\x00\x00\x44\xD2") - ser.write("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") - ser.write("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") - ser.write("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") - ser.write("\xB5\x62\x06\x00\x00\x00\x06\x18") - ser.write("\xB5\x62\x06\x00\x01\x00\x01\x08\x22") - ser.write("\xB5\x62\x06\x00\x01\x00\x02\x09\x23") - ser.write("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24") - ser.write("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10") - ser.write("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63") - ser.write("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37") - ser.write("\xB5\x62\x06\x24\x00\x00\x2A\x84") - ser.write("\xB5\x62\x06\x23\x00\x00\x29\x81") - ser.write("\xB5\x62\x06\x1E\x00\x00\x24\x72") - ser.write("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51") - ser.write("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70") - ser.write("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C") + ser.write(b"\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") + ser.write(b"\xB5\x62\x06\x3E\x00\x00\x44\xD2") + ser.write(b"\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") + ser.write(b"\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") + ser.write(b"\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") + ser.write(b"\xB5\x62\x06\x00\x00\x00\x06\x18") + ser.write(b"\xB5\x62\x06\x00\x01\x00\x01\x08\x22") + ser.write(b"\xB5\x62\x06\x00\x01\x00\x02\x09\x23") + ser.write(b"\xB5\x62\x06\x00\x01\x00\x03\x0A\x24") + ser.write(b"\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10") + ser.write(b"\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63") + ser.write(b"\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37") + ser.write(b"\xB5\x62\x06\x24\x00\x00\x2A\x84") + ser.write(b"\xB5\x62\x06\x23\x00\x00\x29\x81") + ser.write(b"\xB5\x62\x06\x1E\x00\x00\x24\x72") + ser.write(b"\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51") + ser.write(b"\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70") + ser.write(b"\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C") print("Initialized GPS") @@ -163,7 +163,3 @@ if __name__ == "__main__": print("Total max failures: ", max_failures) received_messages = 0 received_bytes = 0 - - - - \ No newline at end of file diff --git a/tests/ir_test.py b/tests/ir_test.py new file mode 100755 index 0000000000..caef9e4909 --- /dev/null +++ b/tests/ir_test.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python +import os +import sys +import time + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +power = 0 +if __name__ == "__main__": + p = Panda() + while True: + p.set_ir_power(power) + print("Power: ", str(power)) + time.sleep(1) + power += 10 + power %=100 diff --git a/tests/language/Dockerfile b/tests/language/Dockerfile index fe957ff723..6a1d8bb7c7 100644 --- a/tests/language/Dockerfile +++ b/tests/language/Dockerfile @@ -14,5 +14,4 @@ RUN pyenv install 3.7.3 RUN pyenv global 3.7.3 RUN pyenv rehash -COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt COPY . /panda diff --git a/tests/language/test_language.py b/tests/language/test_language.py index 353f37e854..98b0290425 100755 --- a/tests/language/test_language.py +++ b/tests/language/test_language.py @@ -20,7 +20,7 @@ if __name__ == "__main__": res = subprocess.check_output(cmd, shell=True, stderr=subprocess.STDOUT) print(res) found_bad_language = True - except subprocess.CalledProcessError as e: + except subprocess.CalledProcessError: pass if found_bad_language: sys.exit("Failed: found bad language") diff --git a/tests/linter_python/.pylintrc b/tests/linter_python/.pylintrc new file mode 100644 index 0000000000..64a55daf8f --- /dev/null +++ b/tests/linter_python/.pylintrc @@ -0,0 +1,585 @@ +[MASTER] + +# A comma-separated list of package or module names from where C extensions may +# be loaded. Extensions are loading into the active Python interpreter and may +# run arbitrary code +extension-pkg-whitelist=scipy + +# Add files or directories to the blacklist. They should be base names, not +# paths. +ignore=CVS + +# Add files or directories matching the regex patterns to the blacklist. The +# regex matches against base names, not paths. +ignore-patterns= + +# Python code to execute, usually for sys.path manipulation such as +# pygtk.require(). +#init-hook= + +# Use multiple processes to speed up Pylint. +jobs=4 + +# List of plugins (as comma separated values of python modules names) to load, +# usually to register additional checkers. +load-plugins= + +# Pickle collected data for later comparisons. +persistent=yes + +# Specify a configuration file. +#rcfile= + +# When enabled, pylint would attempt to guess common misconfiguration and emit +# user-friendly hints instead of false-positive error messages +suggestion-mode=yes + +# Allow loading of arbitrary C extensions. Extensions are imported into the +# active Python interpreter and may run arbitrary code. +unsafe-load-any-extension=no + + +[MESSAGES CONTROL] + +# Only show warnings with the listed confidence levels. Leave empty to show +# all. Valid levels: HIGH, INFERENCE, INFERENCE_FAILURE, UNDEFINED +confidence= + +# Disable the message, report, category or checker with the given id(s). You +# can either give multiple identifiers separated by comma (,) or put this +# option multiple times (only on the command line, not in the configuration +# file where it should appear only once).You can also use "--disable=all" to +# disable everything first and then reenable specific checks. For example, if +# you want to run only the similarities checker, you can use "--disable=all +# --enable=similarities". If you want to run only the classes checker, but have +# no Warning level messages displayed, use"--disable=all --enable=classes +# --disable=W" +disable=print-statement, + parameter-unpacking, + unpacking-in-except, + old-raise-syntax, + backtick, + long-suffix, + old-ne-operator, + old-octal-literal, + import-star-module-level, + non-ascii-bytes-literal, + raw-checker-failed, + bad-inline-option, + locally-disabled, + locally-enabled, + file-ignored, + suppressed-message, + useless-suppression, + deprecated-pragma, + apply-builtin, + basestring-builtin, + buffer-builtin, + cmp-builtin, + coerce-builtin, + execfile-builtin, + file-builtin, + long-builtin, + raw_input-builtin, + reduce-builtin, + standarderror-builtin, + unicode-builtin, + xrange-builtin, + coerce-method, + delslice-method, + getslice-method, + setslice-method, + no-absolute-import, + old-division, + dict-iter-method, + dict-view-method, + next-method-called, + metaclass-assignment, + indexing-exception, + raising-string, + reload-builtin, + oct-method, + hex-method, + nonzero-method, + cmp-method, + input-builtin, + round-builtin, + intern-builtin, + unichr-builtin, + map-builtin-not-iterating, + zip-builtin-not-iterating, + range-builtin-not-iterating, + filter-builtin-not-iterating, + using-cmp-argument, + eq-without-hash, + div-method, + idiv-method, + rdiv-method, + exception-message-attribute, + invalid-str-codec, + sys-max-int, + bad-python3-import, + deprecated-string-function, + deprecated-str-translate-call, + deprecated-itertools-function, + deprecated-types-field, + next-method-defined, + dict-items-not-iterating, + dict-keys-not-iterating, + dict-values-not-iterating, + bad-indentation, + line-too-long, + missing-docstring, + multiple-statements, + bad-continuation, + invalid-name, + too-many-arguments, + too-many-locals, + superfluous-parens, + bad-whitespace, + too-many-instance-attributes, + wrong-import-position, + ungrouped-imports, + wrong-import-order, + protected-access, + trailing-whitespace, + too-many-branches, + too-few-public-methods, + too-many-statements, + trailing-newlines, + attribute-defined-outside-init, + too-many-return-statements, + too-many-public-methods, + unused-argument, + old-style-class, + no-init, + len-as-condition, + unneeded-not, + no-self-use, + multiple-imports, + no-else-return, + logging-not-lazy, + fixme, + redefined-outer-name, + unused-variable, + unsubscriptable-object, + expression-not-assigned, + too-many-boolean-expressions, + consider-using-ternary, + invalid-unary-operand-type, + relative-import, + deprecated-lambda + + +# Enable the message, report, category or checker with the given id(s). You can +# either give multiple identifier separated by comma (,) or put this option +# multiple time (only on the command line, not in the configuration file where +# it should appear only once). See also the "--disable" option for examples. +enable=c-extension-no-member + + +[REPORTS] + +# Python expression which should return a note less than 10 (10 is the highest +# note). You have access to the variables errors warning, statement which +# respectively contain the number of errors / warnings messages and the total +# number of statements analyzed. This is used by the global evaluation report +# (RP0004). +evaluation=10.0 - ((float(5 * error + warning + refactor + convention) / statement) * 10) + +# Template used to display messages. This is a python new-style format string +# used to format the message information. See doc for all details +#msg-template= + +# Set the output format. Available formats are text, parseable, colorized, json +# and msvs (visual studio).You can also give a reporter class, eg +# mypackage.mymodule.MyReporterClass. +output-format=text + +# Tells whether to display a full report or only the messages +reports=no + +# Activate the evaluation score. +score=yes + + +[REFACTORING] + +# Maximum number of nested blocks for function / method body +max-nested-blocks=5 + +# Complete name of functions that never returns. When checking for +# inconsistent-return-statements if a never returning function is called then +# it will be considered as an explicit return statement and no message will be +# printed. +never-returning-functions=optparse.Values,sys.exit + + +[LOGGING] + +# Logging modules to check that the string format arguments are in logging +# function parameter format +logging-modules=logging + + +[SPELLING] + +# Limits count of emitted suggestions for spelling mistakes +max-spelling-suggestions=4 + +# Spelling dictionary name. Available dictionaries: none. To make it working +# install python-enchant package. +spelling-dict= + +# List of comma separated words that should not be checked. +spelling-ignore-words= + +# A path to a file that contains private dictionary; one word per line. +spelling-private-dict-file= + +# Tells whether to store unknown words to indicated private dictionary in +# --spelling-private-dict-file option instead of raising a message. +spelling-store-unknown-words=no + + +[MISCELLANEOUS] + +# List of note tags to take in consideration, separated by a comma. +notes=FIXME, + XXX, + TODO + + +[SIMILARITIES] + +# Ignore comments when computing similarities. +ignore-comments=yes + +# Ignore docstrings when computing similarities. +ignore-docstrings=yes + +# Ignore imports when computing similarities. +ignore-imports=no + +# Minimum lines number of a similarity. +min-similarity-lines=4 + + +[TYPECHECK] + +# List of decorators that produce context managers, such as +# contextlib.contextmanager. Add to this list to register other decorators that +# produce valid context managers. +contextmanager-decorators=contextlib.contextmanager + +# List of members which are set dynamically and missed by pylint inference +# system, and so shouldn't trigger E1101 when accessed. Python regular +# expressions are accepted. +generated-members=capnp.* cereal.* pygame.* zmq.* setproctitle.* smbus2.* usb1.* serial.* cv2.* + +# Tells whether missing members accessed in mixin class should be ignored. A +# mixin class is detected if its name ends with "mixin" (case insensitive). +ignore-mixin-members=yes + +# This flag controls whether pylint should warn about no-member and similar +# checks whenever an opaque object is returned when inferring. The inference +# can return multiple potential results while evaluating a Python object, but +# some branches might not be evaluated, which results in partial inference. In +# that case, it might be useful to still emit no-member and other checks for +# the rest of the inferred objects. +ignore-on-opaque-inference=yes + +# List of class names for which member attributes should not be checked (useful +# for classes with dynamically set attributes). This supports the use of +# qualified names. +ignored-classes=optparse.Values,thread._local,_thread._local + +# List of module names for which member attributes should not be checked +# (useful for modules/projects where namespaces are manipulated during runtime +# and thus existing member attributes cannot be deduced by static analysis. It +# supports qualified module names, as well as Unix pattern matching. +ignored-modules=flask setproctitle usb1 flask.ext.socketio smbus2 usb1.* + +# Show a hint with possible names when a member name was not found. The aspect +# of finding the hint is based on edit distance. +missing-member-hint=yes + +# The minimum edit distance a name should have in order to be considered a +# similar match for a missing member name. +missing-member-hint-distance=1 + +# The total number of similar names that should be taken in consideration when +# showing a hint for a missing member. +missing-member-max-choices=1 + + +[VARIABLES] + +# List of additional names supposed to be defined in builtins. Remember that +# you should avoid to define new builtins when possible. +additional-builtins= + +# Tells whether unused global variables should be treated as a violation. +allow-global-unused-variables=yes + +# List of strings which can identify a callback function by name. A callback +# name must start or end with one of those strings. +callbacks=cb_, + _cb + +# A regular expression matching the name of dummy variables (i.e. expectedly +# not used). +dummy-variables-rgx=_+$|(_[a-zA-Z0-9_]*[a-zA-Z0-9]+?$)|dummy|^ignored_|^unused_ + +# Argument names that match this expression will be ignored. Default to name +# with leading underscore +ignored-argument-names=_.*|^ignored_|^unused_ + +# Tells whether we should check for unused import in __init__ files. +init-import=no + +# List of qualified module names which can have objects that can redefine +# builtins. +redefining-builtins-modules=six.moves,past.builtins,future.builtins + + +[FORMAT] + +# Expected format of line ending, e.g. empty (any line ending), LF or CRLF. +expected-line-ending-format= + +# Regexp for a line that is allowed to be longer than the limit. +ignore-long-lines=^\s*(# )??$ + +# Number of spaces of indent required inside a hanging or continued line. +indent-after-paren=4 + +# String used as indentation unit. This is usually " " (4 spaces) or "\t" (1 +# tab). +indent-string=' ' + +# Maximum number of characters on a single line. +max-line-length=100 + +# Maximum number of lines in a module +max-module-lines=1000 + +# List of optional constructs for which whitespace checking is disabled. `dict- +# separator` is used to allow tabulation in dicts, etc.: {1 : 1,\n222: 2}. +# `trailing-comma` allows a space between comma and closing bracket: (a, ). +# `empty-line` allows space-only lines. +no-space-check=trailing-comma, + dict-separator + +# Allow the body of a class to be on the same line as the declaration if body +# contains single statement. +single-line-class-stmt=no + +# Allow the body of an if to be on the same line as the test if there is no +# else. +single-line-if-stmt=no + + +[BASIC] + +# Naming style matching correct argument names +argument-naming-style=snake_case + +# Regular expression matching correct argument names. Overrides argument- +# naming-style +#argument-rgx= + +# Naming style matching correct attribute names +attr-naming-style=snake_case + +# Regular expression matching correct attribute names. Overrides attr-naming- +# style +#attr-rgx= + +# Bad variable names which should always be refused, separated by a comma +bad-names=foo, + bar, + baz, + toto, + tutu, + tata + +# Naming style matching correct class attribute names +class-attribute-naming-style=any + +# Regular expression matching correct class attribute names. Overrides class- +# attribute-naming-style +#class-attribute-rgx= + +# Naming style matching correct class names +class-naming-style=PascalCase + +# Regular expression matching correct class names. Overrides class-naming-style +#class-rgx= + +# Naming style matching correct constant names +const-naming-style=UPPER_CASE + +# Regular expression matching correct constant names. Overrides const-naming- +# style +#const-rgx= + +# Minimum line length for functions/classes that require docstrings, shorter +# ones are exempt. +docstring-min-length=-1 + +# Naming style matching correct function names +function-naming-style=snake_case + +# Regular expression matching correct function names. Overrides function- +# naming-style +#function-rgx= + +# Good variable names which should always be accepted, separated by a comma +good-names=i, + j, + k, + ex, + Run, + _ + +# Include a hint for the correct naming format with invalid-name +include-naming-hint=no + +# Naming style matching correct inline iteration names +inlinevar-naming-style=any + +# Regular expression matching correct inline iteration names. Overrides +# inlinevar-naming-style +#inlinevar-rgx= + +# Naming style matching correct method names +method-naming-style=snake_case + +# Regular expression matching correct method names. Overrides method-naming- +# style +#method-rgx= + +# Naming style matching correct module names +module-naming-style=snake_case + +# Regular expression matching correct module names. Overrides module-naming- +# style +#module-rgx= + +# Colon-delimited sets of names that determine each other's naming style when +# the name regexes allow several styles. +name-group= + +# Regular expression which should only match function or class names that do +# not require a docstring. +no-docstring-rgx=^_ + +# List of decorators that produce properties, such as abc.abstractproperty. Add +# to this list to register other decorators that produce valid properties. +property-classes=abc.abstractproperty + +# Naming style matching correct variable names +variable-naming-style=snake_case + +# Regular expression matching correct variable names. Overrides variable- +# naming-style +#variable-rgx= + + +[DESIGN] + +# Maximum number of arguments for function / method +max-args=5 + +# Maximum number of attributes for a class (see R0902). +max-attributes=7 + +# Maximum number of boolean expressions in a if statement +max-bool-expr=5 + +# Maximum number of branch for function / method body +max-branches=12 + +# Maximum number of locals for function / method body +max-locals=15 + +# Maximum number of parents for a class (see R0901). +max-parents=7 + +# Maximum number of public methods for a class (see R0904). +max-public-methods=20 + +# Maximum number of return / yield for function / method body +max-returns=6 + +# Maximum number of statements in function / method body +max-statements=50 + +# Minimum number of public methods for a class (see R0903). +min-public-methods=2 + + +[CLASSES] + +# List of method names used to declare (i.e. assign) instance attributes. +defining-attr-methods=__init__, + __new__, + setUp + +# List of member names, which should be excluded from the protected access +# warning. +exclude-protected=_asdict, + _fields, + _replace, + _source, + _make + +# List of valid names for the first argument in a class method. +valid-classmethod-first-arg=cls + +# List of valid names for the first argument in a metaclass class method. +valid-metaclass-classmethod-first-arg=mcs + + +[IMPORTS] + +# Allow wildcard imports from modules that define __all__. +allow-wildcard-with-all=no + +# Analyse import fallback blocks. This can be used to support both Python 2 and +# 3 compatible code, which means that the block might have code that exists +# only in one or another interpreter, leading to false positives when analysed. +analyse-fallback-blocks=no + +# Deprecated modules which should not be used, separated by a comma +deprecated-modules=regsub, + TERMIOS, + Bastion, + rexec + +# Create a graph of external dependencies in the given file (report RP0402 must +# not be disabled) +ext-import-graph= + +# Create a graph of every (i.e. internal and external) dependencies in the +# given file (report RP0402 must not be disabled) +import-graph= + +# Create a graph of internal dependencies in the given file (report RP0402 must +# not be disabled) +int-import-graph= + +# Force import order to recognize a module as part of the standard +# compatibility libraries. +known-standard-library= + +# Force import order to recognize a module as part of a third party library. +known-third-party=enchant + + +[EXCEPTIONS] + +# Exceptions that will emit a warning when being caught. Defaults to +# "Exception" +overgeneral-exceptions=Exception diff --git a/tests/linter_python/Dockerfile b/tests/linter_python/Dockerfile new file mode 100644 index 0000000000..819d692109 --- /dev/null +++ b/tests/linter_python/Dockerfile @@ -0,0 +1,19 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y make python python-pip locales curl git zlib1g-dev libffi-dev bzip2 libssl-dev + +RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen +ENV LANG en_US.UTF-8 +ENV LANGUAGE en_US:en +ENV LC_ALL en_US.UTF-8 + +RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash + +ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" +RUN pyenv install 3.7.3 +RUN pyenv global 3.7.3 +RUN pyenv rehash + +COPY requirements.txt /tmp/ +RUN pip install -r /tmp/requirements.txt +COPY . /panda diff --git a/tests/linter_python/flake8_panda.sh b/tests/linter_python/flake8_panda.sh new file mode 100755 index 0000000000..a1d02ea548 --- /dev/null +++ b/tests/linter_python/flake8_panda.sh @@ -0,0 +1,8 @@ +#!/usr/bin/env bash + +RESULT=$(python3 -m flake8 --select=F $(find ../../ -type f | grep -v "/boardesp/" | grep -v "/cppcheck/" | grep "\.py$")) +if [[ $RESULT ]]; then + echo "Pyflakes found errors in the code. Please fix and try again" + echo "$RESULT" + exit 1 +fi diff --git a/tests/linter_python/pylint_panda.sh b/tests/linter_python/pylint_panda.sh new file mode 100755 index 0000000000..1486bd839c --- /dev/null +++ b/tests/linter_python/pylint_panda.sh @@ -0,0 +1,11 @@ +#!/usr/bin/env bash + +python3 -m pylint --disable=R,C,W $(find ../../ -type f | grep -v "/boardesp/" | grep -v "/cppcheck/" | grep "\.py$") + +exit_status=$? +(( res = exit_status & 3 )) + +if [[ $res != 0 ]]; then + echo "Pylint found errors in the code. Please fix and try again" + exit 1 +fi diff --git a/tests/location_listener.py b/tests/location_listener.py index 62ade10f03..1a784babc9 100755 --- a/tests/location_listener.py +++ b/tests/location_listener.py @@ -30,7 +30,7 @@ if __name__ == "__main__": baudrate = 460800 print("upping baud rate") - msg = add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % baudrate)+"\r\n" + msg = str.encode(add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % baudrate)+"\r\n") print(msg) ser.write(msg) time.sleep(0.1) # needs a wait for it to actually send diff --git a/tests/loopback_test.py b/tests/loopback_test.py index 02c8d2cd14..60009fae51 100755 --- a/tests/loopback_test.py +++ b/tests/loopback_test.py @@ -55,7 +55,7 @@ def run_test_w_pandas(pandas, sleep_duration): # send the characters st = get_test_string() - st = b"\xaa"+chr(len(st)+3).encode()+st + st = bytes([0xaa, len(st) + 3]) + st h[ho[0]].kline_send(st, bus=bus, checksum=False) # check for receive diff --git a/tests/misra/Dockerfile b/tests/misra/Dockerfile index e63cc7e9e1..06882834fc 100644 --- a/tests/misra/Dockerfile +++ b/tests/misra/Dockerfile @@ -1,6 +1,19 @@ FROM ubuntu:16.04 -RUN apt-get update && apt-get install -y make python python-pip git -COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt -RUN pip install -r /panda/tests/safety/requirements.txt +RUN apt-get update && apt-get install -y clang make python python-pip git curl locales zlib1g-dev libffi-dev bzip2 libssl-dev libbz2-dev libusb-1.0-0 + +RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen +ENV LANG en_US.UTF-8 +ENV LANGUAGE en_US:en +ENV LC_ALL en_US.UTF-8 + +RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash + +ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" +RUN pyenv install 3.7.3 +RUN pyenv global 3.7.3 +RUN pyenv rehash + +COPY requirements.txt /tmp/ +RUN pip install -r /tmp/requirements.txt COPY . /panda diff --git a/tests/misra/coverage_table b/tests/misra/coverage_table index a00cd84a5f..dcb5992bc7 100644 --- a/tests/misra/coverage_table +++ b/tests/misra/coverage_table @@ -9,9 +9,9 @@ 2.6 X (Cppcheck) 2.7 3.1 X (Addon) -3.2 +3.2 X (Addon) 4.1 X (Addon) -4.2 +4.2 X (Addon) 5.1 X (Addon) 5.2 X (Addon) 5.3 X (Addon) @@ -123,7 +123,7 @@ 20.12 20.13 X (Addon) 20.14 X (Addon) -21.1 +21.1 X (Addon) 21.2 21.3 X (Addon) 21.4 X (Addon) @@ -134,7 +134,7 @@ 21.9 X (Addon) 21.10 X (Addon) 21.11 X (Addon) -21.12 +21.12 X (Addon) 22.1 X (Cppcheck) 22.2 X (Cppcheck) 22.3 diff --git a/tests/misra/suppressions.txt b/tests/misra/suppressions.txt index b98a491eeb..e0a270831a 100644 --- a/tests/misra/suppressions.txt +++ b/tests/misra/suppressions.txt @@ -4,3 +4,5 @@ misra.19.2 misra.11.4 # Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well misra.11.5 +# Required: it's ok re-defining potentially reserved Macro names. Not likely to cause confusion +misra.21.1 diff --git a/tests/misra/test_misra.sh b/tests/misra/test_misra.sh index c4aceaa92c..2542290744 100755 --- a/tests/misra/test_misra.sh +++ b/tests/misra/test_misra.sh @@ -4,7 +4,7 @@ mkdir /tmp/misra || true git clone https://github.com/danmar/cppcheck.git || true cd cppcheck git fetch -git checkout ff7dba91e177dfb712477faddb9e91bece7e743c +git checkout bdd41151ed550e3d240a6dd6847859216b7ad736 make -j4 cd ../../../ diff --git a/tests/pedal/enter_canloader.py b/tests/pedal/enter_canloader.py index cc37f2b843..4488c32056 100755 --- a/tests/pedal/enter_canloader.py +++ b/tests/pedal/enter_canloader.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import sys import time import struct import argparse diff --git a/tests/rtc_test.py b/tests/rtc_test.py new file mode 100755 index 0000000000..3732cb765f --- /dev/null +++ b/tests/rtc_test.py @@ -0,0 +1,13 @@ +#!/usr/bin/env python +import os +import sys +import datetime + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +if __name__ == "__main__": + p = Panda() + + p.set_datetime(datetime.datetime.now()) + print(p.get_datetime()) diff --git a/tests/safety/Dockerfile b/tests/safety/Dockerfile index b0135b085f..3c70d25341 100644 --- a/tests/safety/Dockerfile +++ b/tests/safety/Dockerfile @@ -14,6 +14,7 @@ RUN pyenv install 3.7.3 RUN pyenv global 3.7.3 RUN pyenv rehash -COPY tests/safety/requirements.txt requirements.txt -RUN pip install -r requirements.txt +COPY requirements.txt /tmp/ +RUN pip install -r /tmp/requirements.txt + COPY . /panda diff --git a/tests/safety/libpandasafety_py.py b/tests/safety/libpandasafety_py.py index bb332e52b6..819fcada37 100644 --- a/tests/safety/libpandasafety_py.py +++ b/tests/safety/libpandasafety_py.py @@ -30,6 +30,8 @@ typedef struct uint32_t CNT; } TIM_TypeDef; +bool board_has_relay(void); + void set_controls_allowed(bool c); bool get_controls_allowed(void); void set_long_controls_allowed(bool c); @@ -94,6 +96,11 @@ void set_subaru_desired_torque_last(int t); void set_subaru_rt_torque_last(int t); void set_subaru_torque_driver(int min, int max); +void init_tests_volkswagen(void); +void set_volkswagen_desired_torque_last(int t); +void set_volkswagen_rt_torque_last(int t); +void set_volkswagen_torque_driver(int min, int max); +int get_volkswagen_gas_prev(void); """) diff --git a/tests/safety/requirements.txt b/tests/safety/requirements.txt deleted file mode 100644 index 0c3124d87f..0000000000 --- a/tests/safety/requirements.txt +++ /dev/null @@ -1,4 +0,0 @@ -cffi==1.11.4 -numpy==1.14.5 -libusb1==1.6.6 -requests diff --git a/tests/safety/test.c b/tests/safety/test.c index d92eb8680f..c61f64077c 100644 --- a/tests/safety/test.c +++ b/tests/safety/test.c @@ -29,10 +29,27 @@ struct sample_t gm_torque_driver; struct sample_t hyundai_torque_driver; struct sample_t chrysler_torque_meas; struct sample_t subaru_torque_driver; +struct sample_t volkswagen_torque_driver; TIM_TypeDef timer; TIM_TypeDef *TIM2 = &timer; +// from board_declarations.h +#define HW_TYPE_UNKNOWN 0U +#define HW_TYPE_WHITE_PANDA 1U +#define HW_TYPE_GREY_PANDA 2U +#define HW_TYPE_BLACK_PANDA 3U +#define HW_TYPE_PEDAL 4U +#define HW_TYPE_UNO 5U + +// from main_declarations.h +uint8_t hw_type = HW_TYPE_UNKNOWN; + +// from board.h +bool board_has_relay(void) { + return hw_type == HW_TYPE_BLACK_PANDA || hw_type == HW_TYPE_UNO; +} + // from config.h #define MIN(a,b) \ ({ __typeof__ (a) _a = (a); \ @@ -52,16 +69,6 @@ TIM_TypeDef *TIM2 = &timer; #define GET_BYTES_04(msg) ((msg)->RDLR) #define GET_BYTES_48(msg) ((msg)->RDHR) -// from board_declarations.h -#define HW_TYPE_UNKNOWN 0U -#define HW_TYPE_WHITE_PANDA 1U -#define HW_TYPE_GREY_PANDA 2U -#define HW_TYPE_BLACK_PANDA 3U -#define HW_TYPE_PEDAL 4U - -// from main_declarations.h -uint8_t hw_type = 0U; - #define UNUSED(x) (void)(x) #define PANDA @@ -155,6 +162,11 @@ void set_subaru_torque_driver(int min, int max){ subaru_torque_driver.max = max; } +void set_volkswagen_torque_driver(int min, int max){ + volkswagen_torque_driver.min = min; + volkswagen_torque_driver.max = max; +} + int get_chrysler_torque_meas_min(void){ return chrysler_torque_meas.min; } @@ -199,6 +211,10 @@ void set_subaru_rt_torque_last(int t){ subaru_rt_torque_last = t; } +void set_volkswagen_rt_torque_last(int t){ + volkswagen_rt_torque_last = t; +} + void set_toyota_desired_torque_last(int t){ toyota_desired_torque_last = t; } @@ -223,6 +239,14 @@ void set_subaru_desired_torque_last(int t){ subaru_desired_torque_last = t; } +void set_volkswagen_desired_torque_last(int t){ + volkswagen_desired_torque_last = t; +} + +int get_volkswagen_gas_prev(void){ + return volkswagen_gas_prev; +} + bool get_honda_moving(void){ return honda_moving; } @@ -316,6 +340,16 @@ void init_tests_subaru(void){ set_timer(0); } +void init_tests_volkswagen(void){ + init_tests(); + volkswagen_torque_driver.min = 0; + volkswagen_torque_driver.max = 0; + volkswagen_desired_torque_last = 0; + volkswagen_rt_torque_last = 0; + volkswagen_ts_last = 0; + set_timer(0); +} + void init_tests_honda(void){ init_tests(); honda_moving = false; diff --git a/tests/safety/test.sh b/tests/safety/test.sh index 2674281add..39d70ff615 100755 --- a/tests/safety/test.sh +++ b/tests/safety/test.sh @@ -6,11 +6,12 @@ # HW_TYPE_GREY_PANDA 2U # HW_TYPE_BLACK_PANDA 3U # HW_TYPE_PEDAL 4U +# HW_TYPE_UNO 5U # Make sure test fails if one HW_TYPE fails set -e -for hw_type in 0 1 2 3 4 +for hw_type in 0 1 2 3 4 5 do echo "Testing HW_TYPE: $hw_type" HW_TYPE=$hw_type python -m unittest discover . diff --git a/tests/safety/test_cadillac.py b/tests/safety/test_cadillac.py index 5573682d0c..f211908b7b 100644 --- a/tests/safety/test_cadillac.py +++ b/tests/safety/test_cadillac.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 2 diff --git a/tests/safety/test_chrysler.py b/tests/safety/test_chrysler.py index 25f50a11f9..37bffe0eaf 100755 --- a/tests/safety/test_chrysler.py +++ b/tests/safety/test_chrysler.py @@ -1,9 +1,7 @@ #!/usr/bin/env python3 -import csv -import glob import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 3 diff --git a/tests/safety/test_gm.py b/tests/safety/test_gm.py index e2251f7b55..304dbbe939 100644 --- a/tests/safety/test_gm.py +++ b/tests/safety/test_gm.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 7 diff --git a/tests/safety/test_honda.py b/tests/safety/test_honda.py index a5eb04ad66..55a376a2e5 100755 --- a/tests/safety/test_honda.py +++ b/tests/safety/test_honda.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_BRAKE = 255 @@ -34,9 +34,9 @@ class TestHondaSafety(unittest.TestCase): to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') to_send[0].RIR = msg << 21 to_send[0].RDLR = buttons << 5 - is_panda_black = self.safety.get_hw_type() == 3 # black_panda + has_relay = self.safety.board_has_relay() honda_bosch_hardware = self.safety.get_honda_bosch_hardware() - bus = 1 if is_panda_black and honda_bosch_hardware else 0 + bus = 1 if has_relay and honda_bosch_hardware else 0 to_send[0].RDTR = bus << 4 return to_send diff --git a/tests/safety/test_honda_bosch.py b/tests/safety/test_honda_bosch.py index 3affc74c9a..7571e1eddc 100755 --- a/tests/safety/test_honda_bosch.py +++ b/tests/safety/test_honda_bosch.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 import unittest -import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_BRAKE = 255 @@ -22,12 +21,13 @@ class TestHondaSafety(unittest.TestCase): return to_send def test_fwd_hook(self): - buss = list(range(0x0, 0x3)) - msgs = list(range(0x1, 0x800)) - is_panda_black = self.safety.get_hw_type() == 3 # black panda - bus_rdr_cam = 2 if is_panda_black else 1 - bus_rdr_car = 0 if is_panda_black else 2 - bus_pt = 1 if is_panda_black else 0 + buss = range(0x0, 0x3) + msgs = range(0x1, 0x800) + #has_relay = self.safety.get_hw_type() == 3 # black panda + has_relay = self.safety.board_has_relay() + bus_rdr_cam = 2 if has_relay else 1 + bus_rdr_car = 0 if has_relay else 2 + bus_pt = 1 if has_relay else 0 blocked_msgs = [0xE4, 0x33D] for b in buss: diff --git a/tests/safety/test_hyundai.py b/tests/safety/test_hyundai.py index d836dad37b..d8fa02691b 100644 --- a/tests/safety/test_hyundai.py +++ b/tests/safety/test_hyundai.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 3 diff --git a/tests/safety/test_subaru.py b/tests/safety/test_subaru.py index 93859e0217..49933e6636 100644 --- a/tests/safety/test_subaru.py +++ b/tests/safety/test_subaru.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 50 diff --git a/tests/safety/test_toyota.py b/tests/safety/test_toyota.py index 135207779d..15d3b20cc5 100644 --- a/tests/safety/test_toyota.py +++ b/tests/safety/test_toyota.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda MAX_RATE_UP = 10 diff --git a/tests/safety/test_toyota_ipas.py b/tests/safety/test_toyota_ipas.py index 8d565553fd..df0f36ffd7 100644 --- a/tests/safety/test_toyota_ipas.py +++ b/tests/safety/test_toyota_ipas.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 import unittest import numpy as np -import libpandasafety_py +import libpandasafety_py # pylint: disable=import-error from panda import Panda IPAS_OVERRIDE_THRESHOLD = 200 @@ -233,8 +233,8 @@ class TestToyotaSafety(unittest.TestCase): self.safety.safety_tx_hook(self._ipas_control_msg(a, 1)) self.safety.set_controls_allowed(1) self.safety.safety_rx_hook(self._speed_msg(s)) - max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) - max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) + #max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) + #max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) self.safety.safety_rx_hook(self._angle_meas_msg(a)) self.assertTrue(self.safety.get_controls_allowed()) self.safety.safety_rx_hook(self._angle_meas_msg(a + 150)) diff --git a/tests/safety/test_volkswagen.py b/tests/safety/test_volkswagen.py new file mode 100644 index 0000000000..aa535cdac9 --- /dev/null +++ b/tests/safety/test_volkswagen.py @@ -0,0 +1,247 @@ +#!/usr/bin/env python3 +import unittest +import numpy as np +import libpandasafety_py # pylint: disable=import-error +from panda import Panda + +MAX_RATE_UP = 4 +MAX_RATE_DOWN = 10 +MAX_STEER = 250 + +MAX_RT_DELTA = 75 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 80 +DRIVER_TORQUE_FACTOR = 3 + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestVolkswagenSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.safety_set_mode(Panda.SAFETY_VOLKSWAGEN, 0) + cls.safety.init_tests_volkswagen() + + def _send_msg(self, bus, addr, length): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = addr << 21 + to_send[0].RDTR = length + to_send[0].RDTR = bus << 4 + return to_send + + def _set_prev_torque(self, t): + self.safety.set_volkswagen_desired_torque_last(t) + self.safety.set_volkswagen_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x9F << 21 + + t = abs(torque) + to_send[0].RDHR = ((t & 0x1FFF) << 8) + if torque < 0: + to_send[0].RDHR |= 0x1 << 23 + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x126 << 21 + + t = abs(torque) + to_send[0].RDLR = (t & 0xFFF) << 16 + if torque < 0: + to_send[0].RDLR |= 0x1 << 31 + return to_send + + def _gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x121 << 21 + to_send[0].RDLR = (gas & 0xFF) << 12 + + return to_send + + def _button_msg(self, bit): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x12B << 21 + to_send[0].RDLR = 1 << bit + to_send[0].RDTR = 2 << 4 + + return to_send + + def test_prev_gas(self): + for g in range(0, 256): + self.safety.safety_rx_hook(self._gas_msg(g)) + self.assertEqual(g, self.safety.get_volkswagen_gas_prev()) + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x122 << 21 + to_push[0].RDHR = 0x30000000 + + self.safety.safety_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x122 << 21 + to_push[0].RDHR = 0 + + self.safety.set_controls_allowed(1) + self.safety.safety_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_disengage_on_gas(self): + for long_controls_allowed in [0, 1]: + self.safety.set_long_controls_allowed(long_controls_allowed) + self.safety.safety_rx_hook(self._gas_msg(0)) + self.safety.set_controls_allowed(True) + self.safety.safety_rx_hook(self._gas_msg(1)) + if long_controls_allowed: + self.assertFalse(self.safety.get_controls_allowed()) + else: + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_long_controls_allowed(True) + + def test_allow_engage_with_gas_pressed(self): + self.safety.safety_rx_hook(self._gas_msg(1)) + self.safety.set_controls_allowed(True) + self.safety.safety_rx_hook(self._gas_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.safety_rx_hook(self._gas_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-500, 500): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(t))) + + 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_spam_cancel_safety_check(self): + BIT_CANCEL = 13 + BIT_RESUME = 19 + BIT_SET = 16 + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.safety_tx_hook(self._button_msg(BIT_CANCEL))) + self.assertFalse(self.safety.safety_tx_hook(self._button_msg(BIT_RESUME))) + self.assertFalse(self.safety.safety_tx_hook(self._button_msg(BIT_SET))) + # do not block resume if we are engaged already + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.safety_tx_hook(self._button_msg(BIT_RESUME))) + + def test_non_realtime_limit_up(self): + self.safety.set_volkswagen_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_volkswagen_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_against_torque_driver(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_volkswagen_torque_driver(t, t) + self._set_prev_torque(MAX_STEER * sign) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(MAX_STEER * sign))) + + self.safety.set_volkswagen_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(-MAX_STEER))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_volkswagen_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_volkswagen_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_volkswagen_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_volkswagen_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_volkswagen_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg((MAX_STEER - 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_volkswagen() + self._set_prev_torque(0) + self.safety.set_volkswagen_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.safety_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.safety_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + + def test_fwd_hook(self): + buss = list(range(0x0, 0x2)) + msgs = list(range(0x1, 0x800)) + blocked_msgs_0to2 = [] + blocked_msgs_2to0 = [0x122, 0x397] + for b in buss: + for m in msgs: + if b == 0: + fwd_bus = -1 if m in blocked_msgs_0to2 else 2 + elif b == 1: + fwd_bus = -1 + elif b == 2: + fwd_bus = -1 if m in blocked_msgs_2to0 else 0 + + # assume len 8 + self.assertEqual(fwd_bus, self.safety.safety_fwd_hook(b, self._send_msg(b, m, 8))) + + +if __name__ == "__main__": + unittest.main() diff --git a/tests/safety_replay/Dockerfile b/tests/safety_replay/Dockerfile index 80663964d3..f5175c7458 100644 --- a/tests/safety_replay/Dockerfile +++ b/tests/safety_replay/Dockerfile @@ -14,8 +14,10 @@ RUN pyenv install 3.7.3 RUN pyenv global 3.7.3 RUN pyenv rehash -COPY tests/safety_replay/requirements.txt requirements.txt -RUN pip install -r requirements.txt +COPY requirements.txt /tmp/ +RUN pip install -r /tmp/requirements.txt +COPY tests/safety_replay/requirements_extra.txt requirements_extra.txt +RUN pip install -r requirements_extra.txt COPY tests/safety_replay/install_capnp.sh install_capnp.sh RUN ./install_capnp.sh diff --git a/tests/safety_replay/replay_drive.py b/tests/safety_replay/replay_drive.py index d92ab8e708..3db57dfd16 100755 --- a/tests/safety_replay/replay_drive.py +++ b/tests/safety_replay/replay_drive.py @@ -2,12 +2,9 @@ import os import sys -from panda import Panda import panda.tests.safety.libpandasafety_py as libpandasafety_py -from panda.tests.safety_replay.helpers import is_steering_msg, get_steer_torque, \ - set_desired_torque_last, package_can_msg, \ - init_segment -from tools.lib.logreader import LogReader +from panda.tests.safety_replay.helpers import package_can_msg, init_segment +from tools.lib.logreader import LogReader # pylint: disable=import-error # replay a drive to check for safety violations def replay_drive(lr, safety_mode, param): diff --git a/tests/safety_replay/requirements.txt b/tests/safety_replay/requirements.txt deleted file mode 100644 index 4c9d301dce..0000000000 --- a/tests/safety_replay/requirements.txt +++ /dev/null @@ -1,8 +0,0 @@ -aenum -cffi==1.11.4 -libusb1==1.6.6 -numpy==1.14.5 -requests -subprocess32 -libarchive -pycapnp diff --git a/tests/safety_replay/requirements_extra.txt b/tests/safety_replay/requirements_extra.txt new file mode 100644 index 0000000000..b04b7674d7 --- /dev/null +++ b/tests/safety_replay/requirements_extra.txt @@ -0,0 +1,4 @@ +aenum +subprocess32 +libarchive +pycapnp diff --git a/tests/safety_replay/test_safety_replay.py b/tests/safety_replay/test_safety_replay.py index e6e49dc02d..cb38a94edf 100755 --- a/tests/safety_replay/test_safety_replay.py +++ b/tests/safety_replay/test_safety_replay.py @@ -5,7 +5,7 @@ import requests from panda import Panda from replay_drive import replay_drive -from tools.lib.logreader import LogReader +from tools.lib.logreader import LogReader # pylint: disable=import-error BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" diff --git a/tests/spam_can.py b/tests/spam_can.py index 6b0c2d9c60..1daffdbd91 100755 --- a/tests/spam_can.py +++ b/tests/spam_can.py @@ -2,7 +2,6 @@ import os import sys -import time import random sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) @@ -21,4 +20,4 @@ if __name__ == "__main__": st = get_test_string()[0:8] bus = random.randint(0, 2) p.can_send(at, st, bus) - #print("Sent message on bus: ", bus) \ No newline at end of file + #print("Sent message on bus: ", bus) diff --git a/tests/throughput_test.py b/tests/throughput_test.py index 69b06c7646..9f60212401 100755 --- a/tests/throughput_test.py +++ b/tests/throughput_test.py @@ -25,7 +25,7 @@ if __name__ == "__main__": # p_in.can_recv() #sys.exit(0) - p_out.set_controls_allowed(True) + p_out.set_safety_mode(Panda.SAFETY_ALLOUTPUT) set_out, set_in = set(), set() diff --git a/tests/tucan_loopback.py b/tests/tucan_loopback.py index 1b5ed01663..cb5d1cbfea 100755 --- a/tests/tucan_loopback.py +++ b/tests/tucan_loopback.py @@ -33,7 +33,7 @@ def run_test_w_pandas(pandas, sleep_duration): print("H", h) for hh in h: - hh.set_controls_allowed(True) + hh.set_safety_mode(Panda.SAFETY_ALLOUTPUT) # test both directions for ho in permutations(list(range(len(h))), r=2): @@ -55,7 +55,7 @@ def run_test_w_pandas(pandas, sleep_duration): # send the characters st = get_test_string() - st = b"\xaa"+chr(len(st)+3).encode()+st + st = bytes([0xaa, len(st) + 3]) + st h[ho[0]].kline_send(st, bus=bus, checksum=False) # check for receive @@ -70,8 +70,8 @@ def run_test_w_pandas(pandas, sleep_duration): time.sleep(sleep_duration) # **** test can line loopback **** -# for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]: -for bus, gmlan in [(0, None), (1, None)]: + # for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]: + for bus, gmlan in [(0, None), (1, None)]: print("\ntest can", bus) # flush cans_echo = panda0.can_recv()