256d274e7 Fix Mac installation instruction per: https://github.com/commaai/panda/pull/308/files
bfd8ff1b1 Update cppcheck commit with more coverage
b143a1cf9 Fixed Misra complaint
606f1d913 Fixed RTC on non-uno boards, second try. Cannot work when there is no xtal.
933c75770 Fix RTC on non-uno boards (#311)
48d0d0c78 VW button spam: fix safety and add tests (#306)
6cccf969a Fan and IR at 0 when in power savings mode (#309)
05373282a board get_sdk scripts were left on python2
de18a7ef1 bump version after uno merge
1965817d3 Changed default values for testing
a12a148d5 Uno (#274)
7d29dc5a2 bump panda version. We really need a better way
40075321d VW: stricter limits to comply with comma safety policy
e2e2be92c add safety mode to health packet
101238c7f turned on VW ignition based CAN logic
a0d8d5dae fix misra 5.3: check_ignition is intended as check_started and can't be used twice
ea636de61 made check_ignition function to both look at ignition_line and ignition_can
1102e6965 make ignition logic common for all cars (#303)
3a110c6f6 bump version after CMSIS core upgrade
55dfa5230 Update core to CMSIS 5.6 release (#251)
ee864907c fix linter 2
f410b110d fix linter
55957d6e4 proper python3 exception inheritance
6ba0f47b5 fix linter errors
5c49fe050 Merge pull request #145 from gregjhogan/uds
0f361999b timeout is float
396d6aad5 safety_replay only installs few extra requirements
25af7d301 Misra also need python 3 env
7434c5ce2 centralize requirements for tests
a0c37c70a coverage not needed in linter reqs
fce38a91d Linter python (#299)
62e2f5caa update cppcheck commit
711810d2f more uds debug
4454e3a6b better CAN comm abstraction
6b1f28f57 fix more encoding and some bytes cleanup (#300)
43adad311 fix WARNING_INDICATOR_REQUESTED name
9c857da37 0x
b64d6fa5d typing
768fdf7e1 bytes() > chr().encode()
1be15ea93 custom errors from thread
68da8315f more python3
eb358e81c uds lib example
4f288586d updates for python3
932745f62 support tx flow control for chunked messages
b1c371292 add timeout param
cdf2f626b bug fixes
b1a319577 fix rx message filtering bug
80fb6a6fa convert uds lib to class
59cd2b47f handle separation time in microseconds
4429600d8 fix separation time parsing
c641e66f7 fix typo
48b8dcc6f fix flow control delay scale
78f413d88 flow control delay
33a5167d9 bug fixes
8ee89a091 multi-frame tx
5e89a9c72 clear rx buffer and numeric error ids
966230063 fix remaining size calculation
01ef1fae3 zero pad messages before sending
1ddc9735d uds can communication
dca176e71 syntax errors
95be4811e SERVICE_TYPE enum
98e73b51d more UDS message type implementation
c1c5b0356 uds lib
162f4853d fix chr to bytes conversions (#298)
4972376de Update VW regression test to follow Comma safety index refactoring (#296)
f9053f5df more Python 3 fixes, attempting to fix jenkins wifi regresison test (#295)
2f9e07628 Panda safety code for Volkswagen, Audi, SEAT, and Škoda (#293)
git-subtree-dir: panda
git-subtree-split: 256d274e760ce00d4e5ff5e0d9b86d0fb5924568
old-commit-hash: 22023ebd58
commatwo_master
parent
6f518e8816
commit
0ba412d52e
123 changed files with 2974 additions and 425 deletions
@ -1,9 +1,9 @@ |
||||
# Updating your panda |
||||
|
||||
Panda should update automatically via the [Chffr](http://chffr.comma.ai/) app ([apple](https://itunes.apple.com/us/app/chffr-dash-cam-that-remembers/id1146683979) and [android](https://play.google.com/store/apps/details?id=ai.comma.chffr)) |
||||
Panda should update automatically via the [openpilot](http://openpilot.comma.ai/). |
||||
|
||||
If it doesn't however, you can use the following commands on linux or Mac OSX |
||||
`sudo pip install --upgrade pandacan` |
||||
` PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` |
||||
|
||||
(You'll need to have `pip` and `sudo` installed.) |
||||
On Linux or Mac OSX, you can manually update it using: |
||||
``` |
||||
sudo pip install --upgrade pandacan` |
||||
PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` |
||||
``` |
||||
|
@ -1 +1 @@ |
||||
from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial |
||||
from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial # noqa: F401 |
||||
|
@ -0,0 +1,247 @@ |
||||
// ///////////// //
|
||||
// Uno + Harness //
|
||||
// ///////////// //
|
||||
|
||||
void uno_enable_can_transciever(uint8_t transciever, bool enabled) { |
||||
switch (transciever){ |
||||
case 1U: |
||||
set_gpio_output(GPIOC, 1, !enabled); |
||||
break; |
||||
case 2U: |
||||
set_gpio_output(GPIOC, 13, !enabled); |
||||
break; |
||||
case 3U: |
||||
set_gpio_output(GPIOA, 0, !enabled); |
||||
break; |
||||
case 4U: |
||||
set_gpio_output(GPIOB, 10, !enabled); |
||||
break; |
||||
default: |
||||
puts("Invalid CAN transciever ("); puth(transciever); puts("): enabling failed\n"); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
void uno_enable_can_transcievers(bool enabled) { |
||||
for(uint8_t i=1U; i<=4U; i++){ |
||||
uno_enable_can_transciever(i, enabled); |
||||
} |
||||
} |
||||
|
||||
void uno_set_led(uint8_t color, bool enabled) { |
||||
switch (color){ |
||||
case LED_RED: |
||||
set_gpio_output(GPIOC, 9, !enabled); |
||||
break; |
||||
case LED_GREEN: |
||||
set_gpio_output(GPIOC, 7, !enabled); |
||||
break; |
||||
case LED_BLUE: |
||||
set_gpio_output(GPIOC, 6, !enabled); |
||||
break; |
||||
default: |
||||
break; |
||||
} |
||||
} |
||||
|
||||
void uno_set_gps_load_switch(bool enabled) { |
||||
set_gpio_output(GPIOC, 12, enabled); |
||||
} |
||||
|
||||
void uno_set_usb_power_mode(uint8_t mode) { |
||||
UNUSED(mode); |
||||
puts("Setting USB mode makes no sense on UNO\n"); |
||||
} |
||||
|
||||
void uno_set_esp_gps_mode(uint8_t mode) { |
||||
switch (mode) { |
||||
case ESP_GPS_DISABLED: |
||||
// GPS OFF
|
||||
set_gpio_output(GPIOB, 1, 0); |
||||
set_gpio_output(GPIOC, 5, 0); |
||||
uno_set_gps_load_switch(false); |
||||
break; |
||||
case ESP_GPS_ENABLED: |
||||
// GPS ON
|
||||
set_gpio_output(GPIOB, 1, 1); |
||||
set_gpio_output(GPIOC, 5, 1); |
||||
uno_set_gps_load_switch(true); |
||||
break; |
||||
case ESP_GPS_BOOTMODE: |
||||
set_gpio_output(GPIOB, 1, 1); |
||||
set_gpio_output(GPIOC, 5, 0); |
||||
uno_set_gps_load_switch(true); |
||||
break; |
||||
default: |
||||
puts("Invalid ESP/GPS mode\n"); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
void uno_set_can_mode(uint8_t mode){ |
||||
switch (mode) { |
||||
case CAN_MODE_NORMAL: |
||||
case CAN_MODE_OBD_CAN2: |
||||
if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(car_harness_status == HARNESS_STATUS_NORMAL)) { |
||||
// B12,B13: disable OBD mode
|
||||
set_gpio_mode(GPIOB, 12, MODE_INPUT); |
||||
set_gpio_mode(GPIOB, 13, MODE_INPUT); |
||||
|
||||
// B5,B6: normal CAN2 mode
|
||||
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); |
||||
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); |
||||
} else { |
||||
// B5,B6: disable normal CAN2 mode
|
||||
set_gpio_mode(GPIOB, 5, MODE_INPUT); |
||||
set_gpio_mode(GPIOB, 6, MODE_INPUT); |
||||
|
||||
// B12,B13: OBD mode
|
||||
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); |
||||
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); |
||||
} |
||||
break; |
||||
default: |
||||
puts("Tried to set unsupported CAN mode: "); puth(mode); puts("\n"); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
void uno_set_bootkick(bool enabled){ |
||||
set_gpio_output(GPIOB, 14, !enabled); |
||||
} |
||||
|
||||
void uno_usb_power_mode_tick(uint64_t tcnt){ |
||||
if(tcnt == 3U){ |
||||
uno_set_bootkick(false); |
||||
} |
||||
} |
||||
|
||||
bool uno_check_ignition(void){ |
||||
// ignition is checked through harness
|
||||
return harness_check_ignition(); |
||||
} |
||||
|
||||
void uno_set_usb_switch(bool phone){ |
||||
set_gpio_output(GPIOB, 3, phone); |
||||
} |
||||
|
||||
void uno_set_ir_power(uint8_t percentage){ |
||||
pwm_set(TIM4, 2, percentage); |
||||
} |
||||
|
||||
void uno_set_fan_power(uint8_t percentage){ |
||||
// Enable fan power only if percentage is non-zero.
|
||||
set_gpio_output(GPIOA, 1, (percentage != 0U)); |
||||
fan_set_power(percentage); |
||||
} |
||||
|
||||
uint32_t uno_read_current(void){ |
||||
// No current sense on Uno
|
||||
return 0U; |
||||
} |
||||
|
||||
void uno_init(void) { |
||||
common_init_gpio(); |
||||
|
||||
// A8,A15: normal CAN3 mode
|
||||
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); |
||||
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); |
||||
|
||||
// C0: OBD_SBU1 (orientation detection)
|
||||
// C3: OBD_SBU2 (orientation detection)
|
||||
set_gpio_mode(GPIOC, 0, MODE_ANALOG); |
||||
set_gpio_mode(GPIOC, 3, MODE_ANALOG); |
||||
|
||||
// C10: OBD_SBU1_RELAY (harness relay driving output)
|
||||
// C11: OBD_SBU2_RELAY (harness relay driving output)
|
||||
set_gpio_mode(GPIOC, 10, MODE_OUTPUT); |
||||
set_gpio_mode(GPIOC, 11, MODE_OUTPUT); |
||||
set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); |
||||
set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); |
||||
set_gpio_output(GPIOC, 10, 1); |
||||
set_gpio_output(GPIOC, 11, 1); |
||||
|
||||
// C8: FAN PWM aka TIM3_CH3
|
||||
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); |
||||
|
||||
// Turn on GPS load switch.
|
||||
uno_set_gps_load_switch(true); |
||||
|
||||
// Turn on phone regulator
|
||||
set_gpio_output(GPIOB, 4, 1); |
||||
|
||||
// Initialize IR PWM and set to 0%
|
||||
set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); |
||||
pwm_init(TIM4, 2); |
||||
uno_set_ir_power(0U); |
||||
|
||||
// Initialize fan and set to 0%
|
||||
fan_init(); |
||||
uno_set_fan_power(0U); |
||||
|
||||
// Initialize harness
|
||||
harness_init(); |
||||
|
||||
// Initialize RTC
|
||||
rtc_init(); |
||||
|
||||
// Enable CAN transcievers
|
||||
uno_enable_can_transcievers(true); |
||||
|
||||
// Disable LEDs
|
||||
uno_set_led(LED_RED, false); |
||||
uno_set_led(LED_GREEN, false); |
||||
uno_set_led(LED_BLUE, false); |
||||
|
||||
// Set normal CAN mode
|
||||
uno_set_can_mode(CAN_MODE_NORMAL); |
||||
|
||||
// flip CAN0 and CAN2 if we are flipped
|
||||
if (car_harness_status == HARNESS_STATUS_NORMAL) { |
||||
can_flip_buses(0, 2); |
||||
} |
||||
|
||||
// init multiplexer
|
||||
can_set_obd(car_harness_status, false); |
||||
|
||||
// Switch to phone usb mode if harness connection is powered by less than 7V
|
||||
if(adc_get_voltage() < 7000U){ |
||||
uno_set_usb_switch(true); |
||||
} else { |
||||
uno_set_usb_switch(false); |
||||
} |
||||
|
||||
// Bootkick phone
|
||||
uno_set_bootkick(true); |
||||
} |
||||
|
||||
const harness_configuration uno_harness_config = { |
||||
.has_harness = true, |
||||
.GPIO_SBU1 = GPIOC, |
||||
.GPIO_SBU2 = GPIOC, |
||||
.GPIO_relay_normal = GPIOC, |
||||
.GPIO_relay_flipped = GPIOC, |
||||
.pin_SBU1 = 0, |
||||
.pin_SBU2 = 3, |
||||
.pin_relay_normal = 10, |
||||
.pin_relay_flipped = 11, |
||||
.adc_channel_SBU1 = 10, |
||||
.adc_channel_SBU2 = 13 |
||||
}; |
||||
|
||||
const board board_uno = { |
||||
.board_type = "Uno", |
||||
.harness_config = &uno_harness_config, |
||||
.init = uno_init, |
||||
.enable_can_transciever = uno_enable_can_transciever, |
||||
.enable_can_transcievers = uno_enable_can_transcievers, |
||||
.set_led = uno_set_led, |
||||
.set_usb_power_mode = uno_set_usb_power_mode, |
||||
.set_esp_gps_mode = uno_set_esp_gps_mode, |
||||
.set_can_mode = uno_set_can_mode, |
||||
.usb_power_mode_tick = uno_usb_power_mode_tick, |
||||
.check_ignition = uno_check_ignition, |
||||
.read_current = uno_read_current, |
||||
.set_fan_power = uno_set_fan_power, |
||||
.set_ir_power = uno_set_ir_power |
||||
}; |
@ -0,0 +1,36 @@ |
||||
void fan_init(void){ |
||||
// Init PWM speed control
|
||||
pwm_init(TIM3, 3); |
||||
|
||||
// Init TACH interrupt
|
||||
SYSCFG->EXTICR[0] = SYSCFG_EXTICR1_EXTI2_PD; |
||||
EXTI->IMR |= (1U << 2); |
||||
EXTI->RTSR |= (1U << 2); |
||||
EXTI->FTSR |= (1U << 2); |
||||
NVIC_EnableIRQ(EXTI2_IRQn); |
||||
} |
||||
|
||||
void fan_set_power(uint8_t percentage){ |
||||
pwm_set(TIM3, 3, percentage); |
||||
} |
||||
|
||||
uint16_t fan_tach_counter = 0U; |
||||
uint16_t fan_rpm = 0U; |
||||
|
||||
// Can be way more acurate than this, but this is probably good enough for our purposes.
|
||||
|
||||
// Call this every second
|
||||
void fan_tick(void){ |
||||
// 4 interrupts per rotation
|
||||
fan_rpm = fan_tach_counter * 15U; |
||||
fan_tach_counter = 0U; |
||||
} |
||||
|
||||
// TACH interrupt handler
|
||||
void EXTI2_IRQHandler(void) { |
||||
volatile unsigned int pr = EXTI->PR & (1U << 2); |
||||
if ((pr & (1U << 2)) != 0U) { |
||||
fan_tach_counter++; |
||||
} |
||||
EXTI->PR = (1U << 2); |
||||
} |
@ -0,0 +1,55 @@ |
||||
#define PWM_COUNTER_OVERFLOW 2000U // To get ~50kHz
|
||||
|
||||
void pwm_init(TIM_TypeDef *TIM, uint8_t channel){ |
||||
// Enable timer and auto-reload
|
||||
TIM->CR1 = TIM_CR1_CEN | TIM_CR1_ARPE; |
||||
|
||||
// Set channel as PWM mode 1 and enable output
|
||||
switch(channel){ |
||||
case 1U: |
||||
TIM->CCMR1 |= (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE); |
||||
TIM->CCER |= TIM_CCER_CC1E; |
||||
break; |
||||
case 2U: |
||||
TIM->CCMR1 |= (TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE); |
||||
TIM->CCER |= TIM_CCER_CC2E; |
||||
break; |
||||
case 3U: |
||||
TIM->CCMR2 |= (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE); |
||||
TIM->CCER |= TIM_CCER_CC3E; |
||||
break; |
||||
case 4U: |
||||
TIM->CCMR2 |= (TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4PE); |
||||
TIM->CCER |= TIM_CCER_CC4E; |
||||
break; |
||||
default: |
||||
break; |
||||
} |
||||
|
||||
// Set max counter value
|
||||
TIM->ARR = PWM_COUNTER_OVERFLOW; |
||||
|
||||
// Update registers and clear counter
|
||||
TIM->EGR |= TIM_EGR_UG; |
||||
} |
||||
|
||||
// TODO: Implement for 32-bit timers
|
||||
void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){ |
||||
uint16_t comp_value = (((uint16_t) percentage * PWM_COUNTER_OVERFLOW) / 100U); |
||||
switch(channel){ |
||||
case 1U: |
||||
TIM->CCR1 = comp_value; |
||||
break; |
||||
case 2U: |
||||
TIM->CCR2 = comp_value; |
||||
break; |
||||
case 3U: |
||||
TIM->CCR3 = comp_value; |
||||
break; |
||||
case 4U: |
||||
TIM->CCR4 = comp_value; |
||||
break; |
||||
default: |
||||
break; |
||||
} |
||||
} |
@ -0,0 +1,108 @@ |
||||
#define RCC_BDCR_OPTIONS (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) |
||||
#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) |
||||
|
||||
#define YEAR_OFFSET 2000U |
||||
|
||||
typedef struct __attribute__((packed)) timestamp_t { |
||||
uint16_t year; |
||||
uint8_t month; |
||||
uint8_t day; |
||||
uint8_t weekday; |
||||
uint8_t hour; |
||||
uint8_t minute; |
||||
uint8_t second; |
||||
} timestamp_t; |
||||
|
||||
uint8_t to_bcd(uint16_t value){ |
||||
return (((value / 10U) & 0x0FU) << 4U) | ((value % 10U) & 0x0FU); |
||||
} |
||||
|
||||
uint16_t from_bcd(uint8_t value){ |
||||
return (((value & 0xF0U) >> 4U) * 10U) + (value & 0x0FU); |
||||
} |
||||
|
||||
void rtc_init(void){ |
||||
if(board_has_rtc()){ |
||||
// Initialize RTC module and clock if not done already.
|
||||
if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ |
||||
puts("Initializing RTC\n"); |
||||
// Reset backup domain
|
||||
RCC->BDCR |= RCC_BDCR_BDRST; |
||||
|
||||
// Disable write protection
|
||||
PWR->CR |= PWR_CR_DBP; |
||||
|
||||
// Clear backup domain reset
|
||||
RCC->BDCR &= ~(RCC_BDCR_BDRST); |
||||
|
||||
// Set RTC options
|
||||
RCC->BDCR = RCC_BDCR_OPTIONS | (RCC->BDCR & (~RCC_BDCR_MASK)); |
||||
|
||||
// Enable write protection
|
||||
PWR->CR &= ~(PWR_CR_DBP); |
||||
} |
||||
} |
||||
} |
||||
|
||||
void rtc_set_time(timestamp_t time){ |
||||
if(board_has_rtc()){ |
||||
puts("Setting RTC time\n"); |
||||
|
||||
// Disable write protection
|
||||
PWR->CR |= PWR_CR_DBP; |
||||
RTC->WPR = 0xCA; |
||||
RTC->WPR = 0x53; |
||||
|
||||
// Enable initialization mode
|
||||
RTC->ISR |= RTC_ISR_INIT; |
||||
while((RTC->ISR & RTC_ISR_INITF) == 0){} |
||||
|
||||
// Set time
|
||||
RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); |
||||
RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); |
||||
|
||||
// Set options
|
||||
RTC->CR = 0U; |
||||
|
||||
// Disable initalization mode
|
||||
RTC->ISR &= ~(RTC_ISR_INIT); |
||||
|
||||
// Wait for synchronization
|
||||
while((RTC->ISR & RTC_ISR_RSF) == 0){} |
||||
|
||||
// Re-enable write protection
|
||||
RTC->WPR = 0x00; |
||||
PWR->CR &= ~(PWR_CR_DBP); |
||||
} |
||||
} |
||||
|
||||
timestamp_t rtc_get_time(void){ |
||||
timestamp_t result; |
||||
// Init with zero values in case there is no RTC running
|
||||
result.year = 0U; |
||||
result.month = 0U; |
||||
result.day = 0U; |
||||
result.weekday = 0U; |
||||
result.hour = 0U; |
||||
result.minute = 0U; |
||||
result.second = 0U; |
||||
|
||||
if(board_has_rtc()){ |
||||
// Wait until the register sync flag is set
|
||||
while((RTC->ISR & RTC_ISR_RSF) == 0){} |
||||
|
||||
// Read time and date registers. Since our HSE > 7*LSE, this should be fine.
|
||||
uint32_t time = RTC->TR; |
||||
uint32_t date = RTC->DR; |
||||
|
||||
// Parse values
|
||||
result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; |
||||
result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); |
||||
result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); |
||||
result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); |
||||
result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); |
||||
result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); |
||||
result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); |
||||
} |
||||
return result; |
||||
} |
@ -1,3 +1,3 @@ |
||||
#!/bin/bash |
||||
sudo apt-get install gcc-arm-none-eabi python-pip |
||||
sudo pip2 install libusb1 pycrypto requests |
||||
sudo pip install libusb1 pycrypto requests |
||||
|
@ -0,0 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:3eeeb716701baca7c9aec136ada74ac29fa5731d188c1728f66b13e54a69ab64 |
||||
size 9482 |
@ -1,3 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:6c7e75d09887cb3035f18bc6f4fdbd7392a50379cd556315deb3bcb762d99078 |
||||
size 40062 |
||||
oid sha256:9bf43ac370e82ed7c9cc9a9fb5b624276fa03d15f96103550c7ab3b043f048f2 |
||||
size 62628 |
||||
|
@ -0,0 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:d649eaa2fb1c421add02950ab9c111ccabb8be27197f3d37e03f03357e817ff8 |
||||
size 1677 |
@ -1,3 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:03a80f17ff18c5d0e3b234009f98698cd402b8ea972df687a6cfafd8b8a78654 |
||||
size 102146 |
||||
oid sha256:01793bb15ec31729c8d1d4422a2e86ce5e0728b6a8834b94f08ea46c4c43b3b5 |
||||
size 109421 |
||||
|
@ -1,3 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:83c5d601dd5640a863fe4dc43cd228b46239bbf9f07b51102bf0c1c8f235cdfa |
||||
size 112561 |
||||
oid sha256:dd13b2caea9d4490a5d49cdb86fbfa3e0d7b01343dc0ad8560c10a924626320e |
||||
size 120868 |
||||
|
@ -1,3 +0,0 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:1fdd226d82bde2a90231ba47a59377158b8907e4cada2a6215f32dcf13ab35cd |
||||
size 3533 |
@ -1,3 +0,0 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:c9b8e36d05097da5d493f197aa7f81ce517f4532536925b568ccbd6e2c01eb8a |
||||
size 3549 |
@ -1,3 +0,0 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:5d338d36730ccbd138126078e17f69c308a015f0a88d85bd639af072e527d53d |
||||
size 3566 |
@ -0,0 +1,3 @@ |
||||
version https://git-lfs.github.com/spec/v1
|
||||
oid sha256:16660b4b9af5c288949272e55dfc463fd704acd7bbbe34f0fa6acbdea2d41c22 |
||||
size 11691 |
@ -0,0 +1,167 @@ |
||||
const int VOLKSWAGEN_MAX_STEER = 250; // 2.5 Nm (EPS side max of 3.0Nm with fault if violated)
|
||||
const int VOLKSWAGEN_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75
|
||||
const uint32_t VOLKSWAGEN_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||
const int VOLKSWAGEN_MAX_RATE_UP = 4; // 2.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s)
|
||||
const int VOLKSWAGEN_MAX_RATE_DOWN = 10; // 5.0 Nm/s available rate of change from the steering rack (EPS side delta-limit of 5.0 Nm/s)
|
||||
const int VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE = 80; |
||||
const int VOLKSWAGEN_DRIVER_TORQUE_FACTOR = 3; |
||||
|
||||
struct sample_t volkswagen_torque_driver; // last few driver torques measured
|
||||
int volkswagen_rt_torque_last = 0; |
||||
int volkswagen_desired_torque_last = 0; |
||||
uint32_t volkswagen_ts_last = 0; |
||||
int volkswagen_gas_prev = 0; |
||||
|
||||
// Safety-relevant CAN messages for the Volkswagen MQB platform.
|
||||
#define MSG_EPS_01 0x09F |
||||
#define MSG_MOTOR_20 0x121 |
||||
#define MSG_ACC_06 0x122 |
||||
#define MSG_HCA_01 0x126 |
||||
#define MSG_GRA_ACC_01 0x12B |
||||
#define MSG_LDW_02 0x397 |
||||
#define MSG_KLEMMEN_STATUS_01 0x3C0 |
||||
|
||||
static void volkswagen_init(int16_t param) { |
||||
UNUSED(param); // May use param in the future to indicate MQB vs PQ35/PQ46/NMS vs MLB, or wiring configuration.
|
||||
controls_allowed = 0; |
||||
} |
||||
|
||||
static void volkswagen_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { |
||||
int bus = GET_BUS(to_push); |
||||
int addr = GET_ADDR(to_push); |
||||
|
||||
// Update driver input torque samples from EPS_01.Driver_Strain for absolute torque, and EPS_01.Driver_Strain_VZ
|
||||
// for the direction.
|
||||
if ((bus == 0) && (addr == MSG_EPS_01)) { |
||||
int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1F) << 8); |
||||
int sign = (GET_BYTE(to_push, 6) & 0x80) >> 7; |
||||
if (sign == 1) { |
||||
torque_driver_new *= -1; |
||||
} |
||||
|
||||
update_sample(&volkswagen_torque_driver, torque_driver_new); |
||||
} |
||||
|
||||
// Monitor ACC_06.ACC_Status_ACC for stock ACC status. Because the current MQB port is lateral-only, OP's control
|
||||
// allowed state is directly driven by stock ACC engagement. Permit the ACC message to come from either bus, in
|
||||
// order to accommodate future camera-side integrations if needed.
|
||||
if (addr == MSG_ACC_06) { |
||||
int acc_status = (GET_BYTE(to_push, 7) & 0x70) >> 4; |
||||
controls_allowed = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0; |
||||
} |
||||
|
||||
// exit controls on rising edge of gas press. Bits [12-20)
|
||||
if (addr == MSG_MOTOR_20) { |
||||
int gas = (GET_BYTES_04(to_push) >> 12) & 0xFF; |
||||
if ((gas > 0) && (volkswagen_gas_prev == 0) && long_controls_allowed) { |
||||
controls_allowed = 0; |
||||
} |
||||
volkswagen_gas_prev = gas; |
||||
} |
||||
} |
||||
|
||||
static int volkswagen_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { |
||||
int addr = GET_ADDR(to_send); |
||||
int bus = GET_BUS(to_send); |
||||
int tx = 1; |
||||
|
||||
// Safety check for HCA_01 Heading Control Assist torque.
|
||||
if (addr == MSG_HCA_01) { |
||||
bool violation = false; |
||||
|
||||
int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x3F) << 8); |
||||
int sign = (GET_BYTE(to_send, 3) & 0x80) >> 7; |
||||
if (sign == 1) { |
||||
desired_torque *= -1; |
||||
} |
||||
|
||||
uint32_t ts = TIM2->CNT; |
||||
|
||||
if (controls_allowed) { |
||||
|
||||
// *** global torque limit check ***
|
||||
violation |= max_limit_check(desired_torque, VOLKSWAGEN_MAX_STEER, -VOLKSWAGEN_MAX_STEER); |
||||
|
||||
// *** torque rate limit check ***
|
||||
violation |= driver_limit_check(desired_torque, volkswagen_desired_torque_last, &volkswagen_torque_driver, |
||||
VOLKSWAGEN_MAX_STEER, VOLKSWAGEN_MAX_RATE_UP, VOLKSWAGEN_MAX_RATE_DOWN, |
||||
VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_DRIVER_TORQUE_FACTOR); |
||||
volkswagen_desired_torque_last = desired_torque; |
||||
|
||||
// *** torque real time rate limit check ***
|
||||
violation |= rt_rate_limit_check(desired_torque, volkswagen_rt_torque_last, VOLKSWAGEN_MAX_RT_DELTA); |
||||
|
||||
// every RT_INTERVAL set the new limits
|
||||
uint32_t ts_elapsed = get_ts_elapsed(ts, volkswagen_ts_last); |
||||
if (ts_elapsed > VOLKSWAGEN_RT_INTERVAL) { |
||||
volkswagen_rt_torque_last = desired_torque; |
||||
volkswagen_ts_last = ts; |
||||
} |
||||
} |
||||
|
||||
// no torque if controls is not allowed
|
||||
if (!controls_allowed && (desired_torque != 0)) { |
||||
violation = true; |
||||
} |
||||
|
||||
// reset to 0 if either controls is not allowed or there's a violation
|
||||
if (violation || !controls_allowed) { |
||||
volkswagen_desired_torque_last = 0; |
||||
volkswagen_rt_torque_last = 0; |
||||
volkswagen_ts_last = ts; |
||||
} |
||||
|
||||
if (violation) { |
||||
tx = 0; |
||||
} |
||||
} |
||||
|
||||
// FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off.
|
||||
// This avoids unintended engagements while still allowing resume spam
|
||||
if ((bus == 2) && (addr == MSG_GRA_ACC_01) && !controls_allowed) { |
||||
// disallow resume and set: bits 16 and 19
|
||||
if ((GET_BYTE(to_send, 2) & 0x9) != 0) { |
||||
tx = 0; |
||||
} |
||||
} |
||||
|
||||
// 1 allows the message through
|
||||
return tx; |
||||
} |
||||
|
||||
static int volkswagen_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { |
||||
int addr = GET_ADDR(to_fwd); |
||||
int bus_fwd = -1; |
||||
|
||||
// NOTE: Will need refactoring for other bus layouts, such as no-forwarding at camera or J533 running-gear CAN
|
||||
|
||||
switch (bus_num) { |
||||
case 0: |
||||
// Forward all traffic from J533 gateway to Extended CAN devices.
|
||||
bus_fwd = 2; |
||||
break; |
||||
case 2: |
||||
if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { |
||||
// OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera.
|
||||
bus_fwd = -1; |
||||
} else { |
||||
// Forward all remaining traffic from Extended CAN devices to J533 gateway.
|
||||
bus_fwd = 0; |
||||
} |
||||
break; |
||||
default: |
||||
// No other buses should be in use; fallback to do-not-forward.
|
||||
bus_fwd = -1; |
||||
break; |
||||
} |
||||
|
||||
return bus_fwd; |
||||
} |
||||
|
||||
const safety_hooks volkswagen_hooks = { |
||||
.init = volkswagen_init, |
||||
.rx = volkswagen_rx_hook, |
||||
.tx = volkswagen_tx_hook, |
||||
.tx_lin = nooutput_tx_lin_hook, |
||||
.fwd = volkswagen_fwd_hook, |
||||
}; |
@ -0,0 +1,59 @@ |
||||
#!/usr/bin/env python3 |
||||
from panda import Panda |
||||
from panda.python.uds import UdsClient, NegativeResponseError, DATA_IDENTIFIER_TYPE |
||||
|
||||
if __name__ == "__main__": |
||||
address = 0x18da30f1 # Honda EPS |
||||
panda = Panda() |
||||
uds_client = UdsClient(panda, address, debug=False) |
||||
|
||||
print("tester present ...") |
||||
uds_client.tester_present() |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: boot software id ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.BOOT_SOFTWARE_IDENTIFICATION) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: application software id ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: application data id ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: boot software fingerprint ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.BOOT_SOFTWARE_FINGERPRINT) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: application software fingerprint ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_FINGERPRINT) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
||||
|
||||
try: |
||||
print("") |
||||
print("read data by id: application data fingerprint ...") |
||||
data = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_FINGERPRINT) |
||||
print(data.decode('utf-8')) |
||||
except NegativeResponseError as e: |
||||
print(e) |
@ -0,0 +1,770 @@ |
||||
#!/usr/bin/env python3 |
||||
import time |
||||
import struct |
||||
from typing import NamedTuple, List |
||||
from enum import IntEnum |
||||
from queue import Queue, Empty |
||||
from threading import Thread |
||||
from binascii import hexlify |
||||
|
||||
class SERVICE_TYPE(IntEnum): |
||||
DIAGNOSTIC_SESSION_CONTROL = 0x10 |
||||
ECU_RESET = 0x11 |
||||
SECURITY_ACCESS = 0x27 |
||||
COMMUNICATION_CONTROL = 0x28 |
||||
TESTER_PRESENT = 0x3E |
||||
ACCESS_TIMING_PARAMETER = 0x83 |
||||
SECURED_DATA_TRANSMISSION = 0x84 |
||||
CONTROL_DTC_SETTING = 0x85 |
||||
RESPONSE_ON_EVENT = 0x86 |
||||
LINK_CONTROL = 0x87 |
||||
READ_DATA_BY_IDENTIFIER = 0x22 |
||||
READ_MEMORY_BY_ADDRESS = 0x23 |
||||
READ_SCALING_DATA_BY_IDENTIFIER = 0x24 |
||||
READ_DATA_BY_PERIODIC_IDENTIFIER = 0x2A |
||||
DYNAMICALLY_DEFINE_DATA_IDENTIFIER = 0x2C |
||||
WRITE_DATA_BY_IDENTIFIER = 0x2E |
||||
WRITE_MEMORY_BY_ADDRESS = 0x3D |
||||
CLEAR_DIAGNOSTIC_INFORMATION = 0x14 |
||||
READ_DTC_INFORMATION = 0x19 |
||||
INPUT_OUTPUT_CONTROL_BY_IDENTIFIER = 0x2F |
||||
ROUTINE_CONTROL = 0x31 |
||||
REQUEST_DOWNLOAD = 0x34 |
||||
REQUEST_UPLOAD = 0x35 |
||||
TRANSFER_DATA = 0x36 |
||||
REQUEST_TRANSFER_EXIT = 0x37 |
||||
|
||||
class SESSION_TYPE(IntEnum): |
||||
DEFAULT = 1 |
||||
PROGRAMMING = 2 |
||||
EXTENDED_DIAGNOSTIC = 3 |
||||
SAFETY_SYSTEM_DIAGNOSTIC = 4 |
||||
|
||||
class RESET_TYPE(IntEnum): |
||||
HARD = 1 |
||||
KEY_OFF_ON = 2 |
||||
SOFT = 3 |
||||
ENABLE_RAPID_POWER_SHUTDOWN = 4 |
||||
DISABLE_RAPID_POWER_SHUTDOWN = 5 |
||||
|
||||
class ACCESS_TYPE(IntEnum): |
||||
REQUEST_SEED = 1 |
||||
SEND_KEY = 2 |
||||
|
||||
class CONTROL_TYPE(IntEnum): |
||||
ENABLE_RX_ENABLE_TX = 0 |
||||
ENABLE_RX_DISABLE_TX = 1 |
||||
DISABLE_RX_ENABLE_TX = 2 |
||||
DISABLE_RX_DISABLE_TX = 3 |
||||
|
||||
class MESSAGE_TYPE(IntEnum): |
||||
NORMAL = 1 |
||||
NETWORK_MANAGEMENT = 2 |
||||
NORMAL_AND_NETWORK_MANAGEMENT = 3 |
||||
|
||||
class TIMING_PARAMETER_TYPE(IntEnum): |
||||
READ_EXTENDED_SET = 1 |
||||
SET_TO_DEFAULT_VALUES = 2 |
||||
READ_CURRENTLY_ACTIVE = 3 |
||||
SET_TO_GIVEN_VALUES = 4 |
||||
|
||||
class DTC_SETTING_TYPE(IntEnum): |
||||
ON = 1 |
||||
OFF = 2 |
||||
|
||||
class RESPONSE_EVENT_TYPE(IntEnum): |
||||
STOP_RESPONSE_ON_EVENT = 0 |
||||
ON_DTC_STATUS_CHANGE = 1 |
||||
ON_TIMER_INTERRUPT = 2 |
||||
ON_CHANGE_OF_DATA_IDENTIFIER = 3 |
||||
REPORT_ACTIVATED_EVENTS = 4 |
||||
START_RESPONSE_ON_EVENT = 5 |
||||
CLEAR_RESPONSE_ON_EVENT = 6 |
||||
ON_COMPARISON_OF_VALUES = 7 |
||||
|
||||
class LINK_CONTROL_TYPE(IntEnum): |
||||
VERIFY_BAUDRATE_TRANSITION_WITH_FIXED_BAUDRATE = 1 |
||||
VERIFY_BAUDRATE_TRANSITION_WITH_SPECIFIC_BAUDRATE = 2 |
||||
TRANSITION_BAUDRATE = 3 |
||||
|
||||
class BAUD_RATE_TYPE(IntEnum): |
||||
PC9600 = 1 |
||||
PC19200 = 2 |
||||
PC38400 = 3 |
||||
PC57600 = 4 |
||||
PC115200 = 5 |
||||
CAN125000 = 16 |
||||
CAN250000 = 17 |
||||
CAN500000 = 18 |
||||
CAN1000000 = 19 |
||||
|
||||
class DATA_IDENTIFIER_TYPE(IntEnum): |
||||
BOOT_SOFTWARE_IDENTIFICATION = 0xF180 |
||||
APPLICATION_SOFTWARE_IDENTIFICATION = 0xF181 |
||||
APPLICATION_DATA_IDENTIFICATION = 0xF182 |
||||
BOOT_SOFTWARE_FINGERPRINT = 0xF183 |
||||
APPLICATION_SOFTWARE_FINGERPRINT = 0xF184 |
||||
APPLICATION_DATA_FINGERPRINT = 0xF185 |
||||
ACTIVE_DIAGNOSTIC_SESSION = 0xF186 |
||||
VEHICLE_MANUFACTURER_SPARE_PART_NUMBER = 0xF187 |
||||
VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER = 0xF188 |
||||
VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER = 0xF189 |
||||
SYSTEM_SUPPLIER_IDENTIFIER = 0xF18A |
||||
ECU_MANUFACTURING_DATE = 0xF18B |
||||
ECU_SERIAL_NUMBER = 0xF18C |
||||
SUPPORTED_FUNCTIONAL_UNITS = 0xF18D |
||||
VEHICLE_MANUFACTURER_KIT_ASSEMBLY_PART_NUMBER = 0xF18E |
||||
VIN = 0xF190 |
||||
VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER = 0xF191 |
||||
SYSTEM_SUPPLIER_ECU_HARDWARE_NUMBER = 0xF192 |
||||
SYSTEM_SUPPLIER_ECU_HARDWARE_VERSION_NUMBER = 0xF193 |
||||
SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER = 0xF194 |
||||
SYSTEM_SUPPLIER_ECU_SOFTWARE_VERSION_NUMBER = 0xF195 |
||||
EXHAUST_REGULATION_OR_TYPE_APPROVAL_NUMBER = 0xF196 |
||||
SYSTEM_NAME_OR_ENGINE_TYPE = 0xF197 |
||||
REPAIR_SHOP_CODE_OR_TESTER_SERIAL_NUMBER = 0xF198 |
||||
PROGRAMMING_DATE = 0xF199 |
||||
CALIBRATION_REPAIR_SHOP_CODE_OR_CALIBRATION_EQUIPMENT_SERIAL_NUMBER = 0xF19A |
||||
CALIBRATION_DATE = 0xF19B |
||||
CALIBRATION_EQUIPMENT_SOFTWARE_NUMBER = 0xF19C |
||||
ECU_INSTALLATION_DATE = 0xF19D |
||||
ODX_FILE = 0xF19E |
||||
ENTITY = 0xF19F |
||||
|
||||
class TRANSMISSION_MODE_TYPE(IntEnum): |
||||
SEND_AT_SLOW_RATE = 1 |
||||
SEND_AT_MEDIUM_RATE = 2 |
||||
SEND_AT_FAST_RATE = 3 |
||||
STOP_SENDING = 4 |
||||
|
||||
class DYNAMIC_DEFINITION_TYPE(IntEnum): |
||||
DEFINE_BY_IDENTIFIER = 1 |
||||
DEFINE_BY_MEMORY_ADDRESS = 2 |
||||
CLEAR_DYNAMICALLY_DEFINED_DATA_IDENTIFIER = 3 |
||||
|
||||
class DynamicSourceDefinition(NamedTuple): |
||||
data_identifier: int |
||||
position: int |
||||
memory_size: int |
||||
memory_address: int |
||||
|
||||
class DTC_GROUP_TYPE(IntEnum): |
||||
EMISSIONS = 0x000000 |
||||
ALL = 0xFFFFFF |
||||
|
||||
class DTC_REPORT_TYPE(IntEnum): |
||||
NUMBER_OF_DTC_BY_STATUS_MASK = 0x01 |
||||
DTC_BY_STATUS_MASK = 0x02 |
||||
DTC_SNAPSHOT_IDENTIFICATION = 0x03 |
||||
DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER = 0x04 |
||||
DTC_SNAPSHOT_RECORD_BY_RECORD_NUMBER = 0x05 |
||||
DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER = 0x06 |
||||
NUMBER_OF_DTC_BY_SEVERITY_MASK_RECORD = 0x07 |
||||
DTC_BY_SEVERITY_MASK_RECORD = 0x08 |
||||
SEVERITY_INFORMATION_OF_DTC = 0x09 |
||||
SUPPORTED_DTC = 0x0A |
||||
FIRST_TEST_FAILED_DTC = 0x0B |
||||
FIRST_CONFIRMED_DTC = 0x0C |
||||
MOST_RECENT_TEST_FAILED_DTC = 0x0D |
||||
MOST_RECENT_CONFIRMED_DTC = 0x0E |
||||
MIRROR_MEMORY_DTC_BY_STATUS_MASK = 0x0F |
||||
MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER = 0x10 |
||||
NUMBER_OF_MIRROR_MEMORY_DTC_BY_STATUS_MASK = 0x11 |
||||
NUMBER_OF_EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK = 0x12 |
||||
EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK = 0x13 |
||||
DTC_FAULT_DETECTION_COUNTER = 0x14 |
||||
DTC_WITH_PERMANENT_STATUS = 0x15 |
||||
|
||||
class DTC_STATUS_MASK_TYPE(IntEnum): |
||||
TEST_FAILED = 0x01 |
||||
TEST_FAILED_THIS_OPERATION_CYCLE = 0x02 |
||||
PENDING_DTC = 0x04 |
||||
CONFIRMED_DTC = 0x08 |
||||
TEST_NOT_COMPLETED_SINCE_LAST_CLEAR = 0x10 |
||||
TEST_FAILED_SINCE_LAST_CLEAR = 0x20 |
||||
TEST_NOT_COMPLETED_THIS_OPERATION_CYCLE = 0x40 |
||||
WARNING_INDICATOR_REQUESTED = 0x80 |
||||
ALL = 0xFF |
||||
|
||||
class DTC_SEVERITY_MASK_TYPE(IntEnum): |
||||
MAINTENANCE_ONLY = 0x20 |
||||
CHECK_AT_NEXT_HALT = 0x40 |
||||
CHECK_IMMEDIATELY = 0x80 |
||||
ALL = 0xE0 |
||||
|
||||
class CONTROL_PARAMETER_TYPE(IntEnum): |
||||
RETURN_CONTROL_TO_ECU = 0 |
||||
RESET_TO_DEFAULT = 1 |
||||
FREEZE_CURRENT_STATE = 2 |
||||
SHORT_TERM_ADJUSTMENT = 3 |
||||
|
||||
class ROUTINE_CONTROL_TYPE(IntEnum): |
||||
START = 1 |
||||
STOP = 2 |
||||
REQUEST_RESULTS = 3 |
||||
|
||||
class ROUTINE_IDENTIFIER_TYPE(IntEnum): |
||||
ERASE_MEMORY = 0xFF00 |
||||
CHECK_PROGRAMMING_DEPENDENCIES = 0xFF01 |
||||
ERASE_MIRROR_MEMORY_DTCS = 0xFF02 |
||||
|
||||
class MessageTimeoutError(Exception): |
||||
pass |
||||
|
||||
class NegativeResponseError(Exception): |
||||
def __init__(self, message, service_id, error_code): |
||||
self.message = message |
||||
self.service_id = service_id |
||||
self.error_code = error_code |
||||
|
||||
def __str__(self): |
||||
return self.message |
||||
|
||||
class InvalidServiceIdError(Exception): |
||||
pass |
||||
|
||||
class InvalidSubFunctioneError(Exception): |
||||
pass |
||||
|
||||
_negative_response_codes = { |
||||
0x00: 'positive response', |
||||
0x10: 'general reject', |
||||
0x11: 'service not supported', |
||||
0x12: 'sub-function not supported', |
||||
0x13: 'incorrect message length or invalid format', |
||||
0x14: 'response too long', |
||||
0x21: 'busy repeat request', |
||||
0x22: 'conditions not correct', |
||||
0x24: 'request sequence error', |
||||
0x25: 'no response from subnet component', |
||||
0x26: 'failure prevents execution of requested action', |
||||
0x31: 'request out of range', |
||||
0x33: 'security access denied', |
||||
0x35: 'invalid key', |
||||
0x36: 'exceed numebr of attempts', |
||||
0x37: 'required time delay not expired', |
||||
0x70: 'upload download not accepted', |
||||
0x71: 'transfer data suspended', |
||||
0x72: 'general programming failure', |
||||
0x73: 'wrong block sequence counter', |
||||
0x78: 'request correctly received - response pending', |
||||
0x7e: 'sub-function not supported in active session', |
||||
0x7f: 'service not supported in active session', |
||||
0x81: 'rpm too high', |
||||
0x82: 'rpm too low', |
||||
0x83: 'engine is running', |
||||
0x84: 'engine is not running', |
||||
0x85: 'engine run time too low', |
||||
0x86: 'temperature too high', |
||||
0x87: 'temperature too low', |
||||
0x88: 'vehicle speed too high', |
||||
0x89: 'vehicle speed too low', |
||||
0x8a: 'throttle/pedal too high', |
||||
0x8b: 'throttle/pedal too low', |
||||
0x8c: 'transmission not in neutral', |
||||
0x8d: 'transmission not in gear', |
||||
0x8f: 'brake switch(es) not closed', |
||||
0x90: 'shifter lever not in park', |
||||
0x91: 'torque converter clutch locked', |
||||
0x92: 'voltage too high', |
||||
0x93: 'voltage too low', |
||||
} |
||||
|
||||
class IsoTpMessage(): |
||||
def __init__(self, can_tx_queue: Queue, can_rx_queue: Queue, timeout: float, debug: bool=False): |
||||
self.can_tx_queue = can_tx_queue |
||||
self.can_rx_queue = can_rx_queue |
||||
self.timeout = timeout |
||||
self.debug = debug |
||||
|
||||
def send(self, dat: bytes) -> None: |
||||
self.tx_dat = dat |
||||
self.tx_len = len(dat) |
||||
self.tx_idx = 0 |
||||
self.tx_done = False |
||||
|
||||
if self.debug: print(f"ISO-TP: REQUEST - {hexlify(self.tx_dat)}") |
||||
self._tx_first_frame() |
||||
|
||||
def _tx_first_frame(self) -> None: |
||||
if self.tx_len < 8: |
||||
# single frame (send all bytes) |
||||
if self.debug: print("ISO-TP: TX - single frame") |
||||
msg = (bytes([self.tx_len]) + self.tx_dat).ljust(8, b"\x00") |
||||
self.tx_done = True |
||||
else: |
||||
# first frame (send first 6 bytes) |
||||
if self.debug: print("ISO-TP: TX - first frame") |
||||
msg = (struct.pack("!H", 0x1000 | self.tx_len) + self.tx_dat[:6]).ljust(8, b"\x00") |
||||
self.can_tx_queue.put(msg) |
||||
|
||||
def recv(self) -> bytes: |
||||
self.rx_dat = b"" |
||||
self.rx_len = 0 |
||||
self.rx_idx = 0 |
||||
self.rx_done = False |
||||
|
||||
try: |
||||
while True: |
||||
self._isotp_rx_next() |
||||
if self.tx_done and self.rx_done: |
||||
return self.rx_dat |
||||
except Empty: |
||||
raise MessageTimeoutError("timeout waiting for response") |
||||
finally: |
||||
if self.debug: print(f"ISO-TP: RESPONSE - {hexlify(self.rx_dat)}") |
||||
|
||||
def _isotp_rx_next(self) -> None: |
||||
rx_data = self.can_rx_queue.get(block=True, timeout=self.timeout) |
||||
|
||||
# single rx_frame |
||||
if rx_data[0] >> 4 == 0x0: |
||||
self.rx_len = rx_data[0] & 0xFF |
||||
self.rx_dat = rx_data[1:1+self.rx_len] |
||||
self.rx_idx = 0 |
||||
self.rx_done = True |
||||
if self.debug: print(f"ISO-TP: RX - single frame - idx={self.rx_idx} done={self.rx_done}") |
||||
return |
||||
|
||||
# first rx_frame |
||||
if rx_data[0] >> 4 == 0x1: |
||||
self.rx_len = ((rx_data[0] & 0x0F) << 8) + rx_data[1] |
||||
self.rx_dat = rx_data[2:] |
||||
self.rx_idx = 0 |
||||
self.rx_done = False |
||||
if self.debug: print(f"ISO-TP: RX - first frame - idx={self.rx_idx} done={self.rx_done}") |
||||
if self.debug: print(f"ISO-TP: TX - flow control continue") |
||||
# send flow control message (send all bytes) |
||||
msg = b"\x30\x00\x00".ljust(8, b"\x00") |
||||
self.can_tx_queue.put(msg) |
||||
return |
||||
|
||||
# consecutive rx frame |
||||
if rx_data[0] >> 4 == 0x2: |
||||
assert self.rx_done == False, "isotp - rx: consecutive frame with no active frame" |
||||
self.rx_idx += 1 |
||||
assert self.rx_idx & 0xF == rx_data[0] & 0xF, "isotp - rx: invalid consecutive frame index" |
||||
rx_size = self.rx_len - len(self.rx_dat) |
||||
self.rx_dat += rx_data[1:1+min(rx_size, 7)] |
||||
if self.rx_len == len(self.rx_dat): |
||||
self.rx_done = True |
||||
if self.debug: print(f"ISO-TP: RX - consecutive frame - idx={self.rx_idx} done={self.rx_done}") |
||||
return |
||||
|
||||
# flow control |
||||
if rx_data[0] >> 4 == 0x3: |
||||
assert self.tx_done == False, "isotp - rx: flow control with no active frame" |
||||
assert rx_data[0] != 0x32, "isotp - rx: flow-control overflow/abort" |
||||
assert rx_data[0] == 0x30 or rx_data[0] == 0x31, "isotp - rx: flow-control transfer state indicator invalid" |
||||
if rx_data[0] == 0x30: |
||||
if self.debug: print("ISO-TP: RX - flow control continue") |
||||
delay_ts = rx_data[2] & 0x7F |
||||
# scale is 1 milliseconds if first bit == 0, 100 micro seconds if first bit == 1 |
||||
delay_div = 1000. if rx_data[2] & 0x80 == 0 else 10000. |
||||
# first frame = 6 bytes, each consecutive frame = 7 bytes |
||||
start = 6 + self.tx_idx * 7 |
||||
count = rx_data[1] |
||||
end = start + count * 7 if count > 0 else self.tx_len |
||||
for i in range(start, end, 7): |
||||
if delay_ts > 0 and i > start: |
||||
delay_s = delay_ts / delay_div |
||||
if self.debug: print(f"ISO-TP: TX - delay - seconds={delay_s}") |
||||
time.sleep(delay_s) |
||||
self.tx_idx += 1 |
||||
# consecutive tx frames |
||||
msg = (bytes([0x20 | (self.tx_idx & 0xF)]) + self.tx_dat[i:i+7]).ljust(8, b"\x00") |
||||
self.can_tx_queue.put(msg) |
||||
if end >= self.tx_len: |
||||
self.tx_done = True |
||||
if self.debug: print(f"ISO-TP: TX - consecutive frame - idx={self.tx_idx} done={self.tx_done}") |
||||
elif rx_data[0] == 0x31: |
||||
# wait (do nothing until next flow control message) |
||||
if self.debug: print("ISO-TP: TX - flow control wait") |
||||
|
||||
class UdsClient(): |
||||
def __init__(self, panda, tx_addr: int, rx_addr: int=None, bus: int=0, timeout: float=10, debug: bool=False): |
||||
self.panda = panda |
||||
self.bus = bus |
||||
self.tx_addr = tx_addr |
||||
if rx_addr == None: |
||||
if tx_addr < 0xFFF8: |
||||
# standard 11 bit response addr (add 8) |
||||
self.rx_addr = tx_addr+8 |
||||
elif tx_addr > 0x10000000 and tx_addr < 0xFFFFFFFF: |
||||
# standard 29 bit response addr (flip last two bytes) |
||||
self.rx_addr = (tx_addr & 0xFFFF0000) + (tx_addr<<8 & 0xFF00) + (tx_addr>>8 & 0xFF) |
||||
else: |
||||
raise ValueError("invalid tx_addr: {}".format(tx_addr)) |
||||
|
||||
self.can_tx_queue = Queue() |
||||
self.can_rx_queue = Queue() |
||||
self.timeout = timeout |
||||
self.debug = debug |
||||
|
||||
self.can_thread = Thread(target=self._can_thread, args=(self.debug,)) |
||||
self.can_thread.daemon = True |
||||
self.can_thread.start() |
||||
|
||||
def _can_thread(self, debug: bool=False): |
||||
try: |
||||
# allow all output |
||||
self.panda.set_safety_mode(0x1337) |
||||
# clear tx buffer |
||||
self.panda.can_clear(self.bus) |
||||
# clear rx buffer |
||||
self.panda.can_clear(0xFFFF) |
||||
|
||||
while True: |
||||
# send |
||||
while not self.can_tx_queue.empty(): |
||||
msg = self.can_tx_queue.get(block=False) |
||||
if debug: print("CAN-TX: {} - {}".format(hex(self.tx_addr), hexlify(msg))) |
||||
self.panda.can_send(self.tx_addr, msg, self.bus) |
||||
|
||||
# receive |
||||
msgs = self.panda.can_recv() |
||||
for rx_addr, rx_ts, rx_data, rx_bus in msgs: |
||||
if rx_bus != self.bus or rx_addr != self.rx_addr or len(rx_data) == 0: |
||||
continue |
||||
if debug: print("CAN-RX: {} - {}".format(hex(self.rx_addr), hexlify(rx_data))) |
||||
self.can_rx_queue.put(rx_data) |
||||
else: |
||||
time.sleep(0.01) |
||||
finally: |
||||
self.panda.close() |
||||
|
||||
# generic uds request |
||||
def _uds_request(self, service_type: SERVICE_TYPE, subfunction: int=None, data: bytes=None) -> bytes: |
||||
req = bytes([service_type]) |
||||
if subfunction is not None: |
||||
req += bytes([subfunction]) |
||||
if data is not None: |
||||
req += data |
||||
|
||||
# send request, wait for response |
||||
isotp_msg = IsoTpMessage(self.can_tx_queue, self.can_rx_queue, self.timeout, self.debug) |
||||
isotp_msg.send(req) |
||||
while True: |
||||
resp = isotp_msg.recv() |
||||
resp_sid = resp[0] if len(resp) > 0 else None |
||||
|
||||
# negative response |
||||
if resp_sid == 0x7F: |
||||
service_id = resp[1] if len(resp) > 1 else -1 |
||||
try: |
||||
service_desc = SERVICE_TYPE(service_id).name |
||||
except Exception: |
||||
service_desc = 'NON_STANDARD_SERVICE' |
||||
error_code = resp[2] if len(resp) > 2 else -1 |
||||
try: |
||||
error_desc = _negative_response_codes[error_code] |
||||
except Exception: |
||||
error_desc = resp[3:] |
||||
# wait for another message if response pending |
||||
if error_code == 0x78: |
||||
if self.debug: print("UDS-RX: response pending") |
||||
continue |
||||
raise NegativeResponseError('{} - {}'.format(service_desc, error_desc), service_id, error_code) |
||||
|
||||
# positive response |
||||
if service_type+0x40 != resp_sid: |
||||
resp_sid_hex = hex(resp_sid) if resp_sid is not None else None |
||||
raise InvalidServiceIdError('invalid response service id: {}'.format(resp_sid_hex)) |
||||
|
||||
if subfunction is not None: |
||||
resp_sfn = resp[1] if len(resp) > 1 else None |
||||
if subfunction != resp_sfn: |
||||
resp_sfn_hex = hex(resp_sfn) if resp_sfn is not None else None |
||||
raise InvalidSubFunctioneError('invalid response subfunction: {}'.format(hex(resp_sfn_hex))) |
||||
|
||||
# return data (exclude service id and sub-function id) |
||||
return resp[(1 if subfunction is None else 2):] |
||||
|
||||
# services |
||||
def diagnostic_session_control(self, session_type: SESSION_TYPE): |
||||
self._uds_request(SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, subfunction=session_type) |
||||
|
||||
def ecu_reset(self, reset_type: RESET_TYPE): |
||||
resp = self._uds_request(SERVICE_TYPE.ECU_RESET, subfunction=reset_type) |
||||
power_down_time = None |
||||
if reset_type == RESET_TYPE.ENABLE_RAPID_POWER_SHUTDOWN: |
||||
power_down_time = resp[0] |
||||
return power_down_time |
||||
|
||||
def security_access(self, access_type: ACCESS_TYPE, security_key: bytes=None): |
||||
request_seed = access_type % 2 != 0 |
||||
if request_seed and security_key is not None: |
||||
raise ValueError('security_key not allowed') |
||||
if not request_seed and security_key is None: |
||||
raise ValueError('security_key is missing') |
||||
resp = self._uds_request(SERVICE_TYPE.SECURITY_ACCESS, subfunction=access_type, data=security_key) |
||||
if request_seed: |
||||
security_seed = resp |
||||
return security_seed |
||||
|
||||
def communication_control(self, control_type: CONTROL_TYPE, message_type: MESSAGE_TYPE): |
||||
data = bytes([message_type]) |
||||
self._uds_request(SERVICE_TYPE.COMMUNICATION_CONTROL, subfunction=control_type, data=data) |
||||
|
||||
def tester_present(self, ): |
||||
self._uds_request(SERVICE_TYPE.TESTER_PRESENT, subfunction=0x00) |
||||
|
||||
def access_timing_parameter(self, timing_parameter_type: TIMING_PARAMETER_TYPE, parameter_values: bytes=None): |
||||
write_custom_values = timing_parameter_type == TIMING_PARAMETER_TYPE.SET_TO_GIVEN_VALUES |
||||
read_values = ( |
||||
timing_parameter_type == TIMING_PARAMETER_TYPE.READ_CURRENTLY_ACTIVE or |
||||
timing_parameter_type == TIMING_PARAMETER_TYPE.READ_EXTENDED_SET |
||||
) |
||||
if not write_custom_values and parameter_values is not None: |
||||
raise ValueError('parameter_values not allowed') |
||||
if write_custom_values and parameter_values is None: |
||||
raise ValueError('parameter_values is missing') |
||||
resp = self._uds_request(SERVICE_TYPE.ACCESS_TIMING_PARAMETER, subfunction=timing_parameter_type, data=parameter_values) |
||||
if read_values: |
||||
# TODO: parse response into values? |
||||
parameter_values = resp |
||||
return parameter_values |
||||
|
||||
def secured_data_transmission(self, data: bytes): |
||||
# TODO: split data into multiple input parameters? |
||||
resp = self._uds_request(SERVICE_TYPE.SECURED_DATA_TRANSMISSION, subfunction=None, data=data) |
||||
# TODO: parse response into multiple output values? |
||||
return resp |
||||
|
||||
def control_dtc_setting(self, dtc_setting_type: DTC_SETTING_TYPE): |
||||
self._uds_request(SERVICE_TYPE.CONTROL_DTC_SETTING, subfunction=dtc_setting_type) |
||||
|
||||
def response_on_event(self, response_event_type: RESPONSE_EVENT_TYPE, store_event: bool, window_time: int, event_type_record: int, service_response_record: int): |
||||
if store_event: |
||||
response_event_type |= 0x20 |
||||
# TODO: split record parameters into arrays |
||||
data = bytes([window_time, event_type_record, service_response_record]) |
||||
resp = self._uds_request(SERVICE_TYPE.RESPONSE_ON_EVENT, subfunction=response_event_type, data=data) |
||||
|
||||
if response_event_type == RESPONSE_EVENT_TYPE.REPORT_ACTIVATED_EVENTS: |
||||
return { |
||||
"num_of_activated_events": resp[0], |
||||
"data": resp[1:], # TODO: parse the reset of response |
||||
} |
||||
|
||||
return { |
||||
"num_of_identified_events": resp[0], |
||||
"event_window_time": resp[1], |
||||
"data": resp[2:], # TODO: parse the reset of response |
||||
} |
||||
|
||||
def link_control(self, link_control_type: LINK_CONTROL_TYPE, baud_rate_type: BAUD_RATE_TYPE=None): |
||||
if link_control_type == LINK_CONTROL_TYPE.VERIFY_BAUDRATE_TRANSITION_WITH_FIXED_BAUDRATE: |
||||
# baud_rate_type = BAUD_RATE_TYPE |
||||
data = bytes([baud_rate_type]) |
||||
elif link_control_type == LINK_CONTROL_TYPE.VERIFY_BAUDRATE_TRANSITION_WITH_SPECIFIC_BAUDRATE: |
||||
# baud_rate_type = custom value (3 bytes big-endian) |
||||
data = struct.pack('!I', baud_rate_type)[1:] |
||||
else: |
||||
data = None |
||||
self._uds_request(SERVICE_TYPE.LINK_CONTROL, subfunction=link_control_type, data=data) |
||||
|
||||
def read_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE): |
||||
# TODO: support list of identifiers |
||||
data = struct.pack('!H', data_identifier_type) |
||||
resp = self._uds_request(SERVICE_TYPE.READ_DATA_BY_IDENTIFIER, subfunction=None, data=data) |
||||
resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None |
||||
if resp_id != data_identifier_type: |
||||
raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) |
||||
return resp[2:] |
||||
|
||||
def read_memory_by_address(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=1): |
||||
if memory_address_bytes < 1 or memory_address_bytes > 4: |
||||
raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) |
||||
if memory_size_bytes < 1 or memory_size_bytes > 4: |
||||
raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) |
||||
data = bytes([memory_size_bytes<<4 | memory_address_bytes]) |
||||
|
||||
if memory_address >= 1<<(memory_address_bytes*8): |
||||
raise ValueError('invalid memory_address: {}'.format(memory_address)) |
||||
data += struct.pack('!I', memory_address)[4-memory_address_bytes:] |
||||
if memory_size >= 1<<(memory_size_bytes*8): |
||||
raise ValueError('invalid memory_size: {}'.format(memory_size)) |
||||
data += struct.pack('!I', memory_size)[4-memory_size_bytes:] |
||||
|
||||
resp = self._uds_request(SERVICE_TYPE.READ_MEMORY_BY_ADDRESS, subfunction=None, data=data) |
||||
return resp |
||||
|
||||
def read_scaling_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE): |
||||
data = struct.pack('!H', data_identifier_type) |
||||
resp = self._uds_request(SERVICE_TYPE.READ_SCALING_DATA_BY_IDENTIFIER, subfunction=None, data=data) |
||||
resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None |
||||
if resp_id != data_identifier_type: |
||||
raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) |
||||
return resp[2:] # TODO: parse the response |
||||
|
||||
def read_data_by_periodic_identifier(self, transmission_mode_type: TRANSMISSION_MODE_TYPE, periodic_data_identifier: int): |
||||
# TODO: support list of identifiers |
||||
data = bytes([transmission_mode_type, periodic_data_identifier]) |
||||
self._uds_request(SERVICE_TYPE.READ_DATA_BY_PERIODIC_IDENTIFIER, subfunction=None, data=data) |
||||
|
||||
def dynamically_define_data_identifier(self, dynamic_definition_type: DYNAMIC_DEFINITION_TYPE, dynamic_data_identifier: int, source_definitions: List[DynamicSourceDefinition], memory_address_bytes: int=4, memory_size_bytes: int=1): |
||||
if memory_address_bytes < 1 or memory_address_bytes > 4: |
||||
raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) |
||||
if memory_size_bytes < 1 or memory_size_bytes > 4: |
||||
raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) |
||||
|
||||
data = struct.pack('!H', dynamic_data_identifier) |
||||
if dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.DEFINE_BY_IDENTIFIER: |
||||
for s in source_definitions: |
||||
data += struct.pack('!H', s["data_identifier"]) + bytes([s["position"], s["memory_size"]]) |
||||
elif dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.DEFINE_BY_MEMORY_ADDRESS: |
||||
data += bytes([memory_size_bytes<<4 | memory_address_bytes]) |
||||
for s in source_definitions: |
||||
if s["memory_address"] >= 1<<(memory_address_bytes*8): |
||||
raise ValueError('invalid memory_address: {}'.format(s["memory_address"])) |
||||
data += struct.pack('!I', s["memory_address"])[4-memory_address_bytes:] |
||||
if s["memory_size"] >= 1<<(memory_size_bytes*8): |
||||
raise ValueError('invalid memory_size: {}'.format(s["memory_size"])) |
||||
data += struct.pack('!I', s["memory_size"])[4-memory_size_bytes:] |
||||
elif dynamic_definition_type == DYNAMIC_DEFINITION_TYPE.CLEAR_DYNAMICALLY_DEFINED_DATA_IDENTIFIER: |
||||
pass |
||||
else: |
||||
raise ValueError('invalid dynamic identifier type: {}'.format(hex(dynamic_definition_type))) |
||||
self._uds_request(SERVICE_TYPE.DYNAMICALLY_DEFINE_DATA_IDENTIFIER, subfunction=dynamic_definition_type, data=data) |
||||
|
||||
def write_data_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE, data_record: bytes): |
||||
data = struct.pack('!H', data_identifier_type) + data_record |
||||
resp = self._uds_request(SERVICE_TYPE.WRITE_DATA_BY_IDENTIFIER, subfunction=None, data=data) |
||||
resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None |
||||
if resp_id != data_identifier_type: |
||||
raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) |
||||
|
||||
def write_memory_by_address(self, memory_address: int, memory_size: int, data_record: bytes, memory_address_bytes: int=4, memory_size_bytes: int=1): |
||||
if memory_address_bytes < 1 or memory_address_bytes > 4: |
||||
raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) |
||||
if memory_size_bytes < 1 or memory_size_bytes > 4: |
||||
raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) |
||||
data = bytes([memory_size_bytes<<4 | memory_address_bytes]) |
||||
|
||||
if memory_address >= 1<<(memory_address_bytes*8): |
||||
raise ValueError('invalid memory_address: {}'.format(memory_address)) |
||||
data += struct.pack('!I', memory_address)[4-memory_address_bytes:] |
||||
if memory_size >= 1<<(memory_size_bytes*8): |
||||
raise ValueError('invalid memory_size: {}'.format(memory_size)) |
||||
data += struct.pack('!I', memory_size)[4-memory_size_bytes:] |
||||
|
||||
data += data_record |
||||
self._uds_request(SERVICE_TYPE.WRITE_MEMORY_BY_ADDRESS, subfunction=0x00, data=data) |
||||
|
||||
def clear_diagnostic_information(self, dtc_group_type: DTC_GROUP_TYPE): |
||||
data = struct.pack('!I', dtc_group_type)[1:] # 3 bytes |
||||
self._uds_request(SERVICE_TYPE.CLEAR_DIAGNOSTIC_INFORMATION, subfunction=None, data=data) |
||||
|
||||
def read_dtc_information(self, dtc_report_type: DTC_REPORT_TYPE, dtc_status_mask_type: DTC_STATUS_MASK_TYPE=DTC_STATUS_MASK_TYPE.ALL, dtc_severity_mask_type: DTC_SEVERITY_MASK_TYPE=DTC_SEVERITY_MASK_TYPE.ALL, dtc_mask_record: int=0xFFFFFF, dtc_snapshot_record_num: int=0xFF, dtc_extended_record_num: int=0xFF): |
||||
data = b'' |
||||
# dtc_status_mask_type |
||||
if dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_DTC_BY_STATUS_MASK or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_BY_STATUS_MASK or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_BY_STATUS_MASK or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_MIRROR_MEMORY_DTC_BY_STATUS_MASK or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.EMISSIONS_RELATED_OBD_DTC_BY_STATUS_MASK: |
||||
data += bytes([dtc_status_mask_type]) |
||||
# dtc_mask_record |
||||
if dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_IDENTIFICATION or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.SEVERITY_INFORMATION_OF_DTC: |
||||
data += struct.pack('!I', dtc_mask_record)[1:] # 3 bytes |
||||
# dtc_snapshot_record_num |
||||
if dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_IDENTIFICATION or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_DTC_NUMBER or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_SNAPSHOT_RECORD_BY_RECORD_NUMBER: |
||||
data += ord(dtc_snapshot_record_num) |
||||
# dtc_extended_record_num |
||||
if dtc_report_type == DTC_REPORT_TYPE.DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.MIRROR_MEMORY_DTC_EXTENDED_DATA_RECORD_BY_DTC_NUMBER: |
||||
data += bytes([dtc_extended_record_num]) |
||||
# dtc_severity_mask_type |
||||
if dtc_report_type == DTC_REPORT_TYPE.NUMBER_OF_DTC_BY_SEVERITY_MASK_RECORD or \ |
||||
dtc_report_type == DTC_REPORT_TYPE.DTC_BY_SEVERITY_MASK_RECORD: |
||||
data += bytes([dtc_severity_mask_type, dtc_status_mask_type]) |
||||
|
||||
resp = self._uds_request(SERVICE_TYPE.READ_DTC_INFORMATION, subfunction=dtc_report_type, data=data) |
||||
|
||||
# TODO: parse response |
||||
return resp |
||||
|
||||
def input_output_control_by_identifier(self, data_identifier_type: DATA_IDENTIFIER_TYPE, control_parameter_type: CONTROL_PARAMETER_TYPE, control_option_record: bytes, control_enable_mask_record: bytes=b''): |
||||
data = struct.pack('!H', data_identifier_type) + bytes([control_parameter_type]) + control_option_record + control_enable_mask_record |
||||
resp = self._uds_request(SERVICE_TYPE.INPUT_OUTPUT_CONTROL_BY_IDENTIFIER, subfunction=None, data=data) |
||||
resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None |
||||
if resp_id != data_identifier_type: |
||||
raise ValueError('invalid response data identifier: {}'.format(hex(resp_id))) |
||||
return resp[2:] |
||||
|
||||
def routine_control(self, routine_control_type: ROUTINE_CONTROL_TYPE, routine_identifier_type: ROUTINE_IDENTIFIER_TYPE, routine_option_record: bytes=b''): |
||||
data = struct.pack('!H', routine_identifier_type) + routine_option_record |
||||
resp = self._uds_request(SERVICE_TYPE.ROUTINE_CONTROL, subfunction=routine_control_type, data=data) |
||||
resp_id = struct.unpack('!H', resp[0:2])[0] if len(resp) >= 2 else None |
||||
if resp_id != routine_identifier_type: |
||||
raise ValueError('invalid response routine identifier: {}'.format(hex(resp_id))) |
||||
return resp[2:] |
||||
|
||||
def request_download(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=4, data_format: int=0x00): |
||||
data = bytes([data_format]) |
||||
|
||||
if memory_address_bytes < 1 or memory_address_bytes > 4: |
||||
raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) |
||||
if memory_size_bytes < 1 or memory_size_bytes > 4: |
||||
raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) |
||||
data += bytes([memory_size_bytes<<4 | memory_address_bytes]) |
||||
|
||||
if memory_address >= 1<<(memory_address_bytes*8): |
||||
raise ValueError('invalid memory_address: {}'.format(memory_address)) |
||||
data += struct.pack('!I', memory_address)[4-memory_address_bytes:] |
||||
if memory_size >= 1<<(memory_size_bytes*8): |
||||
raise ValueError('invalid memory_size: {}'.format(memory_size)) |
||||
data += struct.pack('!I', memory_size)[4-memory_size_bytes:] |
||||
|
||||
resp = self._uds_request(SERVICE_TYPE.REQUEST_DOWNLOAD, subfunction=None, data=data) |
||||
max_num_bytes_len = resp[0] >> 4 if len(resp) > 0 else None |
||||
if max_num_bytes_len >= 1 and max_num_bytes_len <= 4: |
||||
max_num_bytes = struct.unpack('!I', (b"\x00"*(4-max_num_bytes_len))+resp[1:max_num_bytes_len+1])[0] |
||||
else: |
||||
raise ValueError('invalid max_num_bytes_len: {}'.format(max_num_bytes_len)) |
||||
|
||||
return max_num_bytes # max number of bytes per transfer data request |
||||
|
||||
def request_upload(self, memory_address: int, memory_size: int, memory_address_bytes: int=4, memory_size_bytes: int=4, data_format: int=0x00): |
||||
data = bytes([data_format]) |
||||
|
||||
if memory_address_bytes < 1 or memory_address_bytes > 4: |
||||
raise ValueError('invalid memory_address_bytes: {}'.format(memory_address_bytes)) |
||||
if memory_size_bytes < 1 or memory_size_bytes > 4: |
||||
raise ValueError('invalid memory_size_bytes: {}'.format(memory_size_bytes)) |
||||
data += bytes([memory_size_bytes<<4 | memory_address_bytes]) |
||||
|
||||
if memory_address >= 1<<(memory_address_bytes*8): |
||||
raise ValueError('invalid memory_address: {}'.format(memory_address)) |
||||
data += struct.pack('!I', memory_address)[4-memory_address_bytes:] |
||||
if memory_size >= 1<<(memory_size_bytes*8): |
||||
raise ValueError('invalid memory_size: {}'.format(memory_size)) |
||||
data += struct.pack('!I', memory_size)[4-memory_size_bytes:] |
||||
|
||||
resp = self._uds_request(SERVICE_TYPE.REQUEST_UPLOAD, subfunction=None, data=data) |
||||
max_num_bytes_len = resp[0] >> 4 if len(resp) > 0 else None |
||||
if max_num_bytes_len >= 1 and max_num_bytes_len <= 4: |
||||
max_num_bytes = struct.unpack('!I', (b"\x00"*(4-max_num_bytes_len))+resp[1:max_num_bytes_len+1])[0] |
||||
else: |
||||
raise ValueError('invalid max_num_bytes_len: {}'.format(max_num_bytes_len)) |
||||
|
||||
return max_num_bytes # max number of bytes per transfer data request |
||||
|
||||
def transfer_data(self, block_sequence_count: int, data: bytes=b''): |
||||
data = bytes([block_sequence_count]) + data |
||||
resp = self._uds_request(SERVICE_TYPE.TRANSFER_DATA, subfunction=None, data=data) |
||||
resp_id = resp[0] if len(resp) > 0 else None |
||||
if resp_id != block_sequence_count: |
||||
raise ValueError('invalid block_sequence_count: {}'.format(resp_id)) |
||||
return resp[1:] |
||||
|
||||
def request_transfer_exit(self): |
||||
self._uds_request(SERVICE_TYPE.REQUEST_TRANSFER_EXIT, subfunction=None) |
@ -1,7 +1,11 @@ |
||||
libusb1 == 1.6.6 |
||||
hexdump |
||||
pycrypto |
||||
tqdm |
||||
numpy==1.17.2 |
||||
hexdump>=3.3 |
||||
pycrypto==2.6.1 |
||||
tqdm>=4.14.0 |
||||
nose |
||||
parameterized |
||||
requests |
||||
flake8==3.7.8 |
||||
pylint==2.4.2 |
||||
cffi==1.11.4 |
||||
|
@ -0,0 +1,17 @@ |
||||
#!/usr/bin/env python |
||||
import os |
||||
import sys |
||||
import time |
||||
|
||||
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) |
||||
from panda import Panda |
||||
|
||||
power = 0 |
||||
if __name__ == "__main__": |
||||
p = Panda() |
||||
while True: |
||||
p.set_fan_power(power) |
||||
time.sleep(5) |
||||
print("Power: ", power, "RPM: ", str(p.get_fan_rpm())) |
||||
power += 10 |
||||
power %=100 |
@ -1,17 +1,16 @@ |
||||
#!/usr/bin/env python3 |
||||
import time |
||||
from panda import Panda |
||||
|
||||
p = Panda() |
||||
p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) |
||||
p.set_gmlan(bus=2) |
||||
#p.can_send(0xaaa, "\x00\x00", bus=3) |
||||
#p.can_send(0xaaa, b"\x00\x00", bus=3) |
||||
last_add = None |
||||
while 1: |
||||
ret = p.can_recv() |
||||
if len(ret) > 0: |
||||
add = ret[0][0] |
||||
if last_add is not None and add != last_add+1: |
||||
print("MISS %d %d" % (last_add, add)) |
||||
if last_add is not None and add != last_add + 1: |
||||
print("MISS: ", last_add, add) |
||||
last_add = add |
||||
print(ret) |
||||
|
@ -0,0 +1,17 @@ |
||||
#!/usr/bin/env python |
||||
import os |
||||
import sys |
||||
import time |
||||
|
||||
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) |
||||
from panda import Panda |
||||
|
||||
power = 0 |
||||
if __name__ == "__main__": |
||||
p = Panda() |
||||
while True: |
||||
p.set_ir_power(power) |
||||
print("Power: ", str(power)) |
||||
time.sleep(1) |
||||
power += 10 |
||||
power %=100 |
@ -0,0 +1,585 @@ |
||||
[MASTER] |
||||
|
||||
# A comma-separated list of package or module names from where C extensions may |
||||
# be loaded. Extensions are loading into the active Python interpreter and may |
||||
# run arbitrary code |
||||
extension-pkg-whitelist=scipy |
||||
|
||||
# Add files or directories to the blacklist. They should be base names, not |
||||
# paths. |
||||
ignore=CVS |
||||
|
||||
# Add files or directories matching the regex patterns to the blacklist. The |
||||
# regex matches against base names, not paths. |
||||
ignore-patterns= |
||||
|
||||
# Python code to execute, usually for sys.path manipulation such as |
||||
# pygtk.require(). |
||||
#init-hook= |
||||
|
||||
# Use multiple processes to speed up Pylint. |
||||
jobs=4 |
||||
|
||||
# List of plugins (as comma separated values of python modules names) to load, |
||||
# usually to register additional checkers. |
||||
load-plugins= |
||||
|
||||
# Pickle collected data for later comparisons. |
||||
persistent=yes |
||||
|
||||
# Specify a configuration file. |
||||
#rcfile= |
||||
|
||||
# When enabled, pylint would attempt to guess common misconfiguration and emit |
||||
# user-friendly hints instead of false-positive error messages |
||||
suggestion-mode=yes |
||||
|
||||
# Allow loading of arbitrary C extensions. Extensions are imported into the |
||||
# active Python interpreter and may run arbitrary code. |
||||
unsafe-load-any-extension=no |
||||
|
||||
|
||||
[MESSAGES CONTROL] |
||||
|
||||
# Only show warnings with the listed confidence levels. Leave empty to show |
||||
# all. Valid levels: HIGH, INFERENCE, INFERENCE_FAILURE, UNDEFINED |
||||
confidence= |
||||
|
||||
# Disable the message, report, category or checker with the given id(s). You |
||||
# can either give multiple identifiers separated by comma (,) or put this |
||||
# option multiple times (only on the command line, not in the configuration |
||||
# file where it should appear only once).You can also use "--disable=all" to |
||||
# disable everything first and then reenable specific checks. For example, if |
||||
# you want to run only the similarities checker, you can use "--disable=all |
||||
# --enable=similarities". If you want to run only the classes checker, but have |
||||
# no Warning level messages displayed, use"--disable=all --enable=classes |
||||
# --disable=W" |
||||
disable=print-statement, |
||||
parameter-unpacking, |
||||
unpacking-in-except, |
||||
old-raise-syntax, |
||||
backtick, |
||||
long-suffix, |
||||
old-ne-operator, |
||||
old-octal-literal, |
||||
import-star-module-level, |
||||
non-ascii-bytes-literal, |
||||
raw-checker-failed, |
||||
bad-inline-option, |
||||
locally-disabled, |
||||
locally-enabled, |
||||
file-ignored, |
||||
suppressed-message, |
||||
useless-suppression, |
||||
deprecated-pragma, |
||||
apply-builtin, |
||||
basestring-builtin, |
||||
buffer-builtin, |
||||
cmp-builtin, |
||||
coerce-builtin, |
||||
execfile-builtin, |
||||
file-builtin, |
||||
long-builtin, |
||||
raw_input-builtin, |
||||
reduce-builtin, |
||||
standarderror-builtin, |
||||
unicode-builtin, |
||||
xrange-builtin, |
||||
coerce-method, |
||||
delslice-method, |
||||
getslice-method, |
||||
setslice-method, |
||||
no-absolute-import, |
||||
old-division, |
||||
dict-iter-method, |
||||
dict-view-method, |
||||
next-method-called, |
||||
metaclass-assignment, |
||||
indexing-exception, |
||||
raising-string, |
||||
reload-builtin, |
||||
oct-method, |
||||
hex-method, |
||||
nonzero-method, |
||||
cmp-method, |
||||
input-builtin, |
||||
round-builtin, |
||||
intern-builtin, |
||||
unichr-builtin, |
||||
map-builtin-not-iterating, |
||||
zip-builtin-not-iterating, |
||||
range-builtin-not-iterating, |
||||
filter-builtin-not-iterating, |
||||
using-cmp-argument, |
||||
eq-without-hash, |
||||
div-method, |
||||
idiv-method, |
||||
rdiv-method, |
||||
exception-message-attribute, |
||||
invalid-str-codec, |
||||
sys-max-int, |
||||
bad-python3-import, |
||||
deprecated-string-function, |
||||
deprecated-str-translate-call, |
||||
deprecated-itertools-function, |
||||
deprecated-types-field, |
||||
next-method-defined, |
||||
dict-items-not-iterating, |
||||
dict-keys-not-iterating, |
||||
dict-values-not-iterating, |
||||
bad-indentation, |
||||
line-too-long, |
||||
missing-docstring, |
||||
multiple-statements, |
||||
bad-continuation, |
||||
invalid-name, |
||||
too-many-arguments, |
||||
too-many-locals, |
||||
superfluous-parens, |
||||
bad-whitespace, |
||||
too-many-instance-attributes, |
||||
wrong-import-position, |
||||
ungrouped-imports, |
||||
wrong-import-order, |
||||
protected-access, |
||||
trailing-whitespace, |
||||
too-many-branches, |
||||
too-few-public-methods, |
||||
too-many-statements, |
||||
trailing-newlines, |
||||
attribute-defined-outside-init, |
||||
too-many-return-statements, |
||||
too-many-public-methods, |
||||
unused-argument, |
||||
old-style-class, |
||||
no-init, |
||||
len-as-condition, |
||||
unneeded-not, |
||||
no-self-use, |
||||
multiple-imports, |
||||
no-else-return, |
||||
logging-not-lazy, |
||||
fixme, |
||||
redefined-outer-name, |
||||
unused-variable, |
||||
unsubscriptable-object, |
||||
expression-not-assigned, |
||||
too-many-boolean-expressions, |
||||
consider-using-ternary, |
||||
invalid-unary-operand-type, |
||||
relative-import, |
||||
deprecated-lambda |
||||
|
||||
|
||||
# Enable the message, report, category or checker with the given id(s). You can |
||||
# either give multiple identifier separated by comma (,) or put this option |
||||
# multiple time (only on the command line, not in the configuration file where |
||||
# it should appear only once). See also the "--disable" option for examples. |
||||
enable=c-extension-no-member |
||||
|
||||
|
||||
[REPORTS] |
||||
|
||||
# Python expression which should return a note less than 10 (10 is the highest |
||||
# note). You have access to the variables errors warning, statement which |
||||
# respectively contain the number of errors / warnings messages and the total |
||||
# number of statements analyzed. This is used by the global evaluation report |
||||
# (RP0004). |
||||
evaluation=10.0 - ((float(5 * error + warning + refactor + convention) / statement) * 10) |
||||
|
||||
# Template used to display messages. This is a python new-style format string |
||||
# used to format the message information. See doc for all details |
||||
#msg-template= |
||||
|
||||
# Set the output format. Available formats are text, parseable, colorized, json |
||||
# and msvs (visual studio).You can also give a reporter class, eg |
||||
# mypackage.mymodule.MyReporterClass. |
||||
output-format=text |
||||
|
||||
# Tells whether to display a full report or only the messages |
||||
reports=no |
||||
|
||||
# Activate the evaluation score. |
||||
score=yes |
||||
|
||||
|
||||
[REFACTORING] |
||||
|
||||
# Maximum number of nested blocks for function / method body |
||||
max-nested-blocks=5 |
||||
|
||||
# Complete name of functions that never returns. When checking for |
||||
# inconsistent-return-statements if a never returning function is called then |
||||
# it will be considered as an explicit return statement and no message will be |
||||
# printed. |
||||
never-returning-functions=optparse.Values,sys.exit |
||||
|
||||
|
||||
[LOGGING] |
||||
|
||||
# Logging modules to check that the string format arguments are in logging |
||||
# function parameter format |
||||
logging-modules=logging |
||||
|
||||
|
||||
[SPELLING] |
||||
|
||||
# Limits count of emitted suggestions for spelling mistakes |
||||
max-spelling-suggestions=4 |
||||
|
||||
# Spelling dictionary name. Available dictionaries: none. To make it working |
||||
# install python-enchant package. |
||||
spelling-dict= |
||||
|
||||
# List of comma separated words that should not be checked. |
||||
spelling-ignore-words= |
||||
|
||||
# A path to a file that contains private dictionary; one word per line. |
||||
spelling-private-dict-file= |
||||
|
||||
# Tells whether to store unknown words to indicated private dictionary in |
||||
# --spelling-private-dict-file option instead of raising a message. |
||||
spelling-store-unknown-words=no |
||||
|
||||
|
||||
[MISCELLANEOUS] |
||||
|
||||
# List of note tags to take in consideration, separated by a comma. |
||||
notes=FIXME, |
||||
XXX, |
||||
TODO |
||||
|
||||
|
||||
[SIMILARITIES] |
||||
|
||||
# Ignore comments when computing similarities. |
||||
ignore-comments=yes |
||||
|
||||
# Ignore docstrings when computing similarities. |
||||
ignore-docstrings=yes |
||||
|
||||
# Ignore imports when computing similarities. |
||||
ignore-imports=no |
||||
|
||||
# Minimum lines number of a similarity. |
||||
min-similarity-lines=4 |
||||
|
||||
|
||||
[TYPECHECK] |
||||
|
||||
# List of decorators that produce context managers, such as |
||||
# contextlib.contextmanager. Add to this list to register other decorators that |
||||
# produce valid context managers. |
||||
contextmanager-decorators=contextlib.contextmanager |
||||
|
||||
# List of members which are set dynamically and missed by pylint inference |
||||
# system, and so shouldn't trigger E1101 when accessed. Python regular |
||||
# expressions are accepted. |
||||
generated-members=capnp.* cereal.* pygame.* zmq.* setproctitle.* smbus2.* usb1.* serial.* cv2.* |
||||
|
||||
# Tells whether missing members accessed in mixin class should be ignored. A |
||||
# mixin class is detected if its name ends with "mixin" (case insensitive). |
||||
ignore-mixin-members=yes |
||||
|
||||
# This flag controls whether pylint should warn about no-member and similar |
||||
# checks whenever an opaque object is returned when inferring. The inference |
||||
# can return multiple potential results while evaluating a Python object, but |
||||
# some branches might not be evaluated, which results in partial inference. In |
||||
# that case, it might be useful to still emit no-member and other checks for |
||||
# the rest of the inferred objects. |
||||
ignore-on-opaque-inference=yes |
||||
|
||||
# List of class names for which member attributes should not be checked (useful |
||||
# for classes with dynamically set attributes). This supports the use of |
||||
# qualified names. |
||||
ignored-classes=optparse.Values,thread._local,_thread._local |
||||
|
||||
# List of module names for which member attributes should not be checked |
||||
# (useful for modules/projects where namespaces are manipulated during runtime |
||||
# and thus existing member attributes cannot be deduced by static analysis. It |
||||
# supports qualified module names, as well as Unix pattern matching. |
||||
ignored-modules=flask setproctitle usb1 flask.ext.socketio smbus2 usb1.* |
||||
|
||||
# Show a hint with possible names when a member name was not found. The aspect |
||||
# of finding the hint is based on edit distance. |
||||
missing-member-hint=yes |
||||
|
||||
# The minimum edit distance a name should have in order to be considered a |
||||
# similar match for a missing member name. |
||||
missing-member-hint-distance=1 |
||||
|
||||
# The total number of similar names that should be taken in consideration when |
||||
# showing a hint for a missing member. |
||||
missing-member-max-choices=1 |
||||
|
||||
|
||||
[VARIABLES] |
||||
|
||||
# List of additional names supposed to be defined in builtins. Remember that |
||||
# you should avoid to define new builtins when possible. |
||||
additional-builtins= |
||||
|
||||
# Tells whether unused global variables should be treated as a violation. |
||||
allow-global-unused-variables=yes |
||||
|
||||
# List of strings which can identify a callback function by name. A callback |
||||
# name must start or end with one of those strings. |
||||
callbacks=cb_, |
||||
_cb |
||||
|
||||
# A regular expression matching the name of dummy variables (i.e. expectedly |
||||
# not used). |
||||
dummy-variables-rgx=_+$|(_[a-zA-Z0-9_]*[a-zA-Z0-9]+?$)|dummy|^ignored_|^unused_ |
||||
|
||||
# Argument names that match this expression will be ignored. Default to name |
||||
# with leading underscore |
||||
ignored-argument-names=_.*|^ignored_|^unused_ |
||||
|
||||
# Tells whether we should check for unused import in __init__ files. |
||||
init-import=no |
||||
|
||||
# List of qualified module names which can have objects that can redefine |
||||
# builtins. |
||||
redefining-builtins-modules=six.moves,past.builtins,future.builtins |
||||
|
||||
|
||||
[FORMAT] |
||||
|
||||
# Expected format of line ending, e.g. empty (any line ending), LF or CRLF. |
||||
expected-line-ending-format= |
||||
|
||||
# Regexp for a line that is allowed to be longer than the limit. |
||||
ignore-long-lines=^\s*(# )?<?https?://\S+>?$ |
||||
|
||||
# Number of spaces of indent required inside a hanging or continued line. |
||||
indent-after-paren=4 |
||||
|
||||
# String used as indentation unit. This is usually " " (4 spaces) or "\t" (1 |
||||
# tab). |
||||
indent-string=' ' |
||||
|
||||
# Maximum number of characters on a single line. |
||||
max-line-length=100 |
||||
|
||||
# Maximum number of lines in a module |
||||
max-module-lines=1000 |
||||
|
||||
# List of optional constructs for which whitespace checking is disabled. `dict- |
||||
# separator` is used to allow tabulation in dicts, etc.: {1 : 1,\n222: 2}. |
||||
# `trailing-comma` allows a space between comma and closing bracket: (a, ). |
||||
# `empty-line` allows space-only lines. |
||||
no-space-check=trailing-comma, |
||||
dict-separator |
||||
|
||||
# Allow the body of a class to be on the same line as the declaration if body |
||||
# contains single statement. |
||||
single-line-class-stmt=no |
||||
|
||||
# Allow the body of an if to be on the same line as the test if there is no |
||||
# else. |
||||
single-line-if-stmt=no |
||||
|
||||
|
||||
[BASIC] |
||||
|
||||
# Naming style matching correct argument names |
||||
argument-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct argument names. Overrides argument- |
||||
# naming-style |
||||
#argument-rgx= |
||||
|
||||
# Naming style matching correct attribute names |
||||
attr-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct attribute names. Overrides attr-naming- |
||||
# style |
||||
#attr-rgx= |
||||
|
||||
# Bad variable names which should always be refused, separated by a comma |
||||
bad-names=foo, |
||||
bar, |
||||
baz, |
||||
toto, |
||||
tutu, |
||||
tata |
||||
|
||||
# Naming style matching correct class attribute names |
||||
class-attribute-naming-style=any |
||||
|
||||
# Regular expression matching correct class attribute names. Overrides class- |
||||
# attribute-naming-style |
||||
#class-attribute-rgx= |
||||
|
||||
# Naming style matching correct class names |
||||
class-naming-style=PascalCase |
||||
|
||||
# Regular expression matching correct class names. Overrides class-naming-style |
||||
#class-rgx= |
||||
|
||||
# Naming style matching correct constant names |
||||
const-naming-style=UPPER_CASE |
||||
|
||||
# Regular expression matching correct constant names. Overrides const-naming- |
||||
# style |
||||
#const-rgx= |
||||
|
||||
# Minimum line length for functions/classes that require docstrings, shorter |
||||
# ones are exempt. |
||||
docstring-min-length=-1 |
||||
|
||||
# Naming style matching correct function names |
||||
function-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct function names. Overrides function- |
||||
# naming-style |
||||
#function-rgx= |
||||
|
||||
# Good variable names which should always be accepted, separated by a comma |
||||
good-names=i, |
||||
j, |
||||
k, |
||||
ex, |
||||
Run, |
||||
_ |
||||
|
||||
# Include a hint for the correct naming format with invalid-name |
||||
include-naming-hint=no |
||||
|
||||
# Naming style matching correct inline iteration names |
||||
inlinevar-naming-style=any |
||||
|
||||
# Regular expression matching correct inline iteration names. Overrides |
||||
# inlinevar-naming-style |
||||
#inlinevar-rgx= |
||||
|
||||
# Naming style matching correct method names |
||||
method-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct method names. Overrides method-naming- |
||||
# style |
||||
#method-rgx= |
||||
|
||||
# Naming style matching correct module names |
||||
module-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct module names. Overrides module-naming- |
||||
# style |
||||
#module-rgx= |
||||
|
||||
# Colon-delimited sets of names that determine each other's naming style when |
||||
# the name regexes allow several styles. |
||||
name-group= |
||||
|
||||
# Regular expression which should only match function or class names that do |
||||
# not require a docstring. |
||||
no-docstring-rgx=^_ |
||||
|
||||
# List of decorators that produce properties, such as abc.abstractproperty. Add |
||||
# to this list to register other decorators that produce valid properties. |
||||
property-classes=abc.abstractproperty |
||||
|
||||
# Naming style matching correct variable names |
||||
variable-naming-style=snake_case |
||||
|
||||
# Regular expression matching correct variable names. Overrides variable- |
||||
# naming-style |
||||
#variable-rgx= |
||||
|
||||
|
||||
[DESIGN] |
||||
|
||||
# Maximum number of arguments for function / method |
||||
max-args=5 |
||||
|
||||
# Maximum number of attributes for a class (see R0902). |
||||
max-attributes=7 |
||||
|
||||
# Maximum number of boolean expressions in a if statement |
||||
max-bool-expr=5 |
||||
|
||||
# Maximum number of branch for function / method body |
||||
max-branches=12 |
||||
|
||||
# Maximum number of locals for function / method body |
||||
max-locals=15 |
||||
|
||||
# Maximum number of parents for a class (see R0901). |
||||
max-parents=7 |
||||
|
||||
# Maximum number of public methods for a class (see R0904). |
||||
max-public-methods=20 |
||||
|
||||
# Maximum number of return / yield for function / method body |
||||
max-returns=6 |
||||
|
||||
# Maximum number of statements in function / method body |
||||
max-statements=50 |
||||
|
||||
# Minimum number of public methods for a class (see R0903). |
||||
min-public-methods=2 |
||||
|
||||
|
||||
[CLASSES] |
||||
|
||||
# List of method names used to declare (i.e. assign) instance attributes. |
||||
defining-attr-methods=__init__, |
||||
__new__, |
||||
setUp |
||||
|
||||
# List of member names, which should be excluded from the protected access |
||||
# warning. |
||||
exclude-protected=_asdict, |
||||
_fields, |
||||
_replace, |
||||
_source, |
||||
_make |
||||
|
||||
# List of valid names for the first argument in a class method. |
||||
valid-classmethod-first-arg=cls |
||||
|
||||
# List of valid names for the first argument in a metaclass class method. |
||||
valid-metaclass-classmethod-first-arg=mcs |
||||
|
||||
|
||||
[IMPORTS] |
||||
|
||||
# Allow wildcard imports from modules that define __all__. |
||||
allow-wildcard-with-all=no |
||||
|
||||
# Analyse import fallback blocks. This can be used to support both Python 2 and |
||||
# 3 compatible code, which means that the block might have code that exists |
||||
# only in one or another interpreter, leading to false positives when analysed. |
||||
analyse-fallback-blocks=no |
||||
|
||||
# Deprecated modules which should not be used, separated by a comma |
||||
deprecated-modules=regsub, |
||||
TERMIOS, |
||||
Bastion, |
||||
rexec |
||||
|
||||
# Create a graph of external dependencies in the given file (report RP0402 must |
||||
# not be disabled) |
||||
ext-import-graph= |
||||
|
||||
# Create a graph of every (i.e. internal and external) dependencies in the |
||||
# given file (report RP0402 must not be disabled) |
||||
import-graph= |
||||
|
||||
# Create a graph of internal dependencies in the given file (report RP0402 must |
||||
# not be disabled) |
||||
int-import-graph= |
||||
|
||||
# Force import order to recognize a module as part of the standard |
||||
# compatibility libraries. |
||||
known-standard-library= |
||||
|
||||
# Force import order to recognize a module as part of a third party library. |
||||
known-third-party=enchant |
||||
|
||||
|
||||
[EXCEPTIONS] |
||||
|
||||
# Exceptions that will emit a warning when being caught. Defaults to |
||||
# "Exception" |
||||
overgeneral-exceptions=Exception |
@ -0,0 +1,19 @@ |
||||
FROM ubuntu:16.04 |
||||
|
||||
RUN apt-get update && apt-get install -y make python python-pip locales curl git zlib1g-dev libffi-dev bzip2 libssl-dev |
||||
|
||||
RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen |
||||
ENV LANG en_US.UTF-8 |
||||
ENV LANGUAGE en_US:en |
||||
ENV LC_ALL en_US.UTF-8 |
||||
|
||||
RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash |
||||
|
||||
ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" |
||||
RUN pyenv install 3.7.3 |
||||
RUN pyenv global 3.7.3 |
||||
RUN pyenv rehash |
||||
|
||||
COPY requirements.txt /tmp/ |
||||
RUN pip install -r /tmp/requirements.txt |
||||
COPY . /panda |
@ -0,0 +1,8 @@ |
||||
#!/usr/bin/env bash |
||||
|
||||
RESULT=$(python3 -m flake8 --select=F $(find ../../ -type f | grep -v "/boardesp/" | grep -v "/cppcheck/" | grep "\.py$")) |
||||
if [[ $RESULT ]]; then |
||||
echo "Pyflakes found errors in the code. Please fix and try again" |
||||
echo "$RESULT" |
||||
exit 1 |
||||
fi |
@ -0,0 +1,11 @@ |
||||
#!/usr/bin/env bash |
||||
|
||||
python3 -m pylint --disable=R,C,W $(find ../../ -type f | grep -v "/boardesp/" | grep -v "/cppcheck/" | grep "\.py$") |
||||
|
||||
exit_status=$? |
||||
(( res = exit_status & 3 )) |
||||
|
||||
if [[ $res != 0 ]]; then |
||||
echo "Pylint found errors in the code. Please fix and try again" |
||||
exit 1 |
||||
fi |
@ -1,6 +1,19 @@ |
||||
FROM ubuntu:16.04 |
||||
|
||||
RUN apt-get update && apt-get install -y make python python-pip git |
||||
COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt |
||||
RUN pip install -r /panda/tests/safety/requirements.txt |
||||
RUN apt-get update && apt-get install -y clang make python python-pip git curl locales zlib1g-dev libffi-dev bzip2 libssl-dev libbz2-dev libusb-1.0-0 |
||||
|
||||
RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen |
||||
ENV LANG en_US.UTF-8 |
||||
ENV LANGUAGE en_US:en |
||||
ENV LC_ALL en_US.UTF-8 |
||||
|
||||
RUN curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash |
||||
|
||||
ENV PATH="/root/.pyenv/bin:/root/.pyenv/shims:${PATH}" |
||||
RUN pyenv install 3.7.3 |
||||
RUN pyenv global 3.7.3 |
||||
RUN pyenv rehash |
||||
|
||||
COPY requirements.txt /tmp/ |
||||
RUN pip install -r /tmp/requirements.txt |
||||
COPY . /panda |
||||
|
@ -0,0 +1,13 @@ |
||||
#!/usr/bin/env python |
||||
import os |
||||
import sys |
||||
import datetime |
||||
|
||||
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) |
||||
from panda import Panda |
||||
|
||||
if __name__ == "__main__": |
||||
p = Panda() |
||||
|
||||
p.set_datetime(datetime.datetime.now()) |
||||
print(p.get_datetime()) |
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue