Revert commits that broke USB for openpilot.

Revert "fix openpilot board flashing"

This reverts commit 8ff93ad5da.

Revert "Fixed output_enabled led not turning off when mode changed to no output."

This reverts commit 27a8af1107.

Revert "Fixed loopback test for new GMLAN 'can4' behavior."

This reverts commit 59592f599a.

Revert "GMLAN is now always mapped through CAN4 (index 3)"

This reverts commit 329c091024.

Revert "Removed compile time config for CAN loopback, implemented as usb message."

This reverts commit e1a4c32985.

Revert "Change all output safety mode identifier to prevent user mistakes."

This reverts commit 6b363e2e92.

Revert "untabify"

This reverts commit 191f67b083.

Revert "Refactor of safety to support more modular additions of safety policies."

This reverts commit e5b524eddc.

Revert "Split up some more header files into compilation units."

This reverts commit e2a78912f5.

Revert "Enabled emulated control writes over USB."

This reverts commit 133cfe9703.

Revert "Moved CAN and USART code out of main.c and into more appropriate files."

This reverts commit daad2dc062.

Revert "Large Panda CAN cleanup. Restrict GMLAN to valid baud rates."

This reverts commit a0616a2bc2.

Revert "Panda library now correctly sends USB direction bit."

This reverts commit 1712c901d4.

Revert "Board makefile now automatically calculates header file dependencies."

This reverts commit 4a8d4e597b.

Revert "Loopback test works over wifi. (Disable trying to send over wifi)"

This reverts commit dae636968a.

Revert "Fix legacy board build"

This reverts commit 62bf4e5756.

Revert "Style cop"

This reverts commit c439f43726.

Revert "Untabify"

This reverts commit 41e5eec621.

Revert "Fixed disabling gmlan."

This reverts commit 5e1e45a4af.

Revert "Removed dead code, standardized canid in more commands, better erroring behavior."

This reverts commit b59aeb6d87.

Revert "loopback test works with new CAN bus ids."

This reverts commit 75970861cf.

Revert "Large reorganization of code and early integration of can bitrate setting."

This reverts commit a1ed7b62ee.
master
George Hotz 2017-07-12 11:25:10 -07:00
parent 8ff93ad5da
commit 7733b09288
37 changed files with 1733 additions and 2204 deletions

View File

@ -1,6 +1,6 @@
# :set noet
PROJ_NAME = comma
CFLAGS = -g -O0 -Wall -std=gnu90
CFLAGS = -g -O0 -Wall
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx

View File

View File

@ -36,3 +36,4 @@ uint32_t adc_get(int channel) {
return ADC1->JDR1;
}

View File

@ -77,3 +77,4 @@ good:
((void(*)()) _app_start[1])();
return 0;
}

View File

@ -1,7 +1,3 @@
DEPDIR := obj/.d
$(shell mkdir -p $(DEPDIR) >/dev/null)
DEPFLAGS = -MT $@ -MMD -MP -MF $(DEPDIR)/$*.Td
CFLAGS += -I inc -I ../ -nostdlib -fno-builtin
CFLAGS += -Tstm32_flash.ld
@ -11,6 +7,7 @@ OBJDUMP = arm-none-eabi-objdump
ifeq ($(RELEASE),1)
CERT = ../../pandaextra/certs/release
CFLAGS += "-DPANDA_SAFETY"
else
CERT = ../certs/debug
CFLAGS += "-DALLOW_DEBUG"
@ -71,23 +68,23 @@ 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 config.h
$(CC) $(DEPFLAGS) $(CFLAGS) -o $@ -c $<
$(CC) $(CFLAGS) -o $@ -c $<
obj/%.$(PROJ_NAME).o: ../crypto/%.c
$(CC) $(DEPFLAGS) $(CFLAGS) -o $@ -c $<
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(STARTUP_FILE).o: $(STARTUP_FILE).s
$(CC) $(DEPFLAGS) $(CFLAGS) -o $@ -c $<
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o obj/early.$(PROJ_NAME).o obj/llgpio.$(PROJ_NAME).o obj/can.$(PROJ_NAME).o obj/uart.$(PROJ_NAME).o obj/gpio.$(PROJ_NAME).o obj/libc.$(PROJ_NAME).o obj/spi.$(PROJ_NAME).o obj/usb.$(PROJ_NAME).o obj/safety.$(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) $(DEPFLAGS) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
$(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/llgpio.$(PROJ_NAME).o obj/libc.$(PROJ_NAME).o obj/spi.$(PROJ_NAME).o
$(CC) $(DEPFLAGS) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
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 $@
clean:
rm -fr obj
rm -f obj/*

View File

@ -1,487 +0,0 @@
#include <stdint.h>
#include "config.h"
#include "can.h"
#include "uart.h"
#include "gpio.h"
#include "llgpio.h"
#include "libc.h"
#include "rev.h"
#include "safety.h"
bool can_live = false, pending_can_live = false, can_loopback = false;
#define NO_ACTIVE_GMLAN -1
int active_gmlan_port_id = NO_ACTIVE_GMLAN; // default disabled
#define GMLAN_PORT_ID 3
// assign CAN numbering
#ifdef PANDA
// ********************* instantiate can queues *********************
can_buffer(rx_q, 0x1000)
can_buffer(tx1_q, 0x100)
can_buffer(tx2_q, 0x100)
can_buffer(tx3_q, 0x100)
// panda: CAN1 = 0 CAN2 = 1 CAN3 = 2
can_port_desc can_ports[] = {
{CAN_PORT_DESC_INITIALIZER,
.CAN = CAN1,
.msg_buff = &can_tx1_q,
.can_pins = {{GPIOB, 8, GPIO_AF8_CAN1}, {GPIOB, 9, GPIO_AF8_CAN1}},
.enable_pin = {GPIOC, 1, 0},
.gmlan_support = false,
},
{CAN_PORT_DESC_INITIALIZER,
.CAN = CAN2,
.msg_buff = &can_tx2_q,
.can_pins = {{GPIOB, 5, GPIO_AF9_CAN2}, {GPIOB, 6, GPIO_AF9_CAN2}},
.enable_pin = {GPIOC, 13, 0},
.gmlan_support = true,
.gmlan_pins = {{GPIOB, 12, GPIO_AF9_CAN2}, {GPIOB, 13, GPIO_AF9_CAN2}},
},
//TODO Make gmlan support correct for REV B
{CAN_PORT_DESC_INITIALIZER,
.CAN = CAN3,
.msg_buff = &can_tx3_q,
.can_pins = {{GPIOA, 8, GPIO_AF11_CAN3}, {GPIOA, 15, GPIO_AF11_CAN3}},
.enable_pin = {GPIOA, 0, 0},
.gmlan_support = true,
.gmlan_pins = {{GPIOB, 3, GPIO_AF11_CAN3}, {GPIOB, 4, GPIO_AF11_CAN3}},
}
};
#else
// ********************* instantiate can queues *********************
can_buffer(rx_q, 0x1000)
can_buffer(tx1_q, 0x100)
can_buffer(tx2_q, 0x100)
// old: CAN1 = 1 CAN2 = 0
can_port_desc can_ports[] = {
{CAN_PORT_DESC_INITIALIZER,
.CAN = CAN2,
.msg_buff = &can_tx1_q,
.can_pins = {{GPIOB, 5, GPIO_AF9_CAN2}, {GPIOB, 6, GPIO_AF9_CAN2}},
.enable_pin = {GPIOB, 4, 1},
.gmlan_support = false,
},
{CAN_PORT_DESC_INITIALIZER,
.CAN = CAN1,
.msg_buff = &can_tx2_q,
.can_pins = {{GPIOB, 8, GPIO_AF9_CAN1}, {GPIOB, 9, GPIO_AF9_CAN1}},
.enable_pin = {GPIOB, 3, 1},
.gmlan_support = false,
}
};
#endif
int pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
if (q->w_ptr != q->r_ptr) {
*elem = q->elems[q->r_ptr];
if ((q->r_ptr + 1) == q->fifo_size) q->r_ptr = 0;
else q->r_ptr += 1;
return 1;
}
return 0;
}
int push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
uint32_t next_w_ptr;
if ((q->w_ptr + 1) == q->fifo_size) next_w_ptr = 0;
else next_w_ptr = q->w_ptr + 1;
if (next_w_ptr != q->r_ptr) {
q->elems[q->w_ptr] = *elem;
q->w_ptr = next_w_ptr;
return 1;
}
puts("push failed!\n");
return 0;
}
// ********************* CAN Functions *********************
void can_init(uint8_t canid) {
int i;
uint32_t bitrate;
CAN_TypeDef *CAN;
uint8_t quanta;
uint16_t prescaler;
uint8_t seq1, seq2;
can_port_desc *port;
gpio_alt_setting *disable_pins;
gpio_alt_setting *enable_pins;
puts("Can init: ");
puth(canid);
puts("\n");
if(canid >= CAN_MAX) return;
port = &can_ports[canid];
//////////// Set MCU pin modes
if (port->gmlan_support) {
disable_pins = port->gmlan ? port->can_pins : port->gmlan_pins;
enable_pins = port->gmlan ? port->gmlan_pins : port->can_pins;
} else {
disable_pins = 0;
enable_pins = port->can_pins;
}
// Disable output on either CAN or GMLAN pins
if (disable_pins) {
set_gpio_mode(disable_pins[0].port, disable_pins[0].num, MODE_INPUT);
set_gpio_mode(disable_pins[1].port, disable_pins[1].num, MODE_INPUT);
}
// Enable output on either CAN or GMLAN pins
if (enable_pins) {
set_gpio_alternate(enable_pins[0].port, enable_pins[0].num, enable_pins[0].setting);
set_gpio_alternate(enable_pins[1].port, enable_pins[1].num, enable_pins[1].setting);
}
/* GMLAN mode pins:
M0(B15) M1(B14) mode
=======================
0 0 sleep
1 0 100kbit
0 1 high voltage wakeup
1 1 33kbit (normal)
*/
if (port->gmlan) {
set_gpio_output(GPIOB, 14, 1);
set_gpio_output(GPIOB, 15, 1);
} else {
for (i = 0; i < CAN_MAX; i++)
if (can_ports[i].gmlan)
break;
if (i == CAN_MAX){
set_gpio_output(GPIOB, 14, 0);
set_gpio_output(GPIOB, 15, 0);
puts("Disabling GMLAN output\n");
}
}
//////////// Calculate and set CAN bitrate
if (port->gmlan) {
bitrate = (port->gmlan_bitrate) < 58333 ? 33333 : 83333;
} else {
bitrate = port->bitrate;
if(bitrate > 1000000) //MAX 1 Megabaud
bitrate = 1000000;
}
//puts(" Speed req: ");
//puth(bitrate);
//puts("\n");
//TODO: Try doing both and find the more accurate values.
if(min((FREQ / 2) / bitrate, 16) == 16){
quanta = 16;
seq1 = 13;//roundf(quanta * 0.875f) - 1;
seq2 = 2;//roundf(quanta * 0.125f);
}else{
quanta = 8;
seq1 = 6;//roundf(quanta * 0.875f) - 1;
seq2 = 1;//roundf(quanta * 0.125f);
}
// TODO: Look into better accuracy with rounding.
prescaler = FREQ / quanta / bitrate;
//Check the prescaler is not larger than max
if(prescaler > 0x3FF)
prescaler = 0x3FF;
bitrate = FREQ/quanta/prescaler;
if (port->gmlan) {
port->gmlan_bitrate = bitrate;
} else {
port->bitrate = bitrate;
}
puts(" Speed: ");
puth(bitrate);
puts("\n");
if (port->gmlan)
puts(" Type GMLAN\n");
else
puts(" Type CAN\n");
//////////////// Enable CAN port
if (is_output_enabled())
puts(" Output Enabled\n");
else
puts(" Output Disabled\n");
set_can_enable(canid, 1);
CAN = port->CAN;
// Move CAN to initialization mode and sync.
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
// seg 1: 13 time quanta, seg 2: 2 time quanta
CAN->BTR = (CAN_BTR_TS1_0 * (seq1 - 1)) |
(CAN_BTR_TS2_0 * (seq2 - 1)) |
(prescaler - 1);
// silent loopback mode for debugging
if (can_loopback) {
CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM;
}
if (!is_output_enabled()) {
CAN->BTR |= CAN_BTR_SILM;
}
// reset
CAN->MCR = CAN_MCR_TTCM;
int tmp = 0;
while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++;
if (tmp == CAN_TIMEOUT) {
set_led(LED_BLUE, 1);
puts(" init FAILED!!!!!\n");
} else {
puts(" init SUCCESS\n");
}
// accept all filter
CAN->FMR |= CAN_FMR_FINIT;
// no mask
CAN->sFilterRegister[0].FR1 = 0;
CAN->sFilterRegister[0].FR2 = 0;
CAN->sFilterRegister[14].FR1 = 0;
CAN->sFilterRegister[14].FR2 = 0;
CAN->FA1R |= 1 | (1 << 14);
CAN->FMR &= ~(CAN_FMR_FINIT);
// enable all CAN interrupts
CAN->IER = 0xFFFFFFFF;
//CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_FMPIE1;
}
void set_can_mode(uint16_t canid, bool use_gmlan) {
if (canid >= CAN_MAX) return;
if (!can_ports[canid].gmlan_support) use_gmlan = false;
if (use_gmlan) {
// If enabling gmlan, and another port is already enabled, disable it.
if(active_gmlan_port_id != NO_ACTIVE_GMLAN && active_gmlan_port_id != canid)
set_can_mode(active_gmlan_port_id, 0);
active_gmlan_port_id = canid;
} else if(active_gmlan_port_id != NO_ACTIVE_GMLAN && active_gmlan_port_id == canid) {
// If disabling gmlan, and this port is gmlan enabled, unregister it.
active_gmlan_port_id = -1;
}
can_ports[canid].gmlan = use_gmlan;
can_init(canid);
}
// CAN error
void can_sce(uint8_t canid) {
CAN_TypeDef *CAN = can_ports[canid].CAN;
#ifdef DEBUG
if (canid==0) puts("CAN1: ");
if (canid==1) puts("CAN2: ");
if (canid==2) puts("CAN3: ");
puts("MSR:");
puth(CAN->MSR);
puts(" TSR:");
puth(CAN->TSR);
puts(" RF0R:");
puth(CAN->RF0R);
puts(" RF1R:");
puth(CAN->RF1R);
puts(" ESR:");
puth(CAN->ESR);
puts("\n");
#endif
// clear
//CAN->sTxMailBox[0].TIR &= ~(CAN_TI0R_TXRQ);
CAN->TSR |= CAN_TSR_ABRQ0;
//CAN->ESR |= CAN_ESR_LEC;
//CAN->MSR &= ~(CAN_MSR_ERRI);
CAN->MSR = CAN->MSR;
}
void CAN1_SCE_IRQHandler() {
can_sce(0);
}
void CAN2_SCE_IRQHandler() {
can_sce(1);
}
void CAN3_SCE_IRQHandler() {
can_sce(2);
}
// CAN receive handlers
// blink blue when we are receiving CAN messages
void can_rx(uint8_t canid) {
CAN_TypeDef *CAN = can_ports[canid].CAN;
while (CAN->RF0R & CAN_RF0R_FMP0) {
// can is live
pending_can_live = 1;
// add to my fifo
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sFIFOMailBox[0].RIR;
to_push.RDTR = CAN->sFIFOMailBox[0].RDTR;
to_push.RDLR = CAN->sFIFOMailBox[0].RDLR;
to_push.RDHR = CAN->sFIFOMailBox[0].RDHR;
// forwarding (panda only)
#ifdef PANDA
if (can_ports[canid].forwarding != -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;
send_can(&to_send, can_ports[canid].forwarding);
}
#endif
// modify RDTR for our API
if(canid == active_gmlan_port_id) {
to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (GMLAN_PORT_ID << 4);
} else {
to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (canid << 4);
}
safety_rx_hook(&to_push);
#ifdef PANDA
set_led(LED_GREEN, 1);
#endif
push(&can_rx_q, &to_push);
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_RX0_IRQHandler() {
can_rx(0);
}
void CAN2_RX0_IRQHandler() {
can_rx(1);
}
void CAN3_RX0_IRQHandler() {
can_rx(2);
}
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;
}
void process_can(uint8_t canid) {
CAN_TypeDef *CAN;
uint8_t reported_canid = canid;
#ifdef DEBUG
puts("process CAN TX\n");
#endif
// canid of 3 is the virtual GMLAN (CAN4)
if (canid >= CAN_MAX) return;
// Remap canid to gmlan if port has gmlan enabled
if (canid == active_gmlan_port_id) {
reported_canid = GMLAN_PORT_ID;
}
CAN = can_ports[canid].CAN;
// add successfully transmitted message to my fifo
if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) {
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sTxMailBox[0].TIR;
to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) |
((PANDA_CANB_RETURN_FLAG | (reported_canid & 0x7F)) << 4);
puts("RDTR: ");
puth(to_push.RDTR);
puts("\n");
to_push.RDLR = CAN->sTxMailBox[0].TDLR;
to_push.RDHR = CAN->sTxMailBox[0].TDHR;
push(&can_rx_q, &to_push);
}
// check for empty mailbox
CAN_FIFOMailBox_TypeDef to_send;
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
if (pop(can_ports[canid].msg_buff, &to_send)) {
// only send if we have received a packet
CAN->sTxMailBox[0].TDLR = to_send.RDLR;
CAN->sTxMailBox[0].TDHR = to_send.RDHR;
CAN->sTxMailBox[0].TDTR = to_send.RDTR;
CAN->sTxMailBox[0].TIR = to_send.RIR;
}
}
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
// send more, possible for these to not trigger?
void CAN1_TX_IRQHandler() {
process_can(0);
}
void CAN2_TX_IRQHandler() {
process_can(1);
}
void CAN3_TX_IRQHandler() {
process_can(2);
}
void send_can(CAN_FIFOMailBox_TypeDef *to_push, uint8_t canid) {
// canid of 3 is the virtual GMLAN (CAN4)
if (canid >= CAN_MAX && canid != GMLAN_PORT_ID) return;
// TODO: Error for using disabled port
if (active_gmlan_port_id == canid) return;
// Remap gmlan output to real can port
if (canid == GMLAN_PORT_ID) {
if (active_gmlan_port_id == NO_ACTIVE_GMLAN)
return; // No gmlan port enabled
else
canid = active_gmlan_port_id;
}
// add CAN packet to send queue
// bus number isn't passed through
to_push->RDTR &= 0xF;
push(can_ports[canid].msg_buff, to_push);
// canid = can_number
process_can(canid);
}

View File

@ -1,88 +1,101 @@
#ifndef PANDA_CAN_H
#define PANDA_CAN_H
void can_init(CAN_TypeDef *CAN, int silent) {
set_can_enable(CAN, 1);
#include <stdbool.h>
#include "rev.h"
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
#define CAN_TIMEOUT 1000000
#define PANDA_CANB_RETURN_FLAG 0x80
// http://www.bittiming.can-wiki.info/
// PCLK = 24 MHz
uint32_t pclk = 24000;
uint32_t num_time_quanta = 16;
extern bool can_live, pending_can_live, can_loopback;
// 500 kbps
uint32_t prescaler = pclk / num_time_quanta / 500;
// ********************* queues types *********************
// seg 1: 13 time quanta, seg 2: 2 time quanta
CAN->BTR = (CAN_BTR_TS1_0 * 12) |
CAN_BTR_TS2_0 | (prescaler - 1);
typedef struct {
uint32_t w_ptr;
uint32_t r_ptr;
uint32_t fifo_size;
CAN_FIFOMailBox_TypeDef *elems;
} can_ring;
// silent loopback mode for debugging
#ifdef CAN_LOOPBACK_MODE
CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM;
#endif
#define can_buffer(x, size) \
CAN_FIFOMailBox_TypeDef elems_##x[size]; \
can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x };
if (silent) {
CAN->BTR |= CAN_BTR_SILM;
}
extern can_ring can_rx_q;
// reset
CAN->MCR = CAN_MCR_TTCM;
// ********************* port description types *********************
#define CAN_TIMEOUT 1000000
int tmp = 0;
while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++;
#define CAN_PORT_DESC_INITIALIZER \
.forwarding=-1, \
.bitrate=CAN_DEFAULT_BITRATE, \
.bitrate=CAN_DEFAULT_BITRATE, \
.gmlan=false, \
.gmlan_bitrate=GMLAN_DEFAULT_BITRATE
if (tmp == CAN_TIMEOUT) {
set_led(LED_BLUE, 1);
puts("CAN init FAILED!!!!!\n");
} else {
puts("CAN init done\n");
}
typedef struct {
GPIO_TypeDef* port;
uint8_t num;
bool high_val;
} gpio_pin;
// accept all filter
CAN->FMR |= CAN_FMR_FINIT;
typedef struct {
GPIO_TypeDef* port;
uint8_t num;
uint32_t setting;
} gpio_alt_setting;
// no mask
CAN->sFilterRegister[0].FR1 = 0;
CAN->sFilterRegister[0].FR2 = 0;
CAN->sFilterRegister[14].FR1 = 0;
CAN->sFilterRegister[14].FR2 = 0;
CAN->FA1R |= 1 | (1 << 14);
typedef struct {
CAN_TypeDef *CAN;
int8_t forwarding;
uint32_t bitrate;
bool gmlan;
bool gmlan_support;
uint32_t gmlan_bitrate;
gpio_pin enable_pin;
gpio_alt_setting can_pins[2];
gpio_alt_setting gmlan_pins[2];
can_ring *msg_buff;
} can_port_desc;
CAN->FMR &= ~(CAN_FMR_FINIT);
extern can_port_desc can_ports[];
#ifdef PANDA
#define CAN_MAX 3
#else
#define CAN_MAX 2
#endif
// ********************* interrupt safe queue *********************
int pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem);
int push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem);
// ********************* CAN Functions *********************
void can_init(uint8_t canid);
void set_can_mode(uint16_t can, bool use_gmlan);
void send_can(CAN_FIFOMailBox_TypeDef *to_push, uint8_t canid);
// enable all CAN interrupts
CAN->IER = 0xFFFFFFFF;
//CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_FMPIE1;
}
// CAN error
//void can_sce(uint8_t canid);
void can_sce(CAN_TypeDef *CAN) {
#ifdef DEBUG
if (CAN==CAN1) puts("CAN1: ");
if (CAN==CAN2) puts("CAN2: ");
#ifdef CAN3
if (CAN==CAN3) puts("CAN3: ");
#endif
puts("MSR:");
puth(CAN->MSR);
puts(" TSR:");
puth(CAN->TSR);
puts(" RF0R:");
puth(CAN->RF0R);
puts(" RF1R:");
puth(CAN->RF1R);
puts(" ESR:");
puth(CAN->ESR);
puts("\n");
#endif
int can_cksum(uint8_t *dat, int len, int addr, int idx);
// clear
//CAN->sTxMailBox[0].TIR &= ~(CAN_TI0R_TXRQ);
CAN->TSR |= CAN_TSR_ABRQ0;
//CAN->ESR |= CAN_ESR_LEC;
//CAN->MSR &= ~(CAN_MSR_ERRI);
CAN->MSR = CAN->MSR;
}
#endif
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;
}

View File

@ -1,21 +1,23 @@
#ifndef PANDA_CONFIG_H
#define PANDA_CONFIG_H
#include "rev.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
#define CAN_DEFAULT_BITRATE 500000 // 500 khz
#define GMLAN_DEFAULT_BITRATE 33333 // 33.333 khz
#define FIFO_SIZE 0x100
#define NULL ((void*)0)
#define PANDA_SAFETY
#endif

View File

@ -13,3 +13,4 @@ void dac_set(int channel, uint32_t value) {
DAC->DHR12R2 = value;
}
}

View File

@ -1,12 +1,10 @@
#include "config.h"
#include "early.h"
#include "llgpio.h"
#include "uart.h"
#include "rev.h"
int has_external_debug_serial = 0;
int is_giant_panda = 0;
enum rev revision = REV_A;
int revision = PANDA_REV_AB;
void *g_pfnVectors;
// must call again from main because BSS is zeroed
@ -34,9 +32,7 @@ void detect() {
set_gpio_pullup(GPIOA, 13, PULL_DOWN);
for (i=0;i<PULL_EFFECTIVE_DELAY;i++);
if(get_gpio_input(GPIOA, 13))
revision = REV_C;
else
revision = REV_B;
revision = PANDA_REV_C;
// RESET pull up/down
set_gpio_pullup(GPIOA, 13, PULL_NONE);

View File

@ -1,21 +1,17 @@
#ifndef PANDA_EARLY_H
#define PANDA_EARLY_H
#include "rev.h"
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
#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 enum rev revision;
extern int revision;
void spi_flasher();
void detect();
void early();
#endif

View File

@ -1,144 +0,0 @@
#include "config.h"
#include "gpio.h"
#include "llgpio.h"
#include "early.h"
#include "can.h"
#include "rev.h"
void set_led(int led_num, int on) {
if (led_num == -1) return;
#ifdef PANDA
set_gpio_output(GPIOC, led_num, !on);
#else
set_gpio_output(GPIOB, led_num, !on);
#endif
}
/* In REVC, this should always be enabled under normal
* operation. Otherwise, the CAN transceiver chip will try to pull the
* pus lines to ground and anger other CAN devices. Eddie is looking
* into if this is useful or not. */
void set_can_enable(uint8_t canid, int enabled) {
// enable CAN busses
gpio_pin *pin = &can_ports[canid].enable_pin;
//enable, high_val = 1; 1 xnor 1 = 1
//enable, ~high_val = 0; 1 xnor 0 = 0
//~enable, high_val = 0; 0 xnor 1 = 0
//~enable, ~high_val = 1; 0 xnor 0 = 1
set_gpio_output(pin->port, pin->num, !(enabled ^ pin->high_val));
}
// TODO: does this belong here?
void periph_init() {
// enable GPIOB, UART2, CAN, USB clock
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN;
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
#ifdef PANDA
RCC->APB1ENR |= RCC_APB1ENR_UART5EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
#ifdef CAN3
RCC->APB1ENR |= RCC_APB1ENR_CAN3EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_DACEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
//RCC->APB1ENR |= RCC_APB1ENR_TIM4EN;
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// needed?
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
}
// board specific
void gpio_init() {
// pull low to hold ESP in reset??
// enable OTG out tied to ground
GPIOA->ODR = 0;
GPIOB->ODR = 0;
GPIOA->PUPDR = 0;
//GPIOC->ODR = 0;
GPIOB->AFR[0] = 0;
GPIOB->AFR[1] = 0;
// C2,C3: analog mode, voltage and current sense
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// C8: FAN aka TIM3_CH4
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// turn off LEDs and set mode
set_led(LED_RED, 0);
set_led(LED_GREEN, 0);
set_led(LED_BLUE, 0);
// A11,A12: USB
set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS);
set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS);
GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12;
#ifdef PANDA
// enable started_alt on the panda
set_gpio_pullup(GPIOA, 1, PULL_UP);
// A2,A3: USART 2 for debugging
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2);
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2);
// A9,A10: USART 1 for talking to the ESP
set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1);
set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1);
// B12: GMLAN, ignition sense, pull up
set_gpio_pullup(GPIOB, 12, PULL_UP);
// A4,A5,A6,A7: setup SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1);
#endif
#ifdef PANDA
// K-line enable moved from B4->B7 to make room for GMLAN on CAN3
if(revision == 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);
set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5);
set_gpio_pullup(GPIOD, 2, PULL_UP);
// L-line enable
set_gpio_output(GPIOA, 14, 1);
// C10,C11: L-Line setup on USART 3
set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3);
set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3);
set_gpio_pullup(GPIOC, 11, PULL_UP);
#endif
if(revision == REV_C) {
// B2,A13: set DCP mode on the charger (breaks USB!)
//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
}
}

View File

@ -1,9 +1,278 @@
void set_can_enable(uint8_t canid, int enabled);
#ifdef STM32F4
#include "stm32f4xx_hal_gpio_ex.h"
#else
#include "stm32f2xx_hal_gpio_ex.h"
#endif
#include "llgpio.h"
void set_can_enable(CAN_TypeDef *CAN, int enabled) {
// enable CAN busses
if (CAN == CAN1) {
#ifdef PANDA
// CAN1_EN
set_gpio_output(GPIOC, 1, !enabled);
#else
// CAN1_EN
set_gpio_output(GPIOB, 3, enabled);
#endif
} else if (CAN == CAN2) {
#ifdef PANDA
// CAN2_EN
set_gpio_output(GPIOC, 13, !enabled);
#else
// CAN2_EN
set_gpio_output(GPIOB, 4, enabled);
#endif
#ifdef CAN3
} else if (CAN == CAN3) {
// CAN3_EN
set_gpio_output(GPIOA, 0, !enabled);
#endif
}
}
#ifdef PANDA
#define LED_RED 9
#define LED_GREEN 7
#define LED_BLUE 6
#else
#define LED_RED 10
#define LED_GREEN 11
#define LED_BLUE -1
#endif
void set_led(int led_num, int on) {
if (led_num == -1) return;
#ifdef PANDA
set_gpio_output(GPIOC, led_num, !on);
#else
set_gpio_output(GPIOB, led_num, !on);
#endif
}
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;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN;
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
#ifdef PANDA
RCC->APB1ENR |= RCC_APB1ENR_UART5EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
#ifdef CAN3
RCC->APB1ENR |= RCC_APB1ENR_CAN3EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_DACEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
//RCC->APB1ENR |= RCC_APB1ENR_TIM4EN;
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// needed?
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
}
void set_can_mode(int can, int use_gmlan) {
// http://www.bittiming.can-wiki.info/#bxCAN
// 24 MHz, sample point at 87.5%
uint32_t pclk = 24000;
uint32_t num_time_quanta = 16;
uint32_t prescaler;
CAN_TypeDef *CAN = NULL;
if (can == 2) CAN = CAN2;
#ifdef CAN3
else if (can == 3) CAN = CAN3;
#endif
if (CAN == NULL) return;
// connects to CAN2 xcvr or GMLAN xcvr
if (use_gmlan) {
if (can == 2) {
// B5,B6: disable normal mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: gmlan mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
/* GMLAN mode pins:
M0(B15) M1(B14) mode
=======================
0 0 sleep
1 0 100kbit
0 1 high voltage wakeup
1 1 33kbit (normal)
*/
} 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);
// B3,B4: enable gmlan mode
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3);
}
// put gmlan transceiver in normal mode
set_gpio_output(GPIOB, 14, 1);
set_gpio_output(GPIOB, 15, 1);
// 83.3 kbps
// prescaler = pclk / num_time_quanta * 10 / 833;
// 33.3 kbps
prescaler = pclk / num_time_quanta * 10 / 333;
} else {
if (can == 2) {
// B12,B13: disable gmlan mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
} else if (can == 3) {
if(revision == PANDA_REV_C){
// B3,B4: disable gmlan mode
set_gpio_mode(GPIOB, 3, MODE_INPUT);
set_gpio_mode(GPIOB, 4, MODE_INPUT);
}
// A8,A15: normal mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
}
// 500 kbps
prescaler = pclk / num_time_quanta / 500;
}
// init
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
// set speed
// seg 1: 13 time quanta, seg 2: 2 time quanta
CAN->BTR = (CAN_BTR_TS1_0 * 12) |
CAN_BTR_TS2_0 | (prescaler - 1);
// running
CAN->MCR = CAN_MCR_TTCM;
while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK);
}
// board specific
void gpio_init();
void gpio_init() {
// pull low to hold ESP in reset??
// enable OTG out tied to ground
GPIOA->ODR = 0;
GPIOB->ODR = 0;
GPIOA->PUPDR = 0;
//GPIOC->ODR = 0;
GPIOB->AFR[0] = 0;
GPIOB->AFR[1] = 0;
// C2,C3: analog mode, voltage and current sense
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// C8: FAN aka TIM3_CH4
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// turn off LEDs and set mode
set_led(LED_RED, 0);
set_led(LED_GREEN, 0);
set_led(LED_BLUE, 0);
// A11,A12: USB
set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS);
set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS);
GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12;
#ifdef PANDA
// enable started_alt on the panda
set_gpio_pullup(GPIOA, 1, PULL_UP);
// A2,A3: USART 2 for debugging
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2);
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2);
// A9,A10: USART 1 for talking to the ESP
set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1);
set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1);
// B12: GMLAN, ignition sense, pull up
set_gpio_pullup(GPIOB, 12, PULL_UP);
// A4,A5,A6,A7: setup SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1);
#endif
// B8,B9: CAN 1
set_can_enable(CAN1, 0);
#ifdef STM32F4
set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1);
set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1);
#else
set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1);
set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1);
#endif
// B5,B6: CAN 2
set_can_enable(CAN2, 0);
set_can_mode(2, 0);
// A8,A15: CAN3
#ifdef CAN3
set_can_enable(CAN3, 0);
set_can_mode(3, 0);
#endif
#ifdef PANDA
// K-line enable moved from B4->B7 to make room for GMLAN on CAN3
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);
set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5);
set_gpio_pullup(GPIOD, 2, PULL_UP);
// L-line enable
set_gpio_output(GPIOA, 14, 1);
// C10,C11: L-Line setup on USART 3
set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3);
set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3);
set_gpio_pullup(GPIOC, 11, PULL_UP);
#endif
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);
//set_gpio_output(GPIOA, 13, 1); //CTRL 1
//set_gpio_output(GPIOB, 2, 0); //CTRL 2
}
}

View File

@ -4,15 +4,14 @@
// out-state
// cancel button
#include "safety.h"
#include "can.h"
// all commands: brake and steering
// if controls_allowed
// allow all commands up to limit
// else
// block all commands that produce actuation
void honda__rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// state machine to enter and exit controls
// 0x1A6 for the ILX, 0x296 for the Civic Touring
if ((to_push->RIR>>21) == 0x1A6 || (to_push->RIR>>21) == 0x296) {
@ -51,7 +50,7 @@ void honda__rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
}
}
int honda__tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
// BRAKE: safety check
if ((to_send->RIR>>21) == 0x1FA) {
if (controls_allowed) {
@ -68,7 +67,7 @@ int honda__tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
} else {
to_send->RDLR &= 0xFFFF0000;
}
}
}
// GAS: safety check
if ((to_send->RIR>>21) == 0x200) {
@ -77,23 +76,13 @@ int honda__tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
} else {
to_send->RDLR &= 0xFFFF0000;
}
}
}
// 1 allows the message through
return hardwired;
}
int honda__tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired) {
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired) {
return hardwired;
}
void honda__init() {
controls_allowed = true;
}
const safety_hooks honda_hooks = {
.init = honda__init,
.rx = honda__rx_hook,
.tx = honda__tx_hook,
.tx_lin = honda__tx_lin_hook,
};

View File

@ -1,66 +0,0 @@
#include <stdint.h>
#include "config.h"
#include "libc.h"
void clock_init() {
// 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 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
// start PLL
RCC->CR |= RCC_CR_PLLON;
while ((RCC->CR & RCC_CR_PLLRDY) == 0);
// Configure Flash prefetch, Instruction cache, Data cache and wait state
// *** without this, it breaks ***
FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS;
// switch to PLL
RCC->CFGR |= RCC_CFGR_SW_PLL;
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL);
// *** running on PLL ***
}
void delay(int a) {
volatile int i;
for (i=0;i<a;i++);
}
void *memset(void *str, int c, unsigned int n) {
int i;
for (i = 0; i < n; i++) {
*((uint8_t*)str) = c;
++str;
}
return str;
}
void *memcpy(void *dest, const void *src, unsigned int n) {
int i;
// TODO: make not slow
for (i = 0; i < n; i++) {
((uint8_t*)dest)[i] = *(uint8_t*)src;
++src;
}
return dest;
}
int memcmp(const void * ptr1, const void * ptr2, unsigned int num) {
int i;
for (i = 0; i < num; i++) {
if ( ((uint8_t*)ptr1)[i] != ((uint8_t*)ptr2)[i] ) return -1;
}
return 0;
}

View File

@ -1,5 +1,3 @@
#ifndef PANDA_LIBC_H
#define PANDA_LIBC_H
#define min(a,b) \
({ __typeof__ (a) _a = (a); \
@ -13,14 +11,65 @@
// **** shitty libc ****
void clock_init();
void clock_init() {
// enable external oscillator
RCC->CR |= RCC_CR_HSEON;
while ((RCC->CR & RCC_CR_HSERDY) == 0);
void delay(int a);
// divide shit
RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4;
#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
void *memset(void *str, int c, unsigned int n);
// start PLL
RCC->CR |= RCC_CR_PLLON;
while ((RCC->CR & RCC_CR_PLLRDY) == 0);
void *memcpy(void *dest, const void *src, unsigned int n);
// Configure Flash prefetch, Instruction cache, Data cache and wait state
// *** without this, it breaks ***
FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS;
int memcmp(const void * ptr1, const void * ptr2, unsigned int num);
// switch to PLL
RCC->CFGR |= RCC_CFGR_SW_PLL;
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL);
#endif
// *** running on PLL ***
}
void delay(int a) {
volatile int i;
for (i=0;i<a;i++);
}
void *memset(void *str, int c, unsigned int n) {
int i;
for (i = 0; i < n; i++) {
*((uint8_t*)str) = c;
++str;
}
return str;
}
void *memcpy(void *dest, const void *src, unsigned int n) {
int i;
// TODO: make not slow
for (i = 0; i < n; i++) {
((uint8_t*)dest)[i] = *(uint8_t*)src;
++src;
}
return dest;
}
int memcmp(const void * ptr1, const void * ptr2, unsigned int num) {
int i;
for (i = 0; i < num; i++) {
if ( ((uint8_t*)ptr1)[i] != ((uint8_t*)ptr2)[i] ) return -1;
}
return 0;
}

View File

@ -1,21 +1,140 @@
#include "config.h"
#include "early.h"
#include "obj/gitversion.h"
#include "uart.h"
#include "can.h"
#include "libc.h"
#include "gpio.h"
#include "adc.h"
#include "timer.h"
#include "usb.h"
#include "spi.h"
#include "safety.h"
#define NULL ((void*)0)
// assign CAN numbering
// old: CAN1 = 1 CAN2 = 0
// panda: CAN1 = 0 CAN2 = 1 CAN3 = 4
#ifdef PANDA
int can_numbering[] = {0,1,4};
#else
int can_numbering[] = {1,0,-1};
#endif
// can forwards FROM -> TO
#define CAN_MAX 3
int can_forwarding[] = {-1,-1,-1};
// *** end config ***
#include "obj/gitversion.h"
// debug safety check: is controls allowed?
int controls_allowed = 0;
int started = 0;
int can_live = 0, pending_can_live = 0;
// optional features
int gas_interceptor_detected = 0;
int started_signal_detected = 0;
// detect high on UART
// TODO: check for UART high
int did_usb_enumerate = 0;
// Declare puts to supress warning
int puts ( const char * str );
// ********************* instantiate queues *********************
typedef struct {
uint32_t w_ptr;
uint32_t r_ptr;
uint32_t fifo_size;
CAN_FIFOMailBox_TypeDef *elems;
} can_ring;
#define can_buffer(x, size) \
CAN_FIFOMailBox_TypeDef elems_##x[size]; \
can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x };
can_buffer(rx_q, 0x1000)
can_buffer(tx1_q, 0x100)
can_buffer(tx2_q, 0x100)
can_buffer(tx3_q, 0x100)
// ********************* interrupt safe queue *********************
int pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
if (q->w_ptr != q->r_ptr) {
*elem = q->elems[q->r_ptr];
if ((q->r_ptr + 1) == q->fifo_size) q->r_ptr = 0;
else q->r_ptr += 1;
return 1;
}
return 0;
}
int push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
uint32_t next_w_ptr;
if ((q->w_ptr + 1) == q->fifo_size) next_w_ptr = 0;
else next_w_ptr = q->w_ptr + 1;
if (next_w_ptr != q->r_ptr) {
q->elems[q->w_ptr] = *elem;
q->w_ptr = next_w_ptr;
return 1;
}
puts("push failed!\n");
return 0;
}
// ***************************** serial port queues *****************************
#define FIFO_SIZE 0x100
typedef struct uart_ring {
uint8_t w_ptr_tx;
uint8_t r_ptr_tx;
uint8_t elems_tx[FIFO_SIZE];
uint8_t w_ptr_rx;
uint8_t r_ptr_rx;
uint8_t elems_rx[FIFO_SIZE];
USART_TypeDef *uart;
void (*callback)(struct uart_ring*);
} uart_ring;
int getc(uart_ring *q, char *elem);
int putc(uart_ring *q, char elem);
// esp = USART1
uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART1 };
// lin1, K-LINE = UART5
// lin2, L-LINE = USART3
uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = UART5 };
uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART3 };
// debug = USART2
void debug_ring_callback(uart_ring *ring);
uart_ring debug_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART2,
.callback = debug_ring_callback};
uart_ring *get_ring_by_number(int a) {
switch(a) {
case 0:
return &debug_ring;
case 1:
return &esp_ring;
case 2:
return &lin1_ring;
case 3:
return &lin2_ring;
default:
return NULL;
}
}
void accord_framing_callback(uart_ring *q) {
uint8_t r_ptr_rx_tmp = q->r_ptr_rx;
int sof1 = -1;
@ -77,6 +196,264 @@ void accord_framing_callback(uart_ring *q) {
}
}
void debug_ring_callback(uart_ring *ring) {
char rcv;
while (getc(ring, &rcv)) {
putc(ring, rcv);
// jump to DFU flash
if (rcv == 'z') {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
}
if (rcv == 'x') {
// normal reset
NVIC_SystemReset();
}
}
}
// ***************************** serial port *****************************
void uart_ring_process(uart_ring *q) {
// TODO: check if external serial is connected
int sr = q->uart->SR;
if (q->w_ptr_tx != q->r_ptr_tx) {
if (sr & USART_SR_TXE) {
q->uart->DR = q->elems_tx[q->r_ptr_tx];
q->r_ptr_tx += 1;
} else {
// push on interrupt later
q->uart->CR1 |= USART_CR1_TXEIE;
}
} else {
// nothing to send
q->uart->CR1 &= ~USART_CR1_TXEIE;
}
if (sr & USART_SR_RXNE) {
uint8_t c = q->uart->DR; // TODO: can drop packets
uint8_t next_w_ptr = q->w_ptr_rx + 1;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = c;
q->w_ptr_rx = next_w_ptr;
if (q->callback) q->callback(q);
}
}
}
// interrupt boilerplate
void USART1_IRQHandler(void) {
NVIC_DisableIRQ(USART1_IRQn);
uart_ring_process(&esp_ring);
NVIC_EnableIRQ(USART1_IRQn);
}
void USART2_IRQHandler(void) {
NVIC_DisableIRQ(USART2_IRQn);
uart_ring_process(&debug_ring);
NVIC_EnableIRQ(USART2_IRQn);
}
void USART3_IRQHandler(void) {
NVIC_DisableIRQ(USART3_IRQn);
uart_ring_process(&lin2_ring);
NVIC_EnableIRQ(USART3_IRQn);
}
void UART5_IRQHandler(void) {
NVIC_DisableIRQ(UART5_IRQn);
uart_ring_process(&lin1_ring);
NVIC_EnableIRQ(UART5_IRQn);
}
int getc(uart_ring *q, char *elem) {
if (q->w_ptr_rx != q->r_ptr_rx) {
*elem = q->elems_rx[q->r_ptr_rx];
q->r_ptr_rx += 1;
return 1;
}
return 0;
}
int injectc(uart_ring *q, char elem) {
uint8_t next_w_ptr = q->w_ptr_rx + 1;
int ret = 0;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = elem;
q->w_ptr_rx = next_w_ptr;
ret = 1;
}
return ret;
}
int putc(uart_ring *q, char elem) {
uint8_t next_w_ptr = q->w_ptr_tx + 1;
int ret = 0;
if (next_w_ptr != q->r_ptr_tx) {
q->elems_tx[q->w_ptr_tx] = elem;
q->w_ptr_tx = next_w_ptr;
ret = 1;
}
uart_ring_process(q);
return ret;
}
// ********************* includes *********************
#include "libc.h"
#include "gpio.h"
#include "uart.h"
#include "adc.h"
#include "timer.h"
#include "usb.h"
#include "can.h"
#include "spi.h"
void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired);
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired);
#ifdef PANDA_SAFETY
#include "panda_safety.h"
#else
#include "honda_safety.h"
#endif
// ***************************** CAN *****************************
void process_can(CAN_TypeDef *CAN, can_ring *can_q, int can_number) {
#ifdef DEBUG
puts("process CAN TX\n");
#endif
// add successfully transmitted message to my fifo
if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) {
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sTxMailBox[0].TIR;
to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) | ((can_number+2) << 4);
to_push.RDLR = CAN->sTxMailBox[0].TDLR;
to_push.RDHR = CAN->sTxMailBox[0].TDHR;
push(&can_rx_q, &to_push);
}
// check for empty mailbox
CAN_FIFOMailBox_TypeDef to_send;
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
if (pop(can_q, &to_send)) {
// only send if we have received a packet
CAN->sTxMailBox[0].TDLR = to_send.RDLR;
CAN->sTxMailBox[0].TDHR = to_send.RDHR;
CAN->sTxMailBox[0].TDTR = to_send.RDTR;
CAN->sTxMailBox[0].TIR = to_send.RIR;
}
}
// clear interrupt
CAN->TSR |= CAN_TSR_RQCP0;
}
// send more, possible for these to not trigger?
void CAN1_TX_IRQHandler() {
process_can(CAN1, &can_tx1_q, can_numbering[0]);
}
void CAN2_TX_IRQHandler() {
process_can(CAN2, &can_tx2_q, can_numbering[1]);
}
#ifdef CAN3
void CAN3_TX_IRQHandler() {
process_can(CAN3, &can_tx3_q, can_numbering[2]);
}
#endif
void send_can(CAN_FIFOMailBox_TypeDef *to_push, int flags);
// CAN receive handlers
// blink blue when we are receiving CAN messages
void can_rx(CAN_TypeDef *CAN, int can_index) {
int can_number = can_numbering[can_index];
while (CAN->RF0R & CAN_RF0R_FMP0) {
// can is live
pending_can_live = 1;
// add to my fifo
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sFIFOMailBox[0].RIR;
to_push.RDTR = CAN->sFIFOMailBox[0].RDTR;
to_push.RDLR = CAN->sFIFOMailBox[0].RDLR;
to_push.RDHR = CAN->sFIFOMailBox[0].RDHR;
// forwarding (panda only)
#ifdef PANDA
if (can_forwarding[can_index] != -1 && can_numbering[can_forwarding[can_index]] != -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;
send_can(&to_send, can_numbering[can_forwarding[can_index]]);
}
#endif
// modify RDTR for our API
to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (can_number << 4);
safety_rx_hook(&to_push);
#ifdef PANDA
set_led(LED_GREEN, 1);
#endif
push(&can_rx_q, &to_push);
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_RX0_IRQHandler() {
//puts("CANRX1");
//delay(10000);
can_rx(CAN1, 0);
}
void CAN2_RX0_IRQHandler() {
//puts("CANRX0");
//delay(10000);
can_rx(CAN2, 1);
}
#ifdef CAN3
void CAN3_RX0_IRQHandler() {
//puts("CANRX0");
//delay(10000);
can_rx(CAN3, 2);
}
#endif
void CAN1_SCE_IRQHandler() {
//puts("CAN1_SCE\n");
can_sce(CAN1);
}
void CAN2_SCE_IRQHandler() {
//puts("CAN2_SCE\n");
can_sce(CAN2);
}
#ifdef CAN3
void CAN3_SCE_IRQHandler() {
//puts("CAN3_SCE\n");
can_sce(CAN3);
}
#endif
// ***************************** USB port *****************************
int get_health_pkt(void *dat) {
@ -103,7 +480,7 @@ int get_health_pkt(void *dat) {
health->started_alt = 0;
#endif
health->controls_allowed = is_output_enabled();
health->controls_allowed = controls_allowed;
health->gas_interceptor_detected = gas_interceptor_detected;
health->started_signal_detected = started_signal_detected;
@ -114,20 +491,6 @@ void set_fan_speed(int fan_speed) {
TIM3->CCR3 = fan_speed;
}
void usb_cb_ep0_out(USB_Setup_TypeDef *setup, uint8_t *usbdata, int hardwired) {
if (setup->b.bRequest == 0xde) {
puts("Setting baud rate from usb\n");
uint32_t bitrate = *(int*)usbdata;
uint16_t canb_id = setup->b.wValue.w;
if (can_ports[canb_id].gmlan)
can_ports[canb_id].gmlan_bitrate = bitrate;
else
can_ports[canb_id].bitrate = bitrate;
can_init(canb_id);
}
}
int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) {
CAN_FIFOMailBox_TypeDef *reply = (CAN_FIFOMailBox_TypeDef *)usbdata;;
@ -148,9 +511,44 @@ void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) {
}
}
void send_can(CAN_FIFOMailBox_TypeDef *to_push, int flags) {
int i;
CAN_TypeDef *CAN;
can_ring *can_q;
if (flags == can_numbering[0]) {
CAN = CAN1;
can_q = &can_tx1_q;
} else if (flags == can_numbering[1]) {
CAN = CAN2;
can_q = &can_tx2_q;
#ifdef CAN3
} else if (flags == can_numbering[2]) {
CAN = CAN3;
can_q = &can_tx3_q;
#endif
} else if (flags == 8 || flags == 9) {
// fake LIN as CAN
uart_ring *lin_ring = (flags == 8) ? &lin1_ring : &lin2_ring;
for (i = 0; i < min(8, to_push->RDTR & 0xF); i++) {
putc(lin_ring, ((uint8_t*)&to_push->RDLR)[i]);
}
return;
} else {
// no crash
return;
}
// add CAN packet to send queue
// bus number isn't passed through
to_push->RDTR &= 0xF;
push(can_q, to_push);
// flags = can_number
process_can(CAN, can_q, flags);
}
// send on CAN
void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {
puts("usb_cb_ep3_out called\n");
int dpkt = 0;
for (dpkt = 0; dpkt < len; dpkt += 0x10) {
uint32_t *tf = (uint32_t*)(&usbdata[dpkt]);
@ -162,13 +560,21 @@ void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {
to_push.RDTR = tf[1];
to_push.RIR = tf[0];
uint8_t canid = (to_push.RDTR >> 4) & 0xF;
int flags = (to_push.RDTR >> 4) & 0xF;
if (safety_tx_hook(&to_push, hardwired)) {
send_can(&to_push, canid);
send_can(&to_push, flags);
}
}
}
void usb_cb_enumeration_complete() {
// power down the ESP
// this doesn't work and makes the board unflashable
// because the ESP spews shit on serial on startup
//GPIOC->ODR &= ~(1 << 14);
did_usb_enumerate = 1;
}
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
int resp_len = 0;
uart_ring *ur = NULL;
@ -235,75 +641,31 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
}
break;
case 0xdb: // toggle GMLAN
puts("Toggle GMLAN canid: ");
puth(setup->b.wValue.w);
uint16_t canid = setup->b.wValue.w;
bool gmlan_enable = setup->b.wIndex.w;
puth(canid);
puts(" mode ");
puth(gmlan_enable);
puts("\n");
if (canid >= CAN_MAX) {
puts(" !!Out of range!!\n");
return -1;
if (setup->b.wIndex.w == 3) {
set_can_mode(2, 0);
set_can_mode(3, setup->b.wValue.w);
} else {
set_can_mode(3, 0);
set_can_mode(2, setup->b.wValue.w);
}
can_port_desc *port = &can_ports[canid];
//puts(" gmlan_support ");
//puth(port->gmlan_support);
//puts(" mode ");
//puth(gmlan_enable);
//puts("\n");
//Fail if canid doesn't support gmlan
if (!port->gmlan_support) {
puts(" !!Unsupported!!\n");
return -1;
}
//ACK the USB pipe but don't do anything; nothing to do.
if (port->gmlan == gmlan_enable) {
puts(" ~~Nochange~~.\n");
break;
}
// Check to see if anyther canid is acting as gmlan, disable it.
set_can_mode(canid, gmlan_enable);
puts(" Done\n");
break;
case 0xdc: // set controls allowed / safety policy
set_safety_mode(setup->b.wValue.w);
for(i=0; i < CAN_MAX; i++)
can_init(i);
case 0xdc: // set controls allowed
controls_allowed = setup->b.wValue.w == 0x1337;
// take CAN out of SILM, careful with speed!
can_init(CAN1, 0);
can_init(CAN2, 0);
#ifdef CAN3
can_init(CAN3, 0);
#endif
break;
case 0xdd: // enable can forwarding
if (setup->b.wValue.w < CAN_MAX) { //Set forwarding
can_ports[setup->b.wValue.w].forwarding = setup->b.wIndex.w;
} else if (setup->b.wValue.w == 0xFF) { //Clear Forwarding
can_ports[setup->b.wValue.w].forwarding = -1;
} else
return -1;
break;
case 0xde: // Set Can bitrate
if (!(setup->b.wValue.w < CAN_MAX && setup->b.wLength.w == 4))
return -1;
break;
case 0xdf: // Get Can bitrate
if (setup->b.wValue.w < CAN_MAX) {
if(can_ports[setup->b.wValue.w].gmlan){
memcpy(resp, (void *)&can_ports[setup->b.wValue.w].gmlan_bitrate, 4);
}else{
memcpy(resp, (void *)&can_ports[setup->b.wValue.w].bitrate, 4);
if (setup->b.wValue.w != 0 && setup->b.wValue.w <= CAN_MAX) {
// 0 sets it to -1
if (setup->b.wIndex.w <= CAN_MAX) {
can_forwarding[setup->b.wValue.w-1] = setup->b.wIndex.w-1;
}
resp_len = 4;
break;
}
puts("Invalid num\n");
return -1;
break;
case 0xe0: // uart read
ur = get_ring_by_number(setup->b.wValue.w);
if (!ur) break;
@ -353,11 +715,6 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
if (!ur) break;
uart_set_baud(ur->uart, (int)setup->b.wIndex.w*300);
break;
case 0xe5: // Set CAN loopback (for testing)
can_loopback = (setup->b.wValue.w > 0);
for(i=0; i < CAN_MAX; i++)
can_init(i);
break;
case 0xf0: // k-line wValue pulse on uart2
if (setup->b.wValue.w == 1) {
GPIOC->ODR &= ~(1 << 10);
@ -394,11 +751,12 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
puts("NO HANDLER ");
puth(setup->b.bRequest);
puts("\n");
return -1;
break;
}
return resp_len;
}
void OTG_FS_IRQHandler(void) {
NVIC_DisableIRQ(OTG_FS_IRQn);
//__disable_irq();
@ -419,9 +777,7 @@ int spi_buf_count = 0;
int spi_total_count = 0;
uint8_t spi_tx_buf[0x44];
//TODO Jessy: Audit for overflows
void handle_spi(uint8_t *data, int len) {
USB_Setup_TypeDef *fake_setup;
memset(spi_tx_buf, 0xaa, 0x44);
// data[0] = endpoint
// data[2] = length
@ -431,11 +787,7 @@ void handle_spi(uint8_t *data, int len) {
switch (data[0]) {
case 0:
// control transfer
fake_setup = (USB_Setup_TypeDef *)(data+4);
*resp_len = usb_cb_control_msg(fake_setup, spi_tx_buf+4, 0);
// Handle CTRL writes with data
if (*resp_len == 0 && (fake_setup->b.bmRequestType & 0x80) == 0 && fake_setup->b.wLength.w)
usb_cb_ep0_out(fake_setup, data+4+sizeof(USB_Setup_TypeDef), 0);
*resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), spi_tx_buf+4, 0);
break;
case 1:
// ep 1, read
@ -496,8 +848,6 @@ void __initialize_hardware_early() {
}
int main() {
int i;
// init devices
clock_init();
periph_init();
@ -517,11 +867,27 @@ int main() {
uart_init(USART3, 10400);
USART3->CR2 |= USART_CR2_LINEN;
/*puts("EXTERNAL");
puth(has_external_debug_serial);
puts("\n");*/
// enable USB
usb_init();
for(i=0; i < CAN_MAX; i++)
can_init(i);
// default to silent mode to prevent issues with Ford
#ifdef PANDA_SAFETY
can_init(CAN1, 1);
can_init(CAN2, 1);
#ifdef CAN3
can_init(CAN3, 1);
#endif
#else
can_init(CAN1, 0);
can_init(CAN2, 0);
#ifdef CAN3
can_init(CAN3, 0);
#endif
#endif
adc_init();
@ -544,6 +910,7 @@ int main() {
// set PWM
set_fan_speed(65535);
puts("**** INTERRUPTS ON ****\n");
__disable_irq();
@ -594,11 +961,21 @@ int main() {
// reset this every 16th pass
if ((cnt&0xF) == 0) pending_can_live = 0;
/*#ifdef DEBUG
puts("** blink ");
puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" ");
puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" ");
puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n");
#endif*/
/*puts("voltage: "); puth(adc_get(ADCCHAN_VOLTAGE)); puts(" ");
puts("current: "); puth(adc_get(ADCCHAN_CURRENT)); puts("\n");*/
// set LED to be controls allowed, blue on panda, green on legacy
#ifdef PANDA
set_led(LED_BLUE, is_output_enabled());
set_led(LED_BLUE, controls_allowed);
#else
set_led(LED_GREEN, is_output_enabled());
set_led(LED_GREEN, controls_allowed);
#endif
// blink the red LED
@ -612,6 +989,13 @@ int main() {
set_led(LED_GREEN, 0);
#endif
#ifdef ENABLE_SPI
/*if (spi_buf_count > 0) {
hexdump(spi_buf, spi_buf_count);
spi_buf_count = 0;
}*/
#endif
// started logic
#ifdef PANDA
int started_signal = (GPIOB->IDR & (1 << 12)) == 0;

View File

View File

@ -0,0 +1,13 @@
// pandas by default do not allow sending in this firmware
void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
}
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
return hardwired && controls_allowed;
}
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired) {
return hardwired && controls_allowed;
}

View File

@ -1,39 +0,0 @@
#ifndef PANDA_REV_H
#define PANDA_REV_H
enum rev {
REV_A,
REV_B,
REV_C
};
#ifdef STM32F4
#define PANDA
#endif
#ifdef PANDA
#include "stm32f4xx.h"
#include "stm32f4xx_hal_gpio_ex.h"
#else
#include "stm32f2xx.h"
#include "stm32f2xx_hal_gpio_ex.h"
#endif
#ifdef PANDA
#define ENABLE_CURRENT_SENSOR
#define ENABLE_SPI
#endif
#ifdef PANDA
#define LED_RED 9
#define LED_GREEN 7
#define LED_BLUE 6
#else
#define LED_RED 10
#define LED_GREEN 11
#define LED_BLUE -1
#endif
#define FREQ 24000000 // 24 mhz
#endif

View File

@ -1,96 +0,0 @@
#include "safety.h"
int controls_allowed = 0;
// Include the actual safety policies.
#include "safety_honda.h"
//Fields commonly used by various security policies.
int gas_interceptor_detected = 0;
void default__rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {}
void nooutput__init() {
controls_allowed = false;
}
int nooutput__tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
return false;
}
int nooutput__tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired) {
return false;
}
void alloutput__init() {
controls_allowed = true;
}
int alloutput__tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired) {
return hardwired;
}
int alloutput__tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired) {
return hardwired;
}
const safety_hooks nooutput_hooks = {
.init = nooutput__init,
.rx = default__rx_hook,
.tx = alloutput__tx_hook,
.tx_lin = alloutput__tx_lin_hook,
};
const safety_hooks alloutput_hooks = {
.init = alloutput__init,
.rx = default__rx_hook,
.tx = alloutput__tx_hook,
.tx_lin = alloutput__tx_lin_hook,
};
const safety_hooks *current_hooks = &nooutput_hooks;
void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push){
current_hooks->rx(to_push);
}
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired){
return current_hooks->tx(to_send, hardwired);
}
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired){
return current_hooks->tx_lin(lin_num, data, len, hardwired);
}
typedef struct {
uint16_t id;
const safety_hooks *hooks;
} safety_hook_config;
const safety_hook_config safety_hook_registry[] = {
{0x0000, &nooutput_hooks},
{0x0001, &honda_hooks},
{0x1337, &alloutput_hooks},
};
#define HOOK_CONFIG_COUNT (sizeof(safety_hook_registry)/sizeof(safety_hook_config))
// Accessor method to discourage direct access outside of safety files.
// Should be inlined by compiler.
bool is_output_enabled(){
return controls_allowed;
}
int set_safety_mode(uint16_t mode){
int i;
for(i = 0; i < HOOK_CONFIG_COUNT; i++){
if(safety_hook_registry[i].id == mode){
current_hooks = safety_hook_registry[i].hooks;
current_hooks->init();
return 0;
}
}
return -1;
}

View File

@ -1,27 +0,0 @@
#ifndef PANDA_SAFETY_H
#define PANDA_SAFETY_H
#include "can.h"
void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send, int hardwired);
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len, int hardwired);
typedef void (*safety_hook_init)();
typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push);
typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send, int hardwired);
typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len, int hardwired);
typedef struct {
safety_hook_init init;
rx_hook rx;
tx_hook tx;
tx_lin_hook tx_lin;
} safety_hooks;
bool is_output_enabled();
int set_safety_mode(uint16_t mode);
extern int gas_interceptor_detected;
#endif

View File

@ -1,51 +0,0 @@
#include "spi.h"
#include "rev.h"
void spi_init() {
//puts("SPI init\n");
SPI1->CR1 = SPI_CR1_SPE;
// enable SPI interrupts
//SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE;
SPI1->CR2 = SPI_CR2_RXNEIE;
}
void spi_tx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_TXDMAEN;
DMA2_Stream3->CR &= ~DMA_SxCR_EN;
// DMA2, stream 3, channel 3
DMA2_Stream3->M0AR = (uint32_t)addr;
DMA2_Stream3->NDTR = len;
DMA2_Stream3->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, memory -> periph, enable
DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 |
DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN;
DMA2_Stream3->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_TXDMAEN;
}
void spi_rx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_RXDMAEN;
DMA2_Stream2->CR &= ~DMA_SxCR_EN;
// drain the bus
uint8_t dat = SPI1->DR;
(void)dat;
// DMA2, stream 2, channel 3
DMA2_Stream2->M0AR = (uint32_t)addr;
DMA2_Stream2->NDTR = len;
DMA2_Stream2->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, periph -> memory, enable
DMA2_Stream2->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 |
DMA_SxCR_MINC | DMA_SxCR_EN;
DMA2_Stream2->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_RXDMAEN;
}

View File

@ -1,9 +1,47 @@
#ifndef PANDA_SPI_H
#define PANDA_SPI_H
void spi_init() {
//puts("SPI init\n");
SPI1->CR1 = SPI_CR1_SPE;
void spi_init();
// enable SPI interrupts
//SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE;
SPI1->CR2 = SPI_CR2_RXNEIE;
}
void spi_tx_dma(void *addr, int len);
void spi_rx_dma(void *addr, int len);
void spi_tx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_TXDMAEN;
DMA2_Stream3->CR &= ~DMA_SxCR_EN;
// DMA2, stream 3, channel 3
DMA2_Stream3->M0AR = (uint32_t)addr;
DMA2_Stream3->NDTR = len;
DMA2_Stream3->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, memory -> periph, enable
DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN;
DMA2_Stream3->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_TXDMAEN;
}
void spi_rx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_RXDMAEN;
DMA2_Stream2->CR &= ~DMA_SxCR_EN;
// drain the bus
uint8_t dat = SPI1->DR;
(void)dat;
// DMA2, stream 2, channel 3
DMA2_Stream2->M0AR = (uint32_t)addr;
DMA2_Stream2->NDTR = len;
DMA2_Stream2->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, periph -> memory, enable
DMA2_Stream2->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_EN;
DMA2_Stream2->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_RXDMAEN;
}
#endif

View File

@ -1,5 +1,3 @@
#include "libc.h"
/*void lock_bootloader() {
if (FLASH->OPTCR & FLASH_OPTCR_nWRP_0) {
FLASH->OPTKEYR = 0x08192A3B;

View File

@ -4,3 +4,4 @@ void timer_init(TIM_TypeDef *TIM, int psc) {
TIM->CR1 = TIM_CR1_CEN;
TIM->SR = 0;
}

View File

@ -11,9 +11,12 @@ def enter_download_mode(device):
try:
handle.controlWrite(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd1, 0, 0, b'')
except Exception:
pass
time.sleep(1)
except usb1.USBErrorIO as e:
print("Device download mode enabled.")
time.sleep(1)
else:
print("Device failed to enter download mode.")
sys.exit(1)
def find_first_panda(context=None):
context = context or usb1.USBContext()

View File

@ -1,209 +0,0 @@
#include <stdint.h>
#include "config.h"
#include "uart.h"
#include "early.h"
void debug_ring_callback(uart_ring *ring) {
char rcv;
while (getc(ring, &rcv)) {
putc(ring, rcv);
// jump to DFU flash
if (rcv == 'z') {
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
NVIC_SystemReset();
}
if (rcv == 'x') {
// normal reset
NVIC_SystemReset();
}
}
}
// ***************************** serial port queues *****************************
// debug = USART2
uart_ring debug_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART2,
.callback = debug_ring_callback};
// esp = USART1
uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART1 };
// lin1, K-LINE = UART5
// lin2, L-LINE = USART3
uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = UART5 };
uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART3 };
uart_ring *get_ring_by_number(int a) {
switch(a) {
case 0:
return &debug_ring;
case 1:
return &esp_ring;
case 2:
return &lin1_ring;
case 3:
return &lin2_ring;
default:
return NULL;
}
}
void uart_set_baud(USART_TypeDef *u, int baud) {
if (u == USART1) {
// USART1 is on APB2
u->BRR = __USART_BRR(48000000, baud);
} else {
u->BRR = __USART_BRR(24000000, baud);
}
}
void uart_init(USART_TypeDef *u, int baud) {
// enable uart and tx+rx mode
u->CR1 = USART_CR1_UE;
uart_set_baud(u, baud);
u->CR1 |= USART_CR1_TE | USART_CR1_RE;
//u->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1;
//u->CR2 = USART_CR2_STOP_0;
// ** UART is ready to work **
// enable interrupts
u->CR1 |= USART_CR1_RXNEIE;
}
void putch(const char a) {
if (has_external_debug_serial) {
putc(&debug_ring, a);
} else {
injectc(&debug_ring, a);
}
}
int puts(const char *a) {
for (;*a;a++) {
if (*a == '\n') putch('\r');
putch(*a);
}
return 0;
}
void puth(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 28; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void puth2(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 4; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void hexdump(void *a, int l) {
int i;
for (i=0;i<l;i++) {
if (i != 0 && (i&0xf) == 0) puts("\n");
puth2(((unsigned char*)a)[i]);
puts(" ");
}
puts("\n");
}
int getc(uart_ring *q, char *elem) {
if (q->w_ptr_rx != q->r_ptr_rx) {
*elem = q->elems_rx[q->r_ptr_rx];
q->r_ptr_rx += 1;
return 1;
}
return 0;
}
int putc(uart_ring *q, char elem) {
uint8_t next_w_ptr = q->w_ptr_tx + 1;
int ret = 0;
if (next_w_ptr != q->r_ptr_tx) {
q->elems_tx[q->w_ptr_tx] = elem;
q->w_ptr_tx = next_w_ptr;
ret = 1;
}
uart_ring_process(q);
return ret;
}
int injectc(uart_ring *q, char elem) {
uint8_t next_w_ptr = q->w_ptr_rx + 1;
int ret = 0;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = elem;
q->w_ptr_rx = next_w_ptr;
ret = 1;
}
return ret;
}
void uart_ring_process(uart_ring *q) {
// TODO: check if external serial is connected
int sr = q->uart->SR;
if (q->w_ptr_tx != q->r_ptr_tx) {
if (sr & USART_SR_TXE) {
q->uart->DR = q->elems_tx[q->r_ptr_tx];
q->r_ptr_tx += 1;
} else {
// push on interrupt later
q->uart->CR1 |= USART_CR1_TXEIE;
}
} else {
// nothing to send
q->uart->CR1 &= ~USART_CR1_TXEIE;
}
if (sr & USART_SR_RXNE) {
uint8_t c = q->uart->DR; // TODO: can drop packets
uint8_t next_w_ptr = q->w_ptr_rx + 1;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = c;
q->w_ptr_rx = next_w_ptr;
if (q->callback) q->callback(q);
}
}
}
// interrupt boilerplate
void USART1_IRQHandler(void) {
NVIC_DisableIRQ(USART1_IRQn);
uart_ring_process(&esp_ring);
NVIC_EnableIRQ(USART1_IRQn);
}
void USART2_IRQHandler(void) {
NVIC_DisableIRQ(USART2_IRQn);
uart_ring_process(&debug_ring);
NVIC_EnableIRQ(USART2_IRQn);
}
void USART3_IRQHandler(void) {
NVIC_DisableIRQ(USART3_IRQn);
uart_ring_process(&lin2_ring);
NVIC_EnableIRQ(USART3_IRQn);
}
void UART5_IRQHandler(void) {
NVIC_DisableIRQ(UART5_IRQn);
uart_ring_process(&lin1_ring);
NVIC_EnableIRQ(UART5_IRQn);
}

View File

@ -1,48 +1,70 @@
#ifndef PANDA_UART_H
#define PANDA_UART_H
#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_)))
#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100)
#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100)
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F))
#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_)))
#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100)
#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100)
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F))
void uart_set_baud(USART_TypeDef *u, int baud) {
if (u == USART1) {
// USART1 is on APB2
u->BRR = __USART_BRR(48000000, baud);
} else {
u->BRR = __USART_BRR(24000000, baud);
}
}
typedef struct uart_ring {
uint8_t w_ptr_tx;
uint8_t r_ptr_tx;
uint8_t elems_tx[FIFO_SIZE];
uint8_t w_ptr_rx;
uint8_t r_ptr_rx;
uint8_t elems_rx[FIFO_SIZE];
USART_TypeDef *uart;
void (*callback)(struct uart_ring*);
} uart_ring;
void uart_init(USART_TypeDef *u, int baud) {
// enable uart and tx+rx mode
u->CR1 = USART_CR1_UE;
uart_set_baud(u, baud);
u->CR1 |= USART_CR1_TE | USART_CR1_RE;
//u->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1;
//u->CR2 = USART_CR2_STOP_0;
// ** UART is ready to work **
extern int has_external_debug_serial;
// enable interrupts
u->CR1 |= USART_CR1_RXNEIE;
}
extern uart_ring debug_ring;
void putch(const char a) {
if (has_external_debug_serial) {
putc(&debug_ring, a);
} else {
injectc(&debug_ring, a);
}
}
uart_ring *get_ring_by_number(int a);
int puts(const char *a) {
for (;*a;a++) {
if (*a == '\n') putch('\r');
putch(*a);
}
return 0;
}
void uart_set_baud(USART_TypeDef *u, int baud);
void puth(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 28; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void uart_init(USART_TypeDef *u, int baud);
void puth2(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 4; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void putch(const char a);
void hexdump(void *a, int l) {
int i;
for (i=0;i<l;i++) {
if (i != 0 && (i&0xf) == 0) puts("\n");
puth2(((unsigned char*)a)[i]);
puts(" ");
}
puts("\n");
}
int puts(const char *a);
void puth(unsigned int i);
void puth2(unsigned int i);
void hexdump(void *a, int l);
int getc(uart_ring *q, char *elem);
int putc(uart_ring *q, char elem);
int injectc(uart_ring *q, char elem);
void uart_ring_process(uart_ring *q);
#endif

View File

@ -1,661 +0,0 @@
#include "config.h"
#include "usb.h"
#include "can.h"
#include "libc.h"
#include "uart.h"
// detect high on UART
// TODO: check for UART high
int did_usb_enumerate = 0;
uint8_t device_desc[] = {
DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x01, //Length, Type, bcdUSB
0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size
TOUSBORDER(USB_VID), // idVendor
TOUSBORDER(USB_PID), // idProduct
#ifdef STM32F4
0x00, 0x23, // bcdDevice
#else
0x00, 0x22, // bcdDevice
#endif
0x01, 0x02, // Manufacturer, Product
0x03, 0x01 // Serial Number, Num Configurations
};
uint8_t configuration_desc[] = {
DSCR_CONFIG_LEN, DSCR_CONFIG_TYPE, // Length, Type,
TOUSBORDER(0x0045), // Total Len (uint16)
0x01, 0x01, 0x00, // Num Interface, Config Value, Configuration
0xc0, 0x32, // Attributes, Max Power
// interface 0 ALT 0
DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type
0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval (NA)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// interface 0 ALT 1
DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type
0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x05, // Polling Interval (5 frames)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
};
uint8_t string_0_desc[] = {
0x04, DSCR_STRING_TYPE, 0x09, 0x04
};
uint16_t string_1_desc[] = {
0x0312,
'c', 'o', 'm', 'm', 'a', '.', 'a', 'i'
};
#ifdef PANDA
uint16_t string_2_desc[] = {
0x030c,
'p', 'a', 'n', 'd', 'a'
};
#else
uint16_t string_2_desc[] = {
0x030c,
'N', 'E', 'O', 'v', '1'
};
#endif
uint16_t string_3_desc[] = {
0x030a,
'n', 'o', 'n', 'e'
};
// current packet
USB_Setup_TypeDef setup;
uint8_t usbdata[0x100];
// Store the current interface alt setting.
int current_int0_alt_setting = 0;
void usb_cb_enumeration_complete() {
// power down the ESP
// this doesn't work and makes the board unflashable
// because the ESP spews shit on serial on startup
//GPIOC->ODR &= ~(1 << 14);
did_usb_enumerate = 1;
}
// packet read and write
void *USB_ReadPacket(void *dest, uint16_t len) {
uint32_t i=0;
uint32_t count32b = (len + 3) / 4;
for ( i = 0; i < count32b; i++, dest += 4 ) {
// packed?
*(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0);
}
return ((void *)dest);
}
void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) {
#ifdef DEBUG_USB
//puts("writing ");
//hexdump(src, len);
#endif
uint8_t numpacket = (len+(MAX_RESP_LEN-1))/MAX_RESP_LEN;
uint32_t count32b = 0, i = 0;
count32b = (len + 3) / 4;
// bullshit
USBx_INEP(ep)->DIEPTSIZ = ((numpacket << 19) & USB_OTG_DIEPTSIZ_PKTCNT) |
(len & USB_OTG_DIEPTSIZ_XFRSIZ);
USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
// load the FIFO
for (i = 0; i < count32b; i++, src += 4) {
USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src);
}
}
void USB_Stall_EP0(){
//TODO: Handle stalling both in and out requests.
//Check why INEP works for both in and out requests.
USBx_INEP(0)->DIEPCTL |= (USB_OTG_DIEPCTL_STALL | USB_OTG_DIEPCTL_EPENA);
//USBx_OUTEP(0)->DOEPCTL |= (USB_OTG_DOEPCTL_STALL | USB_OTG_DOEPCTL_EPENA);
}
void usb_reset() {
// unmask endpoint interrupts, so many sets
USBx_DEVICE->DAINT = 0xFFFFFFFF;
USBx_DEVICE->DAINTMSK = 0xFFFFFFFF;
//USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM);
// all interrupts for debugging
USBx_DEVICE->DIEPMSK = 0xFFFFFFFF;
USBx_DEVICE->DOEPMSK = 0xFFFFFFFF;
// clear interrupts
USBx_INEP(0)->DIEPINT = 0xFF;
USBx_OUTEP(0)->DOEPINT = 0xFF;
// unset the address
USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD;
// set up USB FIFOs
// RX start address is fixed to 0
USBx->GRXFSIZ = 0x40;
// 0x100 to offset past GRXFSIZ
USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40;
// EP1, massive
USBx->DIEPTXF[0] = (0x40 << 16) | 0x80;
// flush TX fifo
USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH);
// flush RX FIFO
USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH);
// no global NAK
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK;
// ready to receive setup packets
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8);
}
char to_hex_char(int a) {
if (a < 10) {
return '0' + a;
} else {
return 'a' + (a-10);
}
}
void usb_setup() {
int i;
int resp_len;
// setup packet is ready
switch (setup.b.bRequest) {
case USB_REQ_SET_CONFIGURATION:
// enable other endpoints, has to be here?
USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) |
USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP;
USBx_INEP(1)->DIEPINT = 0xFF;
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(2)->DOEPINT = 0xFF;
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(3)->DOEPINT = 0xFF;
// mark ready to receive
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
// TODO: is this the right place for this?
usb_cb_enumeration_complete();
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_ADDRESS:
// set now?
USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4);
#ifdef DEBUG_USB
puts(" set address\n");
#endif
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_GET_DESCRIPTOR:
switch (setup.b.wValue.bw.lsb) {
case USB_DESC_TYPE_DEVICE:
//puts(" writing device descriptor\n");
// setup transfer
USB_WritePacket(device_desc, min(sizeof(device_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
//puts("D");
break;
case USB_DESC_TYPE_CONFIGURATION:
USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_DESC_TYPE_STRING:
switch (setup.b.wValue.bw.msb) {
case 0:
USB_WritePacket((uint8_t*)string_0_desc, min(sizeof(string_0_desc), setup.b.wLength.w), 0);
break;
case 1:
USB_WritePacket((uint8_t*)string_1_desc, min(sizeof(string_1_desc), setup.b.wLength.w), 0);
break;
case 2:
USB_WritePacket((uint8_t*)string_2_desc, min(sizeof(string_2_desc), setup.b.wLength.w), 0);
break;
case 3:
#ifdef PANDA
resp[0] = 0x02 + 12*4;
resp[1] = 0x03;
// 96 bits = 12 bytes
for (i = 0; i < 12; i++){
uint8_t cc = ((uint8_t *)UID_BASE)[i];
resp[2 + i*4 + 0] = to_hex_char((cc>>4)&0xF);
resp[2 + i*4 + 1] = '\0';
resp[2 + i*4 + 2] = to_hex_char((cc>>0)&0xF);
resp[2 + i*4 + 3] = '\0';
}
USB_WritePacket(resp, min(resp[0], setup.b.wLength.w), 0);
#else
USB_WritePacket(string_3_desc, min(sizeof(string_3_desc), setup.b.wLength.w), 0);
#endif
break;
default:
// nothing
USB_WritePacket(0, 0, 0);
break;
}
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
default:
// nothing here?
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
}
break;
case USB_REQ_GET_STATUS:
// empty resp?
resp[0] = 0;
resp[1] = 0;
USB_WritePacket((void*)&resp, 2, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_INTERFACE:
// Store the alt setting number for IN EP behavior.
current_int0_alt_setting = setup.b.wValue.w;
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
//USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT
#ifdef DEBUG_USB
puts("Setting Interface Alt: ");
puth(current_int0_alt_setting);
puts("\n");
#endif
break;
default:
resp_len = usb_cb_control_msg(&setup, resp, 1);
if(resp_len == -1){
USB_Stall_EP0();
}else{
USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
}
void usb_init() {
// full speed PHY, do reset and remove power down
puth(USBx->GRSTCTL);
puts(" resetting PHY\n");
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0);
puts("AHB idle\n");
// reset PHY here
USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST);
puts("reset done\n");
// internal PHY, force device mode
USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD;
// slowest timings
USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
// power up the PHY
#ifdef STM32F4
USBx->GCCFG = USB_OTG_GCCFG_PWRDWN;
//USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN;
/* B-peripheral session valid override enable*/
USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL;
USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN;
#else
USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS;
#endif
// be a device, slowest timings
//USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL;
//USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
//USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL;
// **** for debugging, doesn't seem to work ****
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT;
// reset PHY clock
USBx_PCGCCTL = 0;
// enable the fancy OTG things
// DCFG_FRAME_INTERVAL_80 is 0
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP;
USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK;
//USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD;
//USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD;
// clear pending interrupts
USBx->GINTSTS = 0xBFFFFFFFU;
// setup USB interrupts
// all interrupts except TXFIFO EMPTY
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF);
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM);
//SRQ is when a 'session' starts.
USBx->GINTMSK = USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_OEPINT |
USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_USBRST |
USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM |
USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM;
USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT;
// DCTL startup value is 2 on new chip, 0 on old chip
// THIS IS FUCKING BULLSHIT
USBx_DEVICE->DCTL = 0;
}
// ***************************** USB port *****************************
void usb_irqhandler(void) {
//USBx->GINTMSK = 0;
unsigned int gintsts = USBx->GINTSTS;
unsigned int gotgint = USBx->GOTGINT;
unsigned int daint = USBx_DEVICE->DAINT;
// gintsts SUSPEND? 04008428
#ifdef DEBUG_USB
puts("USB interrupt (DAINT[EP]:");
puth(daint);
puts(" GINTSTS:");
puth(gintsts);
//puts(" GCCFG:");
//puth(USBx->GCCFG);
//puts(" GOTGINT:");
//puth(gotgint);
puts(")\n");
#endif
if (gintsts & USB_OTG_GINTSTS_CIDSCHG) {
puts("connector ID status change\n");
}
if (gintsts & USB_OTG_GINTSTS_ESUSP) {
puts("ESUSP detected\n");
}
if (gintsts & USB_OTG_GINTSTS_USBRST) {
puts("USB reset\n");
usb_reset();
}
if (gintsts & USB_OTG_GINTSTS_ENUMDNE) {
puts("enumeration done ");
// Full speed, ENUMSPD
puth(USBx_DEVICE->DSTS);
puts("\n");
}
if (gintsts & USB_OTG_GINTSTS_OTGINT) {
puts("OTG int:");
puth(USBx->GOTGINT);
puts("\n");
// getting ADTOCHG
//USBx->GOTGINT = USBx->GOTGINT;
}
// RX FIFO Has Data (OUT TRANSFER)
if (gintsts & USB_OTG_GINTSTS_RXFLVL) {
// 1. Read the Receive status pop register
volatile unsigned int rxst = USBx->GRXSTSP;
#ifdef DEBUG_USB
puts(" RX FIFO:");
puth(rxst);
puts(" status: ");
puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17);
puts(" len: ");
puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4);
puts("\n");
#endif
if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) { //OUT DATA PKT RECEIVED
int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM);
int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4;
USB_ReadPacket(&usbdata, len);
#ifdef DEBUG_USB
puts(" data ");
puth(len);
puts("\n");
hexdump(&usbdata, len);
#endif
if(endpoint == 0){
usb_cb_ep0_out(&setup, usbdata, 1);
}
if (endpoint == 2) {
usb_cb_ep2_out(usbdata, len, 1);
}
if (endpoint == 3) {
usb_cb_ep3_out(usbdata, len, 1);
}
} else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) {
USB_ReadPacket(&setup, 8);
#ifdef DEBUG_USB
puts(" setup ");
hexdump(&setup, 8);
puts("\n");
#endif
}
}
/*if (gintsts & USB_OTG_GINTSTS_HPRTINT) {
// host
puts("HPRT:");
puth(USBx_HOST_PORT->HPRT);
puts("\n");
if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) {
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST;
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET;
}
}*/
if ((gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) || (gintsts & USB_OTG_GINTSTS_GINAKEFF)) {
// no global NAK, why is this getting set?
#ifdef DEBUG_USB
puts("GLOBAL NAK\n");
#endif
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK;
}
if (gintsts & USB_OTG_GINTSTS_SRQINT) {
// we want to do "A-device host negotiation protocol" since we are the A-device
puts("start request\n");
puth(USBx->GOTGCTL);
puts("\n");
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD;
//USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA;
//USBx->GOTGCTL |= USB_OTG_GOTGCTL_SRQ;
}
// out endpoint hit
if (gintsts & USB_OTG_GINTSTS_OEPINT) {
#ifdef DEBUG_USB
puts(" 0:");
puth(USBx_OUTEP(0)->DOEPINT);
puts(" 2:");
puth(USBx_OUTEP(2)->DOEPINT);
puts(" 3:");
puth(USBx_OUTEP(3)->DOEPINT);
puts(" ");
puth(USBx_OUTEP(3)->DOEPCTL);
puts(" 4:");
puth(USBx_OUTEP(4)->DOEPINT);
puts(" OUT ENDPOINT\n");
#endif
if (USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) {
#ifdef DEBUG_USB
puts(" OUT2 PACKET XFRC\n");
#endif
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
}
if (USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET XFRC\n");
#endif
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
} else if (USBx_OUTEP(3)->DOEPINT & 0x2000) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET WTF\n");
#endif
// if NAK was set trigger this, unknown interrupt
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
} else if (USBx_OUTEP(3)->DOEPINT) {
puts("OUTEP3 error ");
puth(USBx_OUTEP(3)->DOEPINT);
puts("\n");
}
if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) {
// ready for next packet
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8);
}
// respond to setup packets
if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) {
#ifdef DEBUG_USB
puts("Processing SETUP\n");
#endif
usb_setup();
}
USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT;
USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT;
USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT;
}
// interrupt endpoint hit (Page 1221)
if (gintsts & USB_OTG_GINTSTS_IEPINT) {
#ifdef DEBUG_USB
puts(" ");
puth(USBx_INEP(0)->DIEPINT);
puts(" ");
puth(USBx_INEP(1)->DIEPINT);
puts(" IN ENDPOINT\n");
#endif
// Should likely check the EP of the IN request even if there is
// only one IN endpoint.
// No need to set NAK in OTG_DIEPCTL0 when nothing to send,
// Appears USB core automatically sets NAK. WritePacket clears it.
// Handle the two interface alternate settings. Setting 0 is has
// EP1 as bulk. Setting 1 has EP1 as interrupt. The code to handle
// these two EP variations are very similar and can be
// restructured for smaller code footprint. Keeping split out for
// now for clarity.
//TODO add default case. Should it NAK?
switch(current_int0_alt_setting){
case 0: ////// Bulk config
// *** IN token received when TxFIFO is empty
if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
if (can_rx_q.w_ptr != can_rx_q.r_ptr)
puts("Rx CAN bulk: There is CAN data to send.\n");
else
puts("Rx CAN bulk: No can data\n");
#ifdef DEBUG_USB
puts(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1);
}
break;
case 1: ////// Interrupt config
// Check if there is anything to actually send.
if (can_rx_q.w_ptr != can_rx_q.r_ptr) {
// *** IN token received when TxFIFO is empty
if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
#ifdef DEBUG_USB
puts(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1);
}
}
break;
}
// clear interrupts
USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0?
USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT;
}
// clear all interrupts we handled
USBx_DEVICE->DAINT = daint;
USBx->GOTGINT = gotgint;
USBx->GINTSTS = gintsts;
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF);
}

View File

@ -1,6 +1,3 @@
#ifndef PANDA_USB_H
#define PANDA_USB_H
// **** supporting defines ****
typedef struct
@ -9,7 +6,8 @@ typedef struct
}
USB_OTG_HostPortTypeDef;
#define USBx USB_OTG_FS
USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS;
#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE))
#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE))
#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE))
@ -80,14 +78,12 @@ typedef union _USB_Setup
USB_Setup_TypeDef;
// interfaces
void usb_cb_enumeration_complete();
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *usbdata, int hardwired);
void usb_cb_ep0_out(USB_Setup_TypeDef *setup, uint8_t *usbdata, int hardwired);
int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired);
void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired);
void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired);
extern int did_usb_enumerate;
// descriptor types
// same as setupdat.h
#define DSCR_DEVICE_TYPE 1
@ -113,33 +109,619 @@ extern int did_usb_enumerate;
#define TOUSBORDER(num)\
(num&0xFF), ((num>>8)&0xFF)
uint8_t device_desc[] = {
DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x01, //Length, Type, bcdUSB
0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size
TOUSBORDER(USB_VID), // idVendor
TOUSBORDER(USB_PID), // idProduct
#ifdef STM32F4
0x00, 0x23, // bcdDevice
#else
0x00, 0x22, // bcdDevice
#endif
0x01, 0x02, // Manufacturer, Product
0x03, 0x01 // Serial Number, Num Configurations
};
#define ENDPOINT_RCV 0x80
#define ENDPOINT_SND 0x00
uint8_t configuration_desc[] = {
DSCR_CONFIG_LEN, DSCR_CONFIG_TYPE, // Length, Type,
TOUSBORDER(0x0045), // Total Len (uint16)
0x01, 0x01, 0x00, // Num Interface, Config Value, Configuration
0xc0, 0x32, // Attributes, Max Power
// interface 0 ALT 0
DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type
0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval (NA)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// interface 0 ALT 1
DSCR_INTERFACE_LEN, DSCR_INTERFACE_TYPE, // Length, Type
0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count
0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol
0x00, // Interface
// endpoint 1, read CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x05, // Polling Interval (5 frames)
// endpoint 2, send serial
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
// endpoint 3, send CAN
DSCR_ENDPOINT_LEN, DSCR_ENDPOINT_TYPE, // Length, Type
ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type
TOUSBORDER(0x0040), // Max Packet (0x0040)
0x00, // Polling Interval
};
uint8_t string_0_desc[] = {
0x04, DSCR_STRING_TYPE, 0x09, 0x04
};
uint16_t string_1_desc[] = {
0x0312,
'c', 'o', 'm', 'm', 'a', '.', 'a', 'i'
};
#ifdef PANDA
uint16_t string_2_desc[] = {
0x030c,
'p', 'a', 'n', 'd', 'a'
};
#else
uint16_t string_2_desc[] = {
0x030c,
'N', 'E', 'O', 'v', '1'
};
#endif
uint16_t string_3_desc[] = {
0x030a,
'n', 'o', 'n', 'e'
};
// current packet
extern USB_Setup_TypeDef setup;
extern uint8_t usbdata[0x100];
USB_Setup_TypeDef setup;
uint8_t usbdata[0x100];
// Store the current interface alt setting.
extern int current_int0_alt_setting;
int current_int0_alt_setting = 0;
// packet read and write
void *USB_ReadPacket(void *dest, uint16_t len);
void *USB_ReadPacket(void *dest, uint16_t len) {
uint32_t i=0;
uint32_t count32b = (len + 3) / 4;
void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep);
for ( i = 0; i < count32b; i++, dest += 4 ) {
// packed?
*(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0);
}
return ((void *)dest);
}
void USB_Stall_EP0();
void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) {
#ifdef DEBUG_USB
puts("writing ");
hexdump(src, len);
#endif
void usb_reset();
uint8_t numpacket = (len+(MAX_RESP_LEN-1))/MAX_RESP_LEN;
uint32_t count32b = 0, i = 0;
count32b = (len + 3) / 4;
char to_hex_char(int a);
// bullshit
USBx_INEP(ep)->DIEPTSIZ = ((numpacket << 19) & USB_OTG_DIEPTSIZ_PKTCNT) |
(len & USB_OTG_DIEPTSIZ_XFRSIZ);
USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA);
void usb_setup();
// load the FIFO
for (i = 0; i < count32b; i++, src += 4) {
USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src);
}
}
void usb_init();
void usb_reset() {
// unmask endpoint interrupts, so many sets
USBx_DEVICE->DAINT = 0xFFFFFFFF;
USBx_DEVICE->DAINTMSK = 0xFFFFFFFF;
//USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK);
//USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM);
// all interrupts for debugging
USBx_DEVICE->DIEPMSK = 0xFFFFFFFF;
USBx_DEVICE->DOEPMSK = 0xFFFFFFFF;
// clear interrupts
USBx_INEP(0)->DIEPINT = 0xFF;
USBx_OUTEP(0)->DOEPINT = 0xFF;
// unset the address
USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD;
// set up USB FIFOs
// RX start address is fixed to 0
USBx->GRXFSIZ = 0x40;
// 0x100 to offset past GRXFSIZ
USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40;
// EP1, massive
USBx->DIEPTXF[0] = (0x40 << 16) | 0x80;
// flush TX fifo
USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH);
// flush RX FIFO
USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH);
// no global NAK
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK;
// ready to receive setup packets
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8);
}
char to_hex_char(int a) {
if (a < 10) {
return '0' + a;
} else {
return 'a' + (a-10);
}
}
void usb_setup() {
int i;
int resp_len;
// setup packet is ready
switch (setup.b.bRequest) {
case USB_REQ_SET_CONFIGURATION:
// enable other endpoints, has to be here?
USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) |
USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP;
USBx_INEP(1)->DIEPINT = 0xFF;
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(2)->DOEPINT = 0xFF;
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) |
USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP;
USBx_OUTEP(3)->DOEPINT = 0xFF;
// mark ready to receive
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
// TODO: is this the right place for this?
usb_cb_enumeration_complete();
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_ADDRESS:
// set now?
USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4);
#ifdef DEBUG_USB
puts(" set address\n");
#endif
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_GET_DESCRIPTOR:
switch (setup.b.wValue.bw.lsb) {
case USB_DESC_TYPE_DEVICE:
//puts(" writing device descriptor\n");
// setup transfer
USB_WritePacket(device_desc, min(sizeof(device_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
//puts("D");
break;
case USB_DESC_TYPE_CONFIGURATION:
USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_DESC_TYPE_STRING:
switch (setup.b.wValue.bw.msb) {
case 0:
USB_WritePacket((uint8_t*)string_0_desc, min(sizeof(string_0_desc), setup.b.wLength.w), 0);
break;
case 1:
USB_WritePacket((uint8_t*)string_1_desc, min(sizeof(string_1_desc), setup.b.wLength.w), 0);
break;
case 2:
USB_WritePacket((uint8_t*)string_2_desc, min(sizeof(string_2_desc), setup.b.wLength.w), 0);
break;
case 3:
#ifdef PANDA
resp[0] = 0x02 + 12*4;
resp[1] = 0x03;
// 96 bits = 12 bytes
for (i = 0; i < 12; i++){
uint8_t cc = ((uint8_t *)UID_BASE)[i];
resp[2 + i*4 + 0] = to_hex_char((cc>>4)&0xF);
resp[2 + i*4 + 1] = '\0';
resp[2 + i*4 + 2] = to_hex_char((cc>>0)&0xF);
resp[2 + i*4 + 3] = '\0';
}
USB_WritePacket(resp, min(resp[0], setup.b.wLength.w), 0);
#else
USB_WritePacket(string_3_desc, min(sizeof(string_3_desc), setup.b.wLength.w), 0);
#endif
break;
default:
// nothing
USB_WritePacket(0, 0, 0);
break;
}
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
default:
// nothing here?
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
}
break;
case USB_REQ_GET_STATUS:
// empty resp?
resp[0] = 0;
resp[1] = 0;
USB_WritePacket((void*)&resp, 2, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
case USB_REQ_SET_INTERFACE:
// Store the alt setting number for IN EP behavior.
current_int0_alt_setting = setup.b.wValue.w;
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
default:
resp_len = usb_cb_control_msg(&setup, resp, 1);
USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
}
}
void usb_init() {
// full speed PHY, do reset and remove power down
puth(USBx->GRSTCTL);
puts(" resetting PHY\n");
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0);
puts("AHB idle\n");
// reset PHY here
USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST;
while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST);
puts("reset done\n");
// internal PHY, force device mode
USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD;
// slowest timings
USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
// power up the PHY
#ifdef STM32F4
USBx->GCCFG = USB_OTG_GCCFG_PWRDWN;
//USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN;
/* B-peripheral session valid override enable*/
USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL;
USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN;
#else
USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS;
#endif
// be a device, slowest timings
//USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL;
//USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT);
//USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL;
// **** for debugging, doesn't seem to work ****
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT;
// reset PHY clock
USBx_PCGCCTL = 0;
// enable the fancy OTG things
// DCFG_FRAME_INTERVAL_80 is 0
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP;
USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK;
//USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD;
//USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD;
// clear pending interrupts
USBx->GINTSTS = 0xBFFFFFFFU;
// setup USB interrupts
// all interrupts except TXFIFO EMPTY
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF);
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM);
USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT |
USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM |
USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_USBSUSPM |
USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM;
USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT;
// DCTL startup value is 2 on new chip, 0 on old chip
// THIS IS FUCKING BULLSHIT
USBx_DEVICE->DCTL = 0;
}
// ***************************** USB port *****************************
void usb_irqhandler(void);
#endif
void usb_irqhandler(void) {
//USBx->GINTMSK = 0;
unsigned int gintsts = USBx->GINTSTS;
unsigned int gotgint = USBx->GOTGINT;
unsigned int daint = USBx_DEVICE->DAINT;
// gintsts SUSPEND? 04008428
#ifdef DEBUG_USB
puth(gintsts);
puts(" ");
/*puth(USBx->GCCFG);
puts(" ");*/
puth(gotgint);
puts(" ep ");
puth(daint);
puts(" USB interrupt!\n");
#endif
if (gintsts & USB_OTG_GINTSTS_CIDSCHG) {
puts("connector ID status change\n");
}
if (gintsts & USB_OTG_GINTSTS_ESUSP) {
puts("ESUSP detected\n");
}
if (gintsts & USB_OTG_GINTSTS_USBRST) {
puts("USB reset\n");
usb_reset();
}
if (gintsts & USB_OTG_GINTSTS_ENUMDNE) {
puts("enumeration done ");
// Full speed, ENUMSPD
puth(USBx_DEVICE->DSTS);
puts("\n");
}
if (gintsts & USB_OTG_GINTSTS_OTGINT) {
puts("OTG int:");
puth(USBx->GOTGINT);
puts("\n");
// getting ADTOCHG
//USBx->GOTGINT = USBx->GOTGINT;
}
// RX FIFO first
if (gintsts & USB_OTG_GINTSTS_RXFLVL) {
// 1. Read the Receive status pop register
volatile unsigned int rxst = USBx->GRXSTSP;
#ifdef DEBUG_USB
puts(" RX FIFO:");
puth(rxst);
puts(" status: ");
puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17);
puts(" len: ");
puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4);
puts("\n");
#endif
if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) {
int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM);
int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4;
USB_ReadPacket(&usbdata, len);
#ifdef DEBUG_USB
puts(" data ");
puth(len);
puts("\n");
hexdump(&usbdata, len);
#endif
if (endpoint == 2) {
usb_cb_ep2_out(usbdata, len, 1);
}
if (endpoint == 3) {
usb_cb_ep3_out(usbdata, len, 1);
}
} else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) {
USB_ReadPacket(&setup, 8);
#ifdef DEBUG_USB
puts(" setup ");
hexdump(&setup, 8);
puts("\n");
#endif
}
}
/*if (gintsts & USB_OTG_GINTSTS_HPRTINT) {
// host
puts("HPRT:");
puth(USBx_HOST_PORT->HPRT);
puts("\n");
if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) {
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST;
USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET;
}
}*/
if ((gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) || (gintsts & USB_OTG_GINTSTS_GINAKEFF)) {
// no global NAK, why is this getting set?
#ifdef DEBUG_USB
puts("GLOBAL NAK\n");
#endif
USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK;
}
if (gintsts & USB_OTG_GINTSTS_SRQINT) {
// we want to do "A-device host negotiation protocol" since we are the A-device
puts("start request\n");
puth(USBx->GOTGCTL);
puts("\n");
//USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD;
//USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA;
//USBx->GOTGCTL |= USB_OTG_GOTGCTL_SRQ;
}
// out endpoint hit
if (gintsts & USB_OTG_GINTSTS_OEPINT) {
#ifdef DEBUG_USB
puts(" 0:");
puth(USBx_OUTEP(0)->DOEPINT);
puts(" 2:");
puth(USBx_OUTEP(2)->DOEPINT);
puts(" 3:");
puth(USBx_OUTEP(3)->DOEPINT);
puts(" ");
puth(USBx_OUTEP(3)->DOEPCTL);
puts(" 4:");
puth(USBx_OUTEP(4)->DOEPINT);
puts(" OUT ENDPOINT\n");
#endif
if (USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) {
#ifdef DEBUG_USB
puts(" OUT2 PACKET XFRC\n");
#endif
USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
}
if (USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET XFRC\n");
#endif
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK;
} else if (USBx_OUTEP(3)->DOEPINT & 0x2000) {
#ifdef DEBUG_USB
puts(" OUT3 PACKET WTF\n");
#endif
// if NAK was set trigger this, unknown interrupt
USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40;
USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
} else if (USBx_OUTEP(3)->DOEPINT) {
puts("OUTEP3 error ");
puth(USBx_OUTEP(3)->DOEPINT);
puts("\n");
}
if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) {
// ready for next packet
USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8);
}
// respond to setup packets
if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) {
usb_setup();
}
USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT;
USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT;
USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT;
}
// interrupt endpoint hit (Page 1221)
if (gintsts & USB_OTG_GINTSTS_IEPINT) {
#ifdef DEBUG_USB
puts(" ");
puth(USBx_INEP(0)->DIEPINT);
puts(" ");
puth(USBx_INEP(1)->DIEPINT);
puts(" IN ENDPOINT\n");
#endif
// Should likely check the EP of the IN request even if there is
// only one IN endpoint.
// No need to set NAK in OTG_DIEPCTL0 when nothing to send,
// Appears USB core automatically sets NAK. WritePacket clears it.
// Handle the two interface alternate settings. Setting 0 is has
// EP1 as bulk. Setting 1 has EP1 as interrupt. The code to handle
// these two EP variations are very similar and can be
// restructured for smaller code footprint. Keeping split out for
// now for clarity.
//TODO add default case. Should it NAK?
switch(current_int0_alt_setting){
case 0: ////// Bulk config
// *** IN token received when TxFIFO is empty
if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
#ifdef DEBUG_USB
puts(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1);
}
break;
case 1: ////// Interrupt config
// Check if there is anything to actually send.
if (can_rx_q.w_ptr != can_rx_q.r_ptr) {
// *** IN token received when TxFIFO is empty
if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
#ifdef DEBUG_USB
puts(" IN PACKET QUEUE\n");
#endif
// TODO: always assuming max len, can we get the length?
USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1);
}
}
break;
}
// clear interrupts
USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0?
USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT;
}
// clear all interrupts we handled
USBx_DEVICE->DAINT = daint;
USBx->GOTGINT = gotgint;
USBx->GINTSTS = gintsts;
//USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF);
}

View File

@ -152,16 +152,11 @@ static void panda_urb_unlink(struct panda_inf_priv *priv)
usb_kill_anchored_urbs(&priv->tx_submitted);
}
#define SAFETY_NOOUTPUT 0
#define SAFETY_HONDA 1
#define SAFETY_ALLOUTPUT 0x1337
static int panda_set_output_mode(struct panda_inf_priv* priv, bool enable){
static int panda_set_output_enable(struct panda_inf_priv* priv, bool enable){
return usb_control_msg(priv->priv_dev->udev,
usb_sndctrlpipe(priv->priv_dev->udev, 0),
0xDC, USB_TYPE_VENDOR | USB_RECIP_DEVICE,
enable ? SAFETY_ALLOUTPUT : SAFETY_NOOUTPUT, 0, NULL,
0, USB_CTRL_SET_TIMEOUT);
enable ? 0x1337 : 0, 0, NULL, 0, USB_CTRL_SET_TIMEOUT);
}
static void panda_usb_write_bulk_callback(struct urb *urb)

View File

@ -24,7 +24,7 @@ def parse_can_buffer(dat):
address = f1 >> 3
else:
address = f1 >> 21
ret.append((address, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xFFF))
ret.append((address, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xf))
return ret
class PandaWifiStreaming(object):
@ -57,11 +57,8 @@ class WifiHandle(object):
return ret[4:4+length]
def controlWrite(self, request_type, request, value, index, data, timeout=0):
self.sock.send(
struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, len(data)) + data
)
retdata = self.__recv()
assert len(retdata) == 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):
self.sock.send(struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length))
@ -80,16 +77,10 @@ class WifiHandle(object):
def close(self):
self.sock.close()
SAFETY_NOOUTPUT = 0
SAFETY_HONDA = 1
SAFETY_ALLOUTPUT = 0x1337
class Panda(object):
REQUEST_IN = usb1.ENDPOINT_IN | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE
REQUEST_OUT = usb1.ENDPOINT_OUT | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE
REQUEST_TYPE = usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE
def __init__(self, serial=None, claim=True):
self._serial = serial
if serial == "WIFI":
self._handle = WifiHandle()
print("opening WIFI device")
@ -104,7 +95,7 @@ class Panda(object):
self._handle = device.open()
if claim:
self._handle.claimInterface(0)
#self._handle.setInterfaceAltSetting(0, 0)
self._handle.setInterfaceAltSetting(0, 0)
break
assert self._handle != None
@ -126,7 +117,7 @@ class Panda(object):
# ******************* health *******************
def health(self):
dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, 13)
dat = self._handle.controlRead(Panda.REQUEST_TYPE, 0xd2, 0, 0, 13)
a = struct.unpack("IIBBBBB", dat)
return {"voltage": a[0], "current": a[1],
"started": a[2], "controls_allowed": a[3],
@ -138,45 +129,38 @@ class Panda(object):
def enter_bootloader(self):
try:
self._handle.controlWrite(Panda.REQUEST_OUT, 0xd1, 0, 0, b'')
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xd1, 0, 0, b'')
except Exception as e:
print(e)
pass
def get_serial(self):
dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20)
dat = self._handle.controlRead(Panda.REQUEST_TYPE, 0xd0, 0, 0, 0x20)
hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4]
if hashsig != calc_hash:
raise PandaHashMismatchException(calc_hash, hashsig)
return [dat[0:0x10], dat[0x10:0x10+10]]
def get_secret(self):
return self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 1, 0, 0x10)
return self._handle.controlRead(Panda.REQUEST_TYPE, 0xd0, 1, 0, 0x10)
# ******************* configuration *******************
def set_controls_mode(self, mode=SAFETY_ALLOUTPUT):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xdc, mode, 0, b'')
def set_controls_allowed(self, on):
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xdc, (0x1337 if on else 0), 0, b'')
def set_can_baud(self, bus, baud):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xde, bus, 0, struct.pack('I', baud))
return self.get_can_baud(bus)
def get_can_baud(self, bus):
return struct.unpack("I", self._handle.controlRead(Panda.REQUEST_IN, 0xdf, bus, 0, 4))[0]
def set_gmlan(self, bus, on):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xdb, bus, bool(on), b'')
def set_gmlan(self, on, bus=2):
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xdb, 1, bus, b'')
def set_uart_baud(self, uart, rate):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xe1, uart, rate, b'')
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xe1, uart, rate, b'')
def set_uart_parity(self, uart, parity):
# parity, 0=off, 1=even, 2=odd
self._handle.controlWrite(Panda.REQUEST_OUT, 0xe2, uart, parity, b'')
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xe2, uart, parity, b'')
def set_uart_callback(self, uart, install):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xe3, uart, int(install), b'')
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xe3, uart, int(install), b'')
# ******************* can *******************
@ -218,7 +202,7 @@ class Panda(object):
# ******************* serial *******************
def serial_read(self, port_number):
return self._handle.controlRead(Panda.REQUEST_IN, 0xe0, port_number, 0, 0x40)
return self._handle.controlRead(Panda.REQUEST_TYPE, 0xe0, port_number, 0, 0x40)
def serial_write(self, port_number, ln):
return self._handle.bulkWrite(2, chr(port_number) + ln)
@ -227,13 +211,13 @@ class Panda(object):
# pulse low for wakeup
def kline_wakeup(self):
self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 0, 0, b'')
self._handle.controlWrite(Panda.REQUEST_TYPE, 0xf0, 0, 0, b'')
def kline_drain(self, bus=2):
# drain buffer
bret = bytearray()
while True:
ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40)
ret = self._handle.controlRead(Panda.REQUEST_TYPE, 0xe0, bus, 0, 0x40)
if len(ret) == 0:
break
bret += ret
@ -242,7 +226,7 @@ class Panda(object):
def kline_ll_recv(self, cnt, bus=2):
echo = bytearray()
while len(echo) != cnt:
echo += self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, cnt-len(echo))
echo += self._handle.controlRead(Panda.REQUEST_TYPE, 0xe0, bus, 0, cnt-len(echo))
return echo
def kline_send(self, x, bus=2, checksum=True):

View File

@ -19,10 +19,6 @@ if __name__ == "__main__":
serials = filter(lambda x: x==os.getenv("SERIAL"), serials)
pandas = list(map(lambda x: Panda(x, False), serials))
for i, p in enumerate(pandas):
print("%s Panda %s%s" % (setcolor[i], p._serial, unsetcolor))
while True:
for i, panda in enumerate(pandas):
while True:

View File

@ -4,7 +4,6 @@ import os
import sys
import time
import random
import argparse
from hexdump import hexdump
from itertools import permutations
@ -15,7 +14,7 @@ from panda import Panda
def get_test_string():
return b"test"+os.urandom(10)
def run_test(can_speeds, gmlan_speeds, sleep_duration=0):
def run_test():
pandas = Panda.list()
print(pandas)
@ -26,42 +25,34 @@ def run_test(can_speeds, gmlan_speeds, sleep_duration=0):
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, can_speeds, gmlan_speeds, sleep_duration)
run_test_w_pandas(pandas)
GMLAN_BUS = 3 # Virtual 'CAN 4'
def run_test_w_pandas(pandas, can_speeds, gmlan_speeds, sleep_duration=0):
def run_test_w_pandas(pandas):
h = list(map(lambda x: Panda(x), pandas))
print("H", h)
for hh in h:
hh.set_controls_mode()
hh.set_controls_allowed(True)
# test both directions
for ho in permutations(range(len(h)), r=2):
print("***************** TESTING", ho)
panda_snd, panda_rcv = h[ho[0]], h[ho[1]]
if(panda_snd._serial == "WIFI"):
print(" *** Can not send can data over wifi panda. Skipping! ***")
continue
# **** test health packet ****
print("health", ho[0], panda_snd.health())
print("health", ho[0], h[ho[0]].health())
# **** test K/L line loopback ****
for bus in [2,3]:
# flush the output
panda_rcv.kline_drain(bus=bus)
h[ho[1]].kline_drain(bus=bus)
# send the characters
st = get_test_string()
st = b"\xaa"+chr(len(st)+3).encode()+st
panda_snd.kline_send(st, bus=bus, checksum=False)
h[ho[0]].kline_send(st, bus=bus, checksum=False)
# check for receive
ret = panda_rcv.kline_drain(bus=bus)
ret = h[ho[1]].kline_drain(bus=bus)
print("ST Data:")
hexdump(st)
@ -69,41 +60,40 @@ def run_test_w_pandas(pandas, can_speeds, gmlan_speeds, sleep_duration=0):
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)]:
print("\ntest can", bus, "gmlan" if gmlan else "")
for bus in [0,1,4,5,6]:
panda0 = h[ho[0]]
panda1 = h[ho[1]]
print("\ntest can", bus)
# flush
cans_echo = panda_snd.can_recv()
cans_loop = panda_rcv.can_recv()
cans_echo = panda0.can_recv()
cans_loop = panda1.can_recv()
# set GMLAN mode
if(gmlan is not None):
panda_snd.set_gmlan(bus, gmlan)
panda_rcv.set_gmlan(bus, gmlan)
if gmlan:
print("Setting GMLAN %d Speed to %d" % (bus, gmlan_speeds[bus]))
panda_snd.set_can_baud(bus, gmlan_speeds[bus])
panda_rcv.set_can_baud(bus, gmlan_speeds[bus])
bus = GMLAN_BUS
if bus == 5:
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
panda0.set_gmlan(True,3)
panda1.set_gmlan(True,3)
bus = 4 # GMLAN is also multiplexed with CAN3
else:
print("bus", bus)
print("Setting CanBus %d Speed to %d" % (bus, can_speeds[bus]))
panda_snd.set_can_baud(bus, can_speeds[bus])
panda_rcv.set_can_baud(bus, can_speeds[bus])
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]
panda_snd.can_send(at, st, bus)
panda0.can_send(at, st, bus)
time.sleep(0.1)
# check for receive
cans_echo = panda_snd.can_recv()
cans_loop = panda_rcv.can_recv()
cans_echo = panda0.can_recv()
cans_loop = panda1.can_recv()
print("Bus", bus, "echo", cans_echo, "loop", cans_loop)
@ -116,31 +106,20 @@ def run_test_w_pandas(pandas, can_speeds, gmlan_speeds, sleep_duration=0):
assert cans_echo[0][2] == st
assert cans_loop[0][2] == st
assert cans_echo[0][3] == 0x80 | bus
assert cans_echo[0][3] == bus+2
if cans_loop[0][3] != bus:
print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3]))
assert cans_loop[0][3] == bus
time.sleep(sleep_duration)
print("CAN pass", bus, ho)
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument("-n", type=int, help="Number of test iterations to run")
parser.add_argument("-can1baud", type=int, help="Baud Rate of CAN1", default=500000)
parser.add_argument("-can2baud", type=int, help="Baud Rate of CAN2", default=500000)
parser.add_argument("-can3baud", type=int, help="Baud Rate of CAN3", default=500000)
parser.add_argument("-gmlan2baud", type=int, help="Baud Rate of GMLAN2", default=33333)
parser.add_argument("-gmlan3baud", type=int, help="Baud Rate of GMLAN3", default=33333)
parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0)
args = parser.parse_args()
can_speeds = (args.can1baud, args.can2baud, args.can3baud)
gmlan_speeds = (None, args.gmlan2baud, args.gmlan2baud)
if args.n is None:
if len(sys.argv) > 1:
for i in range(int(sys.argv[1])):
run_test()
else :
i = 0
while True:
run_test(can_speeds, gmlan_speeds, sleep_duration=args.sleep)
else:
for i in range(args.n):
run_test(can_speeds, gmlan_speeds, sleep_duration=args.sleep)
print("************* testing %d" % i)
run_test()
i += 1

View File

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

View File

@ -25,7 +25,7 @@ if __name__ == "__main__":
# p_in.can_recv()
#sys.exit(0)
p_out.set_controls_mode()
p_out.set_controls_allowed(True)
set_out, set_in = set(), set()