From 6f518e8816d77fe251decdd457ed40efbb573d9e Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Wed, 9 Oct 2019 18:31:56 +0000 Subject: [PATCH] Squashed 'panda/' changes from 9881e6118..30c7ca8a5 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 30c7ca8a5 bump version to 1.5.3 9403dbebe Need to fix wifi test before re-enabling. 0812362b5 GPS UART fix until boardd is refactored (#294) ffbdb87a8 python2 -> 3 fixes to pedal flasher (#292) 78b75ef59 Added build type to release version strings 736c2cbf7 Fixed sending of bytes over PandaSerial 0894b28f1 Fixed USB power mode on black (#291) 4b3358c92 patch to be able to switch from EON to PC with a Panda that has EON b… (#290) a95c44a71 Made setting of NOOUTPUT on no heartbeat more efficient (#287) 948683688 UART instability fix with high interrupt load (#283) 9a9e9d47b Fix usb_power_mode missing initialization (#289) af0960ad3 DFU fix (#288) 70219d7bb match safety enum in cereal (#285) a338d3932 Fix build for jenkins test 78ef4a6eb Stop charge (#284) 5266a4028 Fix typo (#286) f4787ec5a Revert "turn on CDP when ignition switches on (#281)" d37daee97 Revert "NONE and CLIENT should be the same thing in white/grey pandas" e97b283e7 NONE and CLIENT should be the same thing in white/grey pandas 8c1df559f turn on CDP when ignition switches on (#281) 847a35d42 Fix bullet points fac027716 Misra update (#280) 5a04df6b1 Added description of regression tests to README c4aabae59 Fixed some python3 bugs in the test scripts and PandaSerial 9af0cb353 Bump version c4ac3d63b Disable GPS load switching on black pandas 078ee588c This is the correct table, actually 578b95ee3 Misra table of coverage added d383a2625 bump panda b98ca010d fix sdk build in python3 env (#279) 63d3dc7d3 Set python3 env before runnign get_sdk, so we know if it fails e951d79c0 legacy code we don't control can remain python2 11b715118 Merge pull request #276 from commaai/python3 9893a842a Merge pull request #277 from zorrobyte/patch-1 d3268690c Revert "revert back esptool to python2 and force to build esptools with python2" 875e76012 revert back esptool to python2 and force to build esptools with python2 9c40e6240 needed to install python3 ed2ac87cf Also moved safety tests to python3 6842b2d2c move esptool sdk installation before python3 env is set. Kind of a cheat b5a2cabcd this hopefully fixes build test 628050955 Fixes safety replay 2c220b623 this fixes language regr test fdbe789b8 use python 3 in Docker container ee1ae4f86 Better hash print 0de9ef73c Revert "Final 2to3 on the whole repo" c92fd3bc9 Final 2to3 on the whole repo 5f2bc4460 better b2a30fdbd make works! b74005d10 fix sign.py fe727706b read file as byte and no tab before sleep 32a344ef6 Update README.md 2dc34096a 2to3 applied ffa68ef71 undo unnecessary brackets for print dbc248027 Fix all the prints with 2to3, some need to be undo 5a7aeba0f xrange is gone 982c4c928 one more python3 env 1e2412a29 env python -> env python3 git-subtree-dir: panda git-subtree-split: 30c7ca8a53a3adb05d23d7cfe64fb716a656ef1a old-commit-hash: 38faf7f8a45dd933437ebdfd44534935c34dacaa --- .circleci/config.yml | 2 +- Dockerfile | 21 +- Jenkinsfile | 13 - README.md | 28 +- VERSION | 2 +- board/board_declarations.h | 2 +- board/boards/black.h | 33 +- board/boards/white.h | 54 +-- board/bootstub.c | 3 +- board/config.h | 3 +- board/drivers/adc.h | 10 + board/drivers/can.h | 9 +- board/drivers/uart.h | 429 +++++++++++++--------- board/drivers/usb.h | 4 +- board/main.c | 75 ++-- board/pedal/main.c | 3 - board/safety.h | 49 +-- board/safety/safety_gm.h | 2 +- board/tools/enter_download_mode.py | 4 +- boardesp/Makefile | 4 +- boardesp/elm327.c | 4 +- boardesp/get_sdk.sh | 4 +- boardesp/get_sdk_ci.sh | 3 +- boardesp/get_sdk_mac.sh | 4 +- boardesp/python2_make.py | 4 + crypto/getcertheader.py | 16 +- crypto/sign.py | 18 +- drivers/linux/panda.c | 5 +- drivers/windows/panda_shared/panda.h | 2 +- examples/can_bit_transition.py | 18 +- examples/can_logger.py | 4 +- examples/can_unique.py | 18 +- examples/get_panda_password.py | 4 +- examples/query_vin_and_stats.py | 10 +- examples/tesla_tester.py | 2 +- python/__init__.py | 70 ++-- python/dfu.py | 34 +- python/esptool.py | 126 +++---- python/flash_release.py | 8 +- python/isotp.py | 54 +-- python/serial.py | 7 +- python/update.py | 4 +- release/make_release.sh | 1 + run_automated_tests.sh | 2 +- tests/all_wifi_test.py | 8 +- tests/automated/1_program.py | 2 +- tests/automated/2_usb_to_can.py | 28 +- tests/automated/3_wifi.py | 4 +- tests/automated/4_wifi_functionality.py | 4 +- tests/automated/5_wifi_udp.py | 6 +- tests/automated/6_two_panda.py | 18 +- tests/automated/helpers.py | 30 +- tests/black_loopback_test.py | 11 +- tests/black_white_loopback_test.py | 27 +- tests/black_white_relay_endurance.py | 25 +- tests/black_white_relay_test.py | 4 +- tests/build/Dockerfile | 18 +- tests/can_printer.py | 8 +- tests/debug_console.py | 26 +- tests/disable_esp.py | 2 +- tests/elm_car_simulator.py | 4 +- tests/elm_throughput.py | 4 +- tests/elm_wifi.py | 8 +- tests/get_version.py | 2 +- tests/gmbitbang/recv.py | 6 +- tests/gmbitbang/rigol.py | 8 +- tests/gmbitbang/test.py | 4 +- tests/gmbitbang/test_one.py | 6 +- tests/gps_stability_test.py | 169 +++++++++ tests/health_test.py | 4 +- tests/language/Dockerfile | 16 +- tests/language/test_language.py | 6 +- tests/location_listener.py | 14 +- tests/loopback_test.py | 8 +- tests/misra/coverage_table | 143 ++++++++ tests/misra/suppressions.txt | 2 - tests/misra/test_misra.sh | 12 +- tests/pedal/enter_canloader.py | 14 +- tests/read_winusb_descriptors.py | 16 +- tests/safety/Dockerfile | 19 +- tests/safety/requirements.txt | 4 +- tests/safety/test_cadillac.py | 9 +- tests/safety/test_chrysler.py | 9 +- tests/safety/test_gm.py | 9 +- tests/safety/test_honda.py | 9 +- tests/safety/test_honda_bosch.py | 9 +- tests/safety/test_hyundai.py | 9 +- tests/safety/test_subaru.py | 9 +- tests/safety/test_toyota.py | 9 +- tests/safety/test_toyota_ipas.py | 7 +- tests/safety_replay/Dockerfile | 16 +- tests/safety_replay/helpers.py | 56 +-- tests/safety_replay/replay_drive.py | 26 +- tests/safety_replay/test_safety_replay.py | 27 +- tests/spam_can.py | 24 ++ tests/standalone_test.py | 2 +- tests/throughput_test.py | 8 +- tests/tucan_loopback.py | 8 +- 98 files changed, 1313 insertions(+), 795 deletions(-) create mode 100644 boardesp/python2_make.py create mode 100755 tests/gps_stability_test.py create mode 100644 tests/misra/coverage_table create mode 100755 tests/spam_can.py diff --git a/.circleci/config.yml b/.circleci/config.yml index d74c1a20e0..6348ff0f55 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -11,7 +11,7 @@ jobs: - run: name: Run safety test command: | - docker run panda_safety /bin/bash -c "cd /panda/tests/safety; ./test.sh" + docker run panda_safety /bin/bash -c "cd /panda/tests/safety; PYTHONPATH=/ ./test.sh" misra-c2012: machine: diff --git a/Dockerfile b/Dockerfile index 1a0d924661..a029a5ffa4 100644 --- a/Dockerfile +++ b/Dockerfile @@ -17,11 +17,15 @@ RUN apt-get update && apt-get install -y \ gperf \ help2man \ iputils-ping \ + libbz2-dev \ libexpat-dev \ + libffi-dev \ + libssl-dev \ libstdc++-arm-none-eabi-newlib \ libtool \ libtool-bin \ libusb-1.0-0 \ + locales \ make \ ncurses-dev \ network-manager \ @@ -38,7 +42,21 @@ RUN apt-get update && apt-get install -y \ screen \ vim \ wget \ - wireless-tools + wireless-tools \ + zlib1g-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 install 2.7.12 +RUN pyenv global 3.7.3 +RUN pyenv rehash RUN pip install --upgrade pip==18.0 @@ -51,6 +69,7 @@ ENV HOME /home/batman ENV PYTHONPATH /tmp:$PYTHONPATH COPY ./boardesp/get_sdk_ci.sh /tmp/panda/boardesp/ +COPY ./boardesp/python2_make.py /tmp/panda/boardesp/ RUN useradd --system -s /sbin/nologin pandauser RUN mkdir -p /tmp/panda/boardesp/esp-open-sdk diff --git a/Jenkinsfile b/Jenkinsfile index 19dc3d4c80..7f147a2fe9 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -46,19 +46,6 @@ 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 42f432dfc3..7c9bd68bf7 100644 --- a/README.md +++ b/README.md @@ -37,6 +37,13 @@ And to send one on bus 0: ``` Find user made scripts on the [wiki](https://community.comma.ai/wiki/index.php/Panda_scripts) +Note that you may have to setup [udev rules](https://community.comma.ai/wiki/index.php/Panda#Linux_udev_rules) for Linux, such as +``` +sudo -i +echo 'SUBSYSTEMS=="usb", ATTR{idVendor}=="bbaa", ATTR{idProduct}=="ddcc", MODE:="0666"' > /etc/udev/rules.d/11-panda.rules +exit +``` + Usage (JavaScript) ------- @@ -80,9 +87,26 @@ To print out the serial console from the ESP8266, run PORT=1 tests/debug_console Safety Model ------ -When a panda powers up, by default it's in "SAFETY_NOOUTPUT" mode. While in no output mode, the buses are also forced to be silent. In order to send messages, you have to select a safety mode. Currently, setting safety modes is only supported over USB. +When a panda powers up, by default it's in `SAFETY_NOOUTPUT` mode. While in no output mode, the buses are also forced to be silent. In order to send messages, you have to select a safety mode. Currently, setting safety modes is only supported over USB. -Safety modes can also optionally support "controls_allowed", which allows or blocks a subset of messages based on a piece of state in the board. +Safety modes optionally supports `controls_allowed`, which allows or blocks a subset of messages based on a customizable state in the board. + +Code Rigor +------ +When compiled from an [EON Dev Kit](https://comma.ai/shop/products/eon-gold-dashcam-devkit), the panda FW is configured and optimized (at compile time) for its use in +conjuction with [openpilot](https://github.com/commaai/openpilot). The panda FW, through its safety model, provides and enforces the +[openpilot Safety](https://github.com/commaai/openpilot/blob/devel/SAFETY.md). Due to its critical function, it's important that the application code rigor within the `board` folder is held to high standards. + +These are the [CI regression tests](https://circleci.com/gh/commaai/panda) we have in place: +* A generic static code analysis is performed by [Cppcheck](https://github.com/danmar/cppcheck/). +* In addition, [Cppcheck](https://github.com/danmar/cppcheck/) has a specific addon to check for [MISRA C:2012](https://www.misra.org.uk/MISRAHome/MISRAC2012/tabid/196/Default.aspx) violations. See [current coverage](https://github.com/commaai/panda/blob/master/tests/misra/coverage_table). +* Compiler options are relatively strict: the flags `-Wall -Wextra -Wstrict-prototypes -Werror` are enforced on board and pedal makefiles. +* The [safety logic](https://github.com/commaai/panda/tree/master/board/safety) is tested and verified by [unit tests](https://github.com/commaai/panda/tree/master/tests/safety) for each supported car variant. +* A recorded drive for each supported car variant is [replayed through the safety logic](https://github.com/commaai/panda/tree/master/tests/safety_replay) +to ensure that the behavior remains unchanged. +* An internal Hardware-in-the-loop test, which currently only runs on pull requests opened by comma.ai's organization members, verifies the following functionalities: + * 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. Hardware ------ diff --git a/VERSION b/VERSION index 880b851599..01558e339a 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -v1.4.7 \ No newline at end of file +v1.5.3 \ No newline at end of file diff --git a/board/board_declarations.h b/board/board_declarations.h index cc93ec7c97..21eb140c3e 100644 --- a/board/board_declarations.h +++ b/board/board_declarations.h @@ -36,7 +36,7 @@ struct board { #define LED_GREEN 1U #define LED_BLUE 2U -// USB power modes +// USB power modes (from cereal.log.health) #define USB_POWER_NONE 0U #define USB_POWER_CLIENT 1U #define USB_POWER_CDP 2U diff --git a/board/boards/black.h b/board/boards/black.h index 62b3b67403..c6078e3b56 100644 --- a/board/boards/black.h +++ b/board/boards/black.h @@ -38,7 +38,7 @@ void black_set_led(uint8_t color, bool enabled) { break; case LED_BLUE: set_gpio_output(GPIOC, 6, !enabled); - break; + break; default: break; } @@ -53,11 +53,22 @@ void black_set_usb_load_switch(bool enabled) { } void black_set_usb_power_mode(uint8_t mode) { - usb_power_mode = mode; - if (mode == USB_POWER_NONE) { - black_set_usb_load_switch(false); - } else { - black_set_usb_load_switch(true); + bool valid = false; + switch (mode) { + case USB_POWER_CLIENT: + black_set_usb_load_switch(false); + valid = true; + break; + case USB_POWER_CDP: + black_set_usb_load_switch(true); + valid = true; + break; + default: + puts("Invalid USB power mode\n"); + break; + } + if (valid) { + usb_power_mode = mode; } } @@ -67,18 +78,15 @@ void black_set_esp_gps_mode(uint8_t mode) { // GPS OFF set_gpio_output(GPIOC, 14, 0); set_gpio_output(GPIOC, 5, 0); - black_set_gps_load_switch(false); break; case ESP_GPS_ENABLED: // GPS ON set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 1); - black_set_gps_load_switch(true); break; case ESP_GPS_BOOTMODE: set_gpio_output(GPIOC, 14, 1); set_gpio_output(GPIOC, 5, 0); - black_set_gps_load_switch(true); break; default: puts("Invalid ESP/GPS mode\n"); @@ -106,7 +114,7 @@ void black_set_can_mode(uint8_t mode){ // 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"); @@ -154,6 +162,9 @@ void black_init(void) { // Turn on USB load switch. black_set_usb_load_switch(true); + // Set right power mode + black_set_usb_power_mode(USB_POWER_CDP); + // Initialize harness harness_init(); @@ -203,4 +214,4 @@ const board board_black = { .set_can_mode = black_set_can_mode, .usb_power_mode_tick = black_usb_power_mode_tick, .check_ignition = black_check_ignition -}; \ No newline at end of file +}; diff --git a/board/boards/white.h b/board/boards/white.h index 46668c3a81..241f1b91bc 100644 --- a/board/boards/white.h +++ b/board/boards/white.h @@ -34,7 +34,7 @@ void white_set_led(uint8_t color, bool enabled) { break; case LED_BLUE: set_gpio_output(GPIOC, 6, !enabled); - break; + break; default: break; } @@ -125,7 +125,7 @@ void white_set_can_mode(uint8_t mode){ // A8,A15: normal CAN3 mode set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); + set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); break; case CAN_MODE_GMLAN_CAN3: // A8,A15: disable CAN3 mode @@ -143,7 +143,7 @@ void white_set_can_mode(uint8_t mode){ // B5,B6: normal CAN2 mode set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - break; + break; default: puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); break; @@ -152,7 +152,9 @@ void white_set_can_mode(uint8_t mode){ uint64_t marker = 0; void white_usb_power_mode_tick(uint64_t tcnt){ - #ifndef BOOTSTUB + + // on EON or BOOTSTUB, no state machine +#if !defined(BOOTSTUB) && !defined(EON) #define CURRENT_THRESHOLD 0xF00U #define CLICKS 5U // 5 seconds to switch modes @@ -177,22 +179,19 @@ void white_usb_power_mode_tick(uint64_t tcnt){ } break; case USB_POWER_CDP: - // On the EON, if we get into CDP mode we stay here. No need to go to DCP. - #ifndef EON - // been CLICKS clicks since we switched to CDP - if ((tcnt-marker) >= CLICKS) { - // measure current draw, if positive and no enumeration, switch to DCP - if (!is_enumerated && (current < CURRENT_THRESHOLD)) { - puts("USBP: no enumeration with current draw, switching to DCP mode\n"); - white_set_usb_power_mode(USB_POWER_DCP); - marker = tcnt; - } - } - // keep resetting the timer if there's no current draw in CDP - if (current >= CURRENT_THRESHOLD) { + // been CLICKS clicks since we switched to CDP + if ((tcnt-marker) >= CLICKS) { + // measure current draw, if positive and no enumeration, switch to DCP + if (!is_enumerated && (current < CURRENT_THRESHOLD)) { + puts("USBP: no enumeration with current draw, switching to DCP mode\n"); + white_set_usb_power_mode(USB_POWER_DCP); marker = tcnt; } - #endif + } + // keep resetting the timer if there's no current draw in CDP + if (current >= CURRENT_THRESHOLD) { + marker = tcnt; + } break; case USB_POWER_DCP: // been at least CLICKS clicks since we switched to DCP @@ -213,9 +212,9 @@ void white_usb_power_mode_tick(uint64_t tcnt){ puts("USB power mode invalid\n"); // set_usb_power_mode prevents assigning invalid values break; } - #else +#else UNUSED(tcnt); - #endif +#endif } bool white_check_ignition(void){ @@ -242,9 +241,6 @@ void white_init(void) { set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); - // Set USB power mode - white_set_usb_power_mode(USB_POWER_CLIENT); - // B12: GMLAN, ignition sense, pull up set_gpio_pullup(GPIOB, 12, PULL_UP); @@ -292,6 +288,16 @@ void white_init(void) { EXTI->RTSR |= (1U << 1); EXTI->FTSR |= (1U << 1); NVIC_EnableIRQ(EXTI1_IRQn); + + // Init usb power mode + uint32_t voltage = adc_get_voltage(); + // Init in CDP mode only if panda is powered by 12V. + // Otherwise a PC would not be able to flash a standalone panda with EON build + if (voltage > 8000U) { // 8V threshold + white_set_usb_power_mode(USB_POWER_CDP); + } else { + white_set_usb_power_mode(USB_POWER_CLIENT); + } } const harness_configuration white_harness_config = { @@ -310,4 +316,4 @@ const board board_white = { .set_can_mode = white_set_can_mode, .usb_power_mode_tick = white_usb_power_mode_tick, .check_ignition = white_check_ignition -}; \ No newline at end of file +}; diff --git a/board/bootstub.c b/board/bootstub.c index 3b6b1e875e..51ce6695db 100644 --- a/board/bootstub.c +++ b/board/bootstub.c @@ -32,6 +32,7 @@ const board *current_board; #include "drivers/clock.h" #include "drivers/llgpio.h" +#include "drivers/adc.h" #include "board.h" @@ -68,8 +69,6 @@ int main(void) { detect_configuration(); detect_board_type(); - current_board->set_usb_power_mode(USB_POWER_CLIENT); - if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { enter_bootloader_mode = 0; soft_flasher_start(); diff --git a/board/config.h b/board/config.h index 7fd203fc30..c2eb412e96 100644 --- a/board/config.h +++ b/board/config.h @@ -2,6 +2,7 @@ #define PANDA_CONFIG_H //#define DEBUG +//#define DEBUG_UART //#define DEBUG_USB //#define DEBUG_SPI @@ -22,7 +23,7 @@ #include #define NULL ((void*)0) -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * (!(pred)))])) +#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) #define MIN(a,b) \ ({ __typeof__ (a) _a = (a); \ diff --git a/board/drivers/adc.h b/board/drivers/adc.h index efd0a16878..2a91fef8dc 100644 --- a/board/drivers/adc.h +++ b/board/drivers/adc.h @@ -36,3 +36,13 @@ uint32_t adc_get(unsigned int channel) { return ADC1->JDR1; } +uint32_t adc_get_voltage(void) { + // REVC has a 10, 1 (1/11) voltage divider + // Here is the calculation for the scale (s) + // ADCV = VIN_S * (1/11) * (4095/3.3) + // RETVAL = ADCV * s = VIN_S*1000 + // s = 1000/((4095/3.3)*(1/11)) = 8.8623046875 + + // Avoid needing floating point math, so output in mV + return (adc_get(ADCCHAN_VOLTAGE) * 8862U) / 1000U; +} diff --git a/board/drivers/can.h b/board/drivers/can.h index d0d7064972..c45a3fe8d1 100644 --- a/board/drivers/can.h +++ b/board/drivers/can.h @@ -298,7 +298,7 @@ void process_can(uint8_t can_number) { to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000FU) | ((CAN_BUS_RET_FLAG | bus_number) << 4); to_push.RDLR = CAN->sTxMailBox[0].TDLR; to_push.RDHR = CAN->sTxMailBox[0].TDHR; - can_send_errs += !can_push(&can_rx_q, &to_push); + can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; } if ((CAN->TSR & CAN_TSR_TERR0) == CAN_TSR_TERR0) { @@ -367,7 +367,7 @@ void can_rx(uint8_t can_number) { safety_rx_hook(&to_push); current_board->set_led(LED_BLUE, true); - can_send_errs += !can_push(&can_rx_q, &to_push); + can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; // next CAN->RF0R |= CAN_RF0R_RFOM0; @@ -393,10 +393,9 @@ void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) { // bus number isn't passed through to_push->RDTR &= 0xF; if ((bus_number == 3U) && (can_num_lookup[3] == 0xFFU)) { - // TODO: why uint8 bro? only int8? - gmlan_send_errs += !bitbang_gmlan(to_push); + gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; } else { - can_fwd_errs += !can_push(can_queues[bus_number], to_push); + can_fwd_errs += can_push(can_queues[bus_number], to_push) ? 0U : 1U; process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); } } diff --git a/board/drivers/uart.h b/board/drivers/uart.h index 451150d1af..3a095f6726 100644 --- a/board/drivers/uart.h +++ b/board/drivers/uart.h @@ -1,18 +1,43 @@ // IRQs: USART1, USART2, USART3, UART5 -#define FIFO_SIZE 0x400U +// ***************************** Definitions ***************************** +#define FIFO_SIZE_INT 0x400U +#define FIFO_SIZE_DMA 0x1000U + typedef struct uart_ring { volatile uint16_t w_ptr_tx; volatile uint16_t r_ptr_tx; - uint8_t elems_tx[FIFO_SIZE]; + uint8_t *elems_tx; + uint32_t tx_fifo_size; volatile uint16_t w_ptr_rx; volatile uint16_t r_ptr_rx; - uint8_t elems_rx[FIFO_SIZE]; + uint8_t *elems_rx; + uint32_t rx_fifo_size; USART_TypeDef *uart; void (*callback)(struct uart_ring*); + bool dma_rx; } uart_ring; -void uart_init(USART_TypeDef *u, int baud); +#define UART_BUFFER(x, size_rx, size_tx, uart_ptr, callback_ptr, rx_dma) \ + uint8_t elems_rx_##x[size_rx]; \ + uint8_t elems_tx_##x[size_tx]; \ + uart_ring uart_ring_##x = { \ + .w_ptr_tx = 0, \ + .r_ptr_tx = 0, \ + .elems_tx = ((uint8_t *)&elems_tx_##x), \ + .tx_fifo_size = size_tx, \ + .w_ptr_rx = 0, \ + .r_ptr_rx = 0, \ + .elems_rx = ((uint8_t *)&elems_rx_##x), \ + .rx_fifo_size = size_rx, \ + .uart = uart_ptr, \ + .callback = callback_ptr, \ + .dma_rx = rx_dma \ + }; + + +// ***************************** Function prototypes ***************************** +void uart_init(uart_ring *q, int baud); bool getc(uart_ring *q, char *elem); bool putc(uart_ring *q, char elem); @@ -21,48 +46,35 @@ void puts(const char *a); void puth(unsigned int i); void hexdump(const void *a, int l); +void debug_ring_callback(uart_ring *ring); -// ***************************** serial port queues ***************************** +// ******************************** UART buffers ******************************** -// esp = USART1 -uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, - .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = USART1, - .callback = NULL}; +// esp_gps = USART1 +UART_BUFFER(esp_gps, FIFO_SIZE_DMA, FIFO_SIZE_INT, USART1, NULL, true) // lin1, K-LINE = UART5 // lin2, L-LINE = USART3 -uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, - .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = UART5, - .callback = NULL}; -uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, - .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = USART3, - .callback = NULL}; +UART_BUFFER(lin1, FIFO_SIZE_INT, FIFO_SIZE_INT, UART5, NULL, false) +UART_BUFFER(lin2, FIFO_SIZE_INT, FIFO_SIZE_INT, USART3, NULL, false) // debug = USART2 -void debug_ring_callback(uart_ring *ring); -uart_ring debug_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, - .w_ptr_rx = 0, .r_ptr_rx = 0, - .uart = USART2, - .callback = debug_ring_callback}; - +UART_BUFFER(debug, FIFO_SIZE_INT, FIFO_SIZE_INT, USART2, debug_ring_callback, false) uart_ring *get_ring_by_number(int a) { uart_ring *ring = NULL; switch(a) { case 0: - ring = &debug_ring; + ring = &uart_ring_debug; break; case 1: - ring = &esp_ring; + ring = &uart_ring_esp_gps; break; case 2: - ring = &lin1_ring; + ring = &uart_ring_lin1; break; case 3: - ring = &lin2_ring; + ring = &uart_ring_lin2; break; default: ring = NULL; @@ -71,52 +83,219 @@ uart_ring *get_ring_by_number(int a) { return ring; } -// ***************************** serial port ***************************** +// ***************************** Interrupt handlers ***************************** -void uart_ring_process(uart_ring *q) { +void uart_tx_ring(uart_ring *q){ ENTER_CRITICAL(); - // TODO: check if external serial is connected - int sr = q->uart->SR; - + // Send out next byte of TX buffer if (q->w_ptr_tx != q->r_ptr_tx) { - if ((sr & USART_SR_TXE) != 0) { - q->uart->DR = q->elems_tx[q->r_ptr_tx]; - q->r_ptr_tx = (q->r_ptr_tx + 1U) % FIFO_SIZE; + // Only send if transmit register is empty (aka last byte has been sent) + if ((q->uart->SR & USART_SR_TXE) != 0) { + q->uart->DR = q->elems_tx[q->r_ptr_tx]; // This clears TXE + q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; + } + + // Enable TXE interrupt if there is still data to be sent + if(q->r_ptr_tx != q->w_ptr_tx){ + q->uart->CR1 |= USART_CR1_TXEIE; + } else { + q->uart->CR1 &= ~USART_CR1_TXEIE; } - // there could be more to send - q->uart->CR1 |= USART_CR1_TXEIE; - } else { - // nothing to send - q->uart->CR1 &= ~USART_CR1_TXEIE; } + EXIT_CRITICAL(); +} - if ((sr & USART_SR_RXNE) || (sr & USART_SR_ORE)) { - uint8_t c = q->uart->DR; // TODO: can drop packets - if (q != &esp_ring) { - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % FIFO_SIZE; - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback != NULL) { - q->callback(q); - } +void uart_rx_ring(uart_ring *q){ + // Do not read out directly if DMA enabled + if (q->dma_rx == false) { + ENTER_CRITICAL(); + + // Read out RX buffer + uint8_t c = q->uart->DR; // This read after reading SR clears a bunch of interrupts + + uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; + // Do not overwrite buffer data + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + if (q->callback != NULL) { + q->callback(q); } } + + EXIT_CRITICAL(); } +} + +// This function should be called on: +// * Half-transfer DMA interrupt +// * Full-transfer DMA interrupt +// * UART IDLE detection +uint32_t prev_w_index = 0; +void dma_pointer_handler(uart_ring *q, uint32_t dma_ndtr) { + ENTER_CRITICAL(); + uint32_t w_index = (q->rx_fifo_size - dma_ndtr); + + // Check for new data + if (w_index != prev_w_index){ + // Check for overflow + if ( + ((prev_w_index < q->r_ptr_rx) && (q->r_ptr_rx <= w_index)) || // No rollover + ((w_index < prev_w_index) && ((q->r_ptr_rx <= w_index) || (prev_w_index < q->r_ptr_rx))) // Rollover + ){ + // We lost data. Set the new read pointer to the oldest byte still available + q->r_ptr_rx = (w_index + 1U) % q->rx_fifo_size; + } + + // Set write pointer + q->w_ptr_rx = w_index; + } + + prev_w_index = w_index; + EXIT_CRITICAL(); +} + +// This read after reading SR clears all error interrupts. We don't want compiler warnings, nor optimizations +#define UART_READ_DR(uart) volatile uint8_t t = (uart)->DR; UNUSED(t); + +void uart_interrupt_handler(uart_ring *q) { + ENTER_CRITICAL(); + + // Read UART status. This is also the first step necessary in clearing most interrupts + uint32_t status = q->uart->SR; + + // If RXNE is set, perform a read. This clears RXNE, ORE, IDLE, NF and FE + if((status & USART_SR_RXNE) != 0U){ + uart_rx_ring(q); + } + + // Detect errors and clear them + uint32_t err = (status & USART_SR_ORE) | (status & USART_SR_NE) | (status & USART_SR_FE) | (status & USART_SR_PE); + if(err != 0U){ + #ifdef DEBUG_UART + puts("Encountered UART error: "); puth(err); puts("\n"); + #endif + UART_READ_DR(q->uart) + } + // Send if necessary + uart_tx_ring(q); + + // Run DMA pointer handler if the line is idle + if(q->dma_rx && (status & USART_SR_IDLE)){ + // Reset IDLE flag + UART_READ_DR(q->uart) + + if(q == &uart_ring_esp_gps){ + dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); + } else { + #ifdef DEBUG_UART + puts("No IDLE dma_pointer_handler implemented for this UART."); + #endif + } + } + + EXIT_CRITICAL(); +} + +void USART1_IRQHandler(void) { uart_interrupt_handler(&uart_ring_esp_gps); } +void USART2_IRQHandler(void) { uart_interrupt_handler(&uart_ring_debug); } +void USART3_IRQHandler(void) { uart_interrupt_handler(&uart_ring_lin2); } +void UART5_IRQHandler(void) { uart_interrupt_handler(&uart_ring_lin1); } + +void DMA2_Stream5_IRQHandler(void) { + ENTER_CRITICAL(); + + // Handle errors + if((DMA2->HISR & DMA_HISR_TEIF5) || (DMA2->HISR & DMA_HISR_DMEIF5) || (DMA2->HISR & DMA_HISR_FEIF5)){ + #ifdef DEBUG_UART + puts("Encountered UART DMA error. Clearing and restarting DMA...\n"); + #endif + + // Clear flags + DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; - if ((sr & USART_SR_ORE) != 0) { - // set dropped packet flag? + // Re-enable the DMA if necessary + DMA2_Stream5->CR |= DMA_SxCR_EN; } + // Re-calculate write pointer and reset flags + dma_pointer_handler(&uart_ring_esp_gps, DMA2_Stream5->NDTR); + DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; + EXIT_CRITICAL(); } -// interrupt boilerplate +// ***************************** Hardware setup ***************************** + +void dma_rx_init(uart_ring *q) { + // Initialization is UART-dependent + if(q == &uart_ring_esp_gps){ + // DMA2, stream 5, channel 4 + + // Disable FIFO mode (enable direct) + DMA2_Stream5->FCR &= ~DMA_SxFCR_DMDIS; + + // Setup addresses + DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); // Source + DMA2_Stream5->M0AR = (uint32_t)q->elems_rx; // Destination + DMA2_Stream5->NDTR = q->rx_fifo_size; // Number of bytes to copy + + // Circular, Increment memory, byte size, periph -> memory, enable + // Transfer complete, half transfer, transfer error and direct mode error interrupt enable + DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_TEIE | DMA_SxCR_DMEIE | DMA_SxCR_EN; + + // Enable DMA receiver in UART + q->uart->CR3 |= USART_CR3_DMAR; + + // Enable UART IDLE interrupt + q->uart->CR1 |= USART_CR1_IDLEIE; + + // Enable interrupt + NVIC_EnableIRQ(DMA2_Stream5_IRQn); + } else { + puts("Tried to initialize RX DMA for an unsupported UART\n"); + } +} + +#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) +#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) +#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) +#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) + +void uart_set_baud(USART_TypeDef *u, unsigned int baud) { + if (u == USART1) { + // USART1 is on APB2 + u->BRR = __USART_BRR(48000000U, baud); + } else { + u->BRR = __USART_BRR(24000000U, baud); + } +} + +void uart_init(uart_ring *q, int baud) { + // Set baud and enable peripheral with TX and RX mode + uart_set_baud(q->uart, baud); + q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; + + // Enable UART interrupts + if(q->uart == USART1){ + NVIC_EnableIRQ(USART1_IRQn); + } else if (q->uart == USART2){ + NVIC_EnableIRQ(USART2_IRQn); + } else if (q->uart == USART3){ + NVIC_EnableIRQ(USART3_IRQn); + } else if (q->uart == UART5){ + NVIC_EnableIRQ(UART5_IRQn); + } else { + // UART not used. Skip enabling interrupts + } + + // Initialise RX DMA if used + if(q->dma_rx){ + dma_rx_init(q); + } +} -void USART1_IRQHandler(void) { uart_ring_process(&esp_ring); } -void USART2_IRQHandler(void) { uart_ring_process(&debug_ring); } -void USART3_IRQHandler(void) { uart_ring_process(&lin2_ring); } -void UART5_IRQHandler(void) { uart_ring_process(&lin1_ring); } +// ************************* Low-level buffer functions ************************* bool getc(uart_ring *q, char *elem) { bool ret = false; @@ -124,7 +303,7 @@ bool getc(uart_ring *q, char *elem) { ENTER_CRITICAL(); if (q->w_ptr_rx != q->r_ptr_rx) { if (elem != NULL) *elem = q->elems_rx[q->r_ptr_rx]; - q->r_ptr_rx = (q->r_ptr_rx + 1U) % FIFO_SIZE; + q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; ret = true; } EXIT_CRITICAL(); @@ -137,7 +316,7 @@ bool injectc(uart_ring *q, char elem) { uint16_t next_w_ptr; ENTER_CRITICAL(); - next_w_ptr = (q->w_ptr_rx + 1U) % FIFO_SIZE; + next_w_ptr = (q->w_ptr_rx + 1U) % q->tx_fifo_size; if (next_w_ptr != q->r_ptr_rx) { q->elems_rx[q->w_ptr_rx] = elem; q->w_ptr_rx = next_w_ptr; @@ -153,7 +332,7 @@ bool putc(uart_ring *q, char elem) { uint16_t next_w_ptr; ENTER_CRITICAL(); - next_w_ptr = (q->w_ptr_tx + 1U) % FIFO_SIZE; + next_w_ptr = (q->w_ptr_tx + 1U) % q->tx_fifo_size; if (next_w_ptr != q->r_ptr_tx) { q->elems_tx[q->w_ptr_tx] = elem; q->w_ptr_tx = next_w_ptr; @@ -161,11 +340,13 @@ bool putc(uart_ring *q, char elem) { } EXIT_CRITICAL(); - uart_ring_process(q); + uart_tx_ring(q); return ret; } +// Seems dangerous to use (might lock CPU if called with interrupts disabled f.e.) +// TODO: Remove? Not used anyways void uart_flush(uart_ring *q) { while (q->w_ptr_tx != q->r_ptr_tx) { __WFI(); @@ -175,7 +356,7 @@ void uart_flush(uart_ring *q) { void uart_flush_sync(uart_ring *q) { // empty the TX buffer while (q->w_ptr_tx != q->r_ptr_tx) { - uart_ring_process(q); + uart_tx_ring(q); } } @@ -193,119 +374,15 @@ void clear_uart_buff(uart_ring *q) { EXIT_CRITICAL(); } -// ***************************** start UART code ***************************** - -#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) -#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) -#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) -#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) - -void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - if (u == USART1) { - // USART1 is on APB2 - u->BRR = __USART_BRR(48000000U, baud); - } else { - u->BRR = __USART_BRR(24000000U, baud); - } -} - -#define USART1_DMA_LEN 0x20 -char usart1_dma[USART1_DMA_LEN]; - -void uart_dma_drain(void) { - uart_ring *q = &esp_ring; - - ENTER_CRITICAL(); - - if ((DMA2->HISR & DMA_HISR_TCIF5) || (DMA2->HISR & DMA_HISR_HTIF5) || (DMA2_Stream5->NDTR != USART1_DMA_LEN)) { - // disable DMA - q->uart->CR3 &= ~USART_CR3_DMAR; - DMA2_Stream5->CR &= ~DMA_SxCR_EN; - while ((DMA2_Stream5->CR & DMA_SxCR_EN) != 0); - - unsigned int i; - for (i = 0; i < (USART1_DMA_LEN - DMA2_Stream5->NDTR); i++) { - char c = usart1_dma[i]; - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % FIFO_SIZE; - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - } - } - - // reset DMA len - DMA2_Stream5->NDTR = USART1_DMA_LEN; - - // clear interrupts - DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; - //DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; - - // enable DMA - DMA2_Stream5->CR |= DMA_SxCR_EN; - q->uart->CR3 |= USART_CR3_DMAR; - } - - EXIT_CRITICAL(); -} - -void DMA2_Stream5_IRQHandler(void) { - //set_led(LED_BLUE, 1); - uart_dma_drain(); - //set_led(LED_BLUE, 0); -} - -void uart_init(USART_TypeDef *u, int baud) { - // enable uart and tx+rx mode - u->CR1 = USART_CR1_UE; - uart_set_baud(u, baud); - - u->CR1 |= USART_CR1_TE | USART_CR1_RE; - //u->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1; - //u->CR2 = USART_CR2_STOP_0; - // ** UART is ready to work ** - - // enable interrupts - if (u != USART1) { - u->CR1 |= USART_CR1_RXNEIE; - } - - if (u == USART1) { - // DMA2, stream 2, channel 3 - DMA2_Stream5->M0AR = (uint32_t)usart1_dma; - DMA2_Stream5->NDTR = USART1_DMA_LEN; - DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); - - // channel4, increment memory, periph -> memory, enable - DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_EN; - - // this one uses DMA receiver - u->CR3 = USART_CR3_DMAR; - - NVIC_EnableIRQ(DMA2_Stream5_IRQn); - NVIC_EnableIRQ(USART1_IRQn); - } else if (u == USART2) { - NVIC_EnableIRQ(USART2_IRQn); - } else if (u == USART3) { - NVIC_EnableIRQ(USART3_IRQn); - } else if (u == UART5) { - NVIC_EnableIRQ(UART5_IRQn); - } else { - // USART type undefined, skip - } -} - +// ************************ High-level debug functions ********************** void putch(const char a) { if (has_external_debug_serial) { - /*while ((debug_ring.uart->SR & USART_SR_TXE) == 0); - debug_ring.uart->DR = a;*/ - // assuming debugging is important if there's external serial connected - while (!putc(&debug_ring, a)); + while (!putc(&uart_ring_debug, a)); - //putc(&debug_ring, a); } else { // misra-c2012-17.7: serial debug function, ok to ignore output - (void)injectc(&debug_ring, a); + (void)injectc(&uart_ring_debug, a); } } @@ -327,7 +404,7 @@ void putui(uint32_t i) { idx--; i_copy /= 10; } while (i_copy != 0U); - puts(str + idx + 1U); + puts(&str[idx + 1U]); } void puth(unsigned int i) { @@ -345,10 +422,12 @@ void puth2(unsigned int i) { } void hexdump(const void *a, int l) { - for (int i=0; i < l; i++) { - if ((i != 0) && ((i & 0xf) == 0)) puts("\n"); - puth2(((const unsigned char*)a)[i]); - puts(" "); + if (a != NULL) { + for (int i=0; i < l; i++) { + if ((i != 0) && ((i & 0xf) == 0)) puts("\n"); + puth2(((const unsigned char*)a)[i]); + puts(" "); + } } puts("\n"); } diff --git a/board/drivers/usb.h b/board/drivers/usb.h index e55906d89e..88455c71ca 100644 --- a/board/drivers/usb.h +++ b/board/drivers/usb.h @@ -439,7 +439,7 @@ void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { USB_WritePacket(src, wplen, 0); if (wplen < len) { - ep0_txdata = src + wplen; + ep0_txdata = &src[wplen]; ep0_txlen = len - wplen; USBx_DEVICE->DIEPEMPMSK |= 1; } else { @@ -985,7 +985,7 @@ void usb_irqhandler(void) { if ((ep0_txlen != 0U) && ((USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40U)) { uint16_t len = MIN(ep0_txlen, 0x40); USB_WritePacket(ep0_txdata, len, 0); - ep0_txdata += len; + ep0_txdata = &ep0_txdata[len]; ep0_txlen -= len; if (ep0_txlen == 0U) { ep0_txdata = NULL; diff --git a/board/main.c b/board/main.c index dcf6e668bd..df134e046b 100644 --- a/board/main.c +++ b/board/main.c @@ -1,4 +1,4 @@ -//#define EON +//#define EON //#define PANDA // ********************* Includes ********************* @@ -78,10 +78,14 @@ void started_interrupt_handler(uint8_t interrupt_line) { // jenky debounce delay(100000); - // set power savings mode here if on EON build #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; 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()) { + current_board->set_usb_power_mode(USB_POWER_CDP); + } #endif } EXTI->PR = (1U << interrupt_line); @@ -134,7 +138,7 @@ void set_safety_mode(uint16_t mode, int16_t param) { } 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) @@ -159,19 +163,10 @@ int get_health_pkt(void *dat) { uint8_t controls_allowed_pkt; uint8_t gas_interceptor_detected_pkt; uint8_t car_harness_status_pkt; + uint8_t usb_power_mode_pkt; } *health = dat; - //Voltage will be measured in mv. 5000 = 5V - uint32_t voltage = adc_get(ADCCHAN_VOLTAGE); - - // REVC has a 10, 1 (1/11) voltage divider - // Here is the calculation for the scale (s) - // ADCV = VIN_S * (1/11) * (4095/3.3) - // RETVAL = ADCV * s = VIN_S*1000 - // s = 1000/((4095/3.3)*(1/11)) = 8.8623046875 - - // Avoid needing floating point math - health->voltage_pkt = (voltage * 8862U) / 1000U; + health->voltage_pkt = adc_get_voltage(); // No current sense on panda black if(hw_type != HW_TYPE_BLACK_PANDA){ @@ -195,7 +190,8 @@ int get_health_pkt(void *dat) { health->can_fwd_errs_pkt = can_fwd_errs; health->gmlan_send_errs_pkt = gmlan_send_errs; health->car_harness_status_pkt = car_harness_status; - + health->usb_power_mode_pkt = usb_power_mode; + return sizeof(*health); } @@ -215,7 +211,7 @@ void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { uint8_t *usbdata8 = (uint8_t *)usbdata; uart_ring *ur = get_ring_by_number(usbdata8[0]); if ((len != 0) && (ur != NULL)) { - if ((usbdata8[0] < 2U) || safety_tx_lin_hook(usbdata8[0] - 2U, usbdata8 + 1, len - 1)) { + if ((usbdata8[0] < 2U) || safety_tx_lin_hook(usbdata8[0] - 2U, &usbdata8[1], len - 1)) { for (int i = 1; i < len; i++) { while (!putc(ur, usbdata8[i])) { // wait @@ -346,7 +342,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) } else { // Disable OBD CAN current_board->set_can_mode(CAN_MODE_NORMAL); - } + } } else { if (setup->b.wValue.w == 1U) { // GMLAN ON @@ -362,7 +358,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) } } break; - + // **** 0xdc: set safety mode case 0xdc: // Blocked over WiFi. @@ -403,9 +399,12 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) if (!ur) { break; } - if (ur == &esp_ring) { - uart_dma_drain(); + + // TODO: Remove this again and fix boardd code to hande the message bursts instead of single chars + if (ur == &uart_ring_esp_gps) { + dma_pointer_handler(ur, DMA2_Stream5->NDTR); } + // read while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && getc(ur, (char*)&resp[resp_len])) { @@ -460,19 +459,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xe6: set USB power case 0xe6: - if (setup->b.wValue.w == 0U) { - puts("user setting NONE mode\n"); - current_board->set_usb_power_mode(USB_POWER_NONE); - } else if (setup->b.wValue.w == 1U) { - puts("user setting CDP mode\n"); - current_board->set_usb_power_mode(USB_POWER_CDP); - } else if (setup->b.wValue.w == 2U) { - puts("user setting DCP mode\n"); - current_board->set_usb_power_mode(USB_POWER_DCP); - } else { - puts("user setting CLIENT mode\n"); - current_board->set_usb_power_mode(USB_POWER_CLIENT); - } + current_board->set_usb_power_mode(setup->b.wValue.w); break; // **** 0xf0: do k-line wValue pulse on uart2 for Acura case 0xf0: @@ -591,8 +578,8 @@ void __attribute__ ((noinline)) enable_fpu(void) { uint64_t tcnt = 0; // go into NOOUTPUT when the EON does not send a heartbeat for this amount of seconds. -#define EON_HEARTBEAT_THRESHOLD_IGNITION_ON 5U -#define EON_HEARTBEAT_THRESHOLD_IGNITION_OFF 2U +#define EON_HEARTBEAT_IGNITION_CNT_ON 5U +#define EON_HEARTBEAT_IGNITION_CNT_OFF 2U // called once per second // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck @@ -629,9 +616,11 @@ 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_THRESHOLD_IGNITION_ON : EON_HEARTBEAT_THRESHOLD_IGNITION_OFF)) { + if (heartbeat_counter >= (current_board->check_ignition() ? 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"); - set_safety_mode(SAFETY_NOOUTPUT, 0U); + if(current_safety_mode != SAFETY_NOOUTPUT){ + set_safety_mode(SAFETY_NOOUTPUT, 0U); + } } #endif @@ -651,7 +640,7 @@ int main(void) { detect_configuration(); detect_board_type(); adc_init(); - + // print hello puts("\n\n\n************************ MAIN START ************************\n"); @@ -676,22 +665,22 @@ int main(void) { if (has_external_debug_serial) { // WEIRDNESS: without this gate around the UART, it would "crash", but only if the ESP is enabled // assuming it's because the lines were left floating and spurious noise was on them - uart_init(USART2, 115200); + uart_init(&uart_ring_debug, 115200); } if (board_has_gps()) { - uart_init(USART1, 9600); + uart_init(&uart_ring_esp_gps, 9600); } else { // enable ESP uart - uart_init(USART1, 115200); + uart_init(&uart_ring_esp_gps, 115200); } // there is no LIN on panda black if(hw_type != HW_TYPE_BLACK_PANDA){ // enable LIN - uart_init(UART5, 10400); + uart_init(&uart_ring_lin1, 10400); UART5->CR2 |= USART_CR2_LINEN; - uart_init(USART3, 10400); + uart_init(&uart_ring_lin2, 10400); USART3->CR2 |= USART_CR2_LINEN; } diff --git a/board/pedal/main.c b/board/pedal/main.c index b6cfa51644..e7642f0c00 100644 --- a/board/pedal/main.c +++ b/board/pedal/main.c @@ -84,9 +84,6 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) if (!ur) { break; } - if (ur == &esp_ring) { - uart_dma_drain(); - } // read while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && getc(ur, (char*)&resp[resp_len])) { diff --git a/board/safety.h b/board/safety.h index e542dde8e9..ffdfebb454 100644 --- a/board/safety.h +++ b/board/safety.h @@ -16,6 +16,26 @@ #include "safety/safety_mazda.h" #include "safety/safety_elm327.h" +// from cereal.car.CarParams.SafetyModel +#define SAFETY_NOOUTPUT 0U +#define SAFETY_HONDA 1U +#define SAFETY_TOYOTA 2U +#define SAFETY_ELM327 3U +#define SAFETY_GM 4U +#define SAFETY_HONDA_BOSCH 5U +#define SAFETY_FORD 6U +#define SAFETY_CADILLAC 7U +#define SAFETY_HYUNDAI 8U +#define SAFETY_CHRYSLER 9U +#define SAFETY_TESLA 10U +#define SAFETY_SUBARU 11U +#define SAFETY_GM_PASSIVE 12U +#define SAFETY_MAZDA 13U +#define SAFETY_TOYOTA_IPAS 16U +#define SAFETY_ALLOUTPUT 17U +#define SAFETY_GM_ASCM 18U + +uint16_t current_safety_mode = SAFETY_NOOUTPUT; const safety_hooks *current_hooks = &nooutput_hooks; void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push){ @@ -45,42 +65,24 @@ typedef struct { const safety_hooks *hooks; } safety_hook_config; -#define SAFETY_NOOUTPUT 0U -#define SAFETY_HONDA 1U -#define SAFETY_TOYOTA 2U -#define SAFETY_GM 3U -#define SAFETY_HONDA_BOSCH 4U -#define SAFETY_FORD 5U -#define SAFETY_CADILLAC 6U -#define SAFETY_HYUNDAI 7U -#define SAFETY_TESLA 8U -#define SAFETY_CHRYSLER 9U -#define SAFETY_SUBARU 10U -#define SAFETY_GM_PASSIVE 11U -#define SAFETY_MAZDA 12U -#define SAFETY_GM_ASCM 0x1334U -#define SAFETY_TOYOTA_IPAS 0x1335U -#define SAFETY_ALLOUTPUT 0x1337U -#define SAFETY_ELM327 0xE327U - const safety_hook_config safety_hook_registry[] = { {SAFETY_NOOUTPUT, &nooutput_hooks}, {SAFETY_HONDA, &honda_hooks}, - {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, {SAFETY_TOYOTA, &toyota_hooks}, + {SAFETY_ELM327, &elm327_hooks}, {SAFETY_GM, &gm_hooks}, + {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, {SAFETY_FORD, &ford_hooks}, {SAFETY_CADILLAC, &cadillac_hooks}, {SAFETY_HYUNDAI, &hyundai_hooks}, {SAFETY_CHRYSLER, &chrysler_hooks}, + {SAFETY_TESLA, &tesla_hooks}, {SAFETY_SUBARU, &subaru_hooks}, + {SAFETY_GM_PASSIVE, &gm_passive_hooks}, {SAFETY_MAZDA, &mazda_hooks}, {SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, - {SAFETY_GM_PASSIVE, &gm_passive_hooks}, - {SAFETY_GM_ASCM, &gm_ascm_hooks}, - {SAFETY_TESLA, &tesla_hooks}, {SAFETY_ALLOUTPUT, &alloutput_hooks}, - {SAFETY_ELM327, &elm327_hooks}, + {SAFETY_GM_ASCM, &gm_ascm_hooks}, }; int safety_set_mode(uint16_t mode, int16_t param) { @@ -89,6 +91,7 @@ int safety_set_mode(uint16_t mode, int16_t param) { for (int i = 0; i < hook_config_count; i++) { if (safety_hook_registry[i].id == mode) { current_hooks = safety_hook_registry[i].hooks; + current_safety_mode = safety_hook_registry[i].id; set_status = 0; // set break; } diff --git a/board/safety/safety_gm.h b/board/safety/safety_gm.h index 3cef579249..ed8217fc02 100644 --- a/board/safety/safety_gm.h +++ b/board/safety/safety_gm.h @@ -204,7 +204,7 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // GAS/REGEN: safety check if (addr == 715) { int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3); - // Disabled message is !engaed with gas + // Disabled message is !engaged with gas // value that corresponds to max regen. if (!current_controls_allowed || !long_controls_allowed) { bool apply = GET_BYTE(to_send, 0) & 1U; diff --git a/board/tools/enter_download_mode.py b/board/tools/enter_download_mode.py index ff3cf84ca9..3dd6545f4c 100755 --- a/board/tools/enter_download_mode.py +++ b/board/tools/enter_download_mode.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import sys import time diff --git a/boardesp/Makefile b/boardesp/Makefile index 0b8fe32b69..c713a0061c 100644 --- a/boardesp/Makefile +++ b/boardesp/Makefile @@ -50,7 +50,7 @@ user1.bin: obj/proxy.o obj/elm327.o obj/webserver.o obj/sha.o obj/rsa.o $(OBJCP) --only-section .data -O binary a.out eagle.app.v6.data.bin $(OBJCP) --only-section .rodata -O binary a.out eagle.app.v6.rodata.bin $(OBJCP) --only-section .irom0.text -O binary a.out eagle.app.v6.irom0text.bin - COMPILE=gcc python ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 + COMPILE=gcc python2 ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 rm -f eagle.app.v6.*.bin mv eagle.app.flash.bin $@ ../crypto/sign.py $@ $@ $(CERT) @@ -61,7 +61,7 @@ user2.bin: obj/proxy.o obj/elm327.o obj/webserver.o obj/sha.o obj/rsa.o $(OBJCP) --only-section .data -O binary a.out eagle.app.v6.data.bin $(OBJCP) --only-section .rodata -O binary a.out eagle.app.v6.rodata.bin $(OBJCP) --only-section .irom0.text -O binary a.out eagle.app.v6.irom0text.bin - COMPILE=gcc python ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 + COMPILE=gcc python2 ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 rm -f eagle.app.v6.*.bin mv eagle.app.flash.bin $@ ../crypto/sign.py $@ $@ $(CERT) diff --git a/boardesp/elm327.c b/boardesp/elm327.c index 58ac4c8638..cec9fd836d 100644 --- a/boardesp/elm327.c +++ b/boardesp/elm327.c @@ -52,6 +52,8 @@ typedef struct __attribute__((packed)) { #define PANDA_USB_CAN_WRITE_BUS_NUM 3 #define PANDA_USB_LIN_WRITE_BUS_NUM 2 +#define SAFETY_ELM327 3U + typedef struct _elm_tcp_conn { struct espconn *conn; struct _elm_tcp_conn *next; @@ -1420,7 +1422,7 @@ static void ICACHE_FLASH_ATTR elm_process_at_cmd(char *cmd, uint16_t len) { elm_append_rsp_const("\r\r"); elm_append_rsp_const(IDENT_MSG); - panda_set_safety_mode(0xE327); + panda_set_safety_mode(SAFETY_ELM327); elm_proto_reinit(elm_current_proto()); return; diff --git a/boardesp/get_sdk.sh b/boardesp/get_sdk.sh index adccf678f9..b1e8bf2be8 100755 --- a/boardesp/get_sdk.sh +++ b/boardesp/get_sdk.sh @@ -8,5 +8,5 @@ sudo apt-get install libtool-bin git clone --recursive https://github.com/pfalcon/esp-open-sdk.git cd esp-open-sdk git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec -LD_LIBRARY_PATH="" make STANDALONE=y - +cp ../python2_make.py . +python2 python2_make.py 'LD_LIBRARY_PATH="" make STANDALONE=y' diff --git a/boardesp/get_sdk_ci.sh b/boardesp/get_sdk_ci.sh index b11cb099a6..e95b7bd262 100755 --- a/boardesp/get_sdk_ci.sh +++ b/boardesp/get_sdk_ci.sh @@ -2,4 +2,5 @@ git clone --recursive https://github.com/pfalcon/esp-open-sdk.git cd esp-open-sdk git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec -LD_LIBRARY_PATH="" make STANDALONE=y +cp ../python2_make.py . +python2 python2_make.py 'LD_LIBRARY_PATH="" make STANDALONE=y' diff --git a/boardesp/get_sdk_mac.sh b/boardesp/get_sdk_mac.sh index a8c2d709d4..c2cfcd53b4 100755 --- a/boardesp/get_sdk_mac.sh +++ b/boardesp/get_sdk_mac.sh @@ -28,5 +28,5 @@ git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec git submodule init git submodule update --recursive -make STANDALONE=y - +cp ../python2_make.py . +python2 python2_make.py 'make STANDALONE=y' diff --git a/boardesp/python2_make.py b/boardesp/python2_make.py new file mode 100644 index 0000000000..85bee34577 --- /dev/null +++ b/boardesp/python2_make.py @@ -0,0 +1,4 @@ +#!/usr/bin/env python2 +import os +import sys +os.system(sys.argv[1]) diff --git a/crypto/getcertheader.py b/crypto/getcertheader.py index 75d04e977a..b323cd101d 100755 --- a/crypto/getcertheader.py +++ b/crypto/getcertheader.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import struct from Crypto.PublicKey import RSA @@ -26,7 +26,7 @@ def to_c_uint32(x): nums = [] for i in range(0x20): nums.append(x%(2**32)) - x /= (2**32) + x //= (2**32) return "{"+'U,'.join(map(str, nums))+"U}" for fn in sys.argv[1:]: @@ -36,11 +36,11 @@ for fn in sys.argv[1:]: cname = fn.split("/")[-1].split(".")[0] + "_rsa_key" - print 'RSAPublicKey '+cname+' = {.len = 0x20,' - print ' .n0inv = %dU,' % n0inv - print ' .n = %s,' % to_c_uint32(rsa.n) - print ' .rr = %s,' % to_c_uint32(rr) - print ' .exponent = %d,' % rsa.e - print '};' + print('RSAPublicKey '+cname+' = {.len = 0x20,') + print(' .n0inv = %dU,' % n0inv) + print(' .n = %s,' % to_c_uint32(rsa.n)) + print(' .rr = %s,' % to_c_uint32(rr)) + print(' .exponent = %d,' % rsa.e) + print('};') diff --git a/crypto/sign.py b/crypto/sign.py index 159299271e..0f1ce03081 100755 --- a/crypto/sign.py +++ b/crypto/sign.py @@ -1,16 +1,17 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os import sys import struct import hashlib from Crypto.PublicKey import RSA +import binascii rsa = RSA.importKey(open(sys.argv[3]).read()) -with open(sys.argv[1]) as f: +with open(sys.argv[1], "rb") as f: dat = f.read() -print "signing", len(dat), "bytes" +print("signing", len(dat), "bytes") with open(sys.argv[2], "wb") as f: if os.getenv("SETLEN") is not None: @@ -20,10 +21,11 @@ with open(sys.argv[2], "wb") as f: else: x = dat dd = hashlib.sha1(dat).digest() - print "hash:",dd.encode("hex") - dd = "\x00\x01" + "\xff"*0x69 + "\x00" + dd - rsa_out = pow(int(dd.encode("hex"), 16), rsa.d, rsa.n) - sig = (hex(rsa_out)[2:-1].rjust(0x100, '0')).decode("hex") - x += sig + + print("hash:", str(binascii.hexlify(dd), "utf-8")) + dd = b"\x00\x01" + b"\xff"*0x69 + b"\x00" + dd + rsa_out = pow(int.from_bytes(dd, byteorder='big', signed=False), rsa.d, rsa.n) + sig = (hex(rsa_out)[2:].rjust(0x100, '0')) + x += binascii.unhexlify(sig) f.write(x) diff --git a/drivers/linux/panda.c b/drivers/linux/panda.c index 4c5980a9d2..3d4f957f9c 100644 --- a/drivers/linux/panda.c +++ b/drivers/linux/panda.c @@ -38,6 +38,9 @@ #define PANDA_DLC_MASK 0x0F +#define SAFETY_ALLOUTPUT 17 +#define SAFETY_NOOUTPUT 0 + struct panda_usb_ctx { struct panda_inf_priv *priv; u32 ndx; @@ -156,7 +159,7 @@ static int panda_set_output_enable(struct panda_inf_priv* priv, bool enable){ return usb_control_msg(priv->priv_dev->udev, usb_sndctrlpipe(priv->priv_dev->udev, 0), 0xDC, USB_TYPE_VENDOR | USB_RECIP_DEVICE, - enable ? 0x1337 : 0, 0, NULL, 0, USB_CTRL_SET_TIMEOUT); + enable ? SAFETY_ALLOUTPUT : SAFETY_NOOUTPUT, 0, NULL, 0, USB_CTRL_SET_TIMEOUT); } static void panda_usb_write_bulk_callback(struct urb *urb) diff --git a/drivers/windows/panda_shared/panda.h b/drivers/windows/panda_shared/panda.h index ade8fa36a8..8d98b08b71 100644 --- a/drivers/windows/panda_shared/panda.h +++ b/drivers/windows/panda_shared/panda.h @@ -40,7 +40,7 @@ namespace panda { typedef enum _PANDA_SAFETY_MODE : uint16_t { SAFETY_NOOUTPUT = 0, SAFETY_HONDA = 1, - SAFETY_ALLOUTPUT = 0x1337, + SAFETY_ALLOUTPUT = 17, } PANDA_SAFETY_MODE; typedef enum _PANDA_SERIAL_PORT : uint8_t { diff --git a/examples/can_bit_transition.py b/examples/can_bit_transition.py index 5c15e4bbc2..1cd72a6831 100755 --- a/examples/can_bit_transition.py +++ b/examples/can_bit_transition.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import binascii import csv @@ -13,13 +13,13 @@ class Message(): def printBitDiff(self, other): """Prints bits that transition from always zero to always 1 and vice versa.""" - for i in xrange(len(self.ones)): + for i in range(len(self.ones)): zero_to_one = other.zeros[i] & self.ones[i] if zero_to_one: - print 'id %s 0 -> 1 at byte %d bitmask %d' % (self.message_id, i, zero_to_one) + print('id %s 0 -> 1 at byte %d bitmask %d' % (self.message_id, i, zero_to_one)) one_to_zero = other.ones[i] & self.zeros[i] if one_to_zero: - print 'id %s 1 -> 0 at byte %d bitmask %d' % (self.message_id, i, one_to_zero) + print('id %s 1 -> 0 at byte %d bitmask %d' % (self.message_id, i, one_to_zero)) class Info(): @@ -56,7 +56,7 @@ class Info(): new_message = True message = self.messages[message_id] bytes = bytearray.fromhex(data) - for i in xrange(len(bytes)): + for i in range(len(bytes)): ones = int(bytes[i]) message.ones[i] = ones if new_message else message.ones[i] & ones # Inverts the data and masks it to a byte to get the zeros as ones. @@ -65,11 +65,11 @@ class Info(): def PrintUnique(log_file, low_range, high_range): # find messages with bits that are always low - start, end = map(float, low_range.split('-')) + start, end = list(map(float, low_range.split('-'))) low = Info() low.load(log_file, start, end) # find messages with bits that are always high - start, end = map(float, high_range.split('-')) + start, end = list(map(float, high_range.split('-'))) high = Info() high.load(log_file, start, end) # print messages that go from low to high @@ -78,10 +78,10 @@ def PrintUnique(log_file, low_range, high_range): if message_id in low.messages: high.messages[message_id].printBitDiff(low.messages[message_id]) found = True - if not found: print 'No messages that transition from always low to always high found!' + if not found: print('No messages that transition from always low to always high found!') if __name__ == "__main__": if len(sys.argv) < 4: - print 'Usage:\n%s log.csv - -' % sys.argv[0] + print('Usage:\n%s log.csv - -' % sys.argv[0]) sys.exit(0) PrintUnique(sys.argv[1], sys.argv[2], sys.argv[3]) diff --git a/examples/can_logger.py b/examples/can_logger.py index 05c28a26df..203023dc92 100755 --- a/examples/can_logger.py +++ b/examples/can_logger.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import binascii import csv import sys diff --git a/examples/can_unique.py b/examples/can_unique.py index ad6de296ee..05f24a7d91 100755 --- a/examples/can_unique.py +++ b/examples/can_unique.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Given an interesting CSV file of CAN messages and a list of background CAN # messages, print which bits in the interesting file have never appeared @@ -28,15 +28,15 @@ class Message(): def printBitDiff(self, other): """Prints bits that are set or cleared compared to other background.""" - for i in xrange(len(self.ones)): + for i in range(len(self.ones)): new_ones = ((~other.ones[i]) & 0xff) & self.ones[i] if new_ones: - print 'id %s new one at byte %d bitmask %d' % ( - self.message_id, i, new_ones) + print('id %s new one at byte %d bitmask %d' % ( + self.message_id, i, new_ones)) new_zeros = ((~other.zeros[i]) & 0xff) & self.zeros[i] if new_zeros: - print 'id %s new zero at byte %d bitmask %d' % ( - self.message_id, i, new_zeros) + print('id %s new zero at byte %d bitmask %d' % ( + self.message_id, i, new_zeros)) class Info(): @@ -67,7 +67,7 @@ class Info(): if data not in self.messages[message_id].data: message.data[data] = True bytes = bytearray.fromhex(data) - for i in xrange(len(bytes)): + for i in range(len(bytes)): message.ones[i] = message.ones[i] | int(bytes[i]) # Inverts the data and masks it to a byte to get the zeros as ones. message.zeros[i] = message.zeros[i] | ( (~int(bytes[i])) & 0xff) @@ -80,7 +80,7 @@ def PrintUnique(interesting_file, background_files): interesting.load(interesting_file) for message_id in sorted(interesting.messages): if message_id not in background.messages: - print 'New message_id: %s' % message_id + print('New message_id: %s' % message_id) else: interesting.messages[message_id].printBitDiff( background.messages[message_id]) @@ -88,6 +88,6 @@ def PrintUnique(interesting_file, background_files): if __name__ == "__main__": if len(sys.argv) < 3: - print 'Usage:\n%s interesting.csv background*.csv' % sys.argv[0] + print('Usage:\n%s interesting.csv background*.csv' % sys.argv[0]) sys.exit(0) PrintUnique(sys.argv[1], sys.argv[2:]) diff --git a/examples/get_panda_password.py b/examples/get_panda_password.py index 575cbb0795..13dacf2534 100644 --- a/examples/get_panda_password.py +++ b/examples/get_panda_password.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from panda import Panda def get_panda_password(): @@ -17,4 +17,4 @@ def get_panda_password(): print("Password: " + wifi[1]) if __name__ == "__main__": - get_panda_password() \ No newline at end of file + get_panda_password() diff --git a/examples/query_vin_and_stats.py b/examples/query_vin_and_stats.py index f3d6c198af..9a0df78ec1 100755 --- a/examples/query_vin_and_stats.py +++ b/examples/query_vin_and_stats.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import time import struct from panda import Panda @@ -36,15 +36,15 @@ if __name__ == "__main__": isotp_send(panda, "\x09\x02", 0x7df) ret = isotp_recv(panda, 0x7e8) hexdump(ret) - print "VIN: %s" % ret[2:] + print("VIN: %s" % ret[2:]) # 03 = get DTCS isotp_send(panda, "\x03", 0x7e0) dtcs = isotp_recv(panda, 0x7e8) - print "DTCs:", dtcs[2:].encode("hex") + print("DTCs:", dtcs[2:].encode("hex")) supported_pids = get_supported_pids() - print "Supported PIDs:",supported_pids + print("Supported PIDs:",supported_pids) while 1: speed = struct.unpack(">B", get_current_data_for_pid(13)[2:])[0] # kph @@ -52,7 +52,7 @@ if __name__ == "__main__": throttle = struct.unpack(">B", get_current_data_for_pid(17)[2:])[0]/255.0 * 100 # percent temp = struct.unpack(">B", get_current_data_for_pid(5)[2:])[0] - 40 # degrees C load = struct.unpack(">B", get_current_data_for_pid(4)[2:])[0]/255.0 * 100 # percent - print "%d KPH, %d RPM, %.1f%% Throttle, %d deg C, %.1f%% load" % (speed, rpm, throttle, temp, load) + print("%d KPH, %d RPM, %.1f%% Throttle, %d deg C, %.1f%% load" % (speed, rpm, throttle, temp, load)) time.sleep(0.2) diff --git a/examples/tesla_tester.py b/examples/tesla_tester.py index 4365e424bb..74f19f2552 100644 --- a/examples/tesla_tester.py +++ b/examples/tesla_tester.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import binascii from panda import Panda diff --git a/python/__init__.py b/python/__init__.py index 573d6f159a..565770918a 100644 --- a/python/__init__.py +++ b/python/__init__.py @@ -1,5 +1,5 @@ # python library to interface with panda -from __future__ import print_function + import binascii import struct import hashlib @@ -9,12 +9,12 @@ import os 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 isotp import isotp_send, isotp_recv +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 .isotp import isotp_send, isotp_recv __version__ = '0.0.9' @@ -23,7 +23,6 @@ BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") DEBUG = os.getenv("PANDADEBUG") is not None # *** wifi mode *** - 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) @@ -46,7 +45,7 @@ def parse_can_buffer(dat): address = f1 >> 21 dddat = ddat[8:8+(f2&0xF)] if DEBUG: - print(" R %x: %s" % (address, str(dddat).encode("hex"))) + print(" R %x: %s" % (address, binascii.hexlify(dddat))) ret.append((address, f2>>16, dddat, (f2>>4)&0xFF)) return ret @@ -109,20 +108,25 @@ class WifiHandle(object): # *** normal mode *** class Panda(object): + + # matches cereal.car.CarParams.SafetyModel SAFETY_NOOUTPUT = 0 SAFETY_HONDA = 1 SAFETY_TOYOTA = 2 - SAFETY_GM = 3 - SAFETY_HONDA_BOSCH = 4 - SAFETY_FORD = 5 - SAFETY_CADILLAC = 6 - SAFETY_HYUNDAI = 7 - SAFETY_TESLA = 8 + SAFETY_ELM327 = 3 + SAFETY_GM = 4 + SAFETY_HONDA_BOSCH = 5 + SAFETY_FORD = 6 + SAFETY_CADILLAC = 7 + SAFETY_HYUNDAI = 8 SAFETY_CHRYSLER = 9 - SAFETY_TOYOTA_IPAS = 0x1335 - SAFETY_TOYOTA_NOLIMITS = 0x1336 - SAFETY_ALLOUTPUT = 0x1337 - SAFETY_ELM327 = 0xE327 + SAFETY_TESLA = 10 + SAFETY_SUBARU = 11 + SAFETY_GM_PASSIVE = 12 + SAFETY_MAZDA = 13 + SAFETY_TOYOTA_IPAS = 16 + SAFETY_ALLOUTPUT = 17 + SAFETY_GM_ASCM = 18 SERIAL_DEBUG = 0 SERIAL_ESP = 1 @@ -135,11 +139,11 @@ class Panda(object): REQUEST_IN = usb1.ENDPOINT_IN | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE REQUEST_OUT = usb1.ENDPOINT_OUT | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE - HW_TYPE_UNKNOWN = '\x00' - HW_TYPE_WHITE_PANDA = '\x01' - HW_TYPE_GREY_PANDA = '\x02' - HW_TYPE_BLACK_PANDA = '\x03' - HW_TYPE_PEDAL = '\x04' + HW_TYPE_UNKNOWN = b'\x00' + HW_TYPE_WHITE_PANDA = b'\x01' + HW_TYPE_GREY_PANDA = b'\x02' + HW_TYPE_BLACK_PANDA = b'\x03' + HW_TYPE_PEDAL = b'\x04' def __init__(self, serial=None, claim=True): self._serial = serial @@ -232,7 +236,7 @@ class Panda(object): def flash_static(handle, code): # confirm flasher is present fr = handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc) - assert fr[4:8] == "\xde\xad\xd0\x0d" + assert fr[4:8] == b"\xde\xad\xd0\x0d" # unlock flash print("flash: unlocking") @@ -274,7 +278,7 @@ class Panda(object): fn = os.path.join(BASEDIR, "board", fn) if code is None: - with open(fn) as f: + with open(fn, "rb") as f: code = f.read() # get version @@ -364,7 +368,7 @@ class Panda(object): pass def get_version(self): - return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40) + return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40).decode('utf8') def get_type(self): return self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40) @@ -429,7 +433,7 @@ class Panda(object): self._handle.controlWrite(Panda.REQUEST_OUT, 0xde, bus, int(speed*10), b'') def set_uart_baud(self, uart, rate): - self._handle.controlWrite(Panda.REQUEST_OUT, 0xe4, uart, rate/300, b'') + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe4, uart, int(rate/300), b'') def set_uart_parity(self, uart, parity): # parity, 0=off, 1=even, 2=odd @@ -447,7 +451,7 @@ class Panda(object): for addr, _, dat, bus in arr: assert len(dat) <= 8 if DEBUG: - print(" W %x: %s" % (addr, dat.encode("hex"))) + print(" W %x: %s" % (addr, binascii.hexlify(dat))) if addr >= 0x800: rir = (addr << 3) | transmit | extended else: @@ -479,7 +483,7 @@ class Panda(object): break except (usb1.USBErrorIO, usb1.USBErrorOverflow): print("CAN: BAD RECV, RETRYING") - time.sleep(0.1) + time.sleep(0.1) return parse_can_buffer(dat) def can_clear(self, bus): @@ -546,7 +550,7 @@ class Panda(object): if len(ret) == 0: break elif DEBUG: - print("kline drain: "+str(ret).encode("hex")) + print("kline drain: " + binascii.hexlify(ret)) bret += ret return bytes(bret) @@ -555,7 +559,7 @@ class Panda(object): while len(echo) != cnt: ret = str(self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))) if DEBUG and len(ret) > 0: - print("kline recv: "+ret.encode("hex")) + print("kline recv: " + binascii.hexlify(ret)) echo += ret return str(echo) @@ -572,7 +576,7 @@ class Panda(object): for i in range(0, len(x), 0xf): ts = x[i:i+0xf] if DEBUG: - print("kline send: "+ts.encode("hex")) + print("kline send: " + binascii.hexlify(ts)) self._handle.bulkWrite(2, chr(bus).encode()+ts) echo = self.kline_ll_recv(len(ts), bus=bus) if echo != ts: diff --git a/python/dfu.py b/python/dfu.py index 02deed47bb..bbab812b07 100644 --- a/python/dfu.py +++ b/python/dfu.py @@ -1,8 +1,9 @@ -from __future__ import print_function + import os import usb1 import struct import time +import binascii # *** DFU mode *** @@ -46,28 +47,27 @@ class PandaDFU(object): def st_serial_to_dfu_serial(st): if st == None or st == "none": return None - uid_base = struct.unpack("H"*6, st.decode("hex")) - return struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4] + 0xA, uid_base[3]).encode("hex").upper() - + uid_base = struct.unpack("H"*6, bytes.fromhex(st)) + return binascii.hexlify(struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4] + 0xA, uid_base[3])).upper().decode("utf-8") def status(self): while 1: - dat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) - if dat[1] == "\x00": + dat = self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6) + if dat[1] == 0: break def clear_status(self): # Clear status - stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) - if stat[4] == "\x0a": + stat = self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6) + if stat[4] == 0xa: self._handle.controlRead(0x21, DFU_CLRSTATUS, 0, 0, 0) - elif stat[4] == "\x09": - self._handle.controlWrite(0x21, DFU_ABORT, 0, 0, "") + elif stat[4] == 0x9: + self._handle.controlWrite(0x21, DFU_ABORT, 0, 0, b"") self.status() stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) def erase(self, address): - self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x41" + struct.pack("I", address)) + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, b"\x41" + struct.pack("I", address)) self.status() def program(self, address, dat, block_size=None): @@ -75,12 +75,12 @@ class PandaDFU(object): block_size = len(dat) # Set Address Pointer - self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x21" + struct.pack("I", address)) + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, b"\x21" + struct.pack("I", address)) self.status() # Program - dat += "\xFF"*((block_size-len(dat)) % block_size) - for i in range(0, len(dat)/block_size): + dat += b"\xFF"*((block_size-len(dat)) % block_size) + for i in range(0, len(dat)//block_size): ldat = dat[i*block_size:(i+1)*block_size] print("programming %d with length %d" % (i, len(ldat))) self._handle.controlWrite(0x21, DFU_DNLOAD, 2+i, 0, ldat) @@ -105,17 +105,17 @@ class PandaDFU(object): build_st(fn) fn = os.path.join(BASEDIR, "board", fn) - with open(fn) as f: + with open(fn, "rb") as f: code = f.read() self.program_bootstub(code) def reset(self): # **** Reset **** - self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x21" + struct.pack("I", 0x8000000)) + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, b"\x21" + struct.pack("I", 0x8000000)) self.status() try: - self._handle.controlWrite(0x21, DFU_DNLOAD, 2, 0, "") + self._handle.controlWrite(0x21, DFU_DNLOAD, 2, 0, b"") stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) except Exception: pass diff --git a/python/esptool.py b/python/esptool.py index 970aa3d4d8..941c3557c8 100755 --- a/python/esptool.py +++ b/python/esptool.py @@ -1,5 +1,5 @@ #!/usr/bin/env python -# NB: Before sending a PR to change the above line to '#!/usr/bin/env python2', please read https://github.com/themadinventor/esptool/issues/21 +# NB: Before sending a PR to change the above line to '#!/usr/bin/env python3', please read https://github.com/themadinventor/esptool/issues/21 # # ESP8266 ROM Bootloader Utility # https://github.com/themadinventor/esptool @@ -48,7 +48,7 @@ class FakePort(object): @baudrate.setter def baudrate(self, x): - print "set baud to", x + print("set baud to", x) self.panda.set_uart_baud(1, x) def write(self, buf): @@ -114,7 +114,7 @@ class ESPROM(object): """ Read a SLIP packet from the serial port """ def read(self): - return self._slip_reader.next() + return next(self._slip_reader) """ Write bytes to the serial port while performing SLIP escaping """ def write(self, packet): @@ -140,7 +140,7 @@ class ESPROM(object): # same operation as the request or a retries limit has # exceeded. This is needed for some esp8266s that # reply with more sync responses than expected. - for retry in xrange(100): + for retry in range(100): p = self.read() if len(p) < 8: continue @@ -156,14 +156,14 @@ class ESPROM(object): """ Perform a connection test """ def sync(self): self.command(ESPROM.ESP_SYNC, '\x07\x07\x12\x20' + 32 * '\x55') - for i in xrange(7): + for i in range(7): self.command() """ Try connecting repeatedly until successful, or giving up """ def connect(self): - print 'Connecting...' + print('Connecting...') - for _ in xrange(4): + for _ in range(4): # issue reset-to-bootloader: # RTS = either CH_PD or nRESET (both active low = chip in reset) # DTR = GPIO0 (active low = boot to flasher) @@ -180,7 +180,7 @@ class ESPROM(object): # worst-case latency timer should be 255ms (probably <20ms) self._port.timeout = 0.3 - for _ in xrange(4): + for _ in range(4): try: self._port.flushInput() self._slip_reader = slip_reader(self._port) @@ -250,7 +250,7 @@ class ESPROM(object): result = self.command(ESPROM.ESP_FLASH_BEGIN, struct.pack(' 16: raise FatalError('Invalid firmware image magic=%d segments=%d' % (magic, segments)) - for i in xrange(segments): + for i in range(segments): self.load_segment(load_file) self.checksum = self.read_checksum(load_file) @@ -480,7 +480,7 @@ class OTAFirmwareImage(BaseFirmwareImage): raise FatalError('Invalid V2 image magic=%d' % (magic)) if segments != 4: # segment count is not really segment count here, but we expect to see '4' - print 'Warning: V2 header has unexpected "segment" count %d (usually 4)' % segments + print('Warning: V2 header has unexpected "segment" count %d (usually 4)' % segments) # irom segment comes before the second header self.load_segment(load_file, True) @@ -501,7 +501,7 @@ class OTAFirmwareImage(BaseFirmwareImage): raise FatalError('Invalid V2 second header magic=%d segments=%d' % (magic, segments)) # load all the usual segments - for _ in xrange(segments): + for _ in range(segments): self.load_segment(load_file) self.checksum = self.read_checksum(load_file) @@ -543,13 +543,13 @@ class ELFFile(object): tool_nm = "xt-nm" proc = subprocess.Popen([tool_nm, self.name], stdout=subprocess.PIPE) except OSError: - print "Error calling %s, do you have Xtensa toolchain in PATH?" % tool_nm + print("Error calling %s, do you have Xtensa toolchain in PATH?" % tool_nm) sys.exit(1) for l in proc.stdout: fields = l.strip().split() try: if fields[0] == "U": - print "Warning: ELF binary has undefined symbol %s" % fields[1] + print("Warning: ELF binary has undefined symbol %s" % fields[1]) continue if fields[0] == "w": continue # can skip weak symbols @@ -568,7 +568,7 @@ class ELFFile(object): try: proc = subprocess.Popen([tool_readelf, "-h", self.name], stdout=subprocess.PIPE) except OSError: - print "Error calling %s, do you have Xtensa toolchain in PATH?" % tool_readelf + print("Error calling %s, do you have Xtensa toolchain in PATH?" % tool_readelf) sys.exit(1) for l in proc.stdout: fields = l.strip().split() @@ -599,7 +599,7 @@ class CesantaFlasher(object): CMD_BOOT_FW = 6 def __init__(self, esp, baud_rate=0): - print 'Running Cesanta flasher stub...' + print('Running Cesanta flasher stub...') if baud_rate <= ESPROM.ESP_ROM_BAUD: # don't change baud rates if we already synced at that rate baud_rate = 0 self._esp = esp @@ -640,7 +640,7 @@ class CesantaFlasher(object): raise FatalError('Expected digest, got: %s' % hexify(p)) digest = hexify(p).upper() expected_digest = hashlib.md5(data).hexdigest().upper() - print + print() if digest != expected_digest: raise FatalError('Digest mismatch: expected %s, got %s' % (expected_digest, digest)) p = self._esp.read() @@ -679,7 +679,7 @@ class CesantaFlasher(object): raise FatalError('Expected digest, got: %s' % hexify(p)) expected_digest = hexify(p).upper() digest = hashlib.md5(data).hexdigest().upper() - print + print() if digest != expected_digest: raise FatalError('Digest mismatch: expected %s, got %s' % (expected_digest, digest)) p = self._esp.read() @@ -791,7 +791,7 @@ def binutils_safe_path(p): try: return subprocess.check_output(["cygpath", "-w", p]).rstrip('\n') except subprocess.CalledProcessError: - print "WARNING: Failed to call cygpath to sanitise Cygwin path." + print("WARNING: Failed to call cygpath to sanitise Cygwin path.") return p @@ -837,9 +837,9 @@ class FatalError(RuntimeError): def load_ram(esp, args): image = LoadFirmwareImage(args.filename) - print 'RAM boot...' + print('RAM boot...') for (offset, size, data) in image.segments: - print 'Downloading %d bytes at %08x...' % (size, offset), + print('Downloading %d bytes at %08x...' % (size, offset), end=' ') sys.stdout.flush() esp.mem_begin(size, div_roundup(size, esp.ESP_RAM_BLOCK), esp.ESP_RAM_BLOCK, offset) @@ -848,31 +848,31 @@ def load_ram(esp, args): esp.mem_block(data[0:esp.ESP_RAM_BLOCK], seq) data = data[esp.ESP_RAM_BLOCK:] seq += 1 - print 'done!' + print('done!') - print 'All segments done, executing at %08x' % image.entrypoint + print('All segments done, executing at %08x' % image.entrypoint) esp.mem_finish(image.entrypoint) def read_mem(esp, args): - print '0x%08x = 0x%08x' % (args.address, esp.read_reg(args.address)) + print('0x%08x = 0x%08x' % (args.address, esp.read_reg(args.address))) def write_mem(esp, args): esp.write_reg(args.address, args.value, args.mask, 0) - print 'Wrote %08x, mask %08x to %08x' % (args.value, args.mask, args.address) + print('Wrote %08x, mask %08x to %08x' % (args.value, args.mask, args.address)) def dump_mem(esp, args): f = file(args.filename, 'wb') - for i in xrange(args.size / 4): + for i in range(args.size / 4): d = esp.read_reg(args.address + (i * 4)) f.write(struct.pack('> 16 args.flash_size = {18: '2m', 19: '4m', 20: '8m', 21: '16m', 22: '32m'}.get(size_id) if args.flash_size is None: - print 'Warning: Could not auto-detect Flash size (FlashID=0x%x, SizeID=0x%x), defaulting to 4m' % (flash_id, size_id) + print('Warning: Could not auto-detect Flash size (FlashID=0x%x, SizeID=0x%x), defaulting to 4m' % (flash_id, size_id)) args.flash_size = '4m' else: - print 'Auto-detected Flash size:', args.flash_size + print('Auto-detected Flash size:', args.flash_size) def write_flash(esp, args): @@ -900,10 +900,10 @@ def write_flash(esp, args): image = argfile.read() argfile.seek(0) # rewind in case we need it again if address + len(image) > int(args.flash_size.split('m')[0]) * (1 << 17): - print 'WARNING: Unlikely to work as data goes beyond end of flash. Hint: Use --flash_size' + print('WARNING: Unlikely to work as data goes beyond end of flash. Hint: Use --flash_size') # Fix sflash config data. if address == 0 and image[0] == '\xe9': - print 'Flash params set to 0x%02x%02x' % (flash_mode, flash_size_freq) + print('Flash params set to 0x%02x%02x' % (flash_mode, flash_size_freq)) image = image[0:2] + flash_params + image[4:] # Pad to sector size, which is the minimum unit of writing (erasing really). if len(image) % esp.ESP_FLASH_SECTOR != 0: @@ -911,11 +911,11 @@ def write_flash(esp, args): t = time.time() flasher.flash_write(address, image, not args.no_progress) t = time.time() - t - print ('\rWrote %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' + print('\rWrote %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' % (len(image), address, t, len(image) / t * 8 / 1000)) - print 'Leaving...' + print('Leaving...') if args.verify: - print 'Verifying just-written flash...' + print('Verifying just-written flash...') _verify_flash(flasher, args, flash_params) flasher.boot_fw() @@ -923,18 +923,18 @@ def write_flash(esp, args): def image_info(args): image = LoadFirmwareImage(args.filename) print('Image version: %d' % image.version) - print('Entry point: %08x' % image.entrypoint) if image.entrypoint != 0 else 'Entry point not set' - print '%d segments' % len(image.segments) - print + print(('Entry point: %08x' % image.entrypoint) if image.entrypoint != 0 else 'Entry point not set') + print('%d segments' % len(image.segments)) + print() checksum = ESPROM.ESP_CHECKSUM_MAGIC for (idx, (offset, size, data)) in enumerate(image.segments): if image.version == 2 and idx == 0: - print 'Segment 1: %d bytes IROM0 (no load address)' % size + print('Segment 1: %d bytes IROM0 (no load address)' % size) else: - print 'Segment %d: %5d bytes at %08x' % (idx + 1, size, offset) + print('Segment %d: %5d bytes at %08x' % (idx + 1, size, offset)) checksum = ESPROM.checksum(data, checksum) - print - print 'Checksum: %02x (%s)' % (image.checksum, 'valid' if image.checksum == checksum else 'invalid!') + print() + print('Checksum: %02x (%s)' % (image.checksum, 'valid' if image.checksum == checksum else 'invalid!')) def make_image(args): @@ -979,7 +979,7 @@ def elf2image(args): if irom_offs < 0: raise FatalError('Address of symbol _irom0_text_start in ELF is located before flash mapping address. Bad linker script?') if (irom_offs & 0xFFF) != 0: # irom0 isn't flash sector aligned - print "WARNING: irom0 section offset is 0x%08x. ELF is probably linked for 'elf2image --version=2'" % irom_offs + print("WARNING: irom0 section offset is 0x%08x. ELF is probably linked for 'elf2image --version=2'" % irom_offs) with open(args.output + "0x%05x.bin" % irom_offs, "wb") as f: f.write(data) f.close() @@ -991,21 +991,21 @@ def elf2image(args): def read_mac(esp, args): mac = esp.read_mac() - print 'MAC: %s' % ':'.join(map(lambda x: '%02x' % x, mac)) + print('MAC: %s' % ':'.join(['%02x' % x for x in mac])) def chip_id(esp, args): chipid = esp.chip_id() - print 'Chip ID: 0x%08x' % chipid + print('Chip ID: 0x%08x' % chipid) def erase_flash(esp, args): flasher = CesantaFlasher(esp, args.baud) - print 'Erasing flash (this may take a while)...' + print('Erasing flash (this may take a while)...') t = time.time() flasher.flash_erase_chip() t = time.time() - t - print 'Erase took %.1f seconds' % t + print('Erase took %.1f seconds' % t) def run(esp, args): @@ -1015,8 +1015,8 @@ def run(esp, args): def flash_id(esp, args): flash_id = esp.flash_id() esp.flash_finish(False) - print 'Manufacturer: %02x' % (flash_id & 0xff) - print 'Device: %02x%02x' % ((flash_id >> 8) & 0xff, (flash_id >> 16) & 0xff) + print('Manufacturer: %02x' % (flash_id & 0xff)) + print('Device: %02x%02x' % ((flash_id >> 8) & 0xff, (flash_id >> 16) & 0xff)) def read_flash(esp, args): @@ -1024,7 +1024,7 @@ def read_flash(esp, args): t = time.time() data = flasher.flash_read(args.address, args.size, not args.no_progress) t = time.time() - t - print ('\rRead %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' + print('\rRead %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' % (len(data), args.address, t, len(data) / t * 8 / 1000)) file(args.filename, 'wb').write(data) @@ -1037,26 +1037,26 @@ def _verify_flash(flasher, args, flash_params=None): if address == 0 and image[0] == '\xe9' and flash_params is not None: image = image[0:2] + flash_params + image[4:] image_size = len(image) - print 'Verifying 0x%x (%d) bytes @ 0x%08x in flash against %s...' % (image_size, image_size, address, argfile.name) + print('Verifying 0x%x (%d) bytes @ 0x%08x in flash against %s...' % (image_size, image_size, address, argfile.name)) # Try digest first, only read if there are differences. digest, _ = flasher.flash_digest(address, image_size) digest = hexify(digest).upper() expected_digest = hashlib.md5(image).hexdigest().upper() if digest == expected_digest: - print '-- verify OK (digest matched)' + print('-- verify OK (digest matched)') continue else: differences = True if getattr(args, 'diff', 'no') != 'yes': - print '-- verify FAILED (digest mismatch)' + print('-- verify FAILED (digest mismatch)') continue flash = flasher.flash_read(address, image_size) assert flash != image - diff = [i for i in xrange(image_size) if flash[i] != image[i]] - print '-- verify FAILED: %d differences, first @ 0x%08x' % (len(diff), address + diff[0]) + diff = [i for i in range(image_size) if flash[i] != image[i]] + print('-- verify FAILED: %d differences, first @ 0x%08x' % (len(diff), address + diff[0])) for d in diff: - print ' %08x %02x %02x' % (address + d, ord(flash[d]), ord(image[d])) + print(' %08x %02x %02x' % (address + d, ord(flash[d]), ord(image[d]))) if differences: raise FatalError("Verify failed.") @@ -1067,7 +1067,7 @@ def verify_flash(esp, args, flash_params=None): def version(args): - print __version__ + print(__version__) # # End of operations functions @@ -1203,12 +1203,12 @@ def main(): 'version', help='Print esptool version') # internal sanity check - every operation matches a module function of the same name - for operation in subparsers.choices.keys(): + for operation in list(subparsers.choices.keys()): assert operation in globals(), "%s should be a module function" % operation args = parser.parse_args() - print 'esptool.py v%s' % __version__ + print('esptool.py v%s' % __version__) # operation function can take 1 arg (args), 2 args (esp, arg) # or be a member function of the ESPROM class. @@ -1310,5 +1310,5 @@ if __name__ == '__main__': try: main() except FatalError as e: - print '\nA fatal error occurred: %s' % e + print('\nA fatal error occurred: %s' % e) sys.exit(2) diff --git a/python/flash_release.py b/python/flash_release.py index 0f407ff22f..b50c9b36b3 100755 --- a/python/flash_release.py +++ b/python/flash_release.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import sys import time import requests import json -import StringIO +import io def flash_release(path=None, st_serial=None): from panda import Panda, PandaDFU, ESPROM, CesantaFlasher @@ -29,7 +29,7 @@ def flash_release(path=None, st_serial=None): url = json.loads(r.text)['url'] r = requests.get(url) print("Fetching firmware from %s" % url) - path = StringIO.StringIO(r.content) + path = io.StringIO(r.content) zf = ZipFile(path) zf.printdir() diff --git a/python/isotp.py b/python/isotp.py index 971827007a..00200f888b 100644 --- a/python/isotp.py +++ b/python/isotp.py @@ -1,13 +1,15 @@ +import binascii + DEBUG = False def msg(x): if DEBUG: - print "S:",x.encode("hex") + print("S:", binascii.hexlify(x)) if len(x) <= 7: ret = chr(len(x)) + x else: assert False - return ret.ljust(8, "\x00") + return ret.ljust(8, b"\x00") kmsgs = [] def recv(panda, cnt, addr, nbus): @@ -24,35 +26,35 @@ def recv(panda, cnt, addr, nbus): # leave around nmsgs.append((ids, ts, dat, bus)) kmsgs = nmsgs[-256:] - return map(str, ret) + return ret def isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr): msg = recv(panda, 1, addr, bus)[0] # TODO: handle other subaddr also communicating - assert ord(msg[0]) == subaddr + assert msg[0] == subaddr - if ord(msg[1])&0xf0 == 0x10: + if msg[1]&0xf0 == 0x10: # first - tlen = ((ord(msg[1]) & 0xf) << 8) | ord(msg[2]) + tlen = ((msg[1] & 0xf) << 8) | msg[2] dat = msg[3:] # 0 block size? - CONTINUE = chr(subaddr) + "\x30" + "\x00"*6 + CONTINUE = chr(subaddr).encode("utf8") + b"\x30" + b"\x00"*6 panda.can_send(sendaddr, CONTINUE, bus) idx = 1 - for mm in recv(panda, (tlen-len(dat) + 5)/6, addr, bus): - assert ord(mm[0]) == subaddr - assert ord(mm[1]) == (0x20 | (idx&0xF)) + for mm in recv(panda, (tlen-len(dat) + 5)//6, addr, bus): + assert mm[0] == subaddr + assert mm[1] == (0x20 | (idx&0xF)) dat += mm[2:] idx += 1 - elif ord(msg[1])&0xf0 == 0x00: + elif msg[1]&0xf0 == 0x00: # single - tlen = ord(msg[1]) & 0xf + tlen = msg[1] & 0xf dat = msg[2:] else: - print msg.encode("hex") + print(binascii.hexlify(msg)) assert False return dat[0:tlen] @@ -69,26 +71,26 @@ def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None): panda.can_send(addr, chr(subaddr)+msg(x)[0:7], bus) else: if subaddr: - ss = chr(subaddr) + chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:5] + ss = (chr(subaddr) + chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF)).encode("utf8") + x[0:5] x = x[5:] else: - ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6] + ss = (chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF)).encode("utf8") + x[0:6] x = x[6:] idx = 1 sends = [] while len(x) > 0: if subaddr: - sends.append(((chr(subaddr) + chr(0x20 + (idx&0xF)) + x[0:6]).ljust(8, "\x00"))) + sends.append((((chr(subaddr) + chr(0x20 + (idx&0xF))).encode('utf8') + x[0:6]).ljust(8, b"\x00"))) x = x[6:] else: - sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00"))) + sends.append(((chr(0x20 + (idx&0xF)).encode("utf8") + x[0:7]).ljust(8, b"\x00"))) x = x[7:] idx += 1 # actually send panda.can_send(addr, ss, bus) rr = recv(panda, 1, recvaddr, bus)[0] - if rr.find("\x30\x01") != -1: + if rr.find(b"\x30\x01") != -1: for s in sends[:-1]: panda.can_send(addr, s, 0) rr = recv(panda, 1, recvaddr, bus)[0] @@ -105,31 +107,31 @@ def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None): else: msg = recv(panda, 1, addr, bus)[0] - if ord(msg[0])&0xf0 == 0x10: + if msg[0]&0xf0 == 0x10: # first - tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1]) + tlen = ((msg[0] & 0xf) << 8) | msg[1] dat = msg[2:] # 0 block size? - CONTINUE = "\x30" + "\x00"*7 + CONTINUE = b"\x30" + b"\x00"*7 panda.can_send(sendaddr, CONTINUE, bus) idx = 1 - for mm in recv(panda, (tlen-len(dat) + 6)/7, addr, bus): - assert ord(mm[0]) == (0x20 | (idx&0xF)) + for mm in recv(panda, (tlen-len(dat) + 6)//7, addr, bus): + assert mm[0] == (0x20 | (idx&0xF)) dat += mm[1:] idx += 1 - elif ord(msg[0])&0xf0 == 0x00: + elif msg[0]&0xf0 == 0x00: # single - tlen = ord(msg[0]) & 0xf + tlen = msg[0] & 0xf dat = msg[1:] else: assert False dat = dat[0:tlen] if DEBUG: - print "R:",dat.encode("hex") + print("R:", binascii.hexlify(dat)) return dat diff --git a/python/serial.py b/python/serial.py index 1bcfebb32e..72ab3de92b 100644 --- a/python/serial.py +++ b/python/serial.py @@ -5,7 +5,7 @@ class PandaSerial(object): self.port = port self.panda.set_uart_parity(self.port, 0) self.panda.set_uart_baud(self.port, baud) - self.buf = "" + self.buf = b"" def read(self, l=1): tt = self.panda.serial_read(self.port) @@ -19,7 +19,10 @@ class PandaSerial(object): def write(self, dat): #print "W: ", dat.encode("hex") #print ' pigeon_send("' + ''.join(map(lambda x: "\\x%02X" % ord(x), dat)) + '");' - return self.panda.serial_write(self.port, dat) + if(isinstance(dat, bytes)): + return self.panda.serial_write(self.port, dat) + else: + return self.panda.serial_write(self.port, str.encode(dat)) def close(self): pass diff --git a/python/update.py b/python/update.py index ce730e4919..d72de11645 100755 --- a/python/update.py +++ b/python/update.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os import time @@ -27,7 +27,7 @@ def ensure_st_up_to_date(): panda_dfu = PandaDFU(panda_dfu[0]) panda_dfu.recover() - print "waiting for board..." + print("waiting for board...") time.sleep(1) if panda.bootstub or not panda.get_version().startswith(repo_version): diff --git a/release/make_release.sh b/release/make_release.sh index 7be994c82c..5aec1a7949 100755 --- a/release/make_release.sh +++ b/release/make_release.sh @@ -7,6 +7,7 @@ if [ ! -d "../../pandaextra" ]; then fi export RELEASE=1 +export BUILDER=DEV # make ST + bootstub pushd . diff --git a/run_automated_tests.sh b/run_automated_tests.sh index 583d6c1ed7..e876c670a7 100755 --- a/run_automated_tests.sh +++ b/run_automated_tests.sh @@ -18,4 +18,4 @@ do nmcli connection delete "$NAME" done -PYTHONPATH="." python $(which nosetests) -v --with-xunit --xunit-file=./$TEST_FILENAME --xunit-testsuite-name=$TESTSUITE_NAME -s $TEST_SCRIPTS +PYTHONPATH="." $(which nosetests) -v --with-xunit --xunit-file=./$TEST_FILENAME --xunit-testsuite-name=$TESTSUITE_NAME -s $TEST_SCRIPTS diff --git a/tests/all_wifi_test.py b/tests/all_wifi_test.py index 4e9d3a5318..85dc173b07 100755 --- a/tests/all_wifi_test.py +++ b/tests/all_wifi_test.py @@ -1,7 +1,7 @@ -#!/usr/bin/python +#!/usr/bin/env python3 import requests import json -from automated.helpers import _connect_wifi +from .automated.helpers import _connect_wifi from panda import Panda from nose.tools import assert_equal @@ -12,12 +12,12 @@ if __name__ == "__main__": for p in Panda.list(): dongle_id, pw = Panda(p).get_serial() - print dongle_id, pw + print(dongle_id, pw) assert(dongle_id.isalnum()) _connect_wifi(dongle_id, pw) r = requests.get("http://192.168.0.10/") - print r.text + print(r.text) wifi_dongle_id = r.text.split("ssid: panda-")[1].split("
")[0] st_version = r.text.split("st version:")[1].strip().split("
")[0] esp_version = r.text.split("esp version:")[1].strip().split("
")[0] diff --git a/tests/automated/1_program.py b/tests/automated/1_program.py index 6b8a3ad487..944db18d9a 100644 --- a/tests/automated/1_program.py +++ b/tests/automated/1_program.py @@ -1,6 +1,6 @@ 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 panda_type_to_serial, test_white_and_grey, 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 f0411b32c6..645f686e15 100644 --- a/tests/automated/2_usb_to_can.py +++ b/tests/automated/2_usb_to_can.py @@ -1,10 +1,10 @@ -from __future__ import print_function + import os import sys import time from panda import Panda from nose.tools import assert_equal, assert_less, assert_greater -from helpers import SPEED_NORMAL, SPEED_GMLAN, time_many_sends, test_white_and_grey, panda_type_to_serial, test_all_pandas, panda_connect_and_init +from .helpers import SPEED_NORMAL, SPEED_GMLAN, time_many_sends, test_white_and_grey, panda_type_to_serial, test_all_pandas, panda_connect_and_init @test_all_pandas @panda_connect_and_init @@ -25,19 +25,19 @@ def test_can_loopback(p): p.set_can_speed_kbps(bus, 250) # send a message on bus 0 - p.can_send(0x1aa, "message", bus) + p.can_send(0x1aa, b"message", bus) # confirm receive both on loopback and send receipt time.sleep(0.05) r = p.can_recv() - sr = filter(lambda x: x[3] == 0x80 | bus, r) - lb = filter(lambda x: x[3] == bus, r) + sr = [x for x in r if x[3] == 0x80 | bus] + lb = [x for x in r if x[3] == bus] assert len(sr) == 1 assert len(lb) == 1 # confirm data is correct assert 0x1aa == sr[0][0] == lb[0][0] - assert "message" == sr[0][2] == lb[0][2] + assert b"message" == sr[0][2] == lb[0][2] @test_all_pandas @panda_connect_and_init @@ -49,7 +49,7 @@ def test_safety_nooutput(p): p.set_can_loopback(True) # send a message on bus 0 - p.can_send(0x1aa, "message", 0) + p.can_send(0x1aa, b"message", 0) # confirm receive nothing time.sleep(0.05) @@ -67,8 +67,8 @@ def test_reliability(p): p.set_can_loopback(True) p.set_can_speed_kbps(0, 1000) - addrs = range(100, 100+MSG_COUNT) - ts = [(j, 0, "\xaa"*8, 0) for j in addrs] + addrs = list(range(100, 100+MSG_COUNT)) + ts = [(j, 0, b"\xaa"*8, 0) for j in addrs] # 100 loops for i in range(LOOP_COUNT): @@ -80,11 +80,11 @@ def test_reliability(p): while len(r) < 200 and (time.time() - st) < 0.5: r.extend(p.can_recv()) - sent_echo = filter(lambda x: x[3] == 0x80, r) - loopback_resp = filter(lambda x: x[3] == 0, r) + sent_echo = [x for x in r if x[3] == 0x80] + loopback_resp = [x for x in r if x[3] == 0] - assert_equal(sorted(map(lambda x: x[0], loopback_resp)), addrs) - assert_equal(sorted(map(lambda x: x[0], sent_echo)), addrs) + assert_equal(sorted([x[0] for x in loopback_resp]), addrs) + assert_equal(sorted([x[0] for x in sent_echo]), addrs) assert_equal(len(r), 200) # take sub 20ms @@ -182,4 +182,4 @@ def test_gmlan_bad_toggle(p): def test_serial_debug(p): junk = p.serial_read(Panda.SERIAL_DEBUG) p.call_control_api(0xc0) - assert(p.serial_read(Panda.SERIAL_DEBUG).startswith("can ")) + 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 2e9c81f3f4..f57dbbd021 100644 --- a/tests/automated/3_wifi.py +++ b/tests/automated/3_wifi.py @@ -1,8 +1,8 @@ -from __future__ import print_function + 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 +from .helpers import connect_wifi, test_white, test_all_pandas, panda_type_to_serial, panda_connect_and_init import requests @test_all_pandas diff --git a/tests/automated/4_wifi_functionality.py b/tests/automated/4_wifi_functionality.py index ee9857d09e..67cce4bf9c 100644 --- a/tests/automated/4_wifi_functionality.py +++ b/tests/automated/4_wifi_functionality.py @@ -1,7 +1,7 @@ -from __future__ import print_function + import time from panda import Panda -from helpers import time_many_sends, connect_wifi, test_white, panda_type_to_serial +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 diff --git a/tests/automated/5_wifi_udp.py b/tests/automated/5_wifi_udp.py index 8b62cf082e..642d8f02a5 100644 --- a/tests/automated/5_wifi_udp.py +++ b/tests/automated/5_wifi_udp.py @@ -1,7 +1,7 @@ -from __future__ import print_function + import sys import time -from helpers import time_many_sends, connect_wifi, test_white, panda_type_to_serial +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 @@ -54,7 +54,7 @@ def test_udp_doesnt_drop(serials=None): missing = True while len(r) > 0: r = p.can_recv() - r = filter(lambda x: x[3] == bus and x[0] == msg_id, r) + r = [x for x in r if x[3] == bus and x[0] == msg_id] if len(r) > 0: missing = False usb_ok_cnt += len(r) diff --git a/tests/automated/6_two_panda.py b/tests/automated/6_two_panda.py index 8b308ce500..711b83fddf 100644 --- a/tests/automated/6_two_panda.py +++ b/tests/automated/6_two_panda.py @@ -1,10 +1,10 @@ -from __future__ import print_function + import os import time import random from panda import Panda from nose.tools import assert_equal, assert_less, assert_greater -from helpers import time_many_sends, test_two_panda, test_two_black_panda, panda_type_to_serial, clear_can_buffers, panda_connect_and_init +from .helpers import time_many_sends, test_two_panda, test_two_black_panda, panda_type_to_serial, clear_can_buffers, panda_connect_and_init @test_two_panda @panda_type_to_serial @@ -18,7 +18,7 @@ def test_send_recv(p_send, p_recv): assert not p_send.legacy assert not p_recv.legacy - p_send.can_send_many([(0x1ba, 0, "message", 0)]*2) + p_send.can_send_many([(0x1ba, 0, b"message", 0)]*2) time.sleep(0.05) p_recv.can_recv() p_send.can_recv() @@ -55,7 +55,7 @@ def test_latency(p_send, p_recv): p_recv.set_can_speed_kbps(0, 100) time.sleep(0.05) - p_send.can_send_many([(0x1ba, 0, "testmsg", 0)]*10) + p_send.can_send_many([(0x1ba, 0, b"testmsg", 0)]*10) time.sleep(0.05) p_recv.can_recv() p_send.can_recv() @@ -80,7 +80,7 @@ def test_latency(p_send, p_recv): for i in range(num_messages): st = time.time() - p_send.can_send(0x1ab, "message", bus) + p_send.can_send(0x1ab, b"message", bus) r = [] while len(r) < 1 and (time.time() - st) < 5: r = p_recv.can_recv() @@ -127,7 +127,7 @@ def test_black_loopback(panda0, panda1): panda1.set_can_loopback(False) # clear stuff - panda0.can_send_many([(0x1ba, 0, "testmsg", 0)]*10) + panda0.can_send_many([(0x1ba, 0, b"testmsg", 0)]*10) time.sleep(0.05) panda0.can_recv() panda1.can_recv() @@ -155,7 +155,7 @@ def test_black_loopback(panda0, panda1): def _test_buses(send_panda, recv_panda, _test_array): for send_bus, send_obd, recv_obd, recv_buses in _test_array: 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) @@ -180,7 +180,7 @@ def test_black_loopback(panda0, panda1): loop_buses.append(loop[3]) if len(cans_loop) == 0: print(" No loop") - + # test loop buses recv_buses.sort() loop_buses.sort() @@ -192,4 +192,4 @@ def test_black_loopback(panda0, panda1): print("***************** TESTING (0 --> 1) *****************") _test_buses(panda0, panda1, test_array) print("***************** TESTING (1 --> 0) *****************") - _test_buses(panda1, panda0, test_array) \ No newline at end of file + _test_buses(panda1, panda0, test_array) diff --git a/tests/automated/helpers.py b/tests/automated/helpers.py index c9e0c67626..f73a17dc04 100644 --- a/tests/automated/helpers.py +++ b/tests/automated/helpers.py @@ -2,9 +2,10 @@ import os import sys import time import random +import binascii import subprocess import requests -import thread +import _thread from functools import wraps from panda import Panda from nose.tools import timed, assert_equal, assert_less, assert_greater @@ -49,7 +50,7 @@ def connect_wifi(serial=None): FNULL = open(os.devnull, 'w') def _connect_wifi(dongle_id, pw, insecure_okay=False): - ssid = str("panda-" + dongle_id) + ssid = "panda-" + dongle_id.decode("utf8") r = subprocess.call(["ping", "-W", "4", "-c", "1", "192.168.0.10"], stdout=FNULL, stderr=subprocess.STDOUT) if not r: @@ -75,7 +76,8 @@ def _connect_wifi(dongle_id, pw, insecure_okay=False): print("WIFI: scanning %d" % cnt) os.system("iwlist %s scanning > /dev/null" % wlan_interface) os.system("nmcli device wifi rescan") - wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n")) + wifi_networks = [x.decode("utf8") for x in subprocess.check_output(["nmcli","dev", "wifi", "list"]).split(b"\n")] + wifi_scan = [x for x in wifi_networks if ssid in x] if len(wifi_scan) != 0: break time.sleep(0.1) @@ -140,7 +142,7 @@ def time_many_sends(p, bus, precv=None, msg_count=100, msg_id=None, two_pandas=F raise ValueError("Cannot have two pandas that are the same panda") st = time.time() - p.can_send_many([(msg_id, 0, "\xaa"*8, bus)]*msg_count) + p.can_send_many([(msg_id, 0, b"\xaa"*8, bus)]*msg_count) r = [] r_echo = [] r_len_expected = msg_count if two_pandas else msg_count*2 @@ -153,11 +155,11 @@ def time_many_sends(p, bus, precv=None, msg_count=100, msg_id=None, two_pandas=F while len(r_echo) < r_echo_len_exected and (time.time() - st) < 10: r_echo.extend(p.can_recv()) - sent_echo = filter(lambda x: x[3] == 0x80 | bus and x[0] == msg_id, r) - sent_echo.extend(filter(lambda x: x[3] == 0x80 | bus and x[0] == msg_id, r_echo)) - resp = filter(lambda x: x[3] == bus and x[0] == msg_id, r) + sent_echo = [x for x in r if x[3] == 0x80 | bus and x[0] == msg_id] + sent_echo.extend([x for x in r_echo if x[3] == 0x80 | bus and x[0] == msg_id]) + resp = [x for x in r if x[3] == bus and x[0] == msg_id] - leftovers = filter(lambda x: (x[3] != 0x80 | bus and x[3] != bus) or x[0] != msg_id, r) + leftovers = [x for x in r if (x[3] != 0x80 | bus and x[3] != bus) or x[0] != msg_id] assert_equal(len(leftovers), 0) assert_equal(len(resp), msg_count) @@ -176,7 +178,7 @@ def panda_type_to_serial(fn): if panda_type is not None: if not isinstance(panda_type, list): panda_type = [panda_type] - + # If not done already, get panda serials and their type global _panda_serials if _panda_serials == None: @@ -185,7 +187,7 @@ def panda_type_to_serial(fn): p = Panda(serial=serial) _panda_serials.append((serial, p.get_type())) p.close() - + # Find a panda with the correct types and add the corresponding serial serials = [] for p_type in panda_type: @@ -216,7 +218,7 @@ def panda_connect_and_init(fn): if panda_serials is not None: if not isinstance(panda_serials, list): panda_serials = [panda_serials] - + # Connect to pandas pandas = [] for panda_serial in panda_serials: @@ -230,7 +232,7 @@ def panda_connect_and_init(fn): for bus, speed in [(0, SPEED_NORMAL), (1, SPEED_NORMAL), (2, SPEED_NORMAL), (3, SPEED_GMLAN)]: panda.set_can_speed_kbps(bus, speed) clear_can_buffers(panda) - thread.start_new_thread(heartbeat_thread, (panda,)) + _thread.start_new_thread(heartbeat_thread, (panda,)) # Run test function ret = fn(*pandas, **kwargs) @@ -247,7 +249,7 @@ def clear_can_buffers(panda): # clear tx buffers for i in range(4): panda.can_clear(i) - + # clear rx buffers panda.can_clear(0xFFFF) r = [1] @@ -257,4 +259,4 @@ def clear_can_buffers(panda): time.sleep(0.05) if (time.time() - st) > 10: print("Unable to clear can buffers for panda ", panda.get_serial()) - assert False \ No newline at end of file + assert False diff --git a/tests/black_loopback_test.py b/tests/black_loopback_test.py index d16ac21af1..0953cba4fa 100755 --- a/tests/black_loopback_test.py +++ b/tests/black_loopback_test.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Loopback test between two black pandas (+ harness and power) # Tests all buses, including OBD CAN, which is on the same bus as CAN0 in this test. # To be sure, the test should be run with both harness orientations -from __future__ import print_function + import os import sys import time @@ -33,11 +33,8 @@ def run_test(sleep_duration): pandas[0] = Panda(pandas[0]) pandas[1] = Panda(pandas[1]) - # find out the hardware types - type0 = pandas[0].get_type() - type1 = pandas[1].get_type() - - if type0 != "\x03" or type1 != "\x03": + # 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 diff --git a/tests/black_white_loopback_test.py b/tests/black_white_loopback_test.py index 7e12134393..7ad2107fa0 100755 --- a/tests/black_white_loopback_test.py +++ b/tests/black_white_loopback_test.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Loopback test between black panda (+ harness and power) and white/grey panda # Tests all buses, including OBD CAN, which is on the same bus as CAN0 in this test. # To be sure, the test should be run with both harness orientations -from __future__ import print_function + import os import sys import time @@ -40,17 +40,14 @@ def run_test(sleep_duration): pandas[0] = Panda(pandas[0]) pandas[1] = Panda(pandas[1]) - # find out which one is black - type0 = pandas[0].get_type() - type1 = pandas[1].get_type() - black_panda = None other_panda = None - - if type0 == "\x03" and type1 != "\x03": + + # find out which one is black + if pandas[0].is_black() and not pandas[1].is_black(): black_panda = pandas[0] other_panda = pandas[1] - elif type0 != "\x03" and type1 == "\x03": + elif not pandas[0].is_black() and pandas[1].is_black(): black_panda = pandas[1] other_panda = pandas[0] else: @@ -71,13 +68,13 @@ def run_test(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 print("Number of cycles:", counter, "Non-zero bus errors:", nonzero_bus_errors, "Zero bus errors:", zero_bus_errors, "Content errors:", content_errors) - + # Toggle relay black_panda.set_safety_mode(Panda.SAFETY_NOOUTPUT) time.sleep(1) black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) time.sleep(1) - + def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): global nonzero_bus_errors, zero_bus_errors, content_errors @@ -91,7 +88,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) @@ -105,8 +102,8 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): if direction: other_panda.can_clear(recv_bus) else: - black_panda.can_clear(recv_bus) - + black_panda.can_clear(recv_bus) + black_panda.can_recv() other_panda.can_recv() @@ -138,7 +135,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_endurance.py b/tests/black_white_relay_endurance.py index 8868b9848f..3eaaa16555 100755 --- a/tests/black_white_relay_endurance.py +++ b/tests/black_white_relay_endurance.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Loopback test between black panda (+ harness and power) and white/grey panda # Tests all buses, including OBD CAN, which is on the same bus as CAN0 in this test. # To be sure, the test should be run with both harness orientations -from __future__ import print_function + import os import sys import time @@ -40,17 +40,14 @@ def run_test(sleep_duration): pandas[0] = Panda(pandas[0]) pandas[1] = Panda(pandas[1]) - # find out which one is black - type0 = pandas[0].get_type() - type1 = pandas[1].get_type() - black_panda = None other_panda = None - if type0 == "\x03" and type1 != "\x03": + # find out which one is black + if pandas[0].is_black() and not pandas[1].is_black(): black_panda = pandas[0] other_panda = pandas[1] - elif type0 != "\x03" and type1 == "\x03": + elif not pandas[0].is_black() and pandas[1].is_black(): black_panda = pandas[1] other_panda = pandas[0] else: @@ -78,11 +75,11 @@ def run_test(sleep_duration): if (time.time() - temp_start_time) > 3600*6: # Toggle relay - black_panda.set_safety_mode(Panda.SAFETY_NOOUTPUT) - time.sleep(1) - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - time.sleep(1) - temp_start_time = time.time() + black_panda.set_safety_mode(Panda.SAFETY_NOOUTPUT) + time.sleep(1) + 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): @@ -111,7 +108,7 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): if direction: other_panda.can_clear(recv_bus) else: - black_panda.can_clear(recv_bus) + black_panda.can_clear(recv_bus) black_panda.can_recv() other_panda.can_recv() diff --git a/tests/black_white_relay_test.py b/tests/black_white_relay_test.py index 21a2ef6d7f..65877dc29f 100755 --- a/tests/black_white_relay_test.py +++ b/tests/black_white_relay_test.py @@ -1,9 +1,9 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Relay test with loopback between black panda (+ harness and power) and white/grey panda # Tests the relay switching multiple times / second by looking at the buses on which loop occurs. -from __future__ import print_function + import os import sys import time diff --git a/tests/build/Dockerfile b/tests/build/Dockerfile index 276a25ed0b..0f982160be 100644 --- a/tests/build/Dockerfile +++ b/tests/build/Dockerfile @@ -1,6 +1,19 @@ FROM ubuntu:16.04 -RUN apt-get update && apt-get install -y gcc-arm-none-eabi libnewlib-arm-none-eabi python python-pip gcc g++ git autoconf gperf bison flex automake texinfo wget help2man gawk libtool libtool-bin ncurses-dev unzip unrar-free libexpat-dev sed bzip2 +RUN apt-get update && apt-get install -y gcc-arm-none-eabi libnewlib-arm-none-eabi python python-pip gcc g++ git autoconf gperf bison flex automake texinfo wget help2man gawk libtool libtool-bin ncurses-dev unzip unrar-free libexpat-dev sed bzip2 locales curl zlib1g-dev libffi-dev 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 2.7.12 +RUN pyenv install 3.7.3 +RUN pyenv global 3.7.3 +RUN pyenv rehash RUN pip install pycrypto==2.6.1 @@ -10,7 +23,8 @@ WORKDIR /panda/boardesp RUN git clone --recursive https://github.com/pfalcon/esp-open-sdk.git WORKDIR /panda/boardesp/esp-open-sdk RUN git checkout 03f5e898a059451ec5f3de30e7feff30455f7ce -RUN CT_ALLOW_BUILD_AS_ROOT_SURE=1 make STANDALONE=y +COPY ./boardesp/python2_make.py /panda/boardesp/esp-open-sdk +RUN python2 python2_make.py "CT_ALLOW_BUILD_AS_ROOT_SURE=1 make STANDALONE=y" COPY . /panda diff --git a/tests/can_printer.py b/tests/can_printer.py index e863889c16..c8bbc3f184 100755 --- a/tests/can_printer.py +++ b/tests/can_printer.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import os import sys import time @@ -15,7 +15,7 @@ def sec_since_boot(): def can_printer(): p = Panda() - p.set_safety_mode(0x1337) + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) start = sec_since_boot() lp = sec_since_boot() @@ -30,7 +30,7 @@ def can_printer(): if sec_since_boot() - lp > 0.1: dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) - for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))): + for k,v in sorted(zip(list(msgs.keys()), [binascii.hexlify(x[-1]) for x in list(msgs.values())])): dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) print(dd) lp = sec_since_boot() diff --git a/tests/debug_console.py b/tests/debug_console.py index e341b266c8..8e66946dd4 100755 --- a/tests/debug_console.py +++ b/tests/debug_console.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import os import sys import time @@ -19,9 +19,9 @@ if __name__ == "__main__": serials = Panda.list() if os.getenv("SERIAL"): - serials = filter(lambda x: x==os.getenv("SERIAL"), serials) + serials = [x for x in serials if x==os.getenv("SERIAL")] - pandas = list(map(lambda x: Panda(x, claim=claim), serials)) + pandas = list([Panda(x, claim=claim) for x in serials]) if not len(pandas): sys.exit("no pandas found") @@ -33,16 +33,16 @@ if __name__ == "__main__": while True: for i, panda in enumerate(pandas): while True: - ret = panda.serial_read(port_number) - if len(ret) > 0: - sys.stdout.write(setcolor[i] + str(ret) + unsetcolor) - sys.stdout.flush() - else: - break + ret = panda.serial_read(port_number) + if len(ret) > 0: + sys.stdout.write(setcolor[i] + ret.decode('ascii') + unsetcolor) + sys.stdout.flush() + else: + break if select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], []): - ln = sys.stdin.readline() - if claim: - panda.serial_write(port_number, ln) + ln = sys.stdin.readline() + if claim: + panda.serial_write(port_number, ln) time.sleep(0.01) except: print("panda disconnected!") diff --git a/tests/disable_esp.py b/tests/disable_esp.py index abebd9c17b..ce1dd6db2e 100755 --- a/tests/disable_esp.py +++ b/tests/disable_esp.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from panda import Panda Panda().set_esp_power(False) diff --git a/tests/elm_car_simulator.py b/tests/elm_car_simulator.py index f931e66ff4..ffb309664e 100755 --- a/tests/elm_car_simulator.py +++ b/tests/elm_car_simulator.py @@ -1,6 +1,6 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 """Used to Reverse/Test ELM protocol auto detect and OBD message response without a car.""" -from __future__ import print_function + import sys import os import struct diff --git a/tests/elm_throughput.py b/tests/elm_throughput.py index 3962572889..2895b09261 100755 --- a/tests/elm_throughput.py +++ b/tests/elm_throughput.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import socket import threading import select diff --git a/tests/elm_wifi.py b/tests/elm_wifi.py index f5a8849833..6c4a334b73 100644 --- a/tests/elm_wifi.py +++ b/tests/elm_wifi.py @@ -1,4 +1,4 @@ -from __future__ import print_function + import os import sys import time @@ -8,7 +8,7 @@ import pytest import struct sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) -import elm_car_simulator +from . import elm_car_simulator sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..", "..")) from panda import Panda @@ -301,7 +301,7 @@ def test_elm_panda_safety_mode_KWPFast(): p_car.kline_drain() p_elm = Panda("WIFI") - p_elm.set_safety_mode(0xE327); + p_elm.set_safety_mode(Panda.SAFETY_ELM327); def get_checksum(dat): result = 0 @@ -625,7 +625,7 @@ def test_elm_panda_safety_mode_ISO15765(): p_car.set_safety_mode(Panda.SAFETY_ALLOUTPUT) p_elm = Panda("WIFI") - p_elm.set_safety_mode(0xE327); + p_elm.set_safety_mode(Panda.SAFETY_ELM327); #sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) #sim.start() diff --git a/tests/get_version.py b/tests/get_version.py index 0cd7795fdc..73e51e1f0d 100755 --- a/tests/get_version.py +++ b/tests/get_version.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from panda import Panda if __name__ == "__main__": diff --git a/tests/gmbitbang/recv.py b/tests/gmbitbang/recv.py index 6eb70aa4ad..92111ed7ec 100755 --- a/tests/gmbitbang/recv.py +++ b/tests/gmbitbang/recv.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import time from panda import Panda @@ -12,6 +12,6 @@ while 1: 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) + print("MISS %d %d" % (last_add, add)) last_add = add - print ret + print(ret) diff --git a/tests/gmbitbang/rigol.py b/tests/gmbitbang/rigol.py index 3d690fdd84..f2efb0340e 100755 --- a/tests/gmbitbang/rigol.py +++ b/tests/gmbitbang/rigol.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import numpy as np import visa import matplotlib.pyplot as plt resources = visa.ResourceManager() -print resources.list_resources() +print(resources.list_resources()) scope = resources.open_resource('USB0::0x1AB1::0x04CE::DS1ZA184652242::INSTR', timeout=2000, chunk_size=1024000) print(scope.query('*IDN?').strip()) @@ -17,7 +17,7 @@ scope.write(":WAV:POIN:MODE RAW") scope.write(":WAV:DATA? CHAN1")[10:] rawdata = scope.read_raw() data = np.frombuffer(rawdata, 'B') -print data.shape +print(data.shape) s1 = data[0:650] s2 = data[650:] @@ -31,5 +31,5 @@ plt.plot(s2) plt.show() #data = (data - 130.0 - voltoffset/voltscale*25) / 25 * voltscale -print data +print(data) diff --git a/tests/gmbitbang/test.py b/tests/gmbitbang/test.py index 652ac1ddd8..0934c64420 100755 --- a/tests/gmbitbang/test.py +++ b/tests/gmbitbang/test.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import time from panda import Panda @@ -28,6 +28,6 @@ while 1: #p1.set_gmlan(bus=2) #p1.can_send(iden, dat, bus=3) time.sleep(0.01) - print p2.can_recv() + print(p2.can_recv()) #exit(0) diff --git a/tests/gmbitbang/test_one.py b/tests/gmbitbang/test_one.py index d7d430437d..635cd2c91f 100755 --- a/tests/gmbitbang/test_one.py +++ b/tests/gmbitbang/test_one.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import time from panda import Panda @@ -9,9 +9,9 @@ p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) p.set_gmlan(bus=2) time.sleep(0.1) while len(p.can_recv()) > 0: - print "clearing" + print("clearing") time.sleep(0.1) -print "cleared" +print("cleared") p.set_gmlan(bus=None) iden = 18000 diff --git a/tests/gps_stability_test.py b/tests/gps_stability_test.py new file mode 100755 index 0000000000..c96aaf123b --- /dev/null +++ b/tests/gps_stability_test.py @@ -0,0 +1,169 @@ +#!/usr/bin/env python3 + +import os +import sys +import time +import random +import threading + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda, PandaSerial + +INIT_GPS_BAUD = 9600 +GPS_BAUD = 460800 + +def connect(): + pandas = Panda.list() + print(pandas) + + # make sure two pandas are connected + if len(pandas) != 2: + print("Connect white and grey/black panda to run this test!") + assert False + + # connect + pandas[0] = Panda(pandas[0]) + pandas[1] = Panda(pandas[1]) + + white_panda = None + gps_panda = None + + # find out which one is white (for spamming the CAN buses) + if pandas[0].is_white() and not pandas[1].is_white(): + white_panda = pandas[0] + gps_panda = pandas[1] + elif not pandas[0].is_white() and pandas[1].is_white(): + white_panda = pandas[1] + gps_panda = pandas[0] + else: + print("Connect white and grey/black panda to run this test!") + assert False + return white_panda, gps_panda + +def spam_buses_thread(panda): + try: + panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + while True: + at = random.randint(1, 2000) + st = (b"test"+os.urandom(10))[0:8] + bus = random.randint(0, 2) + panda.can_send(at, st, bus) + except Exception as e: + print(e) + +def read_can_thread(panda): + try: + while True: + panda.can_recv() + except Exception as e: + print(e) + +def init_gps(panda): + def add_nmea_checksum(msg): + d = msg[1:] + cs = 0 + for i in d: + cs ^= ord(i) + return msg + "*%02X" % cs + + ser = PandaSerial(panda, 1, INIT_GPS_BAUD) + + # Power cycle the gps by toggling reset + print("Resetting GPS") + panda.set_esp_power(0) + time.sleep(0.5) + panda.set_esp_power(1) + time.sleep(0.5) + + # Upping baud rate + print("Upping GPS baud rate") + msg = 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 + + # Reconnecting with the correct baud + ser = PandaSerial(panda, 1, GPS_BAUD) + + # 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") + + print("Initialized GPS") + +received_messages = 0 +received_bytes = 0 +send_something = False +def gps_read_thread(panda): + global received_messages, received_bytes, send_something + ser = PandaSerial(panda, 1, GPS_BAUD) + while True: + ret = ser.read(1024) + time.sleep(0.001) + l = len(ret) + if l > 0: + received_messages+=1 + received_bytes+=l + if send_something: + ser.write("test") + send_something = False + + +CHECK_PERIOD = 5 +MIN_BYTES = 10000 +MAX_BYTES = 50000 + +min_failures = 0 +max_failures = 0 + +if __name__ == "__main__": + white_panda, gps_panda = connect() + + # Start spamming the CAN buses with the white panda. Also read the messages to add load on the GPS panda + threading.Thread(target=spam_buses_thread, args=(white_panda,)).start() + threading.Thread(target=read_can_thread, args=(gps_panda,)).start() + + # Start GPS checking + init_gps(gps_panda) + + read_thread = threading.Thread(target=gps_read_thread, args=(gps_panda,)) + read_thread.start() + while True: + time.sleep(CHECK_PERIOD) + if(received_bytes < MIN_BYTES): + print("Panda is not sending out enough data! Got " + str(received_messages) + " (" + str(received_bytes) + "B) in the last " + str(CHECK_PERIOD) + " seconds") + send_something = True + min_failures+=1 + elif(received_bytes > MAX_BYTES): + print("Panda is not sending out too much data! Got " + str(received_messages) + " (" + str(received_bytes) + "B) in the last " + str(CHECK_PERIOD) + " seconds") + print("Probably not on the right baud rate, got reset somehow? Resetting...") + max_failures+=1 + init_gps(gps_panda) + else: + print("Got " + str(received_messages) + " (" + str(received_bytes) + "B) messages in the last " + str(CHECK_PERIOD) + " seconds.") + if(min_failures > 0): + print("Total min failures: ", min_failures) + if(max_failures > 0): + print("Total max failures: ", max_failures) + received_messages = 0 + received_bytes = 0 + + + + \ No newline at end of file diff --git a/tests/health_test.py b/tests/health_test.py index 1042c860d8..69234c7d64 100755 --- a/tests/health_test.py +++ b/tests/health_test.py @@ -1,7 +1,7 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import time from panda import Panda - + if __name__ == "__main__": panda_serials = Panda.list() pandas = [] diff --git a/tests/language/Dockerfile b/tests/language/Dockerfile index 068847145e..fe957ff723 100644 --- a/tests/language/Dockerfile +++ b/tests/language/Dockerfile @@ -1,6 +1,18 @@ FROM ubuntu:16.04 -RUN apt-get update && apt-get install -y make python python-pip +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 tests/safety/requirements.txt /panda/tests/safety/requirements.txt -RUN pip install -r /panda/tests/safety/requirements.txt COPY . /panda diff --git a/tests/language/test_language.py b/tests/language/test_language.py index 3afb34619a..353f37e854 100755 --- a/tests/language/test_language.py +++ b/tests/language/test_language.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import subprocess import sys @@ -18,11 +18,11 @@ if __name__ == "__main__": try: cmd = "cd ../../; grep -R -i -w " + suffix_cmd + " '" + line + "'" res = subprocess.check_output(cmd, shell=True, stderr=subprocess.STDOUT) - print res + print(res) found_bad_language = True except subprocess.CalledProcessError as e: pass if found_bad_language: sys.exit("Failed: found bad language") else: - print "Success" + print("Success") diff --git a/tests/location_listener.py b/tests/location_listener.py index cbbb00d794..62ade10f03 100755 --- a/tests/location_listener.py +++ b/tests/location_listener.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os import time import sys @@ -18,20 +18,20 @@ if __name__ == "__main__": ser = PandaSerial(panda, 1, 9600) # power cycle by toggling reset - print "resetting" + print("resetting") panda.set_esp_power(0) time.sleep(0.5) panda.set_esp_power(1) time.sleep(0.5) - print "done" - print ser.read(1024) + print("done") + print(ser.read(1024)) # upping baud rate baudrate = 460800 - print "upping baud rate" + print("upping baud rate") msg = add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % baudrate)+"\r\n" - print msg + print(msg) ser.write(msg) time.sleep(0.1) # needs a wait for it to actually send @@ -41,7 +41,7 @@ if __name__ == "__main__": while True: ret = ser.read(1024) if len(ret) > 0: - sys.stdout.write(ret) + sys.stdout.write(ret.decode('ascii', 'ignore')) sys.stdout.flush() #print str(ret).encode("hex") diff --git a/tests/loopback_test.py b/tests/loopback_test.py index a871295ad6..02c8d2cd14 100755 --- a/tests/loopback_test.py +++ b/tests/loopback_test.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import os import sys import time @@ -29,14 +29,14 @@ def run_test(sleep_duration): run_test_w_pandas(pandas, sleep_duration) def run_test_w_pandas(pandas, sleep_duration): - h = list(map(lambda x: Panda(x), pandas)) + h = list([Panda(x) for x in pandas]) print("H", h) for hh in h: hh.set_safety_mode(Panda.SAFETY_ALLOUTPUT) # test both directions - for ho in permutations(range(len(h)), r=2): + for ho in permutations(list(range(len(h))), r=2): print("***************** TESTING", ho) panda0, panda1 = h[ho[0]], h[ho[1]] diff --git a/tests/misra/coverage_table b/tests/misra/coverage_table new file mode 100644 index 0000000000..a00cd84a5f --- /dev/null +++ b/tests/misra/coverage_table @@ -0,0 +1,143 @@ +1.1 +1.2 +1.3 X (Cppcheck) +2.1 X (Cppcheck) +2.2 X (Cppcheck) +2.3 +2.4 X (Cppcheck) +2.5 +2.6 X (Cppcheck) +2.7 +3.1 X (Addon) +3.2 +4.1 X (Addon) +4.2 +5.1 X (Addon) +5.2 X (Addon) +5.3 X (Addon) +5.4 X (Addon) +5.5 X (Addon) +5.6 +5.7 +5.8 +5.9 +6.1 +6.2 +7.1 X (Addon) +7.2 +7.3 X (Addon) +7.4 +8.1 +8.2 +8.3 X (Cppcheck) +8.4 +8.5 +8.6 +8.7 +8.8 +8.9 +8.10 +8.11 X (Addon) +8.12 X (Addon) +8.13 +8.14 X (Addon) +9.1 +9.2 +9.3 +9.4 +9.5 X (Addon) +10.1 X (Addon) +10.2 +10.3 +10.4 X (Addon) +10.5 +10.6 X (Addon) +10.7 +10.8 X (Addon) +11.1 +11.2 +11.3 X (Addon) +11.4 X (Addon) +11.5 X (Addon) +11.6 X (Addon) +11.7 X (Addon) +11.8 X (Addon) +11.9 X (Addon) +12.1 X (Addon) +12.2 X (Addon) +12.3 X (Addon) +12.4 X (Addon) +13.1 X (Addon) +13.2 X (Cppcheck) +13.3 X (Addon) +13.4 X (Addon) +13.5 X (Addon) +13.6 X (Addon) +14.1 X (Addon) +14.2 X (Addon) +14.3 X (Cppcheck) +14.4 X (Addon) +15.1 X (Addon) +15.2 X (Addon) +15.3 X (Addon) +15.4 +15.5 X (Addon) +15.6 X (Addon) +15.7 X (Addon) +16.1 +16.2 X (Addon) +16.3 X (Addon) +16.4 X (Addon) +16.5 X (Addon) +16.6 X (Addon) +16.7 X (Addon) +17.1 X (Addon) +17.2 X (Addon) +17.3 +17.4 +17.5 X (Cppcheck) +17.6 X (Addon) +17.7 X (Addon) +17.8 X (Addon) +18.1 X (Cppcheck) +18.2 X (Cppcheck) +18.3 X (Cppcheck) +18.4 X (Addon) +18.5 X (Addon) +18.6 X (Cppcheck) +18.7 X (Addon) +18.8 X (Addon) +19.1 +19.2 X (Addon) +20.1 X (Addon) +20.2 X (Addon) +20.3 X (Addon) +20.4 X (Addon) +20.5 X (Addon) +20.6 X (Cppcheck) +20.7 X (Addon) +20.8 +20.9 +20.10 X (Addon) +20.11 +20.12 +20.13 X (Addon) +20.14 X (Addon) +21.1 +21.2 +21.3 X (Addon) +21.4 X (Addon) +21.5 X (Addon) +21.6 X (Addon) +21.7 X (Addon) +21.8 X (Addon) +21.9 X (Addon) +21.10 X (Addon) +21.11 X (Addon) +21.12 +22.1 X (Cppcheck) +22.2 X (Cppcheck) +22.3 +22.4 X (Cppcheck) +22.5 +22.6 X (Cppcheck) diff --git a/tests/misra/suppressions.txt b/tests/misra/suppressions.txt index 8e58b6e340..b98a491eeb 100644 --- a/tests/misra/suppressions.txt +++ b/tests/misra/suppressions.txt @@ -1,7 +1,5 @@ # Advisory: union types can be used misra.19.2 -# FIXME: add it back when fixed in cppcheck. Macro identifiers are unique but it false triggers on defines in #ifdef..#else conditions -misra.5.4 # Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well misra.11.4 # Advisory: casting from void pointer to type pointer is ok. Done by STM libraries as well diff --git a/tests/misra/test_misra.sh b/tests/misra/test_misra.sh index 6338009120..c4aceaa92c 100755 --- a/tests/misra/test_misra.sh +++ b/tests/misra/test_misra.sh @@ -4,10 +4,12 @@ mkdir /tmp/misra || true git clone https://github.com/danmar/cppcheck.git || true cd cppcheck git fetch -git checkout 862c4ef87b109ae86c2d5f12769b7c8d199f35c5 +git checkout ff7dba91e177dfb712477faddb9e91bece7e743c make -j4 cd ../../../ +# generate coverage matrix +python tests/misra/cppcheck/addons/misra.py -generate-table > tests/misra/coverage_table printf "\nPANDA CODE\n" tests/misra/cppcheck/cppcheck -DPANDA -UPEDAL -DCAN3 -DUID_BASE -DEON \ @@ -18,8 +20,8 @@ tests/misra/cppcheck/cppcheck -DPANDA -UPEDAL -DCAN3 -DUID_BASE -DEON \ python tests/misra/cppcheck/addons/misra.py board/main.c.dump 2> /tmp/misra/misra_output.txt || true # strip (information) lines -cppcheck_output=$( cat /tmp/misra/cppcheck_output.txt | grep -v "(information) " ) || true -misra_output=$( cat /tmp/misra/misra_output.txt | grep -v "(information) " ) || true +cppcheck_output=$( cat /tmp/misra/cppcheck_output.txt | grep -v ": information: " ) || true +misra_output=$( cat /tmp/misra/misra_output.txt | grep -v ": information: " ) || true printf "\nPEDAL CODE\n" @@ -31,8 +33,8 @@ tests/misra/cppcheck/cppcheck -UPANDA -DPEDAL -UCAN3 \ python tests/misra/cppcheck/addons/misra.py board/pedal/main.c.dump 2> /tmp/misra/misra_pedal_output.txt || true # strip (information) lines -cppcheck_pedal_output=$( cat /tmp/misra/cppcheck_pedal_output.txt | grep -v "(information) " ) || true -misra_pedal_output=$( cat /tmp/misra/misra_pedal_output.txt | grep -v "(information) " ) || true +cppcheck_pedal_output=$( cat /tmp/misra/cppcheck_pedal_output.txt | grep -v ": information: " ) || true +misra_pedal_output=$( cat /tmp/misra/misra_pedal_output.txt | grep -v ": information: " ) || true if [[ -n "$misra_output" ]] || [[ -n "$cppcheck_output" ]] then diff --git a/tests/pedal/enter_canloader.py b/tests/pedal/enter_canloader.py index c6f06ca354..cc37f2b843 100755 --- a/tests/pedal/enter_canloader.py +++ b/tests/pedal/enter_canloader.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import time import struct @@ -53,24 +53,24 @@ if __name__ == "__main__": args = parser.parse_args() p = Panda() - p.set_safety_mode(0x1337) + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) while 1: if len(p.can_recv()) == 0: break if args.recover: - p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x02", 0) + p.can_send(0x200, b"\xce\xfa\xad\xde\x1e\x0b\xb0\x02", 0) exit(0) else: - p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0) + p.can_send(0x200, b"\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0) if args.fn: time.sleep(0.1) - print "flashing", args.fn - code = open(args.fn).read() + print("flashing", args.fn) + code = open(args.fn, "rb").read() Panda.flash_static(CanHandle(p), code) - print "can flash done" + print("can flash done") diff --git a/tests/read_winusb_descriptors.py b/tests/read_winusb_descriptors.py index e38df8d1ca..ea5e93f32d 100644 --- a/tests/read_winusb_descriptors.py +++ b/tests/read_winusb_descriptors.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from panda import Panda from hexdump import hexdump @@ -8,22 +8,22 @@ if __name__ == "__main__": p = Panda() len = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1) - print 'Microsoft OS String Descriptor' + print('Microsoft OS String Descriptor') dat = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, len[0]) - if DEBUG: print 'LEN: {}'.format(hex(len[0])) + if DEBUG: print('LEN: {}'.format(hex(len[0]))) hexdump("".join(map(chr, dat))) ms_vendor_code = dat[16] - if DEBUG: print 'MS_VENDOR_CODE: {}'.format(hex(len[0])) + if DEBUG: print('MS_VENDOR_CODE: {}'.format(hex(len[0]))) - print '\nMicrosoft Compatible ID Feature Descriptor' + print('\nMicrosoft Compatible ID Feature Descriptor') len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, 1) - if DEBUG: print 'LEN: {}'.format(hex(len[0])) + if DEBUG: print('LEN: {}'.format(hex(len[0]))) dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, len[0]) hexdump("".join(map(chr, dat))) - print '\nMicrosoft Extended Properties Feature Descriptor' + print('\nMicrosoft Extended Properties Feature Descriptor') len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1) - if DEBUG: print 'LEN: {}'.format(hex(len[0])) + if DEBUG: print('LEN: {}'.format(hex(len[0]))) dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, len[0]) hexdump("".join(map(chr, dat))) diff --git a/tests/safety/Dockerfile b/tests/safety/Dockerfile index 9381fdc408..b0135b085f 100644 --- a/tests/safety/Dockerfile +++ b/tests/safety/Dockerfile @@ -1,6 +1,19 @@ FROM ubuntu:16.04 -RUN apt-get update && apt-get install -y clang make python python-pip -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 tests/safety/requirements.txt requirements.txt +RUN pip install -r requirements.txt COPY . /panda diff --git a/tests/safety/requirements.txt b/tests/safety/requirements.txt index 8bbfb1d7df..0c3124d87f 100644 --- a/tests/safety/requirements.txt +++ b/tests/safety/requirements.txt @@ -1,2 +1,4 @@ cffi==1.11.4 -numpy==1.14.1 +numpy==1.14.5 +libusb1==1.6.6 +requests diff --git a/tests/safety/test_cadillac.py b/tests/safety/test_cadillac.py index af89e69cc7..5573682d0c 100644 --- a/tests/safety/test_cadillac.py +++ b/tests/safety/test_cadillac.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 2 MAX_RATE_DOWN = 5 @@ -31,7 +32,7 @@ class TestCadillacSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(6, 0) + cls.safety.safety_set_mode(Panda.SAFETY_CADILLAC, 0) cls.safety.init_tests_cadillac() def _send_msg(self, bus, addr, length): @@ -183,8 +184,8 @@ class TestCadillacSafety(unittest.TestCase): def test_fwd_hook(self): # nothing allowed - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) for b in buss: for m in msgs: diff --git a/tests/safety/test_chrysler.py b/tests/safety/test_chrysler.py index 09aa424dd9..25f50a11f9 100755 --- a/tests/safety/test_chrysler.py +++ b/tests/safety/test_chrysler.py @@ -1,9 +1,10 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import csv import glob import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 3 MAX_RATE_DOWN = 3 @@ -35,7 +36,7 @@ class TestChryslerSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(9, 0) + cls.safety.safety_set_mode(Panda.SAFETY_CHRYSLER, 0) cls.safety.init_tests_chrysler() def _send_msg(self, bus, addr, length): @@ -181,8 +182,8 @@ class TestChryslerSafety(unittest.TestCase): self.assertEqual(0, self.safety.get_chrysler_torque_meas_min()) def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) chrysler_camera_detected = [0, 1] for ccd in chrysler_camera_detected: diff --git a/tests/safety/test_gm.py b/tests/safety/test_gm.py index d9a1d39ec7..e2251f7b55 100644 --- a/tests/safety/test_gm.py +++ b/tests/safety/test_gm.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 7 MAX_RATE_DOWN = 17 @@ -32,7 +33,7 @@ class TestGmSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(3, 0) + cls.safety.safety_set_mode(Panda.SAFETY_GM, 0) cls.safety.init_tests_gm() def _send_msg(self, bus, addr, length): @@ -282,8 +283,8 @@ class TestGmSafety(unittest.TestCase): def test_fwd_hook(self): # nothing allowed - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) for b in buss: for m in msgs: diff --git a/tests/safety/test_honda.py b/tests/safety/test_honda.py index f2f5938976..a5eb04ad66 100755 --- a/tests/safety/test_honda.py +++ b/tests/safety/test_honda.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_BRAKE = 255 @@ -11,7 +12,7 @@ class TestHondaSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(1, 0) + cls.safety.safety_set_mode(Panda.SAFETY_HONDA, 0) cls.safety.init_tests_honda() def _send_msg(self, bus, addr, length): @@ -254,8 +255,8 @@ class TestHondaSafety(unittest.TestCase): self.assertTrue(self.safety.safety_tx_hook(self._button_msg(RESUME_BTN, BUTTON_MSG))) def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) long_controls_allowed = [0, 1] fwd_brake = [False, True] diff --git a/tests/safety/test_honda_bosch.py b/tests/safety/test_honda_bosch.py index 0d37cbe807..3affc74c9a 100755 --- a/tests/safety/test_honda_bosch.py +++ b/tests/safety/test_honda_bosch.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_BRAKE = 255 @@ -9,7 +10,7 @@ class TestHondaSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(4, 0) + cls.safety.safety_set_mode(Panda.SAFETY_HONDA_BOSCH, 0) cls.safety.init_tests_honda() def _send_msg(self, bus, addr, length): @@ -21,8 +22,8 @@ class TestHondaSafety(unittest.TestCase): return to_send def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + 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 diff --git a/tests/safety/test_hyundai.py b/tests/safety/test_hyundai.py index 539982fab9..d836dad37b 100644 --- a/tests/safety/test_hyundai.py +++ b/tests/safety/test_hyundai.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 3 MAX_RATE_DOWN = 7 @@ -29,7 +30,7 @@ class TestHyundaiSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(7, 0) + cls.safety.safety_set_mode(Panda.SAFETY_HYUNDAI, 0) cls.safety.init_tests_hyundai() def _send_msg(self, bus, addr, length): @@ -190,8 +191,8 @@ class TestHyundaiSafety(unittest.TestCase): def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) hyundai_giraffe_switch_2 = [0, 1] self.safety.set_hyundai_camera_bus(2) diff --git a/tests/safety/test_subaru.py b/tests/safety/test_subaru.py index 13fe1fb14f..93859e0217 100644 --- a/tests/safety/test_subaru.py +++ b/tests/safety/test_subaru.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 50 MAX_RATE_DOWN = 70 @@ -29,7 +30,7 @@ class TestSubaruSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(10, 0) + cls.safety.safety_set_mode(Panda.SAFETY_SUBARU, 0) cls.safety.init_tests_subaru() def _send_msg(self, bus, addr, length): @@ -174,8 +175,8 @@ class TestSubaruSafety(unittest.TestCase): def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) blocked_msgs = [290, 356, 545, 802] for b in buss: for m in msgs: diff --git a/tests/safety/test_toyota.py b/tests/safety/test_toyota.py index dc5b21ac8f..135207779d 100644 --- a/tests/safety/test_toyota.py +++ b/tests/safety/test_toyota.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda MAX_RATE_UP = 10 MAX_RATE_DOWN = 25 @@ -33,7 +34,7 @@ class TestToyotaSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(2, 100) + cls.safety.safety_set_mode(Panda.SAFETY_TOYOTA, 100) cls.safety.init_tests_toyota() def _send_msg(self, bus, addr, length): @@ -281,8 +282,8 @@ class TestToyotaSafety(unittest.TestCase): def test_fwd_hook(self): - buss = range(0x0, 0x3) - msgs = range(0x1, 0x800) + buss = list(range(0x0, 0x3)) + msgs = list(range(0x1, 0x800)) long_controls_allowed = [0, 1] toyota_camera_forwarded = [0, 1] diff --git a/tests/safety/test_toyota_ipas.py b/tests/safety/test_toyota_ipas.py index 7a382093e0..8d565553fd 100644 --- a/tests/safety/test_toyota_ipas.py +++ b/tests/safety/test_toyota_ipas.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import unittest import numpy as np import libpandasafety_py +from panda import Panda IPAS_OVERRIDE_THRESHOLD = 200 @@ -25,7 +26,7 @@ class TestToyotaSafety(unittest.TestCase): @classmethod def setUp(cls): cls.safety = libpandasafety_py.libpandasafety - cls.safety.safety_set_mode(0x1335, 66) + cls.safety.safety_set_mode(Panda.SAFETY_TOYOTA_IPAS, 66) cls.safety.init_tests_toyota() def _torque_driver_msg(self, torque): @@ -135,7 +136,7 @@ class TestToyotaSafety(unittest.TestCase): # test angle cmd too far from actual angle_refs = [-10, 10] - deltas = range(-2, 3) + deltas = list(range(-2, 3)) expected_results = [False, True, True, True, False] for a in angle_refs: diff --git a/tests/safety_replay/Dockerfile b/tests/safety_replay/Dockerfile index 5d59ca38d5..80663964d3 100644 --- a/tests/safety_replay/Dockerfile +++ b/tests/safety_replay/Dockerfile @@ -1,6 +1,18 @@ FROM ubuntu:16.04 -RUN apt-get update && apt-get install -y make clang python python-pip git libarchive-dev libusb-1.0-0 +RUN apt-get update && apt-get install -y make clang python python-pip git libarchive-dev libusb-1.0-0 locales curl zlib1g-dev libffi-dev bzip2 libssl-dev libbz2-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 tests/safety_replay/requirements.txt requirements.txt RUN pip install -r requirements.txt @@ -17,4 +29,4 @@ COPY . /openpilot/panda WORKDIR /openpilot/panda/tests/safety_replay RUN git clone https://github.com/commaai/openpilot-tools.git tools || true WORKDIR tools -RUN git checkout feb724a14f0f5223c700c94317efaf46923fd48a +RUN git checkout d69c6bc85f221766305ec53956e9a1d3bf283160 diff --git a/tests/safety_replay/helpers.py b/tests/safety_replay/helpers.py index 05bbe08930..6f4e63c325 100644 --- a/tests/safety_replay/helpers.py +++ b/tests/safety_replay/helpers.py @@ -1,23 +1,7 @@ +#!/usr/bin/env python3 import struct import panda.tests.safety.libpandasafety_py as libpandasafety_py - -safety_modes = { - "NOOUTPUT": 0, - "HONDA": 1, - "TOYOTA": 2, - "GM": 3, - "HONDA_BOSCH": 4, - "FORD": 5, - "CADILLAC": 6, - "HYUNDAI": 7, - "TESLA": 8, - "CHRYSLER": 9, - "SUBARU": 10, - "GM_ASCM": 0x1334, - "TOYOTA_IPAS": 0x1335, - "ALLOUTPUT": 0x1337, - "ELM327": 0xE327 -} +from panda import Panda def to_signed(d, bits): ret = d @@ -27,51 +11,51 @@ def to_signed(d, bits): def is_steering_msg(mode, addr): ret = False - if mode == safety_modes["HONDA"] or mode == safety_modes["HONDA_BOSCH"]: + if mode == Panda.SAFETY_HONDA or mode == Panda.SAFETY_HONDA_BOSCH: ret = (addr == 0xE4) or (addr == 0x194) or (addr == 0x33D) - elif mode == safety_modes["TOYOTA"]: + elif mode == Panda.SAFETY_TOYOTA: ret = addr == 0x2E4 - elif mode == safety_modes["GM"]: + elif mode == Panda.SAFETY_GM: ret = addr == 384 - elif mode == safety_modes["HYUNDAI"]: + elif mode == Panda.SAFETY_HYUNDAI: ret = addr == 832 - elif mode == safety_modes["CHRYSLER"]: + elif mode == Panda.SAFETY_CHRYSLER: ret = addr == 0x292 - elif mode == safety_modes["SUBARU"]: + elif mode == Panda.SAFETY_SUBARU: ret = addr == 0x122 return ret def get_steer_torque(mode, to_send): ret = 0 - if mode == safety_modes["HONDA"] or mode == safety_modes["HONDA_BOSCH"]: + if mode == Panda.SAFETY_HONDA or mode == Panda.SAFETY_HONDA_BOSCH: ret = to_send.RDLR & 0xFFFF0000 - elif mode == safety_modes["TOYOTA"]: + elif mode == Panda.SAFETY_TOYOTA: ret = (to_send.RDLR & 0xFF00) | ((to_send.RDLR >> 16) & 0xFF) ret = to_signed(ret, 16) - elif mode == safety_modes["GM"]: + elif mode == Panda.SAFETY_GM: ret = ((to_send.RDLR & 0x7) << 8) + ((to_send.RDLR & 0xFF00) >> 8) ret = to_signed(ret, 11) - elif mode == safety_modes["HYUNDAI"]: + elif mode == Panda.SAFETY_HYUNDAI: ret = ((to_send.RDLR >> 16) & 0x7ff) - 1024 - elif mode == safety_modes["CHRYSLER"]: + elif mode == Panda.SAFETY_CHRYSLER: ret = ((to_send.RDLR & 0x7) << 8) + ((to_send.RDLR & 0xFF00) >> 8) - 1024 - elif mode == safety_modes["SUBARU"]: + elif mode == Panda.SAFETY_SUBARU: ret = ((to_send.RDLR >> 16) & 0x1FFF) ret = to_signed(ret, 13) return ret def set_desired_torque_last(safety, mode, torque): - if mode == safety_modes["HONDA"] or mode == safety_modes["HONDA_BOSCH"]: + if mode == Panda.SAFETY_HONDA or mode == Panda.SAFETY_HONDA_BOSCH: pass # honda safety mode doesn't enforce a rate on steering msgs - elif mode == safety_modes["TOYOTA"]: + elif mode == Panda.SAFETY_TOYOTA: safety.set_toyota_desired_torque_last(torque) - elif mode == safety_modes["GM"]: + elif mode == Panda.SAFETY_GM: safety.set_gm_desired_torque_last(torque) - elif mode == safety_modes["HYUNDAI"]: + elif mode == Panda.SAFETY_HYUNDAI: safety.set_hyundai_desired_torque_last(torque) - elif mode == safety_modes["CHRYSLER"]: + elif mode == Panda.SAFETY_CHRYSLER: safety.set_chrysler_desired_torque_last(torque) - elif mode == safety_modes["SUBARU"]: + elif mode == Panda.SAFETY_SUBARU: safety.set_subaru_desired_torque_last(torque) def package_can_msg(msg): diff --git a/tests/safety_replay/replay_drive.py b/tests/safety_replay/replay_drive.py index 1b2ba082ac..d92ab8e708 100755 --- a/tests/safety_replay/replay_drive.py +++ b/tests/safety_replay/replay_drive.py @@ -1,11 +1,12 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 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, safety_modes + init_segment from tools.lib.logreader import LogReader # replay a drive to check for safety violations @@ -25,7 +26,7 @@ def replay_drive(lr, safety_mode, param): for msg in lr: if start_t is None: start_t = msg.logMonoTime - safety.set_timer(((msg.logMonoTime / 1000)) % 0xFFFFFFFF) + safety.set_timer(((msg.logMonoTime // 1000)) % 0xFFFFFFFF) if msg.which() == 'sendcan': for canmsg in msg.sendcan: @@ -37,7 +38,7 @@ def replay_drive(lr, safety_mode, param): blocked_addrs.add(canmsg.address) if "DEBUG" in os.environ: - print "blocked %d at %f" % (canmsg.address, (msg.logMonoTime - start_t)/(1e9)) + print("blocked %d at %f" % (canmsg.address, (msg.logMonoTime - start_t)/(1e9))) tx_controls += safety.get_controls_allowed() tx_tot += 1 elif msg.which() == 'can': @@ -48,23 +49,20 @@ def replay_drive(lr, safety_mode, param): to_push = package_can_msg(canmsg) safety.safety_rx_hook(to_push) - print "total openpilot msgs:", tx_tot - print "total msgs with controls allowed:", tx_controls - print "blocked msgs:", tx_blocked - print "blocked with controls allowed:", tx_controls_blocked - print "blocked addrs:", blocked_addrs + print("total openpilot msgs:", tx_tot) + print("total msgs with controls allowed:", tx_controls) + print("blocked msgs:", tx_blocked) + print("blocked with controls allowed:", tx_controls_blocked) + print("blocked addrs:", blocked_addrs) return tx_controls_blocked == 0 if __name__ == "__main__": - if sys.argv[2] in safety_modes: - mode = safety_modes[sys.argv[2]] - else: - mode = int(sys.argv[2]) + mode = int(sys.argv[2]) param = 0 if len(sys.argv) < 4 else int(sys.argv[3]) lr = LogReader(sys.argv[1]) - print "replaying drive %s with safety mode %d and param %d" % (sys.argv[1], mode, param) + print("replaying drive %s with safety mode %d and param %d" % (sys.argv[1], mode, param)) replay_drive(lr, mode, param) diff --git a/tests/safety_replay/test_safety_replay.py b/tests/safety_replay/test_safety_replay.py index ecc34161f2..e6e49dc02d 100755 --- a/tests/safety_replay/test_safety_replay.py +++ b/tests/safety_replay/test_safety_replay.py @@ -1,9 +1,9 @@ -#!/usr/bin/env python2 +#!/usr/bin/env python3 import os import requests -from helpers import safety_modes +from panda import Panda from replay_drive import replay_drive from tools.lib.logreader import LogReader @@ -11,31 +11,30 @@ BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" # (route, safety mode, param) logs = [ - ("b0c9d2329ad1606b|2019-05-30--20-23-57.bz2", "HONDA", 0), # HONDA.CIVIC - ("38bfd238edecbcd7|2019-06-07--10-15-25.bz2", "TOYOTA", 66), # TOYOTA.PRIUS - ("f89c604cf653e2bf|2018-09-29--13-46-50.bz2", "GM", 0), # GM.VOLT - ("0375fdf7b1ce594d|2019-05-21--20-10-33.bz2", "HONDA_BOSCH", 1), # HONDA.ACCORD - ("02ec6bea180a4d36|2019-04-17--11-21-35.bz2", "HYUNDAI", 0), # HYUNDAI.SANTA_FE - ("03efb1fda29e30fe|2019-02-21--18-03-45.bz2", "CHRYSLER", 0), # CHRYSLER.PACIFICA_2018_HYBRID - ("791340bc01ed993d|2019-04-08--10-26-00.bz2", "SUBARU", 0), # SUBARU.IMPREZA + ("b0c9d2329ad1606b|2019-05-30--20-23-57.bz2", Panda.SAFETY_HONDA, 0), # HONDA.CIVIC + ("38bfd238edecbcd7|2019-06-07--10-15-25.bz2", Panda.SAFETY_TOYOTA, 66), # TOYOTA.PRIUS + ("f89c604cf653e2bf|2018-09-29--13-46-50.bz2", Panda.SAFETY_GM, 0), # GM.VOLT + ("0375fdf7b1ce594d|2019-05-21--20-10-33.bz2", Panda.SAFETY_HONDA_BOSCH, 1), # HONDA.ACCORD + ("02ec6bea180a4d36|2019-04-17--11-21-35.bz2", Panda.SAFETY_HYUNDAI, 0), # HYUNDAI.SANTA_FE + ("03efb1fda29e30fe|2019-02-21--18-03-45.bz2", Panda.SAFETY_CHRYSLER, 0), # CHRYSLER.PACIFICA_2018_HYBRID + ("791340bc01ed993d|2019-04-08--10-26-00.bz2", Panda.SAFETY_SUBARU, 0), # SUBARU.IMPREZA ] if __name__ == "__main__": for route, _, _ in logs: if not os.path.isfile(route): - with open(route, "w") as f: + with open(route, "wb") as f: f.write(requests.get(BASE_URL + route).content) failed = [] for route, mode, param in logs: lr = LogReader(route) - m = safety_modes.get(mode, mode) - print "\nreplaying %s with safety mode %d and param %s" % (route, m, param) - if not replay_drive(lr, m, int(param)): + print("\nreplaying %s with safety mode %d and param %s" % (route, mode, param)) + if not replay_drive(lr, mode, int(param)): failed.append(route) for f in failed: - print "\n**** failed on %s ****" % f + print("\n**** failed on %s ****" % f) assert len(failed) == 0, "\nfailed on %d logs" % len(failed) diff --git a/tests/spam_can.py b/tests/spam_can.py new file mode 100755 index 0000000000..6b0c2d9c60 --- /dev/null +++ b/tests/spam_can.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python3 + +import os +import sys +import time +import random + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +def get_test_string(): + return b"test"+os.urandom(10) + +if __name__ == "__main__": + p = Panda() + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + print("Spamming all buses...") + while True: + at = random.randint(1, 2000) + 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 diff --git a/tests/standalone_test.py b/tests/standalone_test.py index ca6ea49f10..9e181d8fc9 100755 --- a/tests/standalone_test.py +++ b/tests/standalone_test.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import os import sys import struct diff --git a/tests/throughput_test.py b/tests/throughput_test.py index 5812ce42c2..69b06c7646 100755 --- a/tests/throughput_test.py +++ b/tests/throughput_test.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import os import sys import struct @@ -34,7 +34,7 @@ if __name__ == "__main__": p_in.can_recv() BATCH_SIZE = 16 - for a in tqdm(range(0, 10000, BATCH_SIZE)): + for a in tqdm(list(range(0, 10000, BATCH_SIZE))): for b in range(0, BATCH_SIZE): msg = b"\xaa"*4 + struct.pack("I", a+b) if a%1 == 0: @@ -61,4 +61,4 @@ if __name__ == "__main__": if len(set_out - set_in): print("MISSING %d" % len(set_out - set_in)) if len(set_out - set_in) < 256: - print(map(hex, sorted(list(set_out - set_in)))) + print(list(map(hex, sorted(list(set_out - set_in))))) diff --git a/tests/tucan_loopback.py b/tests/tucan_loopback.py index a3f3e6e2d7..1b5ed01663 100755 --- a/tests/tucan_loopback.py +++ b/tests/tucan_loopback.py @@ -1,5 +1,5 @@ -#!/usr/bin/env python -from __future__ import print_function +#!/usr/bin/env python3 + import os import sys import time @@ -29,14 +29,14 @@ def run_test(sleep_duration): run_test_w_pandas(pandas, sleep_duration) def run_test_w_pandas(pandas, sleep_duration): - h = list(map(lambda x: Panda(x), pandas)) + h = list([Panda(x) for x in pandas]) print("H", h) for hh in h: hh.set_controls_allowed(True) # test both directions - for ho in permutations(range(len(h)), r=2): + for ho in permutations(list(range(len(h))), r=2): print("***************** TESTING", ho) panda0, panda1 = h[ho[0]], h[ho[1]]