Merge panda subtree

pull/219/head
Vehicle Researcher 7 years ago
commit 02968cda63
  1. 2
      panda/README.md
  2. 2
      panda/VERSION
  3. 6
      panda/board/bootstub.c
  4. 2
      panda/board/build.mk
  5. 11
      panda/board/drivers/can.h
  6. 2
      panda/board/drivers/drivers.h
  7. 102
      panda/board/drivers/usb.h
  8. 2
      panda/board/get_sdk.sh
  9. 2
      panda/board/get_sdk_mac.sh
  10. 31
      panda/board/gpio.h
  11. 1
      panda/board/pedal/.gitignore
  12. 59
      panda/board/pedal/Makefile
  13. 28
      panda/board/pedal/README
  14. 295
      panda/board/pedal/main.c
  15. 11
      panda/board/safety.h
  16. 10
      panda/board/safety/safety_defaults.h
  17. 5
      panda/board/safety/safety_elm327.h
  18. 186
      panda/board/safety/safety_gm.h
  19. 43
      panda/board/safety/safety_honda.h
  20. 10
      panda/board/safety/safety_toyota.h
  21. 128
      panda/board/spi_flasher.h
  22. 80
      panda/boardesp/proxy.c
  23. 18
      panda/boardesp/webserver.c
  24. 2
      panda/drivers/windows/ECUsim DLL/ECUsim.h
  25. 67
      panda/drivers/windows/README.md
  26. 182
      panda/drivers/windows/panda.sln
  27. 6
      panda/drivers/windows/panda/panda.vcxproj
  28. 99
      panda/drivers/windows/panda/panda.vcxproj.filters
  29. 2
      panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp
  30. 2
      panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp
  31. 2
      panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h
  32. 2
      panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp
  33. 3
      panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj
  34. 2
      panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp
  35. 38
      panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp
  36. 2
      panda/drivers/windows/pandaJ2534DLL/J2534Connection.h
  37. 2
      panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h
  38. 5
      panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp
  39. 2
      panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h
  40. 4
      panda/drivers/windows/pandaJ2534DLL/J2534Frame.h
  41. 2
      panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp
  42. 44
      panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp
  43. 10
      panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h
  44. 21
      panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp
  45. 10
      panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj
  46. 90
      panda/drivers/windows/panda_install.nsi
  47. 3
      panda/drivers/windows/panda_shared/device.cpp
  48. 1
      panda/drivers/windows/panda_shared/device.h
  49. 181
      panda/drivers/windows/panda_shared/panda.cpp
  50. 29
      panda/drivers/windows/panda_shared/panda.h
  51. 25
      panda/drivers/windows/panda_shared/panda_shared.vcxitems
  52. 0
      panda/drivers/windows/panda_shared/targetver.h
  53. 25
      panda/examples/can_bit_transition.md
  54. 87
      panda/examples/can_bit_transition.py
  55. 85
      panda/examples/isotp.py
  56. 125
      panda/python/__init__.py
  57. 135
      panda/python/isotp.py
  58. 52
      panda/tests/automated/helpers.py
  59. 4
      panda/tests/can_printer.py
  60. 0
      panda/tests/elm_wifi.py
  61. 76
      panda/tests/pedal/enter_canloader.py
  62. 29
      panda/tests/read_winusb_descriptors.py
  63. 2
      panda/tests/standalone_test.py
  64. 125
      panda/tests/tucan_loopback.py

@ -45,7 +45,7 @@ As a universal car interface, it should support every reasonable software interf
- User space ([done](https://github.com/commaai/panda/tree/master/python))
- socketcan in kernel ([alpha](https://github.com/commaai/panda/tree/master/drivers/linux))
- ELM327 ([done](https://github.com/commaai/panda/blob/master/boardesp/elm327.c))
- Windows J2534 ([alpha](https://github.com/commaai/panda/tree/master/drivers/windows))
- Windows J2534 ([done](https://github.com/commaai/panda/tree/master/drivers/windows))
Directory structure
------

@ -1 +1 @@
v1.0.7
v1.0.9

@ -24,6 +24,12 @@
#include "drivers/usb.h"
//#include "drivers/uart.h"
#ifdef PEDAL
#define CUSTOM_CAN_INTERRUPTS
#include "safety.h"
#include "drivers/can.h"
#endif
int puts(const char *a) { return 0; }
void puth(unsigned int i) {}

@ -1,4 +1,4 @@
CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O0
CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O2
CFLAGS += -Tstm32_flash.ld
CC = arm-none-eabi-gcc

@ -199,6 +199,7 @@ void can_init_all() {
}
void can_set_gmlan(int bus) {
#ifdef PANDA
if (bus == -1 || bus != can_num_lookup[3]) {
// GMLAN OFF
switch (can_num_lookup[3]) {
@ -238,6 +239,7 @@ void can_set_gmlan(int bus) {
can_num_lookup[3] = 2;
can_init(2);
}
#endif
}
// CAN error
@ -346,13 +348,14 @@ void can_rx(uint8_t can_number) {
// forwarding (panda only)
#ifdef PANDA
if (can_forwarding[bus_number] != -1) {
int bus_fwd_num = can_forwarding[bus_number] != -1 ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push);
if (bus_fwd_num != -1) {
CAN_FIFOMailBox_TypeDef to_send;
to_send.RIR = to_push.RIR | 1; // TXRQ
to_send.RDTR = to_push.RDTR;
to_send.RDLR = to_push.RDLR;
to_send.RDHR = to_push.RDHR;
can_send(&to_send, can_forwarding[bus_number]);
can_send(&to_send, bus_fwd_num);
}
#endif
@ -370,6 +373,8 @@ void can_rx(uint8_t can_number) {
}
}
#ifndef CUSTOM_CAN_INTERRUPTS
void CAN1_TX_IRQHandler() { process_can(0); }
void CAN1_RX0_IRQHandler() { can_rx(0); }
void CAN1_SCE_IRQHandler() { can_sce(CAN1); }
@ -384,6 +389,8 @@ void CAN3_RX0_IRQHandler() { can_rx(2); }
void CAN3_SCE_IRQHandler() { can_sce(CAN3); }
#endif
#endif
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) {
if (safety_tx_hook(to_push)) {
if (bus_number < BUS_MAX) {

@ -88,7 +88,7 @@ uint32_t adc_get(int channel);
// ********************* DAC *********************
void dac_init();
uint32_t dac_set(int channel, uint32_t value);
void dac_set(int channel, uint32_t value);
// ********************* TIMER *********************

@ -71,12 +71,15 @@ uint8_t resp[MAX_RESP_LEN];
#define ENDPOINT_TYPE_BULK 2
#define ENDPOINT_TYPE_INT 3
// This is an arbitrary value used in bRequest
#define MS_VENDOR_CODE 0x20
//Convert machine byte order to USB byte order
#define TOUSBORDER(num)\
(num&0xFF), ((num>>8)&0xFF)
uint8_t device_desc[] = {
DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x01, //Length, Type, bcdUSB
DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x02, //Length, Type, bcdUSB
0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size
TOUSBORDER(USB_VID), // idVendor
TOUSBORDER(USB_PID), // idProduct
@ -165,9 +168,47 @@ uint16_t string_3_desc[] = {
'n', 'o', 'n', 'e'
};
#ifdef PANDA
// WCID (auto install WinUSB driver)
// https://github.com/pbatard/libwdi/wiki/WCID-Devices
// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file
uint8_t string_238_desc[] = {
0x12, 0x03, // bLength, bDescriptorType
'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100)
MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad
};
uint8_t winusb_ext_compatid_os_desc[] = {
0x28, 0x00, 0x00, 0x00, // dwLength
0x00, 0x01, // bcdVersion
0x04, 0x00, // wIndex
0x01, // bCount
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved
0x00, // bFirstInterfaceNumber
0x00, // Reserved
'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB)
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none)
0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved
};
uint8_t winusb_ext_prop_os_desc[] = {
0x8e, 0x00, 0x00, 0x00, // dwLength
0x00, 0x01, // bcdVersion
0x05, 0x00, // wIndex
0x01, 0x00, // wCount
// first property
0x84, 0x00, 0x00, 0x00, // dwSize
0x01, 0x00, 0x00, 0x00, // dwPropertyDataType
0x28, 0x00, // wPropertyNameLength
'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID)
0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength
'{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9})
};
#endif
// current packet
USB_Setup_TypeDef setup;
uint8_t usbdata[0x100];
uint8_t* ep0_txdata = NULL;
uint16_t ep0_txlen = 0;
// Store the current interface alt setting.
int current_int0_alt_setting = 0;
@ -206,6 +247,26 @@ void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) {
}
}
// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest)
// so use TX FIFO empty interrupt to send larger amounts of data
void USB_WritePacket_EP0(uint8_t *src, uint16_t len) {
#ifdef DEBUG_USB
puts("writing ");
hexdump(src, len);
#endif
uint16_t wplen = min(len, 0x40);
USB_WritePacket(src, wplen, 0);
if (wplen < len) {
ep0_txdata = src + wplen;
ep0_txlen = len - wplen;
USBx_DEVICE->DIEPEMPMSK |= 1;
} else {
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
void usb_reset() {
// unmask endpoint interrupts, so many sets
USBx_DEVICE->DAINT = 0xFFFFFFFF;
@ -345,6 +406,11 @@ void usb_setup() {
USB_WritePacket((const uint8_t *)string_3_desc, min(sizeof(string_3_desc), setup.b.wLength.w), 0);
#endif
break;
#ifdef PANDA
case 238:
USB_WritePacket((uint8_t*)string_238_desc, min(sizeof(string_238_desc), setup.b.wLength.w), 0);
break;
#endif
default:
// nothing
USB_WritePacket(0, 0, 0);
@ -372,6 +438,22 @@ void usb_setup() {
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
#ifdef PANDA
case MS_VENDOR_CODE:
switch (setup.b.wIndex.w) {
// Extended Compat ID OS Descriptor
case 4:
USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, min(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w));
break;
// Extended Properties OS Descriptor
case 5:
USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, min(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w));
break;
default:
USB_WritePacket_EP0(0, 0);
}
break;
#endif
default:
resp_len = usb_cb_control_msg(&setup, resp, 1);
USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0);
@ -682,6 +764,24 @@ void usb_irqhandler(void) {
break;
}
if (USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
#ifdef DEBUG_USB
puts(" IN PACKET QUEUE\n");
#endif
if (ep0_txlen != 0 && (USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40) {
uint16_t len = min(ep0_txlen, 0x40);
USB_WritePacket(ep0_txdata, len, 0);
ep0_txdata += len;
ep0_txlen -= len;
if (ep0_txlen == 0) {
ep0_txdata = NULL;
USBx_DEVICE->DIEPEMPMSK &= ~1;
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
}
// clear interrupts
USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0?
USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT;

@ -1,3 +1,3 @@
#!/bin/bash
sudo apt-get install gcc-arm-none-eabi python-pip
sudo pip2 install libusb1
sudo pip2 install libusb1 pycrypto requests

@ -2,4 +2,4 @@
# Need formula for gcc
brew tap ArmMbed/homebrew-formulae
brew install python dfu-util arm-none-eabi-gcc
pip2 install libusb1
pip2 install libusb1 pycrypto requests

@ -72,8 +72,15 @@ void clock_init() {
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE;
#else
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE;
#ifdef PEDAL
// comma pedal has a 16mhz crystal
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE;
#else
// NEO board has a 8mhz crystal
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE;
#endif
#endif
// start PLL
@ -132,8 +139,13 @@ void set_can_enable(CAN_TypeDef *CAN, int enabled) {
// CAN1_EN
set_gpio_output(GPIOC, 1, !enabled);
#else
// CAN1_EN
set_gpio_output(GPIOB, 3, enabled);
#ifdef PEDAL
// CAN1_EN (not flipped)
set_gpio_output(GPIOB, 3, !enabled);
#else
// CAN1_EN
set_gpio_output(GPIOB, 3, enabled);
#endif
#endif
} else if (CAN == CAN2) {
#ifdef PANDA
@ -285,6 +297,14 @@ void gpio_init() {
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
#ifdef PEDAL
// comma pedal has inputs on C0 and C1
set_gpio_mode(GPIOC, 0, MODE_ANALOG);
set_gpio_mode(GPIOC, 1, MODE_ANALOG);
// DAC outputs on A4 and A5
// apparently they don't need GPIO setup
#endif
// C8: FAN aka TIM3_CH4
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
@ -443,9 +463,10 @@ void early() {
if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) {
#ifdef PANDA
set_esp_mode(ESP_DISABLED);
#endif
set_led(LED_GREEN, 1);
jump_to_bootloader();
}

@ -0,0 +1,59 @@
# :set noet
PROJ_NAME = comma
CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx
CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib
CFLAGS += -T../stm32_flash.ld
STARTUP_FILE = startup_stm32f205xx
CC = arm-none-eabi-gcc
OBJCOPY = arm-none-eabi-objcopy
OBJDUMP = arm-none-eabi-objdump
DFU_UTIL = "dfu-util"
# pedal only uses the debug cert
CERT = ../../certs/debug
CFLAGS += "-DALLOW_DEBUG"
canflash: obj/$(PROJ_NAME).bin
../../tests/pedal/enter_canloader.py $<
usbflash: obj/$(PROJ_NAME).bin
../../tests/pedal/enter_canloader.py; sleep 0.5
PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)"
recover: obj/bootstub.bin obj/$(PROJ_NAME).bin
../../tests/pedal/enter_canloader.py --recover; sleep 0.5
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin
obj/main.o: main.c ../*.h
mkdir -p obj
$(CC) $(CFLAGS) -o $@ -c $<
obj/bootstub.o: ../bootstub.c ../*.h
mkdir -p obj
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s
$(CC) $(CFLAGS) -o $@ -c $<
obj/%.o: ../../crypto/%.c
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.o
# hack
$(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
$(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin
SETLEN=1 ../../crypto/sign.py obj/code.bin $@ $(CERT)
obj/bootstub.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
clean:
rm -f obj/*

@ -0,0 +1,28 @@
This is the firmware for the comma pedal. It borrows a lot from panda.
The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal.
This is the open source software. Note that it is not ready to use yet.
== Test Plan ==
* Startup
** Confirm STATE_FAULT_STARTUP
* Timeout
** Send value
** Confirm value is output
** Stop sending messages
** Confirm value is passthru after 100ms
** Confirm STATE_FAULT_TIMEOUT
* Random values
** Send random 6 byte messages
** Confirm random values cause passthru
** Confirm STATE_FAULT_BAD_CHECKSUM
* Same message lockout
** Send same message repeated
** Confirm timeout behavior
* Don't set enable
** Confirm no output
* Set enable and values
** Confirm output

@ -0,0 +1,295 @@
//#define DEBUG
//#define CAN_LOOPBACK_MODE
//#define USE_INTERNAL_OSC
#include "../config.h"
#include "drivers/drivers.h"
#include "drivers/llgpio.h"
#include "gpio.h"
#define CUSTOM_CAN_INTERRUPTS
#include "libc.h"
#include "safety.h"
#include "drivers/adc.h"
#include "drivers/uart.h"
#include "drivers/dac.h"
#include "drivers/can.h"
#include "drivers/timer.h"
#define CAN CAN1
//#define PEDAL_USB
#ifdef PEDAL_USB
#include "drivers/usb.h"
#endif
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
uint32_t enter_bootloader_mode;
void __initialize_hardware_early() {
early();
}
// ********************* serial debugging *********************
void debug_ring_callback(uart_ring *ring) {
char rcv;
while (getc(ring, &rcv)) {
putc(ring, rcv);
}
}
#ifdef PEDAL_USB
int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; }
void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) {}
void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {}
void usb_cb_enumeration_complete() {}
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
int resp_len = 0;
uart_ring *ur = NULL;
switch (setup->b.bRequest) {
// **** 0xe0: uart read
case 0xe0:
ur = get_ring_by_number(setup->b.wValue.w);
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])) {
++resp_len;
}
break;
}
return resp_len;
}
#endif
// ***************************** honda can checksum *****************************
int can_cksum(uint8_t *dat, int len, int addr, int idx) {
int i;
int s = 0;
for (i = 0; i < len; i++) {
s += (dat[i] >> 4);
s += dat[i] & 0xF;
}
s += (addr>>0)&0xF;
s += (addr>>4)&0xF;
s += (addr>>8)&0xF;
s += idx;
s = 8-s;
return s&0xF;
}
// ***************************** can port *****************************
// addresses to be used on CAN
#define CAN_GAS_INPUT 0x200
#define CAN_GAS_OUTPUT 0x201
void CAN1_TX_IRQHandler() {
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
// two independent values
uint16_t gas_set_0 = 0;
uint16_t gas_set_1 = 0;
#define MAX_TIMEOUT 10
uint32_t timeout = 0;
uint32_t current_index = 0;
#define NO_FAULT 0
#define FAULT_BAD_CHECKSUM 1
#define FAULT_SEND 2
#define FAULT_SCE 3
#define FAULT_STARTUP 4
#define FAULT_TIMEOUT 5
#define FAULT_INVALID 6
uint8_t state = FAULT_STARTUP;
void CAN1_RX0_IRQHandler() {
while (CAN->RF0R & CAN_RF0R_FMP0) {
#ifdef DEBUG
puts("CAN RX\n");
#endif
uint32_t address = CAN->sFIFOMailBox[0].RIR>>21;
if (address == CAN_GAS_INPUT) {
// softloader entry
if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) {
if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) {
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
NVIC_SystemReset();
} else if (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
}
}
// normal packet
uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
uint16_t value_0 = (dat[0] << 8) | dat[1];
uint16_t value_1 = (dat[2] << 8) | dat[3];
uint8_t enable = (dat2[0] >> 7) & 1;
uint8_t index = (dat2[1] >> 4) & 3;
if (can_cksum(dat, 5, CAN_GAS_INPUT, index) == (dat2[1] & 0xF)) {
if (((current_index+1)&3) == index) {
#ifdef DEBUG
puts("setting gas ");
puth(value);
puts("\n");
#endif
if (enable) {
gas_set_0 = value_0;
gas_set_1 = value_1;
} else {
// clear the fault state if values are 0
if (value_0 == 0 && value_1 == 0) {
state = NO_FAULT;
} else {
state = FAULT_INVALID;
}
gas_set_0 = gas_set_1 = 0;
}
// clear the timeout
timeout = 0;
}
current_index = index;
} else {
// wrong checksum = fault
state = FAULT_BAD_CHECKSUM;
}
}
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_SCE_IRQHandler() {
state = FAULT_SCE;
can_sce(CAN);
}
int pdl0 = 0, pdl1 = 0;
int pkt_idx = 0;
int led_value = 0;
void TIM3_IRQHandler() {
#ifdef DEBUG
puth(TIM3->CNT);
puts(" ");
puth(pdl0);
puts(" ");
puth(pdl1);
puts("\n");
#endif
// check timer for sending the user pedal and clearing the CAN
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
uint8_t dat[8];
dat[0] = (pdl0>>8)&0xFF;
dat[1] = (pdl0>>0)&0xFF;
dat[2] = (pdl1>>8)&0xFF;
dat[3] = (pdl1>>0)&0xFF;
dat[4] = state;
dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT, pkt_idx) | (pkt_idx<<4);
CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24);
CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8);
CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5
CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1;
++pkt_idx;
pkt_idx &= 3;
} else {
// old can packet hasn't sent!
state = FAULT_SEND;
#ifdef DEBUG
puts("CAN MISS\n");
#endif
}
// blink the LED
set_led(LED_GREEN, led_value);
led_value = !led_value;
TIM3->SR = 0;
// up timeout for gas set
if (timeout == MAX_TIMEOUT) {
state = FAULT_TIMEOUT;
} else {
timeout += 1;
}
}
// ***************************** main code *****************************
void pedal() {
// read/write
pdl0 = adc_get(ADCCHAN_ACCEL0);
pdl1 = adc_get(ADCCHAN_ACCEL1);
// write the pedal to the DAC
if (state == NO_FAULT) {
dac_set(0, max(gas_set_0, pdl0));
dac_set(1, max(gas_set_1, pdl1));
} else {
dac_set(0, pdl0);
dac_set(1, pdl1);
}
// feed the watchdog
IWDG->KR = 0xAAAA;
}
int main() {
__disable_irq();
// init devices
clock_init();
periph_init();
gpio_init();
#ifdef PEDAL_USB
// enable USB
usb_init();
#endif
// pedal stuff
dac_init();
adc_init();
// init can
can_silent = ALL_CAN_LIVE;
can_init(0);
// 48mhz / 65536 ~= 732
timer_init(TIM3, 15);
NVIC_EnableIRQ(TIM3_IRQn);
// setup watchdog
IWDG->KR = 0x5555;
IWDG->PR = 0; // divider /4
// 0 = 0.125 ms, let's have a 50ms watchdog
IWDG->RLR = 400 - 1;
IWDG->KR = 0xCCCC;
puts("**** INTERRUPTS ON ****\n");
__enable_irq();
// main pedal loop
while (1) {
pedal();
}
return 0;
}

@ -6,12 +6,14 @@ typedef void (*safety_hook_init)(int16_t param);
typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push);
typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send);
typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len);
typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd);
typedef struct {
safety_hook_init init;
rx_hook rx;
tx_hook tx;
tx_lin_hook tx_lin;
fwd_hook fwd;
} safety_hooks;
// This can be set by the safety hooks.
@ -21,6 +23,7 @@ int controls_allowed = 0;
#include "safety/safety_defaults.h"
#include "safety/safety_honda.h"
#include "safety/safety_toyota.h"
#include "safety/safety_gm.h"
#include "safety/safety_elm327.h"
const safety_hooks *current_hooks = &nooutput_hooks;
@ -37,6 +40,10 @@ int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){
return current_hooks->tx_lin(lin_num, data, len);
}
int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return current_hooks->fwd(bus_num, to_fwd);
}
typedef struct {
uint16_t id;
const safety_hooks *hooks;
@ -46,14 +53,18 @@ typedef struct {
#define SAFETY_HONDA 1
#define SAFETY_TOYOTA 2
#define SAFETY_TOYOTA_NOLIMITS 0x1336
#define SAFETY_GM 3
#define SAFETY_HONDA_BOSCH 4
#define SAFETY_ALLOUTPUT 0x1337
#define SAFETY_ELM327 0xE327
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_TOYOTA_NOLIMITS, &toyota_nolimits_hooks},
{SAFETY_GM, &gm_hooks},
{SAFETY_ALLOUTPUT, &alloutput_hooks},
{SAFETY_ELM327, &elm327_hooks},
};

@ -14,11 +14,16 @@ static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) {
return false;
}
static int nooutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks nooutput_hooks = {
.init = nooutput_init,
.rx = default_rx_hook,
.tx = nooutput_tx_hook,
.tx_lin = nooutput_tx_lin_hook,
.fwd = nooutput_fwd_hook,
};
// *** all output safety mode ***
@ -35,10 +40,15 @@ static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) {
return true;
}
static int alloutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks alloutput_hooks = {
.init = alloutput_init,
.rx = default_rx_hook,
.tx = alloutput_tx_hook,
.tx_lin = alloutput_tx_lin_hook,
.fwd = alloutput_fwd_hook,
};

@ -31,9 +31,14 @@ static void elm327_init(int16_t param) {
controls_allowed = 1;
}
static int elm327_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks elm327_hooks = {
.init = elm327_init,
.rx = elm327_rx_hook,
.tx = elm327_tx_hook,
.tx_lin = elm327_tx_lin_hook,
.fwd = elm327_fwd_hook,
};

@ -0,0 +1,186 @@
// board enforces
// in-state
// accel set/resume
// out-state
// cancel button
// regen paddle
// accel rising edge
// brake rising edge
// brake > 0mph
// gm_: poor man's namespacing
int gm_brake_prev = 0;
int gm_gas_prev = 0;
int gm_speed = 0;
// silence everything if stock ECUs are still online
int gm_ascm_detected = 0;
static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
uint32_t addr;
if (to_push->RIR & 4) {
// Extended
// Not looked at, but have to be separated
// to avoid address collision
addr = to_push->RIR >> 3;
} else {
// Normal
addr = to_push->RIR >> 21;
}
// sample speed, really only care if car is moving or not
// rear left wheel speed
if (addr == 842) {
gm_speed = to_push->RDLR & 0xFFFF;
}
// check if stock ASCM ECU is still online
int bus_number = (to_push->RDTR >> 4) & 0xFF;
if (bus_number == 0 && addr == 715) {
gm_ascm_detected = 1;
controls_allowed = 0;
}
// ACC steering wheel buttons
if (addr == 481) {
int buttons = (to_push->RDHR >> 12) & 0x7;
// res/set - enable, cancel button - disable
if (buttons == 2 || buttons == 3) {
controls_allowed = 1;
} else if (buttons == 6) {
controls_allowed = 0;
}
}
// exit controls on rising edge of brake press or on brake press when
// speed > 0
if (addr == 241) {
int brake = (to_push->RDLR & 0xFF00) >> 8;
// Brake pedal's potentiometer returns near-zero reading
// even when pedal is not pressed
if (brake < 10) {
brake = 0;
}
if (brake && (!gm_brake_prev || gm_speed)) {
controls_allowed = 0;
}
gm_brake_prev = brake;
}
// exit controls on rising edge of gas press
if (addr == 417) {
int gas = to_push->RDHR & 0xFF0000;
if (gas && !gm_gas_prev) {
controls_allowed = 0;
}
gm_gas_prev = gas;
}
// exit controls on regen paddle
if (addr == 189) {
int regen = to_push->RDLR & 0x20;
if (regen) {
controls_allowed = 0;
}
}
}
// all commands: gas/regen, friction brake and steering
// if controls_allowed and no pedals pressed
// allow all commands up to limit
// else
// block all commands that produce actuation
static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// There can be only one! (ASCM)
if (gm_ascm_detected) {
return 0;
}
// disallow actuator commands if gas or brake (with vehicle moving) are pressed
// and the the latching controls_allowed flag is True
int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_speed);
int current_controls_allowed = controls_allowed && !pedal_pressed;
uint32_t addr;
if (to_send->RIR & 4) {
// Extended
addr = to_send->RIR >> 3;
} else {
// Normal
addr = to_send->RIR >> 21;
}
// BRAKE: safety check
if (addr == 789) {
int rdlr = to_send->RDLR;
int brake = ((rdlr & 0xF) << 8) + ((rdlr & 0xFF00) >> 8);
brake = (0x1000 - brake) & 0xFFF;
if (current_controls_allowed) {
if (brake > 255) return 0;
} else {
if (brake != 0) return 0;
}
}
// LKA STEER: safety check
if (addr == 384) {
int rdlr = to_send->RDLR;
int steer = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8);
int max_steer = 255;
if (current_controls_allowed) {
// Signed arithmetic
if (steer & 0x400) {
if (steer < (0x800 - max_steer)) return 0;
} else {
if (steer > max_steer) return 0;
}
} else {
if (steer != 0) return 0;
}
}
// PARK ASSIST STEER: unlimited torque, no thanks
if (addr == 823) return 0;
// GAS/REGEN: safety check
if (addr == 715) {
int rdlr = to_send->RDLR;
int gas_regen = ((rdlr & 0x7F0000) >> 11) + ((rdlr & 0xF8000000) >> 27);
int apply = rdlr & 1;
if (current_controls_allowed) {
if (gas_regen > 3072) return 0;
} else {
// Disabled message is !engaed with gas
// value that corresponds to max regen.
if (apply || gas_regen != 1404) return 0;
}
}
// 1 allows the message through
return true;
}
static int gm_tx_lin_hook(int lin_num, uint8_t *data, int len) {
// LIN is not used in Volt
return false;
}
static void gm_init(int16_t param) {
controls_allowed = 0;
}
static int gm_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks gm_hooks = {
.init = gm_init,
.rx = gm_rx_hook,
.tx = gm_tx_hook,
.tx_lin = gm_tx_lin_hook,
.fwd = gm_fwd_hook,
};

@ -13,6 +13,8 @@ int brake_prev = 0;
int gas_prev = 0;
int gas_interceptor_prev = 0;
int ego_speed = 0;
// TODO: auto-detect bosch hardware based on CAN messages?
bool bosch_hardware = false;
static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
@ -33,19 +35,24 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
}
}
// user brake signal is different for nidec vs bosch hardware
// nidec hardware: 0x17C bit 53
// bosch hardware: 0x1BE bit 4
#define IS_USER_BRAKE_MSG(to_push) (!bosch_hardware ? to_push->RIR>>21 == 0x17C : to_push->RIR>>21 == 0x1BE)
#define USER_BRAKE_VALUE(to_push) (!bosch_hardware ? to_push->RDHR & 0x200000 : to_push->RDLR & 0x10)
// exit controls on rising edge of brake press or on brake press when
// speed > 0
if ((to_push->RIR>>21) == 0x17C) {
// bit 53
int brake = to_push->RDHR & 0x200000;
if (IS_USER_BRAKE_MSG(to_push)) {
int brake = USER_BRAKE_VALUE(to_push);
if (brake && (!(brake_prev) || ego_speed)) {
controls_allowed = 0;
}
brake_prev = brake;
}
// exit controls on rising edge of gas press if interceptor
if ((to_push->RIR>>21) == 0x201) {
// exit controls on rising edge of gas press if interceptor (0x201 w/ len = 6)
// length check because bosch hardware also uses this id (0x201 w/ len = 8)
if ((to_push->RIR>>21) == 0x201 && (to_push->RDTR & 0xf) == 6) {
gas_interceptor_detected = 1;
int gas_interceptor = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8);
if ((gas_interceptor > 328) && (gas_interceptor_prev <= 328)) {
@ -117,6 +124,11 @@ static int honda_tx_lin_hook(int lin_num, uint8_t *data, int len) {
static void honda_init(int16_t param) {
controls_allowed = 0;
bosch_hardware = false;
}
static int honda_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks honda_hooks = {
@ -124,5 +136,26 @@ const safety_hooks honda_hooks = {
.rx = honda_rx_hook,
.tx = honda_tx_hook,
.tx_lin = honda_tx_lin_hook,
.fwd = honda_fwd_hook,
};
static void honda_bosch_init(int16_t param) {
controls_allowed = 0;
bosch_hardware = true;
}
static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
if (bus_num == 1 || bus_num == 2) {
int addr = to_fwd->RIR>>21;
return addr != 0xE4 && addr != 0x33D ? (uint8_t)(~bus_num & 0x3) : -1;
}
return -1;
}
const safety_hooks honda_bosch_hooks = {
.init = honda_bosch_init,
.rx = honda_rx_hook,
.tx = honda_tx_hook,
.tx_lin = honda_tx_lin_hook,
.fwd = honda_bosch_fwd_hook,
};

@ -32,10 +32,10 @@ uint32_t ts_last = 0;
static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// get eps motor torque (0.66 factor in dbc)
if ((to_push->RIR>>21) == 0x260) {
int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF));
int16_t torque_meas_new_16 = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF));
// increase torque_meas by 1 to be conservative on rounding
torque_meas_new = (torque_meas_new * dbc_eps_torque_factor / 100) + (torque_meas_new > 0 ? 1 : -1);
int torque_meas_new = ((int)(torque_meas_new_16) * dbc_eps_torque_factor / 100) + (torque_meas_new_16 > 0 ? 1 : -1);
// shift the array
for (int i = sizeof(torque_meas)/sizeof(torque_meas[0]) - 1; i > 0; i--) {
@ -161,11 +161,16 @@ static void toyota_init(int16_t param) {
dbc_eps_torque_factor = param;
}
static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
return -1;
}
const safety_hooks toyota_hooks = {
.init = toyota_init,
.rx = toyota_rx_hook,
.tx = toyota_tx_hook,
.tx_lin = toyota_tx_lin_hook,
.fwd = toyota_fwd_hook,
};
static void toyota_nolimits_init(int16_t param) {
@ -179,4 +184,5 @@ const safety_hooks toyota_nolimits_hooks = {
.rx = toyota_rx_hook,
.tx = toyota_tx_hook,
.tx_lin = toyota_tx_lin_hook,
.fwd = toyota_fwd_hook,
};

@ -130,6 +130,120 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
return resp_len;
}
#ifdef PEDAL
#define CAN CAN1
#define CAN_BL_INPUT 0x1
#define CAN_BL_OUTPUT 0x2
void CAN1_TX_IRQHandler() {
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
#define ISOTP_BUF_SIZE 0x110
uint8_t isotp_buf[ISOTP_BUF_SIZE];
uint8_t *isotp_buf_ptr = NULL;
int isotp_buf_remain = 0;
uint8_t isotp_buf_out[ISOTP_BUF_SIZE];
uint8_t *isotp_buf_out_ptr = NULL;
int isotp_buf_out_remain = 0;
int isotp_buf_out_idx = 0;
void bl_can_send(uint8_t *odat) {
// wait for send
while (!(CAN->TSR & CAN_TSR_TME0));
// send continue
CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0];
CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1];
CAN->sTxMailBox[0].TDTR = 8;
CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1;
}
void CAN1_RX0_IRQHandler() {
while (CAN->RF0R & CAN_RF0R_FMP0) {
if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) {
uint8_t dat[8];
((uint32_t*)dat)[0] = CAN->sFIFOMailBox[0].RDLR;
((uint32_t*)dat)[1] = CAN->sFIFOMailBox[0].RDHR;
uint8_t odat[8];
uint8_t type = dat[0] & 0xF0;
if (type == 0x30) {
// continue
while (isotp_buf_out_remain > 0) {
// wait for send
while (!(CAN->TSR & CAN_TSR_TME0));
odat[0] = 0x20 | isotp_buf_out_idx;
memcpy(odat+1, isotp_buf_out_ptr, 7);
isotp_buf_out_remain -= 7;
isotp_buf_out_ptr += 7;
isotp_buf_out_idx++;
bl_can_send(odat);
}
} else if (type == 0x20) {
if (isotp_buf_remain > 0) {
memcpy(isotp_buf_ptr, dat+1, 7);
isotp_buf_ptr += 7;
isotp_buf_remain -= 7;
}
if (isotp_buf_remain <= 0) {
int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain;
// call the function
memset(isotp_buf_out, 0, ISOTP_BUF_SIZE);
isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out);
isotp_buf_out_ptr = isotp_buf_out;
isotp_buf_out_idx = 0;
// send initial
if (isotp_buf_out_remain <= 7) {
odat[0] = isotp_buf_out_remain;
memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain);
} else {
odat[0] = 0x10 | (isotp_buf_out_remain>>8);
odat[1] = isotp_buf_out_remain & 0xFF;
memcpy(odat+2, isotp_buf_out_ptr, 6);
isotp_buf_out_remain -= 6;
isotp_buf_out_ptr += 6;
isotp_buf_out_idx++;
}
bl_can_send(odat);
}
} else if (type == 0x10) {
int len = ((dat[0]&0xF)<<8) | dat[1];
// setup buffer
isotp_buf_ptr = isotp_buf;
memcpy(isotp_buf_ptr, dat+2, 6);
if (len < (ISOTP_BUF_SIZE-0x10)) {
isotp_buf_ptr += 6;
isotp_buf_remain = len-6;
}
memset(odat, 0, 8);
odat[0] = 0x30;
bl_can_send(odat);
}
}
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_SCE_IRQHandler() {
can_sce(CAN);
}
#endif
void soft_flasher_start() {
puts("\n\n\n************************ FLASHER START ************************\n");
@ -140,6 +254,20 @@ void soft_flasher_start() {
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
// pedal has the canloader
#ifdef PEDAL
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
// B8,B9: CAN 1
set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1);
set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1);
set_can_enable(CAN1, 1);
// init can
can_silent = ALL_CAN_LIVE;
can_init(0);
#endif
// A4,A5,A6,A7: setup SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);

@ -20,6 +20,9 @@
_a > _b ? _a : _b; })
char ssid[32];
char password[] = "testing123";
int wifi_secure_mode = 0;
static const int pin = 2;
// Structure holding the TCP connection information.
@ -218,11 +221,50 @@ void ICACHE_FLASH_ATTR inter_recv_cb(void *arg, char *pusrdata, unsigned short l
}
}
void ICACHE_FLASH_ATTR wifi_configure(int secure) {
wifi_secure_mode = secure;
// start wifi AP
wifi_set_opmode(SOFTAP_MODE);
struct softap_config config = {0};
wifi_softap_get_config(&config);
strcpy(config.ssid, ssid);
if (wifi_secure_mode == 0) strcat(config.ssid, "-pair");
strcpy(config.password, password);
config.ssid_len = strlen(config.ssid);
config.authmode = wifi_secure_mode ? AUTH_WPA2_PSK : AUTH_OPEN;
config.beacon_interval = 100;
config.max_connection = 4;
wifi_softap_set_config(&config);
if (wifi_secure_mode) {
// setup tcp server
tcp_proto.local_port = 1337;
tcp_conn.type = ESPCONN_TCP;
tcp_conn.state = ESPCONN_NONE;
tcp_conn.proto.tcp = &tcp_proto;
espconn_regist_connectcb(&tcp_conn, tcp_connect_cb);
espconn_accept(&tcp_conn);
espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections
// setup inter server
inter_proto.local_port = 1338;
const char udp_remote_ip[4] = {255, 255, 255, 255};
os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4);
inter_proto.remote_port = 1338;
inter_conn.type = ESPCONN_UDP;
inter_conn.proto.udp = &inter_proto;
espconn_regist_recvcb(&inter_conn, inter_recv_cb);
espconn_create(&inter_conn);
}
}
void ICACHE_FLASH_ATTR wifi_init() {
// default ssid and password
memset(ssid, 0, 32);
os_sprintf(ssid, "panda-%08x-BROKEN", system_get_chip_id());
char password[] = "testing123";
// fetch secure ssid and password
// update, try 20 times, for 1 second
@ -242,19 +284,7 @@ void ICACHE_FLASH_ATTR wifi_init() {
os_delay_us(50000);
}
// start wifi AP
wifi_set_opmode(SOFTAP_MODE);
struct softap_config config;
wifi_softap_get_config(&config);
strcpy(config.ssid, ssid);
strcpy(config.password, password);
config.ssid_len = strlen(ssid);
config.authmode = AUTH_WPA2_PSK;
config.beacon_interval = 100;
config.max_connection = 4;
wifi_softap_set_config(&config);
//set IP
// set IP
wifi_softap_dhcps_stop(); //stop DHCP before setting static IP
struct ip_info ip_config;
IP4_ADDR(&ip_config.ip, 192, 168, 0, 10);
@ -265,27 +295,7 @@ void ICACHE_FLASH_ATTR wifi_init() {
wifi_softap_set_dhcps_offer_option(OFFER_ROUTER, &stupid_gateway);
wifi_softap_dhcps_start();
// setup tcp server
tcp_proto.local_port = 1337;
tcp_conn.type = ESPCONN_TCP;
tcp_conn.state = ESPCONN_NONE;
tcp_conn.proto.tcp = &tcp_proto;
espconn_regist_connectcb(&tcp_conn, tcp_connect_cb);
espconn_accept(&tcp_conn);
espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections
// setup inter server
inter_proto.local_port = 1338;
const char udp_remote_ip[4] = {255, 255, 255, 255};
os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4);
inter_proto.remote_port = 1338;
inter_conn.type = ESPCONN_UDP;
inter_conn.proto.udp = &inter_proto;
espconn_regist_recvcb(&inter_conn, inter_recv_cb);
espconn_create(&inter_conn);
wifi_configure(0);
}
#define LOOP_PRIO 2

@ -40,6 +40,7 @@ char OK_header[] = "HTTP/1.0 200 OK\nContent-Type: text/html\n\n";
static struct espconn web_conn;
static esp_tcp web_proto;
extern char ssid[];
extern int wifi_secure_mode;
char *st_firmware;
int real_content_length, content_length = 0;
@ -205,6 +206,12 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
} else {
ets_strcat(resp, "\nesp flash file: user1.bin");
}
if (wifi_secure_mode) {
ets_strcat(resp, "\nin secure mode");
} else {
ets_strcat(resp, "\nin INSECURE mode...<a href=\"/secure\">secure it</a>");
}
ets_strcat(resp,"\nSet USB Mode:"
"<button onclick=\"var xhr = new XMLHttpRequest(); xhr.open('GET', 'set_property?usb_mode=0'); xhr.send()\" type='button'>Client</button>"
@ -215,8 +222,9 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
} else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0) {
} else if (memcmp(data, "GET /secure", 11) == 0 && !wifi_secure_mode) {
wifi_configure(1);
} else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0 && wifi_secure_mode) {
char mode_value = data[27] - '0';
if (mode_value >= '\x00' && mode_value <= '\x02') {
memset(resp, 0, MAX_RESP);
@ -228,7 +236,7 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
}
} else if (memcmp(data, "PUT /stupdate ", 14) == 0) {
} else if (memcmp(data, "PUT /stupdate ", 14) == 0 && wifi_secure_mode) {
os_printf("init st firmware\n");
char *cl = strstr(data, "Content-Length: ");
if (cl != NULL) {
@ -244,8 +252,8 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
state = RECEIVING_ST_FIRMWARE;
}
} else if ((memcmp(data, "PUT /espupdate1 ", 16) == 0) ||
(memcmp(data, "PUT /espupdate2 ", 16) == 0)) {
} else if (((memcmp(data, "PUT /espupdate1 ", 16) == 0) ||
(memcmp(data, "PUT /espupdate2 ", 16) == 0)) && wifi_secure_mode) {
// 0x1000 = user1.bin
// 0x81000 = user2.bin
// 0x3FE000 = blank.bin

@ -1,7 +1,7 @@
#pragma once
#include <string>
#include "panda\panda.h"
#include "panda_shared/panda.h"
#include <queue>
// The following ifdef block is the standard way of creating macros which make exporting

@ -56,10 +56,8 @@ features.
# Building the Project:
This project was developed with Visual Studio 2015, the Windows SDK,
and the Windows Driver Kit (WDK). At the time of writing, there is not
a stable WDK for Visual Studio 2017, but this project should build
with the new WDK and Visual Studio when it is available.
This project is developed with Visual Studio 2017, the Windows SDK,
and the Windows Driver Kit (WDK).
The WDK is only required for creating the signed WinUSB inf file. The
WDK may also provide the headers for WinUSB.
@ -102,50 +100,18 @@ A simple tool for testing J2534 drivers is DrewTech's 'J2534-1 Bus Analysis
Tool' available in the 'Other Support Applications' section of their
[Download Page](http://www.drewtech.com/downloads/).
# Dealing with self signed drivers:
# Installing WinUSB driver:
Installation would be straightforward were it not for the USB Driver
that needs to be setup. The driver itself is only a WinUSB inf file
(no actual driver), but it still needs to be signed.
Installation automatically happens for Windows 8 and Windows 10 because the panda
firmware contains the USB descriptors necessary to auto-install the WinUSB driver.
Driver signing is a requirement of Windows starting in 8 (64 bit
versions only for some reason). If your Windows refuses to install
the driver, there are three choices:
Windows 7 will not auto-install the WinUSB driver. You can use Zadig to install
the WinUSB driver. This software is not tested on anything before 7.
- Self Sign the Driver.
- Disable Driver Signature Verification
- Purchase a certificate signed by a trusted authority.
Since self signed certificates have no chain of trust to a known
certificate authority, if you self sign, you will have to add your
cert to the root certificate store of your Windows' installation. This
is dangerous because it means anything signed with your cert will be
trusted. If you make your own cert, add a password so someone can't
copy it and screw with your computer's trust.
Disabling Signature Verification allows you to temporarily install
drivers without a trusted signature. Once you reboot, new drivers will
need to be verified again, but any installed drivers will stay where
they are. This option is irritating if you are installing and
uninstalling the inf driver multiple times, but overall, is safer than
the custom root certificate described above.
Purchasing a signed certificate is the best long term option, but it
is not useful for open source contributors, since the certificate will
be kept safe by the comma.ai team. Developers should use one of the
other two options.
**Note that certificate issues apply no matter if you are building
from source or running an insaller .exe file.**
Some people have reported that the driver installs without needing to
disable driver signing, or that visual studio correctly sets up a
temporary signing key for them. I call witchcraft because I have not
had that happen to me. The signed certificate is still the correct
thing to do in the end.
Windows 7 will not force driver signing. This software is not tested
on anything before 7.
More details here:
[WinUSB (Winusb.sys) Installation](https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation)
[WCID Devices](https://github.com/pbatard/libwdi/wiki/WCID-Devices)
[Zadig for installing libusb compatible driver](https://github.com/pbatard/libwdi/wiki/Zadig)
# Developing:
@ -154,8 +120,6 @@ on anything before 7.
# ToDo Items:
- Get official signing key for WinUSB driver inf file.
- Implement TxClear and RxClear. (Requires reading vague specifications).
- Apply a style-guide and consistent naming convention for Classes/Functions/Variables.
- Send multiple messages (each with a different address) from a given connection at the same time.
- Implement ISO14230/KWP2000 FAST (LIN communication is already supported with the raw panda USB driver).
@ -173,5 +137,14 @@ on anything before 7.
relaxed to allow serialization of messages based on their address
(making multiple queues, effectively one queue per address).
# Troubleshooting:
troubleshooting:
1. Install DrewTech J2534-1 Bus Analysis Tool
http://www.drewtech.com/downloads/tools/Drew%20Technologies%20Tool%20for%20J2534-1%20API%20v1.07.msi
2. Open DrewTech tool and make sure it shows "panda" as a device listed (this means registry settings are correct)
3. When DrewTech tool attempts to load the driver it will show an error if it fails
4. To figure out why the driver fails to load install Process Monitor and filter by the appropriate process name
https://docs.microsoft.com/en-us/sysinternals/downloads/procmon
# Other:
Panda head ASCII art by dcau

@ -1,90 +1,92 @@

Microsoft Visual Studio Solution File, Format Version 12.00
# Visual Studio 14
VisualStudioVersion = 14.0.25420.1
MinimumVisualStudioVersion = 10.0.40219.1
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}"
ProjectSection(ProjectDependencies) = postProject
{5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
EndProjectSection
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}"
ProjectSection(ProjectDependencies) = postProject
{5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
EndProjectSection
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}"
EndProject
Global
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|x64 = Debug|x64
Debug|x86 = Debug|x86
Release|x64 = Release|x64
Release|x86 = Release|x86
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.Build.0 = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Build.0 = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Deploy.0 = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Build.0 = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Deploy.0 = Release|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.Build.0 = Release|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.Build.0 = Release|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.Build.0 = Release|Win32
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE
EndGlobalSection
EndGlobal

Microsoft Visual Studio Solution File, Format Version 12.00
# Visual Studio 15
VisualStudioVersion = 15.0.27130.2027
MinimumVisualStudioVersion = 10.0.40219.1
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}"
ProjectSection(ProjectDependencies) = postProject
{5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
EndProjectSection
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_shared", "panda_shared\panda_shared.vcxitems", "{0C843279-68C7-4679-AE51-9BC463D50D1C}"
EndProject
Global
GlobalSection(SharedMSBuildProjectFiles) = preSolution
panda_shared\panda_shared.vcxitems*{0c843279-68c7-4679-ae51-9bc463d50d1c}*SharedItemsImports = 9
panda_shared\panda_shared.vcxitems*{5528aefb-638d-49af-b9d4-965154e7d531}*SharedItemsImports = 4
panda_shared\panda_shared.vcxitems*{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}*SharedItemsImports = 4
EndGlobalSection
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|x64 = Debug|x64
Debug|x86 = Debug|x86
Release|x64 = Release|x64
Release|x86 = Release|x86
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32
{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32
{5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64
{691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32
{BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32
{7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64
{96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64
{D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE
EndGlobalSection
GlobalSection(ExtensibilityGlobals) = postSolution
SolutionGuid = {8AF3826E-406A-4F1C-BA80-B4D7FD4B52E1}
EndGlobalSection
GlobalSection(Performance) = preSolution
HasPerformanceSessions = true
EndGlobalSection
EndGlobal

@ -55,6 +55,7 @@
<ImportGroup Label="ExtensionSettings">
</ImportGroup>
<ImportGroup Label="Shared">
<Import Project="..\panda_shared\panda_shared.vcxitems" Label="Shared" />
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
@ -151,14 +152,10 @@
</Link>
</ItemDefinitionGroup>
<ItemGroup>
<ClInclude Include="device.h" />
<ClInclude Include="panda.h" />
<ClInclude Include="resource.h" />
<ClInclude Include="stdafx.h" />
<ClInclude Include="targetver.h" />
</ItemGroup>
<ItemGroup>
<ClCompile Include="device.cpp" />
<ClCompile Include="dllmain.cpp">
<CompileAsManaged Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">false</CompileAsManaged>
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
@ -173,7 +170,6 @@
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Release|x64'">
</PrecompiledHeader>
</ClCompile>
<ClCompile Include="panda.cpp" />
<ClCompile Include="stdafx.cpp">
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">Create</PrecompiledHeader>
<PrecompiledHeader Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">Create</PrecompiledHeader>

@ -1,58 +1,43 @@
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<ItemGroup>
<Filter Include="Source Files">
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
<Extensions>cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
</Filter>
<Filter Include="Header Files">
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
<Extensions>h;hh;hpp;hxx;hm;inl;inc;xsd</Extensions>
</Filter>
<Filter Include="Resource Files">
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
</Filter>
</ItemGroup>
<ItemGroup>
<ClInclude Include="stdafx.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="targetver.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="panda.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="device.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="resource.h">
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<ClCompile Include="stdafx.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="panda.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="dllmain.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="device.cpp">
<Filter>Source Files</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ResourceCompile Include="panda.rc">
<Filter>Resource Files</Filter>
</ResourceCompile>
</ItemGroup>
<ItemGroup>
<Image Include="panda.ico">
<Filter>Resource Files</Filter>
</Image>
</ItemGroup>
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<ItemGroup>
<Filter Include="Source Files">
<UniqueIdentifier>{4FC737F1-C7A5-4376-A066-2A32D752A2FF}</UniqueIdentifier>
<Extensions>cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx</Extensions>
</Filter>
<Filter Include="Header Files">
<UniqueIdentifier>{93995380-89BD-4b04-88EB-625FBE52EBFB}</UniqueIdentifier>
<Extensions>h;hh;hpp;hxx;hm;inl;inc;xsd</Extensions>
</Filter>
<Filter Include="Resource Files">
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
</Filter>
</ItemGroup>
<ItemGroup>
<ClInclude Include="stdafx.h">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="resource.h">
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<ClCompile Include="stdafx.cpp">
<Filter>Source Files</Filter>
</ClCompile>
<ClCompile Include="dllmain.cpp">
<Filter>Source Files</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ResourceCompile Include="panda.rc">
<Filter>Resource Files</Filter>
</ResourceCompile>
</ItemGroup>
<ItemGroup>
<Image Include="panda.ico">
<Filter>Resource Files</Filter>
</Image>
</ItemGroup>
</Project>

@ -1,7 +1,7 @@
#include "stdafx.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "Timer.h"
#include "ECUsim DLL\ECUsim.h"
#include "TestHelpers.h"

@ -2,7 +2,7 @@
#include "TestHelpers.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "Timer.h"
using namespace Microsoft::VisualStudio::CppUnitTestFramework;

@ -1,7 +1,7 @@
#pragma once
#include "stdafx.h"
#include "pandaJ2534DLL/J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
using namespace Microsoft::VisualStudio::CppUnitTestFramework;

@ -1,7 +1,7 @@
#include "stdafx.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "Timer.h"
#include "ECUsim DLL\ECUsim.h"
#include "TestHelpers.h"

@ -115,9 +115,6 @@
<ProjectReference Include="..\pandaJ2534DLL\pandaJ2534DLL.vcxproj">
<Project>{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}</Project>
</ProjectReference>
<ProjectReference Include="..\panda\panda.vcxproj">
<Project>{5528aefb-638d-49af-b9d4-965154e7d531}</Project>
</ProjectReference>
</ItemGroup>
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
<ImportGroup Label="ExtensionTargets">

@ -1,5 +1,5 @@
#include "stdafx.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "TestHelpers.h"
#include <tchar.h>

@ -33,6 +33,7 @@ long J2534Connection::PassThruReadMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMs
messageRxBuff_mutex.unlock();
if (Timeout == 0)
break;
Sleep(2);
continue;
}
@ -146,16 +147,35 @@ long J2534Connection::PassThruIoctl(unsigned long IoctlID, void *pInput, void *p
return STATUS_NOERROR;
}
long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return STATUS_NOERROR; }
long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return STATUS_NOERROR; }
long J2534Connection::clearTXBuff() { return STATUS_NOERROR; }
long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return ERR_FAILED; }
long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return ERR_FAILED; }
long J2534Connection::clearTXBuff() {
if (auto panda_ps = this->panda_dev.lock()) {
synchronized(staged_writes_lock) {
this->txbuff = {};
panda_ps->panda->can_clear(panda::PANDA_CAN1_TX);
}
}
return STATUS_NOERROR;
}
long J2534Connection::clearRXBuff() {
synchronized(messageRxBuff_mutex) {
this->messageRxBuff = {};
if (auto panda_ps = this->panda_dev.lock()) {
synchronized(messageRxBuff_mutex) {
this->messageRxBuff = {};
panda_ps->panda->can_clear(panda::PANDA_CAN_RX);
}
}
return STATUS_NOERROR;
}
long J2534Connection::clearPeriodicMsgs() { return STATUS_NOERROR; }
long J2534Connection::clearPeriodicMsgs() {
for (int i = 0; i < this->periodicMessages.size(); i++) {
if (periodicMessages[i] == nullptr) continue;
this->periodicMessages[i]->cancel();
this->periodicMessages[i] = nullptr;
}
return STATUS_NOERROR;
}
long J2534Connection::clearMsgFilters() {
for (auto& filter : this->filters) filter = nullptr;
return STATUS_NOERROR;
@ -202,6 +222,7 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo
switch (Parameter) {
case DATA_RATE: // 5-500000
this->setBaud(Value);
break;
case LOOPBACK: // 0 (OFF), 1 (ON) [0]
this->loopback = (Value != 0);
break;
@ -236,6 +257,11 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo
default:
printf("Got unknown SET code %X\n", Parameter);
}
// reserved parameters usually mean special equiptment is required
if (Parameter >= 0x20) {
throw ERR_NOT_SUPPORTED;
}
}
unsigned long J2534Connection::processIOCTLGetConfig(unsigned long Parameter) {

@ -1,5 +1,5 @@
#pragma once
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "J2534_v0404.h"
#include "synchronize.h"
#include "J2534Frame.h"

@ -1,7 +1,7 @@
#pragma once
#include "J2534Connection.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#define val_is_29bit(num) check_bmask(num, CAN_29BIT_ID)

@ -43,7 +43,7 @@ std::shared_ptr<MessageTx> J2534Connection_ISO15765::parseMessageTx(PASSTHRU_MSG
void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) {
if (msg.ProtocolID != CAN) return;
int fid = get_matching_in_fc_filter_id(msg);
int fid = get_matching_in_fc_filter_id(msg, this->Flags);
if (fid == -1) return;
auto filter = this->filters[fid];
@ -136,6 +136,9 @@ void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) {
if (flowfilter.size() > 4)
flowstrlresp += flowfilter[4];
flowstrlresp += std::string("\x30\x00\x00", 3);
if (check_bmask(filter->flags, ISO15765_FRAME_PAD)) {
flowstrlresp += std::string(8 - flowstrlresp.size(), '\x00');
}
if (auto panda_dev_sp = this->panda_dev.lock()) {
panda_dev_sp->panda->can_send(flow_addr, val_is_29bit(msg.RxStatus), (const uint8_t *)flowstrlresp.c_str(), (uint8_t)flowstrlresp.size(), panda::PANDA_CAN1);

@ -25,7 +25,7 @@ public:
int get_matching_out_fc_filter_id(const std::string & msgdata, unsigned long flags, unsigned long flagmask);
int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask = CAN_29BIT_ID);
int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask);
virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg);

@ -1,6 +1,6 @@
#pragma once
#include "J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
/*A move convenient container for J2534 Messages than the static buffer provided by default.*/
class J2534Frame {
@ -10,7 +10,7 @@ public:
J2534Frame(const panda::PANDA_CAN_MSG& msg_in) {
ProtocolID = CAN;
ExtraDataIndex = 0;
ExtraDataIndex = msg_in.len + 4;
Data.reserve(msg_in.len + 4);
Data += msg_in.addr >> 24;
Data += (msg_in.addr >> 16) & 0xFF;

@ -95,7 +95,7 @@ BOOL MessageTx_ISO15765::checkTxReceipt(J2534Frame frame) {
J2534Frame outframe(ISO15765);
outframe.Timestamp = frame.Timestamp;
outframe.RxStatus = TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID));
outframe.RxStatus = TX_MSG_TYPE | TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID));
outframe.Data = frame.Data.substr(0, addressLength());
conn_sp->addMsgToRxQueue(outframe);

@ -8,11 +8,15 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr<panda::Panda> new_panda) : tx
this->panda->set_esp_power(FALSE);
this->panda->set_safety_mode(panda::SAFETY_ALLOUTPUT);
this->panda->set_can_loopback(FALSE);
this->panda->set_alt_setting(1);
this->panda->set_alt_setting(0);
DWORD canListenThreadID;
this->thread_kill_event = CreateEvent(NULL, TRUE, FALSE, NULL);
this->can_thread_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID);
DWORD canListenThreadID;
this->can_recv_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID);
DWORD canProcessThreadID;
this->can_process_handle = CreateThread(NULL, 0, _can_process_threadBootstrap, (LPVOID)this, 0, &canProcessThreadID);
DWORD flowControlSendThreadID;
this->flow_control_wakeup_event = CreateEvent(NULL, TRUE, FALSE, NULL);
@ -21,8 +25,11 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr<panda::Panda> new_panda) : tx
PandaJ2534Device::~PandaJ2534Device() {
SetEvent(this->thread_kill_event);
DWORD res = WaitForSingleObject(this->can_thread_handle, INFINITE);
CloseHandle(this->can_thread_handle);
DWORD res = WaitForSingleObject(this->can_recv_handle, INFINITE);
CloseHandle(this->can_recv_handle);
res = WaitForSingleObject(this->can_process_handle, INFINITE);
CloseHandle(this->can_process_handle);
res = WaitForSingleObject(this->flow_control_thread_handle, INFINITE);
CloseHandle(this->flow_control_thread_handle);
@ -67,11 +74,28 @@ DWORD PandaJ2534Device::addChannel(std::shared_ptr<J2534Connection>& conn, unsig
}
DWORD PandaJ2534Device::can_recv_thread() {
DWORD err = TRUE;
while (err) {
std::vector<panda::PANDA_CAN_MSG> msg_recv;
err = this->panda->can_recv_async(this->thread_kill_event, msg_recv);
for (auto msg_in : msg_recv) {
this->panda->can_clear(panda::PANDA_CAN_RX);
this->panda->can_rx_q_push(this->thread_kill_event);
return 0;
}
DWORD PandaJ2534Device::can_process_thread() {
panda::PANDA_CAN_MSG msg_recv[CAN_RX_MSG_LEN];
while (true) {
if (!WaitForSingleObject(this->thread_kill_event, 0)) {
break;
}
int count = 0;
this->panda->can_rx_q_pop(msg_recv, count);
if (count == 0) {
continue;
}
for (int i = 0; i < count; i++) {
auto msg_in = msg_recv[i];
J2534Frame msg_out(msg_in);
if (msg_in.is_receipt) {

@ -5,7 +5,7 @@
#include <set>
#include <chrono>
#include "J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "synchronize.h"
#include "Action.h"
#include "MessageTx.h"
@ -55,12 +55,18 @@ public:
private:
HANDLE thread_kill_event;
HANDLE can_thread_handle;
HANDLE can_recv_handle;
static DWORD WINAPI _can_recv_threadBootstrap(LPVOID This) {
return ((PandaJ2534Device*)This)->can_recv_thread();
}
DWORD can_recv_thread();
HANDLE can_process_handle;
static DWORD WINAPI _can_process_threadBootstrap(LPVOID This) {
return ((PandaJ2534Device*)This)->can_process_thread();
}
DWORD can_process_thread();
HANDLE flow_control_wakeup_event;
HANDLE flow_control_thread_handle;
static DWORD WINAPI _msg_tx_threadBootstrap(LPVOID This) {

@ -5,7 +5,7 @@
#include "stdafx.h"
#include "J2534_v0404.h"
#include "panda/panda.h"
#include "panda_shared/panda.h"
#include "J2534Connection.h"
#include "J2534Connection_CAN.h"
#include "J2534Connection_ISO15765.h"
@ -57,7 +57,7 @@ long ret_code(long code) {
return code;
}
#define EXTRACT_DID(CID) (CID & 0xFFFF)
#define EXTRACT_DID(CID) ((CID & 0xFFFF) - 1)
#define EXTRACT_CID(CID) ((CID >> 16) & 0xFFFF)
long check_valid_DeviceID(unsigned long DeviceID) {
@ -68,7 +68,7 @@ long check_valid_DeviceID(unsigned long DeviceID) {
}
long check_valid_ChannelID(unsigned long ChannelID) {
uint16_t dev_id = EXTRACT_DID(ChannelID);;
uint16_t dev_id = EXTRACT_DID(ChannelID);
uint16_t con_id = EXTRACT_CID(ChannelID);
if (pandas.size() <= dev_id || pandas[dev_id] == nullptr)
@ -117,7 +117,7 @@ PANDAJ2534DLL_API long PTAPI PassThruOpen(void *pName, unsigned long *pDevice
panda_index = pandas.size()-1;
}
*pDeviceID = panda_index;
*pDeviceID = panda_index + 1; // TIS doesn't like it when ID == 0
return ret_code(STATUS_NOERROR);
}
PANDAJ2534DLL_API long PTAPI PassThruClose(unsigned long DeviceID) {
@ -140,14 +140,12 @@ PANDAJ2534DLL_API long PTAPI PassThruConnect(unsigned long DeviceID, unsigned lo
switch (ProtocolID) {
//SW seems to refer to Single Wire. https://www.nxp.com/files-static/training_pdf/20451_BUS_COMM_WBT.pdf
//SW_ protocols may be touched on here: https://www.iso.org/obp/ui/#iso:std:iso:22900:-2:ed-1:v1:en
case J1850VPW: //These protocols are outdated and will not be supported. HDS wants them to not fail to open.
case J1850PWM:
case J1850VPW_PS:
case J1850PWM_PS:
//case J1850VPW: // These protocols are outdated and will not be supported. HDS wants them to not fail to open.
//case J1850PWM: // ^-- it appears HDS no longer needs this, and TIS needs it disabled --^
//case J1850VPW_PS:
//case J1850PWM_PS:
case ISO9141: //This protocol could be implemented if 5 BAUD init support is added to the panda.
case ISO9141_PS:
conn = std::make_shared<J2534Connection>(panda, ProtocolID, Flags, BaudRate);
break;
case ISO14230: //Only supporting Fast init until panda adds support for 5 BAUD init.
case ISO14230_PS:
conn = std::make_shared<J2534Connection>(panda, ProtocolID, Flags, BaudRate);
@ -263,8 +261,7 @@ PANDAJ2534DLL_API long PTAPI PassThruReadVersion(unsigned long DeviceID, char *p
} else {
j2534dll_ver = GetProductAndVersion(pandalib_filename);
}
std::string pandalib_ver = GetProductAndVersion(_T("panda.dll"));
std::string fullver = "(" + j2534dll_ver + "; " + pandalib_ver + ")";
std::string fullver = "(" + j2534dll_ver + ")";
strcpy_s(pDllVersion, 80, fullver.c_str());
strcpy_s(pApiVersion, 80, J2534_APIVER_NOVEMBER_2004);

@ -34,6 +34,7 @@
<ImportGroup Label="ExtensionSettings">
</ImportGroup>
<ImportGroup Label="Shared">
<Import Project="..\panda_shared\panda_shared.vcxitems" Label="Shared" />
</ImportGroup>
<ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
@ -64,7 +65,7 @@
<Link>
<SubSystem>Windows</SubSystem>
<GenerateDebugInformation>true</GenerateDebugInformation>
<AdditionalDependencies>kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib</AdditionalDependencies>
<AdditionalDependencies>kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib</AdditionalDependencies>
</Link>
</ItemDefinitionGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
@ -83,7 +84,7 @@
<EnableCOMDATFolding>true</EnableCOMDATFolding>
<OptimizeReferences>true</OptimizeReferences>
<GenerateDebugInformation>true</GenerateDebugInformation>
<AdditionalDependencies>kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib</AdditionalDependencies>
<AdditionalDependencies>kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib</AdditionalDependencies>
</Link>
</ItemDefinitionGroup>
<ItemGroup>
@ -135,11 +136,6 @@
</ClCompile>
<ClCompile Include="Timer.cpp" />
</ItemGroup>
<ItemGroup>
<ProjectReference Include="..\panda\panda.vcxproj">
<Project>{5528aefb-638d-49af-b9d4-965154e7d531}</Project>
</ProjectReference>
</ItemGroup>
<ItemGroup>
<ResourceCompile Include="pandaJ2534DLL.rc" />
</ItemGroup>

@ -1,5 +1,5 @@
!define J2534_Reg_Path "Software\PassThruSupport.04.04\comma.ai - panda"
!define Install_Name "panda J2534 Drivers"
!define Install_Name "panda J2534 driver"
;NOTE! The panda software requires a VC runtime to be installed in order to work.
;This installer must be bundled with the appropriate runtime installer, and have
@ -21,10 +21,10 @@
Unicode true
# Set the installer display name
Name "panda Driver"
Name "${Install_Name}"
# set the name of the installer
Outfile "panda install.exe"
Outfile "${Install_Name} install.exe"
; The default installation directory
InstallDir $PROGRAMFILES\comma.ai\panda
@ -63,18 +63,19 @@ VIProductVersion "1.0.0.0"
;--------------------------------
; Install Sections
Section "panda driver (required)"
Section "prerequisites"
SectionIn RO
SetOutPath "$INSTDIR"
File "panda.ico"
;If the visual studio version this project is compiled with changes, this section
;must be revisited. The registry key must be changed, and the VS redistributable
;binary must be updated to the VS version used.
ClearErrors
ReadRegStr $0 HKLM ${VCRuntimeRegKey} "Version"
ReadRegStr $0 HKCR ${VCRuntimeRegKey} "Version"
${If} ${Errors}
DetailPrint "Installing Visual Studio C Runtime..."
File "${VCRuntimeSetupPath}\${VCRuntimeSetupFile}"
@ -87,35 +88,22 @@ Section "panda driver (required)"
Delete "$INSTDIR\${VCRuntimeSetupFile}"
;Do the rest of the install
SetOutPath "$INSTDIR\driver"
; SetOutPath "$INSTDIR\driver"
; The inf file works for both 32 and 64 bit.
File "Debug_x86\panda Driver Package\panda.inf"
File "Debug_x86\panda Driver Package\panda.cat"
${DisableX64FSRedirection}
nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"'
${EnableX64FSRedirection}
SetOutPath $SYSDIR
File Release_x86\panda.dll
${If} ${RunningX64}
${DisableX64FSRedirection}
;Note that the x64 VS redistributable is not installed to prevent bloat.
;If you are the rare person who uses the 64 bit raw panda driver, please
;install the correct x64 VS runtime manually.
File Release_x64\panda.dll
${EnableX64FSRedirection}
${EndIf}
; File "Debug_x86\panda Driver Package\panda.inf"
; File "Debug_x86\panda Driver Package\panda.cat"
; ${DisableX64FSRedirection}
; nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"'
; ${EnableX64FSRedirection}
; Write the installation path into the registry
WriteRegStr HKLM "SOFTWARE\panda J2534 Drivers" "Install_Dir" "$INSTDIR"
WriteRegStr HKLM "SOFTWARE\${Install_Name}" "Install_Dir" "$INSTDIR"
; Write the uninstall keys for Windows
;WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" ""
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$SYSDIR\panda.dll",0'
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "panda J2534 Drivers"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" ""
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$INSTDIR\panda.ico",0'
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "${Install_Name}"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "Publisher" "comma.ai"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "UninstallString" '"$INSTDIR\uninstall.exe"'
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "URLInfoAbout" "https://github.com/commaai/panda/"
@ -127,19 +115,6 @@ Section "panda driver (required)"
SectionEnd
Section "panda devel lib/header"
SetOutPath "$INSTDIR\devel"
File panda\panda.h
SetOutPath "$INSTDIR\devel\x86"
File Release_x86\panda.lib
SetOutPath "$INSTDIR\devel\x64"
File Release_x64\panda.lib
SectionEnd
Section "J2534 Driver"
SetOutPath $INSTDIR
@ -165,6 +140,32 @@ Section "J2534 Driver"
SectionEnd
Section /o "Development lib/header"
SetOutPath $SYSDIR
File Release_x86\panda.dll
${If} ${RunningX64}
${DisableX64FSRedirection}
;Note that the x64 VS redistributable is not installed to prevent bloat.
;If you are the rare person who uses the 64 bit raw panda driver, please
;install the correct x64 VS runtime manually.
File Release_x64\panda.dll
${EnableX64FSRedirection}
${EndIf}
SetOutPath "$INSTDIR\devel"
File panda_shared\panda.h
SetOutPath "$INSTDIR\devel\x86"
File Release_x86\panda.lib
SetOutPath "$INSTDIR\devel\x64"
File Release_x64\panda.lib
SectionEnd
;--------------------------------
; Uninstaller
Section "Uninstall"
@ -176,9 +177,9 @@ Section "Uninstall"
; if Microsoft wants these inf files to be removed.
; Consider https://blog.sverrirs.com/2015/12/creating-windows-installer-and.html
; These lines just remove the inf backups.
Delete "$INSTDIR\driver\panda.inf"
Delete "$INSTDIR\driver\panda.cat"
RMDir "$INSTDIR\driver"
; Delete "$INSTDIR\driver\panda.inf"
; Delete "$INSTDIR\driver\panda.cat"
; RMDir "$INSTDIR\driver"
; Remove WinUSB driver library
Delete $SYSDIR\panda.dll
@ -204,6 +205,7 @@ Section "Uninstall"
; Remove files and uninstaller
Delete "$INSTDIR\uninstall.exe"
Delete "$INSTDIR\pandaJ2534_0404_32.dll"
Delete "$INSTDIR\panda.ico"
; Remove directories used
RMDir "$INSTDIR"

@ -1,10 +1,13 @@
#include "stdafx.h"
#include <SetupAPI.h>
#include <Devpkey.h>
#include <unordered_map>
#include <string>
#include <winusb.h>
#include "device.h"
using namespace panda;

@ -4,7 +4,6 @@
//
// Define below GUIDs
//
#include "stdafx.h"
#include <initguid.h>
#include <unordered_map>

@ -1,7 +1,7 @@
// panda.cpp : Defines the exported functions for the DLL application.
//
#include "stdafx.h"
#include "device.h"
#include "panda.h"
@ -13,13 +13,6 @@
using namespace panda;
#pragma pack(1)
typedef struct _PANDA_CAN_MSG_INTERNAL {
uint32_t rir;
uint32_t f2;
uint8_t dat[8];
} PANDA_CAN_MSG_INTERNAL;
Panda::Panda(
WINUSB_INTERFACE_HANDLE WinusbHandle,
HANDLE DeviceHandle,
@ -28,6 +21,7 @@ Panda::Panda(
) : usbh(WinusbHandle), devh(DeviceHandle), devPath(devPath_), sn(sn_) {
printf("CREATED A PANDA %s\n", this->sn.c_str());
this->set_can_loopback(FALSE);
this->set_raw_io(TRUE);
this->set_alt_setting(0);
}
@ -167,7 +161,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) {
this->set_can_loopback(TRUE);
Sleep(20); // Give time for any sent messages to appear in the RX buffer.
this->can_clear(PANDA_CAN_RX);
for (int i = 0; i < 2; i++) {
// send 4 messages becaus can_recv reads 4 messages at a time
for (int i = 0; i < 4; i++) {
printf("Sending PAD %d\n", i);
if (this->can_send(0x7FF, FALSE, {}, 0, PANDA_CAN1) == FALSE) {
auto err = GetLastError();
@ -177,14 +172,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) {
Sleep(10);
//this->can_clear(PANDA_CAN_RX);
std::vector<PANDA_CAN_MSG> msg_recv;
if (alt_setting == 1) {
//Read the messages so they do not contaimnate the real message stream.
auto err = this->can_recv_async(NULL, msg_recv, 1000);
}
else {
msg_recv = this->can_recv();
}
//Read the messages so they do not contaimnate the real message stream.
this->can_recv();
//this->set_can_loopback(FALSE);
this->set_can_loopback(loopback_backup);
@ -203,6 +192,17 @@ UCHAR Panda::get_current_alt_setting() {
return alt_setting;
}
bool Panda::set_raw_io(bool val) {
UCHAR raw_io = val;
if (!WinUsb_SetPipePolicy(this->usbh, 0x81, RAW_IO, sizeof(raw_io), &raw_io)) {
_tprintf(_T(" Error setting usb raw I/O pipe policy %d, Msg: '%s'\n"),
GetLastError(), GetLastErrorAsString().c_str());
return FALSE;
}
return TRUE;
}
PANDA_HEALTH Panda::get_health()
{
WINUSB_SETUP_PACKET SetupPacket;
@ -351,69 +351,85 @@ bool Panda::can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t l
return this->can_send_many(std::vector<PANDA_CAN_MSG>{msg});
}
void Panda::parse_can_recv(std::vector<PANDA_CAN_MSG>& msg_recv, char *buff, int retcount) {
for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i);
PANDA_CAN_MSG in_msg;
in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED);
in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21);
in_msg.recv_time = this->runningTime.getTimePassedUS();
in_msg.recv_time_point = std::chrono::steady_clock::now();
//The timestamp from the device is (in_msg_raw->f2 >> 16),
//but this 16 bit value is a little hard to use. Using a
//timer since the initialization of this device.
in_msg.len = in_msg_raw->f2 & 0xF;
memcpy(in_msg.dat, in_msg_raw->dat, 8);
in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80;
switch ((in_msg_raw->f2 >> 4) & 0x7F) {
case PANDA_CAN1:
in_msg.bus = PANDA_CAN1;
break;
case PANDA_CAN2:
in_msg.bus = PANDA_CAN2;
break;
case PANDA_CAN3:
in_msg.bus = PANDA_CAN3;
break;
default:
in_msg.bus = PANDA_CAN_UNK;
}
msg_recv.push_back(in_msg);
PANDA_CAN_MSG Panda::parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw) {
PANDA_CAN_MSG in_msg;
in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED);
in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21);
in_msg.recv_time = this->runningTime.getTimePassedUS();
in_msg.recv_time_point = std::chrono::steady_clock::now();
//The timestamp from the device is (in_msg_raw->f2 >> 16),
//but this 16 bit value is a little hard to use. Using a
//timer since the initialization of this device.
in_msg.len = in_msg_raw->f2 & 0xF;
memcpy(in_msg.dat, in_msg_raw->dat, 8);
in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80;
switch ((in_msg_raw->f2 >> 4) & 0x7F) {
case PANDA_CAN1:
in_msg.bus = PANDA_CAN1;
break;
case PANDA_CAN2:
in_msg.bus = PANDA_CAN2;
break;
case PANDA_CAN3:
in_msg.bus = PANDA_CAN3;
break;
default:
in_msg.bus = PANDA_CAN_UNK;
}
return in_msg;
}
bool Panda::can_recv_async(HANDLE kill_event, std::vector<PANDA_CAN_MSG>& msg_buff, DWORD timeoutms) {
int retcount;
char buff[sizeof(PANDA_CAN_MSG_INTERNAL) * 4];
bool Panda::can_rx_q_push(HANDLE kill_event, DWORD timeoutms) {
while (1) {
auto w_ptr = this->w_ptr;
auto n_ptr = w_ptr + 1;
if (n_ptr == CAN_RX_QUEUE_LEN) {
n_ptr = 0;
}
// Pause if there is not a slot available in the queue
if (n_ptr == this->r_ptr) {
printf("RX queue full!\n");
Sleep(1);
continue;
}
// Overlapped structure required for async read.
HANDLE m_hReadFinishedEvent = CreateEvent(NULL, TRUE, TRUE, NULL);
OVERLAPPED m_overlappedData;
memset(&m_overlappedData, sizeof(OVERLAPPED), 0);
m_overlappedData.hEvent = m_hReadFinishedEvent;
if (this->can_rx_q[n_ptr].complete) {
// TODO: is ResetEvent() faster?
CloseHandle(this->can_rx_q[n_ptr].complete);
}
HANDLE phSignals[2] = { m_hReadFinishedEvent, kill_event };
// Overlapped structure required for async read.
this->can_rx_q[n_ptr].complete = CreateEvent(NULL, TRUE, TRUE, NULL);
memset(&this->can_rx_q[n_ptr].overlapped, sizeof(OVERLAPPED), 0);
this->can_rx_q[n_ptr].overlapped.hEvent = this->can_rx_q[n_ptr].complete;
this->can_rx_q[n_ptr].error = 0;
if (!WinUsb_ReadPipe(this->usbh, 0x81, (PUCHAR)buff, sizeof(buff), (PULONG)&retcount, &m_overlappedData)) {
// An overlapped read will return true if done, or false with an
// error of ERROR_IO_PENDING if the transfer is still in process.
DWORD dwError = GetLastError();
if (dwError == ERROR_IO_PENDING) {
dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms);
if (!WinUsb_ReadPipe(this->usbh, 0x81, this->can_rx_q[n_ptr].data, sizeof(this->can_rx_q[n_ptr].data), &this->can_rx_q[n_ptr].count, &this->can_rx_q[n_ptr].overlapped)) {
// An overlapped read will return true if done, or false with an
// error of ERROR_IO_PENDING if the transfer is still in process.
this->can_rx_q[n_ptr].error = GetLastError();
}
// Process the pipe read call from the previous invocation of this function
if (this->can_rx_q[w_ptr].error == ERROR_IO_PENDING) {
HANDLE phSignals[2] = { this->can_rx_q[w_ptr].complete, kill_event };
auto dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms);
// Check if packet, timeout (nope), or break
if (dwError == WAIT_OBJECT_0) {
// Signal came from our usb object. Read the returned data.
if (!GetOverlappedResult(this->usbh, &m_overlappedData, (PULONG)&retcount, FALSE)) {
if (!GetOverlappedResult(this->usbh, &this->can_rx_q[w_ptr].overlapped, &this->can_rx_q[w_ptr].count, TRUE)) {
// TODO: handle other error cases better.
dwError = GetLastError();
printf("Got overlap error %d\n", dwError);
return TRUE;
continue;
}
} else {
}
else {
WinUsb_AbortPipe(this->usbh, 0x81);
// Return FALSE to show that the optional signal
@ -422,17 +438,40 @@ bool Panda::can_recv_async(HANDLE kill_event, std::vector<PANDA_CAN_MSG>& msg_bu
if (dwError == (WAIT_OBJECT_0 + 1)) {
return FALSE;
}
return TRUE;
continue;
}
} else { // ERROR_BAD_COMMAND happens when device is unplugged.
}
else if (this->can_rx_q[w_ptr].error != 0) { // ERROR_BAD_COMMAND happens when device is unplugged.
return FALSE;
}
this->w_ptr = n_ptr;
}
parse_can_recv(msg_buff, buff, retcount);
return TRUE;
}
void Panda::can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count) {
count = 0;
// No data left in queue
if (this->r_ptr == this->w_ptr) {
Sleep(1);
return;
}
auto r_ptr = this->r_ptr;
for (int i = 0; i < this->can_rx_q[r_ptr].count; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
auto in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(this->can_rx_q[r_ptr].data + i);
msg_out[count] = parse_can_recv(in_msg_raw);
++count;
}
// Advance read pointer (wrap around if needed)
++r_ptr;
this->r_ptr = (r_ptr == CAN_RX_QUEUE_LEN ? 0 : r_ptr);
}
std::vector<PANDA_CAN_MSG> Panda::can_recv() {
std::vector<PANDA_CAN_MSG> msg_recv;
int retcount;
@ -441,7 +480,11 @@ std::vector<PANDA_CAN_MSG> Panda::can_recv() {
if (this->bulk_read(0x81, buff, sizeof(buff), (PULONG)&retcount, 0) == FALSE)
return msg_recv;
parse_can_recv(msg_recv, buff, retcount);
for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i);
auto in_msg = parse_can_recv(in_msg_raw);
msg_recv.push_back(in_msg);
}
return msg_recv;
}

@ -9,7 +9,7 @@
#ifdef PANDA_EXPORTS
#define PANDA_API __declspec(dllexport)
#else
#define PANDA_API __declspec(dllimport)
#define PANDA_API
#endif
#include <vector>
@ -31,6 +31,8 @@
#endif
#define LIN_MSG_MAX_LEN 10
#define CAN_RX_QUEUE_LEN 10000
#define CAN_RX_MSG_LEN 1000
//template class __declspec(dllexport) std::basic_string<char>;
@ -139,6 +141,7 @@ namespace panda {
std::string get_usb_sn();
bool set_alt_setting(UCHAR alt_setting);
UCHAR get_current_alt_setting();
bool Panda::set_raw_io(bool val);
PANDA_HEALTH get_health();
bool enter_bootloader();
@ -160,9 +163,9 @@ namespace panda {
bool can_send_many(const std::vector<PANDA_CAN_MSG>& can_msgs);
bool can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t len, PANDA_CAN_PORT bus);
void parse_can_recv(std::vector<PANDA_CAN_MSG>& msg_recv, char *buff, int retcount);
bool can_recv_async(HANDLE kill_event, std::vector<PANDA_CAN_MSG>& msg_buff, DWORD timeoutms = INFINITE);
std::vector<PANDA_CAN_MSG> can_recv();
bool can_rx_q_push(HANDLE kill_event, DWORD timeoutms = INFINITE);
void can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count);
bool can_clear(PANDA_CAN_PORT_CLEAR bus);
std::string serial_read(PANDA_SERIAL_PORT port_number);
@ -202,6 +205,23 @@ namespace panda {
ULONG timeout
);
#pragma pack(1)
typedef struct _PANDA_CAN_MSG_INTERNAL {
uint32_t rir;
uint32_t f2;
uint8_t dat[8];
} PANDA_CAN_MSG_INTERNAL;
typedef struct _CAN_RX_PIPE_READ {
unsigned char data[sizeof(PANDA_CAN_MSG_INTERNAL) * CAN_RX_MSG_LEN];
unsigned long count;
OVERLAPPED overlapped;
HANDLE complete;
DWORD error;
} CAN_RX_PIPE_READ;
PANDA_CAN_MSG parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw);
WINUSB_INTERFACE_HANDLE usbh;
HANDLE devh;
tstring devPath;
@ -209,6 +229,9 @@ namespace panda {
bool loopback;
Timer runningTime;
CAN_RX_PIPE_READ can_rx_q[CAN_RX_QUEUE_LEN];
unsigned long w_ptr = 0;
unsigned long r_ptr = 0;
};
}

@ -0,0 +1,25 @@
<?xml version="1.0" encoding="utf-8"?>
<Project xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<PropertyGroup Label="Globals">
<MSBuildAllProjects>$(MSBuildAllProjects);$(MSBuildThisFileFullPath)</MSBuildAllProjects>
<HasSharedItems>true</HasSharedItems>
<ItemsProjectGuid>{0c843279-68c7-4679-ae51-9bc463d50d1c}</ItemsProjectGuid>
</PropertyGroup>
<ItemDefinitionGroup>
<ClCompile>
<AdditionalIncludeDirectories>%(AdditionalIncludeDirectories);$(MSBuildThisFileDirectory)</AdditionalIncludeDirectories>
</ClCompile>
</ItemDefinitionGroup>
<ItemGroup>
<ProjectCapability Include="SourceItemsFromImports" />
</ItemGroup>
<ItemGroup>
<ClCompile Include="$(MSBuildThisFileDirectory)device.cpp" />
<ClCompile Include="$(MSBuildThisFileDirectory)panda.cpp" />
</ItemGroup>
<ItemGroup>
<ClInclude Include="$(MSBuildThisFileDirectory)device.h" />
<ClInclude Include="$(MSBuildThisFileDirectory)panda.h" />
<ClInclude Include="$(MSBuildThisFileDirectory)targetver.h" />
</ItemGroup>
</Project>

@ -0,0 +1,25 @@
# How to use can_bit_transition.py to reverse engineer a single bit field
Let's say our goal is to find a brake pedal signal (caused by your foot pressing the brake pedal vs adaptive cruise control braking).
The following process will allow you to quickly find bits that are always 0 during a period of time (when you know you were not pressing the brake with your foot) and always 1 in a different period of time (when you know you were pressing the brake with your foot).
Open up a drive in cabana where you can find a place you used the brake pedal and another place where you did not use the brake pedal (and you can identify when you were on the brake pedal and when you were not). You may want to go out for a drive and put something in front of the camera after you put your foot on the brake and take it away before you take your foot off the brake so you can easily identify exactly when you had your foot on the brake based on the video in cabana. This is critical because this script needs the brake signal to always be high the entire time for one of the time frames. A 10 second time frame worked well for me.
I found a drive where I knew I was not pressing the brake between timestamp 50.0 thru 65.0 and I was pressing the brake between timestamp 69.0 thru 79.0. Determine what the timestamps are in cabana by plotting any message and putting your mouse over the plot at the location you want to discover the timestamp. The tool tip on mouse hover has the format: timestamp: value
Now download the log from cabana (Save Log button) and run the script passing in the timestamps
(replace csv file name with cabana log you downloaded and time ranges with your own)
```
./can_bit_transition.py ./honda_crv_ex_2017_can-1520354796875.csv 50.0-65.0 69.0-79.0
```
The script will output bits that were always low in the first time range and always high in the second time range (and vice versa)
```
id 17c 0 -> 1 at byte 4 bitmask 1
id 17c 0 -> 1 at byte 6 bitmask 32
id 221 1 -> 0 at byte 0 bitmask 4
id 1be 0 -> 1 at byte 0 bitmask 16
```
Now I go back to cabana and graph the above bits by searching for the message by id, double clicking on the appropriate bit, and then selecting "show plot". I already knew that message id 0x17c is both user brake and adaptive cruise control braking combined, so I plotted one of those signals along side 0x221 and 0x1be. By replaying a drive I could see that 0x221 was not a brake signal (when high at random times that did not correspond to braking). Next I looked at 0x1be and I found it was the brake pedal signal I was looking for (went high whenever I pressed the brake pedal and did not go high when adaptive cruise control was braking).

@ -0,0 +1,87 @@
#!/usr/bin/env python
import binascii
import csv
import sys
class Message():
"""Details about a specific message ID."""
def __init__(self, message_id):
self.message_id = message_id
self.ones = [0] * 8 # bit set if 1 is always seen
self.zeros = [0] * 8 # bit set if 0 is always seen
def printBitDiff(self, other):
"""Prints bits that transition from always zero to always 1 and vice versa."""
for i in xrange(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)
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)
class Info():
"""A collection of Messages."""
def __init__(self):
self.messages = {} # keyed by MessageID
def load(self, filename, start, end):
"""Given a CSV file, adds information about message IDs and their values."""
with open(filename, 'rb') as input:
reader = csv.reader(input)
next(reader, None) # skip the CSV header
for row in reader:
if not len(row): continue
time = float(row[0])
bus = int(row[2])
if time < start or bus > 127:
continue
elif time > end:
break
if row[1].startswith('0x'):
message_id = row[1][2:] # remove leading '0x'
else:
message_id = hex(int(row[1]))[2:] # old message IDs are in decimal
if row[3].startswith('0x'):
data = row[3][2:] # remove leading '0x'
else:
data = row[3]
new_message = False
if message_id not in self.messages:
self.messages[message_id] = Message(message_id)
new_message = True
message = self.messages[message_id]
bytes = bytearray.fromhex(data)
for i in xrange(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.
zeros = (~int(bytes[i])) & 0xff
message.zeros[i] = zeros if new_message else message.zeros[i] & zeros
def PrintUnique(log_file, low_range, high_range):
# find messages with bits that are always low
start, end = 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('-'))
high = Info()
high.load(log_file, start, end)
# print messages that go from low to high
found = False
for message_id in high.messages:
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 __name__ == "__main__":
if len(sys.argv) < 4:
print 'Usage:\n%s log.csv <low-start>-<low-end> <high-start>-<high-end>' % sys.argv[0]
sys.exit(0)
PrintUnique(sys.argv[1], sys.argv[2], sys.argv[3])

@ -1,85 +0,0 @@
DEBUG = False
def msg(x):
if DEBUG:
print "S:",x.encode("hex")
if len(x) <= 7:
ret = chr(len(x)) + x
else:
assert False
return ret.ljust(8, "\x00")
kmsgs = []
def recv(panda, cnt, addr, nbus):
global kmsgs
ret = []
while len(ret) < cnt:
kmsgs += panda.can_recv()
nmsgs = []
for ids, ts, dat, bus in kmsgs:
if ids == addr and bus == nbus and len(ret) < cnt:
ret.append(dat)
else:
# leave around
nmsgs.append((ids, ts, dat, bus))
kmsgs = nmsgs[-256:]
return map(str, ret)
def isotp_send(panda, x, addr, bus=0, recvaddr=None):
if recvaddr is None:
recvaddr = addr+8
if len(x) <= 7:
panda.can_send(addr, msg(x), bus)
else:
ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6]
x = x[6:]
idx = 1
sends = []
while len(x) > 0:
sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00")))
x = x[7:]
idx += 1
# actually send
panda.can_send(addr, ss, bus)
rr = recv(panda, 1, recvaddr, bus)[0]
panda.can_send_many([(addr, None, s, 0) for s in sends])
def isotp_recv(panda, addr, bus=0, sendaddr=None):
msg = recv(panda, 1, addr, bus)[0]
if sendaddr is None:
sendaddr = addr-8
if ord(msg[0])&0xf0 == 0x10:
# first
tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1])
dat = msg[2:]
# 0 block size?
CONTINUE = "\x30" + "\x00"*7
panda.can_send(sendaddr, CONTINUE, bus)
idx = 1
for mm in recv(panda, (tlen-len(dat) + 7)/8, addr, bus):
assert ord(mm[0]) == (0x20 | idx)
dat += mm[1:]
idx += 1
elif ord(msg[0])&0xf0 == 0x00:
# single
tlen = ord(msg[0]) & 0xf
dat = msg[1:]
else:
assert False
dat = dat[0:tlen]
if DEBUG:
print "R:",dat.encode("hex")
return dat

@ -13,8 +13,9 @@ 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.6'
__version__ = '0.0.7'
BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")
@ -104,6 +105,7 @@ class Panda(object):
SAFETY_NOOUTPUT = 0
SAFETY_HONDA = 1
SAFETY_TOYOTA = 2
SAFETY_HONDA_BOSCH = 4
SAFETY_TOYOTA_NOLIMITS = 0x1336
SAFETY_ALLOUTPUT = 0x1337
SAFETY_ELM327 = 0xE327
@ -181,27 +183,58 @@ class Panda(object):
except Exception:
pass
if not enter_bootloader:
self.close()
time.sleep(1.0)
success = False
# wait up to 15 seconds
for i in range(0, 15):
self.reconnect()
def reconnect(self):
self.close()
time.sleep(1.0)
success = False
# wait up to 15 seconds
for i in range(0, 15):
try:
self.connect()
success = True
break
except Exception:
print("reconnecting is taking %d seconds..." % (i+1))
try:
self.connect()
success = True
break
dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial))
dfu.recover()
except Exception:
print("reconnecting is taking %d seconds..." % (i+1))
try:
dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial))
dfu.recover()
except Exception:
pass
time.sleep(1.0)
if not success:
raise Exception("reset failed")
pass
time.sleep(1.0)
if not success:
raise Exception("reconnect failed")
@staticmethod
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"
# unlock flash
print("flash: unlocking")
handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'')
def flash(self, fn=None, code=None):
# erase sectors 1 and 2
print("flash: erasing")
handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'')
handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'')
# flash over EP2
STEP = 0x10
print("flash: flashing")
for i in range(0, len(code), STEP):
handle.bulkWrite(2, code[i:i+STEP])
# reset
print("flash: resetting")
try:
handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'')
except Exception:
pass
def flash(self, fn=None, code=None, reconnect=True):
if not self.bootstub:
self.reset(enter_bootstub=True)
assert(self.bootstub)
@ -224,28 +257,12 @@ class Panda(object):
# get version
print("flash: version is "+self.get_version())
# confirm flasher is present
fr = self._handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc)
assert fr[4:8] == "\xde\xad\xd0\x0d"
# unlock flash
print("flash: unlocking")
self._handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'')
# erase sectors 1 and 2
print("flash: erasing")
self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'')
self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'')
# flash over EP2
STEP = 0x10
print("flash: flashing")
for i in range(0, len(code), STEP):
self._handle.bulkWrite(2, code[i:i+STEP])
# do flash
Panda.flash_static(self._handle, code)
# reset
print("flash: resetting")
self.reset()
# reconnect
if reconnect:
self.reconnect()
def recover(self):
self.reset(enter_bootloader=True)
@ -315,6 +332,10 @@ class Panda(object):
def get_version(self):
return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40)
def is_grey(self):
ret = self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40)
return ret == "\x01"
def get_serial(self):
dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20)
hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4]
@ -420,6 +441,14 @@ class Panda(object):
"""
self._handle.controlWrite(Panda.REQUEST_OUT, 0xf1, bus, 0, b'')
# ******************* isotp *******************
def isotp_send(self, addr, dat, bus, recvaddr=None, subaddr=None):
return isotp_send(self, dat, addr, bus, recvaddr, subaddr)
def isotp_recv(self, addr, bus=0, sendaddr=None, subaddr=None):
return isotp_recv(self, addr, bus, sendaddr, subaddr)
# ******************* serial *******************
def serial_read(self, port_number):
@ -451,7 +480,11 @@ class Panda(object):
# pulse low for wakeup
def kline_wakeup(self):
if DEBUG:
print("kline wakeup...")
self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 0, 0, b'')
if DEBUG:
print("kline wakeup done")
def kline_drain(self, bus=2):
# drain buffer
@ -460,19 +493,25 @@ class Panda(object):
ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40)
if len(ret) == 0:
break
elif DEBUG:
print("kline drain: "+str(ret).encode("hex"))
bret += ret
return bytes(bret)
def kline_ll_recv(self, cnt, bus=2):
echo = bytearray()
while len(echo) != cnt:
echo += self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))
return echo
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"))
echo += ret
return str(echo)
def kline_send(self, x, bus=2, checksum=True):
def get_checksum(dat):
result = 0
result += sum(map(ord, dat)) if isinstance(b'dat', str) else sum(dat)
result = -result
return struct.pack("B", result % 0x100)
self.kline_drain(bus=bus)
@ -480,6 +519,8 @@ class Panda(object):
x += get_checksum(x)
for i in range(0, len(x), 0xf):
ts = x[i:i+0xf]
if DEBUG:
print("kline send: "+ts.encode("hex"))
self._handle.bulkWrite(2, chr(bus).encode()+ts)
echo = self.kline_ll_recv(len(ts), bus=bus)
if echo != ts:

@ -0,0 +1,135 @@
DEBUG = False
def msg(x):
if DEBUG:
print "S:",x.encode("hex")
if len(x) <= 7:
ret = chr(len(x)) + x
else:
assert False
return ret.ljust(8, "\x00")
kmsgs = []
def recv(panda, cnt, addr, nbus):
global kmsgs
ret = []
while len(ret) < cnt:
kmsgs += panda.can_recv()
nmsgs = []
for ids, ts, dat, bus in kmsgs:
if ids == addr and bus == nbus and len(ret) < cnt:
ret.append(dat)
else:
# leave around
nmsgs.append((ids, ts, dat, bus))
kmsgs = nmsgs[-256:]
return map(str, 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
if ord(msg[1])&0xf0 == 0x10:
# first
tlen = ((ord(msg[1]) & 0xf) << 8) | ord(msg[2])
dat = msg[3:]
# 0 block size?
CONTINUE = chr(subaddr) + "\x30" + "\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)
dat += mm[2:]
idx += 1
elif ord(msg[1])&0xf0 == 0x00:
# single
tlen = ord(msg[1]) & 0xf
dat = msg[2:]
else:
print msg.encode("hex")
assert False
return dat[0:tlen]
# **** import below this line ****
def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None):
if recvaddr is None:
recvaddr = addr+8
if len(x) <= 7 and subaddr is None:
panda.can_send(addr, msg(x), bus)
elif len(x) <= 6 and subaddr is not 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]
x = x[5:]
else:
ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6]
x = x[6:]
idx = 1
sends = []
while len(x) > 0:
if subaddr:
sends.append(((chr(subaddr) + chr(0x20 + (idx&0xF)) + x[0:6]).ljust(8, "\x00")))
x = x[6:]
else:
sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\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:
for s in sends[:-1]:
panda.can_send(addr, s, 0)
rr = recv(panda, 1, recvaddr, bus)[0]
panda.can_send(addr, sends[-1], 0)
else:
panda.can_send_many([(addr, None, s, 0) for s in sends])
def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None):
if sendaddr is None:
sendaddr = addr-8
if subaddr is not None:
dat = isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr)
else:
msg = recv(panda, 1, addr, bus)[0]
if ord(msg[0])&0xf0 == 0x10:
# first
tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1])
dat = msg[2:]
# 0 block size?
CONTINUE = "\x30" + "\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)
dat += mm[1:]
idx += 1
elif ord(msg[0])&0xf0 == 0x00:
# single
tlen = ord(msg[0]) & 0xf
dat = msg[1:]
else:
assert False
dat = dat[0:tlen]
if DEBUG:
print "R:",dat.encode("hex")
return dat

@ -3,6 +3,7 @@ import sys
import time
import random
import subprocess
import requests
from panda import Panda
from nose.tools import timed, assert_equal, assert_less, assert_greater
@ -25,27 +26,46 @@ def connect_wifi():
assert(dongle_id.isalnum())
_connect_wifi(dongle_id, pw)
def _connect_wifi(dongle_id, pw):
def _connect_wifi(dongle_id, pw, insecure_okay=False):
ssid = str("panda-" + dongle_id)
print("WIFI: connecting to %s" % ssid)
if sys.platform == "darwin":
os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw))
else:
cnt = 0
MAX_TRIES = 10
while cnt < MAX_TRIES:
print "WIFI: scanning %d" % cnt
os.system("nmcli device wifi rescan")
wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n"))
if len(wifi_scan) != 0:
while 1:
if sys.platform == "darwin":
os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw))
else:
cnt = 0
MAX_TRIES = 10
while cnt < MAX_TRIES:
print "WIFI: scanning %d" % cnt
if os.system("ifconfig | grep wlp3s0") == 0:
os.system("sudo iwlist wlp3s0 scanning > /dev/null")
os.system("nmcli device wifi rescan")
wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n"))
if len(wifi_scan) != 0:
break
time.sleep(0.1)
# MAX_TRIES tries, ~10 seconds max
cnt += 1
assert cnt < MAX_TRIES
if "-pair" in wifi_scan[0]:
os.system("nmcli d wifi connect %s-pair" % (ssid))
if insecure_okay:
break
# fetch webpage
print "connecting to insecure network to secure"
r = requests.get("http://192.168.0.10/")
assert r.status_code==200
print "securing"
try:
r = requests.get("http://192.168.0.10/secure", timeout=0.01)
except requests.exceptions.Timeout:
pass
else:
os.system("nmcli d wifi connect %s password %s" % (ssid, pw))
break
time.sleep(0.1)
# MAX_TRIES tries, ~10 seconds max
cnt += 1
assert cnt < MAX_TRIES
os.system("nmcli d wifi connect %s password %s" % (ssid, pw))
# TODO: confirm that it's connected to the right panda

@ -4,6 +4,7 @@ import os
import sys
import time
from collections import defaultdict
import binascii
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), ".."))
from panda import Panda
@ -14,6 +15,7 @@ def sec_since_boot():
def can_printer():
p = Panda()
p.set_safety_mode(0x1337)
start = sec_since_boot()
lp = sec_since_boot()
@ -28,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: x[-1].encode("hex"), msgs.values()))):
for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))):
dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v)
print(dd)
lp = sec_since_boot()

@ -0,0 +1,76 @@
#!/usr/bin/env python
import sys
import time
import struct
import argparse
import signal
from panda import Panda
class CanHandle(object):
def __init__(self, p):
self.p = p
def transact(self, dat):
#print "W:",dat.encode("hex")
self.p.isotp_send(1, dat, 0, recvaddr=2)
def _handle_timeout(signum, frame):
# will happen on reset
raise Exception("timeout")
signal.signal(signal.SIGALRM, _handle_timeout)
signal.alarm(1)
try:
ret = self.p.isotp_recv(2, 0, sendaddr=1)
finally:
signal.alarm(0)
#print "R:",ret.encode("hex")
return ret
def controlWrite(self, request_type, request, value, index, data, timeout=0):
# ignore data in reply, panda doesn't use it
return self.controlRead(request_type, request, value, index, 0, timeout)
def controlRead(self, request_type, request, value, index, length, timeout=0):
dat = struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length)
return self.transact(dat)
def bulkWrite(self, endpoint, data, timeout=0):
if len(data) > 0x10:
raise ValueError("Data must not be longer than 0x10")
dat = struct.pack("HH", endpoint, len(data))+data
return self.transact(dat)
def bulkRead(self, endpoint, length, timeout=0):
dat = struct.pack("HH", endpoint, 0)
return self.transact(dat)
if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Flash pedal over can')
parser.add_argument('--recover', action='store_true')
parser.add_argument("fn", type=str, nargs='?', help="flash file")
args = parser.parse_args()
p = Panda()
p.set_safety_mode(0x1337)
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)
exit(0)
else:
p.can_send(0x200, "\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()
Panda.flash_static(CanHandle(p), code)
print "can flash done"

@ -0,0 +1,29 @@
#!/usr/bin/env python
from panda import Panda
from hexdump import hexdump
DEBUG = False
if __name__ == "__main__":
p = Panda()
len = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1)
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]))
hexdump("".join(map(chr, dat)))
ms_vendor_code = dat[16]
if DEBUG: print 'MS_VENDOR_CODE: {}'.format(hex(len[0]))
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]))
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'
len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1)
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)))

@ -21,7 +21,7 @@ if __name__ == "__main__":
t2 = time.time()
print("100 requests took %.2f ms" % ((t2-t1)*1000))
p.set_controls_allowed(True)
p.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
a = 0
while True:

@ -0,0 +1,125 @@
#!/usr/bin/env python
from __future__ import print_function
import os
import sys
import time
import random
import argparse
from hexdump import hexdump
from itertools import permutations
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), ".."))
from panda import Panda
def get_test_string():
return b"test"+os.urandom(10)
def run_test(sleep_duration):
pandas = Panda.list()
print(pandas)
if len(pandas) == 0:
print("NO PANDAS")
assert False
if len(pandas) == 1:
# if we only have one on USB, assume the other is on wifi
pandas.append("WIFI")
run_test_w_pandas(pandas, sleep_duration)
def run_test_w_pandas(pandas, sleep_duration):
h = list(map(lambda x: Panda(x), 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):
print("***************** TESTING", ho)
panda0, panda1 = h[ho[0]], h[ho[1]]
if(panda0._serial == "WIFI"):
print(" *** Can not send can data over wifi panda. Skipping! ***")
continue
# **** test health packet ****
print("health", ho[0], h[ho[0]].health())
# **** test K/L line loopback ****
for bus in [2,3]:
# flush the output
h[ho[1]].kline_drain(bus=bus)
# send the characters
st = get_test_string()
st = b"\xaa"+chr(len(st)+3).encode()+st
h[ho[0]].kline_send(st, bus=bus, checksum=False)
# check for receive
ret = h[ho[1]].kline_drain(bus=bus)
print("ST Data:")
hexdump(st)
print("RET Data:")
hexdump(ret)
assert st == ret
print("K/L pass", bus, ho, "\n")
time.sleep(sleep_duration)
# **** test can line loopback ****
# for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]:
for bus, gmlan in [(0, None), (1, None)]:
print("\ntest can", bus)
# flush
cans_echo = panda0.can_recv()
cans_loop = panda1.can_recv()
if gmlan is not None:
panda0.set_gmlan(gmlan, bus)
panda1.set_gmlan(gmlan, bus)
# send the characters
# pick addresses high enough to not conflict with honda code
at = random.randint(1024, 2000)
st = get_test_string()[0:8]
panda0.can_send(at, st, bus)
time.sleep(0.1)
# check for receive
cans_echo = panda0.can_recv()
cans_loop = panda1.can_recv()
print("Bus", bus, "echo", cans_echo, "loop", cans_loop)
assert len(cans_echo) == 1
assert len(cans_loop) == 1
assert cans_echo[0][0] == at
assert cans_loop[0][0] == at
assert cans_echo[0][2] == st
assert cans_loop[0][2] == st
assert cans_echo[0][3] == 0x80 | bus
if cans_loop[0][3] != bus:
print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3]))
assert cans_loop[0][3] == bus
print("CAN pass", bus, ho)
time.sleep(sleep_duration)
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("-n", type=int, help="Number of test iterations to run")
parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0)
args = parser.parse_args()
if args.n is None:
while True:
run_test(sleep_duration=args.sleep)
else:
for i in range(args.n):
run_test(sleep_duration=args.sleep)
Loading…
Cancel
Save