📋📷 2019 Chrysler Pacifica and 2019 Jeep Grand Cherokee support (#590)

* 2019 Chrysler Pacfica and 2019 Jeep Grand Cherokee support, along with likely support for arbitrary models.
This is done by copying most values from the stock LKAS camera which is active with https://github.com/commaai/panda/pull/177

* No longer send LKAS_HEARTBIT because Panda now forwards it for us.

* Pacifica Hybrid 2018 combine fingerprints, add 808: 8

* panda chrysler: forward bus 0 to bus 2
copy of Panda commit: 1049502644

old-commit-hash: 1efa3f0eba
commatwo_master
Drew Hintz 6 years ago committed by rbiasini
parent b460d2ae90
commit df649841fc
  1. 23
      panda/board/safety/safety_chrysler.h
  2. 25
      selfdrive/car/chrysler/carcontroller.py
  3. 18
      selfdrive/car/chrysler/carstate.py
  4. 38
      selfdrive/car/chrysler/chryslercan.py
  5. 49
      selfdrive/car/chrysler/chryslercan_test.py
  6. 16
      selfdrive/car/chrysler/interface.py
  7. 10
      selfdrive/car/chrysler/values.py

@ -5,7 +5,7 @@ const int CHRYSLER_MAX_RATE_UP = 3;
const int CHRYSLER_MAX_RATE_DOWN = 3; const int CHRYSLER_MAX_RATE_DOWN = 3;
const int CHRYSLER_MAX_TORQUE_ERROR = 80; // max torque cmd in excess of torque motor const int CHRYSLER_MAX_TORQUE_ERROR = 80; // max torque cmd in excess of torque motor
int chrysler_camera_detected = 0; int chrysler_camera_detected = 0; // is giraffe switch 2 high?
int chrysler_rt_torque_last = 0; int chrysler_rt_torque_last = 0;
int chrysler_desired_torque_last = 0; int chrysler_desired_torque_last = 0;
int chrysler_cruise_engaged_last = 0; int chrysler_cruise_engaged_last = 0;
@ -125,12 +125,29 @@ static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
return true; return true;
} }
static void chrysler_init(int16_t param) {
chrysler_camera_detected = 0;
}
static int chrysler_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
int32_t addr = to_fwd->RIR >> 21;
// forward CAN 0 -> 2 so stock LKAS camera sees messages
if (bus_num == 0 && !chrysler_camera_detected) {
return 2;
}
// forward LKAS_HEARTBIT message from stock camera
if (bus_num == 2 && !chrysler_camera_detected && addr == 0x2d9) {
return 0;
}
return -1; // do not forward
}
const safety_hooks chrysler_hooks = { const safety_hooks chrysler_hooks = {
.init = nooutput_init, .init = chrysler_init,
.rx = chrysler_rx_hook, .rx = chrysler_rx_hook,
.tx = chrysler_tx_hook, .tx = chrysler_tx_hook,
.tx_lin = nooutput_tx_lin_hook, .tx_lin = nooutput_tx_lin_hook,
.ignition = default_ign_hook, .ignition = default_ign_hook,
.fwd = nooutput_fwd_hook, .fwd = chrysler_fwd_hook,
}; };

@ -2,9 +2,9 @@ from cereal import car
from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car import apply_toyota_steer_torque_limits from selfdrive.car import apply_toyota_steer_torque_limits
from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, \ from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, \
create_wheel_buttons, create_lkas_heartbit, \ create_wheel_buttons, \
create_chimes create_chimes
from selfdrive.car.chrysler.values import ECU from selfdrive.car.chrysler.values import ECU, CAR
from selfdrive.can.packer import CANPacker from selfdrive.can.packer import CANPacker
AudibleAlert = car.CarControl.HUDControl.AudibleAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert
@ -29,6 +29,7 @@ class CarController(object):
self.car_fingerprint = car_fingerprint self.car_fingerprint = car_fingerprint
self.alert_active = False self.alert_active = False
self.send_chime = False self.send_chime = False
self.gone_fast_yet = False
self.fake_ecus = set() self.fake_ecus = set()
if enable_camera: if enable_camera:
@ -39,8 +40,8 @@ class CarController(object):
def update(self, sendcan, enabled, CS, frame, actuators, def update(self, sendcan, enabled, CS, frame, actuators,
pcm_cancel_cmd, hud_alert, audible_alert): pcm_cancel_cmd, hud_alert, audible_alert):
# this seems needed to avoid steering faults and to force the sync with the EPS counter # this seems needed to avoid steering faults and to force the sync with the EPS counter
frame = CS.lkas_counter
if self.prev_frame == frame: if self.prev_frame == frame:
return return
@ -51,6 +52,11 @@ class CarController(object):
CS.steer_torque_motor, SteerLimitParams) CS.steer_torque_motor, SteerLimitParams)
moving_fast = CS.v_ego > CS.CP.minSteerSpeed # for status message moving_fast = CS.v_ego > CS.CP.minSteerSpeed # for status message
if CS.v_ego > (CS.CP.minSteerSpeed - 0.5): # for command high bit
self.gone_fast_yet = True
elif self.car_fingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.JEEP_CHEROKEE_2019):
if CS.v_ego < (CS.CP.minSteerSpeed - 3.0):
self.gone_fast_yet = False # < 14.5m/s stock turns off this bit, but fine down to 13.5
lkas_active = moving_fast and enabled lkas_active = moving_fast and enabled
if not lkas_active: if not lkas_active:
@ -76,18 +82,17 @@ class CarController(object):
new_msg = create_wheel_buttons(self.ccframe) new_msg = create_wheel_buttons(self.ccframe)
can_sends.append(new_msg) can_sends.append(new_msg)
# LKAS_HEARTBIT is forwarded by Panda so no need to send it here.
# frame is 100Hz (0.01s period) # frame is 100Hz (0.01s period)
if (self.ccframe % 10 == 0): # 0.1s period
new_msg = create_lkas_heartbit(self.car_fingerprint)
can_sends.append(new_msg)
if (self.ccframe % 25 == 0): # 0.25s period if (self.ccframe % 25 == 0): # 0.25s period
new_msg = create_lkas_hud(self.packer, CS.gear_shifter, lkas_active, hud_alert, self.car_fingerprint, if (CS.lkas_car_model != -1):
self.hud_count) new_msg = create_lkas_hud(
self.packer, CS.gear_shifter, lkas_active, hud_alert,
self.hud_count, CS.lkas_car_model)
can_sends.append(new_msg) can_sends.append(new_msg)
self.hud_count += 1 self.hud_count += 1
new_msg = create_lkas_command(self.packer, int(apply_steer), frame) new_msg = create_lkas_command(self.packer, int(apply_steer), self.gone_fast_yet, frame)
can_sends.append(new_msg) can_sends.append(new_msg)
self.ccframe += 1 self.ccframe += 1

@ -63,6 +63,18 @@ def get_can_parser(CP):
return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
def get_camera_parser(CP):
signals = [
# sig_name, sig_address, default
# TODO read in all the other values
("COUNTER", "LKAS_COMMAND", -1),
("CAR_MODEL", "LKAS_HUD", -1),
("LKAS_STATUS_OK", "LKAS_HEARTBIT", -1)
]
checks = []
return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
class CarState(object): class CarState(object):
def __init__(self, CP): def __init__(self, CP):
@ -85,7 +97,7 @@ class CarState(object):
self.v_ego = 0.0 self.v_ego = 0.0
def update(self, cp): def update(self, cp, cp_cam):
# copy can_valid # copy can_valid
self.can_valid = cp.can_valid self.can_valid = cp.can_valid
@ -142,3 +154,7 @@ class CarState(object):
self.pcm_acc_status = self.main_on self.pcm_acc_status = self.main_on
self.generic_toggle = bool(cp.vl["STEERING_LEVERS"]['HIGH_BEAM_FLASH']) self.generic_toggle = bool(cp.vl["STEERING_LEVERS"]['HIGH_BEAM_FLASH'])
self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]['COUNTER']
self.lkas_car_model = cp_cam.vl["LKAS_HUD"]['CAR_MODEL']
self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]['LKAS_STATUS_OK']

@ -5,14 +5,6 @@ from selfdrive.car.chrysler.values import CAR
VisualAlert = car.CarControl.HUDControl.VisualAlert VisualAlert = car.CarControl.HUDControl.VisualAlert
AudibleAlert = car.CarControl.HUDControl.AudibleAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert
MODEL_TO_CONSTANT = {
CAR.PACIFICA_2017_HYBRID: 0,
CAR.PACIFICA_2018: 0x64,
CAR.PACIFICA_2018_HYBRID: 0xa8,
CAR.PACIFICA_2019_HYBRID: 0x68,
CAR.JEEP_CHEROKEE: 0xa4,
}
def calc_checksum(data): def calc_checksum(data):
"""This function does not want the checksum byte in the input data. """This function does not want the checksum byte in the input data.
@ -53,28 +45,26 @@ def calc_checksum(data):
def make_can_msg(addr, dat): def make_can_msg(addr, dat):
return [addr, 0, dat, 0] return [addr, 0, dat, 0]
def create_lkas_heartbit(car_fingerprint): def create_lkas_heartbit(packer, lkas_status_ok):
# LKAS_HEARTBIT (729) Lane-keeping heartbeat. # LKAS_HEARTBIT 0x2d9 (729) Lane-keeping heartbeat.
msg = '0000000820'.decode('hex') # 2017 values = {
return make_can_msg(0x2d9, msg) "LKAS_STATUS_OK": lkas_status_ok
}
return packer.make_can_msg("LKAS_HEARTBIT", 0, values)
def create_lkas_hud(packer, gear, lkas_active, hud_alert, car_fingerprint, hud_count): def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_model):
# LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed. # LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed.
if hud_alert == VisualAlert.steerRequired: if hud_alert == VisualAlert.steerRequired:
msg = '0000000300000000'.decode('hex') msg = '0000000300000000'.decode('hex')
return make_can_msg(0x2a6, msg) return make_can_msg(0x2a6, msg)
color = 0 # default values are for park or neutral color = 1 # default values are for park or neutral in 2017 are 0 0, but trying 1 1 for 2019
lines = 0 lines = 1
alerts = 0 alerts = 0
if hud_count < (3 *4): # first 3 seconds, 4Hz if hud_count < (1 *4): # first 3 seconds, 4Hz
lines = 1
alerts = 1 alerts = 1
elif hud_count < (6 * 4): # next 3 seconds, 4Hz
lines = 1
alerts = 0
# CAR.PACIFICA_2018_HYBRID and CAR.PACIFICA_2019_HYBRID # CAR.PACIFICA_2018_HYBRID and CAR.PACIFICA_2019_HYBRID
# had color = 1 and lines = 1 but trying 2017 hybrid style for now. # had color = 1 and lines = 1 but trying 2017 hybrid style for now.
if gear in ('drive', 'reverse', 'low'): if gear in ('drive', 'reverse', 'low'):
@ -87,7 +77,7 @@ def create_lkas_hud(packer, gear, lkas_active, hud_alert, car_fingerprint, hud_c
values = { values = {
"LKAS_ICON_COLOR": color, # byte 0, last 2 bits "LKAS_ICON_COLOR": color, # byte 0, last 2 bits
"CAR_MODEL": MODEL_TO_CONSTANT[car_fingerprint], # byte 1 "CAR_MODEL": lkas_car_model, # byte 1
"LKAS_LANE_LINES": lines, # byte 2, last 4 bits "LKAS_LANE_LINES": lines, # byte 2, last 4 bits
"LKAS_ALERTS": alerts, # byte 3, last 4 bits "LKAS_ALERTS": alerts, # byte 3, last 4 bits
} }
@ -95,11 +85,11 @@ def create_lkas_hud(packer, gear, lkas_active, hud_alert, car_fingerprint, hud_c
return packer.make_can_msg("LKAS_HUD", 0, values) # 0x2a6 return packer.make_can_msg("LKAS_HUD", 0, values) # 0x2a6
def create_lkas_command(packer, apply_steer, frame): def create_lkas_command(packer, apply_steer, moving_fast, frame):
# LKAS_COMMAND (658) Lane-keeping signal to turn the wheel. # LKAS_COMMAND 0x292 (658) Lane-keeping signal to turn the wheel.
values = { values = {
"LKAS_STEERING_TORQUE": apply_steer, "LKAS_STEERING_TORQUE": apply_steer,
"LKAS_HIGH_TORQUE": 1, "LKAS_HIGH_TORQUE": int(moving_fast),
"COUNTER": frame % 0x10, "COUNTER": frame % 0x10,
} }

@ -1,5 +1,6 @@
import chryslercan import chryslercan
from values import CAR from values import CAR
from carcontroller import CarController
from selfdrive.can.packer import CANPacker from selfdrive.can.packer import CANPacker
from cereal import car from cereal import car
@ -16,32 +17,52 @@ class TestChryslerCan(unittest.TestCase):
self.assertEqual(0xcc, chryslercan.calc_checksum([0x14, 0, 0, 0, 0x20])) self.assertEqual(0xcc, chryslercan.calc_checksum([0x14, 0, 0, 0, 0x20]))
def test_heartbit(self): def test_heartbit(self):
packer = CANPacker('chrysler_pacifica_2017_hybrid')
self.assertEqual( self.assertEqual(
[0x2d9, 0, '0000000820'.decode('hex'), 0], [0x2d9, 0, '0000000820'.decode('hex'), 0],
chryslercan.create_lkas_heartbit(CAR.PACIFICA_2017_HYBRID)) chryslercan.create_lkas_heartbit(packer, 0x820))
def test_hud(self): def test_hud(self):
packer = CANPacker('chrysler_pacifica_2017_hybrid') packer = CANPacker('chrysler_pacifica_2017_hybrid')
self.assertEqual( self.assertEqual(
[0x2a6, 0, '0000010100000000'.decode('hex'), 0], [0x2a6, 0, '0100010100000000'.decode('hex'), 0],
chryslercan.create_lkas_hud(packer, chryslercan.create_lkas_hud(
'park', False, False, CAR.PACIFICA_2017_HYBRID, 1)) packer,
'park', False, False, 1, 0))
self.assertEqual( self.assertEqual(
[0x2a6, 0, '0000010000000000'.decode('hex'), 0], [0x2a6, 0, '0100010000000000'.decode('hex'), 0],
chryslercan.create_lkas_hud(packer, chryslercan.create_lkas_hud(
'park', False, False, CAR.PACIFICA_2017_HYBRID, 5*4)) packer,
'park', False, False, 5*4, 0))
self.assertEqual( self.assertEqual(
[0x2a6, 0, '0000000000000000'.decode('hex'), 0], [0x2a6, 0, '0100010000000000'.decode('hex'), 0],
chryslercan.create_lkas_hud(packer, chryslercan.create_lkas_hud(
'park', False, False, CAR.PACIFICA_2017_HYBRID, 99999)) packer,
'park', False, False, 99999, 0))
self.assertEqual( self.assertEqual(
[0x2a6, 0, '0200060000000000'.decode('hex'), 0], [0x2a6, 0, '0200060000000000'.decode('hex'), 0],
chryslercan.create_lkas_hud(packer, chryslercan.create_lkas_hud(
'drive', True, False, CAR.PACIFICA_2017_HYBRID, 99999)) packer,
'drive', True, False, 99999, 0))
self.assertEqual( self.assertEqual(
[0x2a6, 0, '0264060000000000'.decode('hex'), 0], [0x2a6, 0, '0264060000000000'.decode('hex'), 0],
chryslercan.create_lkas_hud(packer, chryslercan.create_lkas_hud(
'drive', True, False, CAR.PACIFICA_2018, 99999)) packer,
'drive', True, False, 99999, 0x64))
def test_command(self):
packer = CANPacker('chrysler_pacifica_2017_hybrid')
self.assertEqual(
[0x292, 0, '140000001086'.decode('hex'), 0],
chryslercan.create_lkas_command(
packer,
0, True, 1))
self.assertEqual(
[0x292, 0, '040000008083'.decode('hex'), 0],
chryslercan.create_lkas_command(
packer,
0, False, 8))
if __name__ == '__main__': if __name__ == '__main__':
unittest.main() unittest.main()

@ -4,7 +4,7 @@ from cereal import car
from selfdrive.config import Conversions as CV from selfdrive.config import Conversions as CV
from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event
from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.controls.lib.vehicle_model import VehicleModel
from selfdrive.car.chrysler.carstate import CarState, get_can_parser from selfdrive.car.chrysler.carstate import CarState, get_can_parser, get_camera_parser
from selfdrive.car.chrysler.values import ECU, check_ecu_msgs, CAR from selfdrive.car.chrysler.values import ECU, check_ecu_msgs, CAR
try: try:
@ -27,8 +27,8 @@ class CarInterface(object):
# *** init the major players *** # *** init the major players ***
self.CS = CarState(CP) self.CS = CarState(CP)
self.cp = get_can_parser(CP) self.cp = get_can_parser(CP)
self.cp_cam = get_camera_parser(CP)
# sending if read only is False # sending if read only is False
if sendcan is not None: if sendcan is not None:
@ -79,7 +79,7 @@ class CarInterface(object):
ret.steerActuatorDelay = 0.1 ret.steerActuatorDelay = 0.1
ret.steerRateCost = 0.7 ret.steerRateCost = 0.7
if candidate == CAR.JEEP_CHEROKEE: if candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019):
ret.wheelbase = 2.91 # in meters ret.wheelbase = 2.91 # in meters
ret.steerRatio = 12.7 ret.steerRatio = 12.7
ret.steerActuatorDelay = 0.2 # in seconds ret.steerActuatorDelay = 0.2 # in seconds
@ -91,6 +91,9 @@ class CarInterface(object):
ret.minSteerSpeed = 3.8 # m/s ret.minSteerSpeed = 3.8 # m/s
ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this
if candidate in (CAR.PACIFICA_2019_HYBRID, CAR.JEEP_CHEROKEE_2019):
ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged.
# TODO allow 2019 cars to steer down to 13 m/s if already engaged.
centerToRear = ret.wheelbase - ret.centerToFront centerToRear = ret.wheelbase - ret.centerToFront
# TODO: get actual value, for now starting with reasonable value for # TODO: get actual value, for now starting with reasonable value for
@ -137,10 +140,9 @@ class CarInterface(object):
def update(self, c): def update(self, c):
# ******************* do can recv ******************* # ******************* do can recv *******************
canMonoTimes = [] canMonoTimes = []
self.cp.update(int(sec_since_boot() * 1e9), False) self.cp.update(int(sec_since_boot() * 1e9), False)
self.cp_cam.update(int(sec_since_boot() * 1e9), False)
self.CS.update(self.cp) self.CS.update(self.cp, self.cp_cam)
# create message # create message
ret = car.CarState.new_message() ret = car.CarState.new_message()
@ -208,6 +210,8 @@ class CarInterface(object):
self.low_speed_alert = (ret.vEgo < self.CP.minSteerSpeed) self.low_speed_alert = (ret.vEgo < self.CP.minSteerSpeed)
ret.genericToggle = self.CS.generic_toggle ret.genericToggle = self.CS.generic_toggle
#ret.lkasCounter = self.CS.lkas_counter
#ret.lkasCarModel = self.CS.lkas_car_model
# events # events
events = [] events = []

@ -6,6 +6,7 @@ class CAR:
PACIFICA_2019_HYBRID = "CHRYSLER PACIFICA HYBRID 2019" PACIFICA_2019_HYBRID = "CHRYSLER PACIFICA HYBRID 2019"
PACIFICA_2018 = "CHRYSLER PACIFICA 2018" PACIFICA_2018 = "CHRYSLER PACIFICA 2018"
JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # Also covers Tailhawk 2017. JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # Also covers Tailhawk 2017.
JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019"
# Unique can messages: # Unique can messages:
# Only the hybrids have 270: 8 # Only the hybrids have 270: 8
@ -24,11 +25,9 @@ FINGERPRINTS = {
], ],
CAR.PACIFICA_2018: [ CAR.PACIFICA_2018: [
{55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8}, {55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8},
], ],
CAR.PACIFICA_2018_HYBRID: [ CAR.PACIFICA_2018_HYBRID: [
{68: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8}, {68: 8, 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8},
{168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8},
], ],
CAR.PACIFICA_2019_HYBRID: [ CAR.PACIFICA_2019_HYBRID: [
{168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770:8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8}, {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770:8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8},
@ -42,6 +41,8 @@ FINGERPRINTS = {
{55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8},
# Jeep Grand Cherokee 2017 Trailhawk # Jeep Grand Cherokee 2017 Trailhawk
{257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, {257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8},
],
CAR.JEEP_CHEROKEE_2019: [
# Jeep Grand Cherokee 2019 from Switzerland # Jeep Grand Cherokee 2019 from Switzerland
# 530: 8 is so far only in this Jeep. # 530: 8 is so far only in this Jeep.
{55: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 671: 8, 672: 8, 676: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 792: 8, 799: 8, 804: 8, 806: 2, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, {55: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 671: 8, 672: 8, 676: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 792: 8, 799: 8, 804: 8, 806: 2, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8},
@ -65,6 +66,9 @@ DBC = {
CAR.JEEP_CHEROKEE: dbc_dict( # Same DBC file works. CAR.JEEP_CHEROKEE: dbc_dict( # Same DBC file works.
'chrysler_pacifica_2017_hybrid', # 'pt' 'chrysler_pacifica_2017_hybrid', # 'pt'
'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar'
CAR.JEEP_CHEROKEE_2019: dbc_dict( # Same DBC file works.
'chrysler_pacifica_2017_hybrid', # 'pt'
'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar'
} }
STEER_THRESHOLD = 120 STEER_THRESHOLD = 120

Loading…
Cancel
Save