mirror of https://github.com/commaai/panda.git
commit
311d133288
|
@ -33,6 +33,11 @@ dfu:
|
|||
$(DFU_UTIL) -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||
$(DFU_UTIL) --reset-stm32 -a 0 -s 0x08000000
|
||||
|
||||
dfu_recover:
|
||||
$(DFU_UTIL) -a 0 -s 0x08000000 -D obj/bootstub.$(PROJ_NAME).bin
|
||||
$(DFU_UTIL) -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||
$(DFU_UTIL) --reset-stm32 -a 0 -s 0x08000000
|
||||
|
||||
bootstub: obj/bootstub.$(PROJ_NAME).bin
|
||||
./tools/enter_download_mode.py
|
||||
$(DFU_UTIL) -a 0 -s 0x08000000 -D obj/bootstub.$(PROJ_NAME).bin
|
||||
|
@ -62,7 +67,7 @@ endif
|
|||
obj/cert.h: ../crypto/getcertheader.py
|
||||
../crypto/getcertheader.py ../certs/debug.pub ../certs/release.pub > $@
|
||||
|
||||
obj/%.$(PROJ_NAME).o: %.c obj/cert.h obj/gitversion.h
|
||||
obj/%.$(PROJ_NAME).o: %.c obj/cert.h obj/gitversion.h config.h
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/%.$(PROJ_NAME).o: ../crypto/%.c
|
||||
|
@ -71,13 +76,13 @@ obj/%.$(PROJ_NAME).o: ../crypto/%.c
|
|||
obj/$(STARTUP_FILE).o: $(STARTUP_FILE).s
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o obj/early.$(PROJ_NAME).o
|
||||
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o obj/early.$(PROJ_NAME).o obj/llgpio.$(PROJ_NAME).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.$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/bootstub.$(PROJ_NAME).o obj/sha.$(PROJ_NAME).o obj/rsa.$(PROJ_NAME).o obj/early.$(PROJ_NAME).o
|
||||
obj/bootstub.$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/bootstub.$(PROJ_NAME).o obj/sha.$(PROJ_NAME).o obj/rsa.$(PROJ_NAME).o obj/early.$(PROJ_NAME).o obj/llgpio.$(PROJ_NAME).o
|
||||
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
|
||||
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
|
||||
|
||||
|
|
|
@ -99,4 +99,3 @@ int can_cksum(uint8_t *dat, int len, int addr, int idx) {
|
|||
s = 8-s;
|
||||
return s&0xF;
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,23 @@
|
|||
#ifndef PANDA_CONFIG_H
|
||||
#define PANDA_CONFIG_H
|
||||
|
||||
//#define DEBUG
|
||||
//#define DEBUG_USB
|
||||
//#define CAN_LOOPBACK_MODE
|
||||
|
||||
#ifdef STM32F4
|
||||
#define PANDA
|
||||
#include "stm32f4xx.h"
|
||||
#else
|
||||
#include "stm32f2xx.h"
|
||||
#endif
|
||||
|
||||
#ifdef PANDA
|
||||
#define ENABLE_CURRENT_SENSOR
|
||||
#define ENABLE_SPI
|
||||
#endif
|
||||
|
||||
#define USB_VID 0xbbaa
|
||||
#define USB_PID 0xddcc
|
||||
|
||||
#endif
|
|
@ -1,14 +1,10 @@
|
|||
#ifdef STM32F4
|
||||
#define PANDA
|
||||
#include "stm32f4xx.h"
|
||||
#else
|
||||
#include "stm32f2xx.h"
|
||||
#endif
|
||||
|
||||
#include "config.h"
|
||||
#include "early.h"
|
||||
#include "llgpio.h"
|
||||
|
||||
int has_external_debug_serial = 0;
|
||||
int is_giant_panda = 0;
|
||||
int revision = PANDA_REV_AB;
|
||||
void *g_pfnVectors;
|
||||
|
||||
// must call again from main because BSS is zeroed
|
||||
|
@ -19,12 +15,28 @@ void detect() {
|
|||
for (i=0;i<PULL_EFFECTIVE_DELAY;i++);
|
||||
has_external_debug_serial = (GPIOA->IDR & (1 << 3)) == (1 << 3);
|
||||
|
||||
// detect is_giant_panda
|
||||
is_giant_panda = 0;
|
||||
#ifdef PANDA
|
||||
GPIOB->PUPDR |= GPIO_PUPDR_PUPDR1_1;
|
||||
// detect is_giant_panda
|
||||
set_gpio_pullup(GPIOB, 1, PULL_DOWN);
|
||||
for (i=0;i<PULL_EFFECTIVE_DELAY;i++);
|
||||
is_giant_panda = (GPIOB->IDR & (1 << 1)) == (1 << 1);
|
||||
is_giant_panda = get_gpio_input(GPIOB, 1);
|
||||
|
||||
// detect panda REV C.
|
||||
// A13 floats in REV AB. In REV C, A13 is pulled up to 5V with a 10K
|
||||
// resistor and attached to the USB power control chip CTRL
|
||||
// line. Pulling A13 down with an internal 50k resistor in REV C
|
||||
// will produce a voltage divider that results in a high logic
|
||||
// level. Checking if this pin reads high with a pull down should
|
||||
// differentiate REV AB from C.
|
||||
set_gpio_mode(GPIOA, 13, MODE_INPUT);
|
||||
set_gpio_pullup(GPIOA, 13, PULL_DOWN);
|
||||
for (i=0;i<PULL_EFFECTIVE_DELAY;i++);
|
||||
if(get_gpio_input(GPIOA, 13))
|
||||
revision = PANDA_REV_C;
|
||||
|
||||
// RESET pull up/down
|
||||
set_gpio_pullup(GPIOA, 13, PULL_NONE);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -2,11 +2,15 @@
|
|||
#define POST_BOOTLOADER_MAGIC 0xdeadb111
|
||||
#define PULL_EFFECTIVE_DELAY 10
|
||||
|
||||
#define PANDA_REV_AB 0
|
||||
#define PANDA_REV_C 1
|
||||
|
||||
extern uint32_t enter_bootloader_mode;
|
||||
extern void *_app_start[];
|
||||
extern void *g_pfnVectors;
|
||||
extern int has_external_debug_serial;
|
||||
extern int is_giant_panda;
|
||||
extern int revision;
|
||||
|
||||
void spi_flasher();
|
||||
void detect();
|
||||
|
|
31
board/gpio.h
31
board/gpio.h
|
@ -54,7 +54,7 @@ void set_led(int led_num, int on) {
|
|||
|
||||
|
||||
// TODO: does this belong here?
|
||||
void periph_init() {
|
||||
void periph_init() {
|
||||
// enable GPIOB, UART2, CAN, USB clock
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
|
||||
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
|
||||
|
@ -118,8 +118,7 @@ void set_can_mode(int can, int use_gmlan) {
|
|||
1 1 33kbit (normal)
|
||||
*/
|
||||
|
||||
#ifdef REVC
|
||||
} else if (can == 3) {
|
||||
} else if (revision == PANDA_REV_C && can == 3) {
|
||||
// A8,A15: disable normal mode
|
||||
set_gpio_mode(GPIOA, 8, MODE_INPUT);
|
||||
set_gpio_mode(GPIOA, 15, MODE_INPUT);
|
||||
|
@ -127,7 +126,6 @@ void set_can_mode(int can, int use_gmlan) {
|
|||
// B3,B4: enable gmlan mode
|
||||
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3);
|
||||
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3);
|
||||
#endif
|
||||
}
|
||||
|
||||
// put gmlan transceiver in normal mode
|
||||
|
@ -149,11 +147,11 @@ void set_can_mode(int can, int use_gmlan) {
|
|||
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
|
||||
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
|
||||
} else if (can == 3) {
|
||||
#ifdef REVC
|
||||
if(revision == PANDA_REV_C){
|
||||
// B3,B4: disable gmlan mode
|
||||
set_gpio_mode(GPIOB, 3, MODE_INPUT);
|
||||
set_gpio_mode(GPIOB, 4, MODE_INPUT);
|
||||
#endif
|
||||
}
|
||||
|
||||
// A8,A15: normal mode
|
||||
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
|
||||
|
@ -250,11 +248,10 @@ void gpio_init() {
|
|||
|
||||
#ifdef PANDA
|
||||
// K-line enable moved from B4->B7 to make room for GMLAN on CAN3
|
||||
#ifdef REVC
|
||||
set_gpio_output(GPIOB, 7, 1);
|
||||
#else
|
||||
set_gpio_output(GPIOB, 4, 1);
|
||||
#endif
|
||||
if(revision == PANDA_REV_C)
|
||||
set_gpio_output(GPIOB, 7, 1); // REV C
|
||||
else
|
||||
set_gpio_output(GPIOB, 4, 1); // REV AB
|
||||
|
||||
// C12,D2: K-Line setup on UART 5
|
||||
set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5);
|
||||
|
@ -270,10 +267,12 @@ void gpio_init() {
|
|||
set_gpio_pullup(GPIOC, 11, PULL_UP);
|
||||
#endif
|
||||
|
||||
#ifdef REVC
|
||||
if(revision == PANDA_REV_C) {
|
||||
// B2,A13: set DCP mode on the charger (breaks USB!)
|
||||
/*set_gpio_output(GPIOB, 2, 0);
|
||||
set_gpio_output(GPIOA, 13, 0);*/
|
||||
#endif
|
||||
}
|
||||
//set_gpio_output(GPIOB, 2, 0);
|
||||
//set_gpio_output(GPIOA, 13, 0);
|
||||
|
||||
//set_gpio_output(GPIOA, 13, 1); //CTRL 1
|
||||
//set_gpio_output(GPIOB, 2, 0); //CTRL 2
|
||||
}
|
||||
}
|
||||
|
|
26
board/libc.h
26
board/libc.h
|
@ -12,29 +12,18 @@
|
|||
// **** shitty libc ****
|
||||
|
||||
void clock_init() {
|
||||
#ifdef USE_INTERNAL_OSC
|
||||
// enable internal oscillator
|
||||
RCC->CR |= RCC_CR_HSION;
|
||||
while ((RCC->CR & RCC_CR_HSIRDY) == 0);
|
||||
#else
|
||||
// enable external oscillator
|
||||
RCC->CR |= RCC_CR_HSEON;
|
||||
while ((RCC->CR & RCC_CR_HSERDY) == 0);
|
||||
#endif
|
||||
// enable external oscillator
|
||||
RCC->CR |= RCC_CR_HSEON;
|
||||
while ((RCC->CR & RCC_CR_HSERDY) == 0);
|
||||
|
||||
// divide shit
|
||||
RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4;
|
||||
#ifdef USE_INTERNAL_OSC
|
||||
#ifdef PANDA
|
||||
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
|
||||
RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSI;
|
||||
RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE;
|
||||
#else
|
||||
#ifdef PANDA
|
||||
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;
|
||||
#endif
|
||||
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
|
||||
RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE;
|
||||
#endif
|
||||
|
||||
// start PLL
|
||||
|
@ -84,4 +73,3 @@ int memcmp(const void * ptr1, const void * ptr2, unsigned int num) {
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
#include "config.h"
|
||||
#include "llgpio.h"
|
||||
|
||||
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->MODER;
|
||||
tmp &= ~(3 << (pin*2));
|
||||
tmp |= (mode << (pin*2));
|
||||
GPIO->MODER = tmp;
|
||||
}
|
||||
|
||||
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val) {
|
||||
if (val) {
|
||||
GPIO->ODR |= (1 << pin);
|
||||
} else {
|
||||
GPIO->ODR &= ~(1 << pin);
|
||||
}
|
||||
set_gpio_mode(GPIO, pin, MODE_OUTPUT);
|
||||
}
|
||||
|
||||
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->AFR[pin>>3];
|
||||
tmp &= ~(0xF << ((pin&7)*4));
|
||||
tmp |= mode << ((pin&7)*4);
|
||||
GPIO->AFR[pin>>3] = tmp;
|
||||
set_gpio_mode(GPIO, pin, MODE_ALTERNATE);
|
||||
}
|
||||
|
||||
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->PUPDR;
|
||||
tmp &= ~(3 << (pin*2));
|
||||
tmp |= (mode << (pin*2));
|
||||
GPIO->PUPDR = tmp;
|
||||
}
|
||||
|
||||
int get_gpio_input(GPIO_TypeDef *GPIO, int pin) {
|
||||
return (GPIO->IDR & (1 << pin)) == (1 << pin);
|
||||
}
|
|
@ -1,40 +1,23 @@
|
|||
#ifndef PANDA_LLGPIO_H
|
||||
#define PANDA_LLGPIO_H
|
||||
|
||||
#define MODE_INPUT 0
|
||||
#define MODE_OUTPUT 1
|
||||
#define MODE_ALTERNATE 2
|
||||
#define MODE_ANALOG 3
|
||||
|
||||
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->MODER;
|
||||
tmp &= ~(3 << (pin*2));
|
||||
tmp |= (mode << (pin*2));
|
||||
GPIO->MODER = tmp;
|
||||
}
|
||||
|
||||
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val) {
|
||||
if (val) {
|
||||
GPIO->ODR |= (1 << pin);
|
||||
} else {
|
||||
GPIO->ODR &= ~(1 << pin);
|
||||
}
|
||||
set_gpio_mode(GPIO, pin, MODE_OUTPUT);
|
||||
}
|
||||
|
||||
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->AFR[pin>>3];
|
||||
tmp &= ~(0xF << ((pin&7)*4));
|
||||
tmp |= mode << ((pin&7)*4);
|
||||
GPIO->AFR[pin>>3] = tmp;
|
||||
set_gpio_mode(GPIO, pin, MODE_ALTERNATE);
|
||||
}
|
||||
|
||||
#define PULL_NONE 0
|
||||
#define PULL_UP 1
|
||||
#define PULL_DOWN 2
|
||||
#define PULL_DOWN 2
|
||||
|
||||
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode) {
|
||||
uint32_t tmp = GPIO->PUPDR;
|
||||
tmp &= ~(3 << (pin*2));
|
||||
tmp |= (mode << (pin*2));
|
||||
GPIO->PUPDR = tmp;
|
||||
}
|
||||
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode);
|
||||
|
||||
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val);
|
||||
|
||||
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode);
|
||||
|
||||
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode);
|
||||
|
||||
int get_gpio_input(GPIO_TypeDef *GPIO, int pin);
|
||||
|
||||
#endif
|
||||
|
|
23
board/main.c
23
board/main.c
|
@ -1,27 +1,8 @@
|
|||
//#define DEBUG
|
||||
//#define DEBUG_USB
|
||||
//#define CAN_LOOPBACK_MODE
|
||||
//#define USE_INTERNAL_OSC
|
||||
//#define REVC
|
||||
|
||||
#ifdef STM32F4
|
||||
#define PANDA
|
||||
#include "stm32f4xx.h"
|
||||
#else
|
||||
#include "stm32f2xx.h"
|
||||
#endif
|
||||
|
||||
#ifdef PANDA
|
||||
#define ENABLE_CURRENT_SENSOR
|
||||
#define ENABLE_SPI
|
||||
#endif
|
||||
|
||||
#define USB_VID 0xbbaa
|
||||
#define USB_PID 0xddcc
|
||||
#include "config.h"
|
||||
#include "early.h"
|
||||
|
||||
#define NULL ((void*)0)
|
||||
|
||||
#include "early.h"
|
||||
|
||||
// assign CAN numbering
|
||||
// old: CAN1 = 1 CAN2 = 0
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
* @brief Driver for the Comma.ai Panda CAN adapter to allow it to be controlled via
|
||||
* the Linux SocketCAN interface.
|
||||
* @see https://github.com/commaai/panda for the full project.
|
||||
* @see Inspired by net/can/usb/mcba_usb.c from Linux Kernel 4.12-rc4.
|
||||
*/
|
||||
|
||||
#include <linux/can.h>
|
||||
|
|
|
@ -95,8 +95,7 @@ class Panda(object):
|
|||
self._handle = device.open()
|
||||
if claim:
|
||||
self._handle.claimInterface(0)
|
||||
# TODO: Do we need to cupport claim=False?
|
||||
self._handle.setInterfaceAltSetting(0,0)
|
||||
self._handle.setInterfaceAltSetting(0, 0)
|
||||
break
|
||||
|
||||
assert self._handle != None
|
||||
|
@ -222,7 +221,7 @@ class Panda(object):
|
|||
if len(ret) == 0:
|
||||
break
|
||||
bret += ret
|
||||
return bret
|
||||
return bytes(bret)
|
||||
|
||||
def kline_ll_recv(self, cnt, bus=2):
|
||||
echo = bytearray()
|
||||
|
@ -242,7 +241,7 @@ class Panda(object):
|
|||
x += get_checksum(x)
|
||||
for i in range(0, len(x), 0xf):
|
||||
ts = x[i:i+0xf]
|
||||
self._handle.bulkWrite(2, chr(bus)+ts)
|
||||
self._handle.bulkWrite(2, chr(bus).encode()+ts)
|
||||
echo = self.kline_ll_recv(len(ts), bus=bus)
|
||||
if echo != ts:
|
||||
print("**** ECHO ERROR %d ****" % i)
|
||||
|
|
|
@ -18,7 +18,7 @@ if __name__ == "__main__":
|
|||
if os.getenv("SERIAL"):
|
||||
serials = filter(lambda x: x==os.getenv("SERIAL"), serials)
|
||||
|
||||
pandas = map(lambda x: Panda(x, False), serials)
|
||||
pandas = list(map(lambda x: Panda(x, False), serials))
|
||||
while True:
|
||||
for i, panda in enumerate(pandas):
|
||||
while True:
|
||||
|
@ -28,7 +28,7 @@ if __name__ == "__main__":
|
|||
sys.stdout.flush()
|
||||
else:
|
||||
break
|
||||
if select.select([sys.stdin], [], [], 0)[0][0] == sys.stdin:
|
||||
if select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], []):
|
||||
ln = sys.stdin.readline()
|
||||
panda.serial_write(port_number, ln)
|
||||
time.sleep(0.01)
|
||||
|
|
|
@ -12,7 +12,7 @@ sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), ".."))
|
|||
from panda import Panda
|
||||
|
||||
def get_test_string():
|
||||
return "test"+os.urandom(10)
|
||||
return b"test"+os.urandom(10)
|
||||
|
||||
def run_test():
|
||||
pandas = Panda.list()
|
||||
|
@ -28,8 +28,8 @@ def run_test():
|
|||
run_test_w_pandas(pandas)
|
||||
|
||||
def run_test_w_pandas(pandas):
|
||||
h = map(lambda x: Panda(x), pandas)
|
||||
print(h)
|
||||
h = list(map(lambda x: Panda(x), pandas))
|
||||
print("H", h)
|
||||
|
||||
for hh in h:
|
||||
hh.set_controls_allowed(True)
|
||||
|
@ -48,50 +48,54 @@ def run_test_w_pandas(pandas):
|
|||
|
||||
# send the characters
|
||||
st = get_test_string()
|
||||
st = "\xaa"+chr(len(st)+3)+st
|
||||
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)
|
||||
print("K/L pass", bus, ho, "\n")
|
||||
|
||||
# **** test can line loopback ****
|
||||
for bus in [0,1,4,5,6]:
|
||||
print("test can", bus)
|
||||
panda0 = h[ho[0]]
|
||||
panda1 = h[ho[1]]
|
||||
print("\ntest can", bus)
|
||||
# flush
|
||||
cans_echo = h[ho[0]].can_recv()
|
||||
cans_loop = h[ho[1]].can_recv()
|
||||
cans_echo = panda0.can_recv()
|
||||
cans_loop = panda1.can_recv()
|
||||
|
||||
# set GMLAN mode
|
||||
if bus == 5:
|
||||
h[ho[0]].set_gmlan(True,2)
|
||||
h[ho[1]].set_gmlan(True,2)
|
||||
panda0.set_gmlan(True,2)
|
||||
panda1.set_gmlan(True,2)
|
||||
bus = 1 # GMLAN is multiplexed with CAN2
|
||||
elif bus == 6:
|
||||
# on REV B panda, this just retests CAN2 GMLAN
|
||||
h[ho[0]].set_gmlan(True,3)
|
||||
h[ho[1]].set_gmlan(True,3)
|
||||
panda0.set_gmlan(True,3)
|
||||
panda1.set_gmlan(True,3)
|
||||
bus = 4 # GMLAN is also multiplexed with CAN3
|
||||
else:
|
||||
h[ho[0]].set_gmlan(False)
|
||||
h[ho[1]].set_gmlan(False)
|
||||
panda0.set_gmlan(False)
|
||||
panda1.set_gmlan(False)
|
||||
|
||||
# send the characters
|
||||
# pick addresses high enough to not conflict with honda code
|
||||
at = random.randint(1024, 2000)
|
||||
st = get_test_string()[0:8]
|
||||
h[ho[0]].can_send(at, st, bus)
|
||||
panda0.can_send(at, st, bus)
|
||||
time.sleep(0.1)
|
||||
|
||||
# check for receive
|
||||
cans_echo = h[ho[0]].can_recv()
|
||||
cans_loop = h[ho[1]].can_recv()
|
||||
cans_echo = panda0.can_recv()
|
||||
cans_loop = panda1.can_recv()
|
||||
|
||||
print(bus, cans_echo, cans_loop)
|
||||
print("Bus", bus, "echo", cans_echo, "loop", cans_loop)
|
||||
|
||||
assert len(cans_echo) == 1
|
||||
assert len(cans_loop) == 1
|
||||
|
@ -118,4 +122,4 @@ if __name__ == "__main__":
|
|||
while True:
|
||||
print("************* testing %d" % i)
|
||||
run_test()
|
||||
i += 1
|
||||
i += 1
|
||||
|
|
Loading…
Reference in New Issue