Merge pull request #165 from commaai/devel

openpilot v0.4.0.1
pull/185/head
espes 8 years ago committed by GitHub
commit c2e120c362
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 9
      .gitmodules
  2. 19
      README.md
  3. 9
      RELEASES.md
  4. BIN
      apk/ai.comma.plus.black.apk
  5. BIN
      apk/ai.comma.plus.frame.apk
  6. BIN
      apk/ai.comma.plus.offroad.apk
  7. BIN
      apk/com.baseui.apk
  8. 2
      apk/external/.gitignore
  9. BIN
      apk/external/com.spotify.music.apkpatch
  10. BIN
      apk/external/com.waze.apkpatch
  11. 0
      apk/external/out/.gitkeep
  12. 122
      apk/external/patcher.py
  13. 0
      apk/external/src/.gitkeep
  14. BIN
      apk/external/tools/ApkPatch.android.jar
  15. 7
      apk/external/tools/apkpatch_android
  16. 17
      apk/external/tools/certificate.pem
  17. BIN
      apk/external/tools/key.pk8
  18. BIN
      apk/external/tools/signapk.android.jar
  19. 7
      apk/external/tools/signapk_android
  20. 11
      cereal/car.capnp
  21. 41
      cereal/log.capnp
  22. 2
      common/basedir.py
  23. 3
      common/fingerprints.py
  24. 6
      common/kalman/ekf.py
  25. 3
      common/params.py
  26. 49
      common/profiler.py
  27. 39
      launch_openpilot.sh
  28. 1
      opendbc
  29. 2
      opendbc/.gitignore
  30. 49
      opendbc/README.md
  31. 2
      opendbc/__init__.py
  32. 323
      opendbc/acura_ilx_2016_can.dbc
  33. 185
      opendbc/acura_ilx_2016_nidec.dbc
  34. 315
      opendbc/acura_rdx_2018_can.dbc
  35. 1068
      opendbc/ford_cgea1_2_bodycan_2011.dbc
  36. 1485
      opendbc/ford_cgea1_2_ptcan_2011.dbc
  37. 75
      opendbc/gm_global_a_chassis.dbc
  38. 110
      opendbc/gm_global_a_lowspeed.dbc
  39. 3993
      opendbc/gm_global_a_lowspeed_1818125.dbc
  40. 255
      opendbc/gm_global_a_object.dbc
  41. 216
      opendbc/gm_global_a_powertrain.dbc
  42. 396
      opendbc/honda_accord_touring_2016_can.dbc
  43. 463
      opendbc/honda_civic_hatchback_ex_2017_can.dbc
  44. 435
      opendbc/honda_civic_touring_2016_can.dbc
  45. 423
      opendbc/honda_crv_ex_2017_can.dbc
  46. 312
      opendbc/honda_crv_touring_2016_can.dbc
  47. 386
      opendbc/honda_odyssey_exl_2018.dbc
  48. 322
      opendbc/honda_pilot_touring_2017_can.dbc
  49. 549
      opendbc/hyundai_i30_2014.dbc
  50. 62
      opendbc/mercedes_benz_e350_2010.dbc
  51. 73
      opendbc/subaru_outback_2016_eyesight.dbc
  52. 420
      opendbc/tesla_can.dbc
  53. 197
      opendbc/toyota_iQ_2009_can.dbc
  54. 261
      opendbc/toyota_prius_2017_adas.dbc
  55. 206
      opendbc/toyota_prius_2017_pt.dbc
  56. 204
      opendbc/toyota_rav4_2017_pt.dbc
  57. 203
      opendbc/toyota_rav4_hybrid_2017_pt.dbc
  58. 1041
      opendbc/vw_golf_mk4.dbc
  59. 1192
      opendbc/vw_mqb_2010.dbc
  60. 1
      panda
  61. 12
      panda/.gitignore
  62. 20
      panda/.travis.yml
  63. 7
      panda/LICENSE
  64. 89
      panda/README.md
  65. 31
      panda/TODO
  66. 9
      panda/UPDATING.md
  67. 1
      panda/VERSION
  68. 1
      panda/__init__.py
  69. 8
      panda/board/Makefile
  70. 9
      panda/board/Makefile.legacy
  71. 41
      panda/board/README.md
  72. 0
      panda/board/__init__.py
  73. 91
      panda/board/bootstub.c
  74. 59
      panda/board/build.mk
  75. 40
      panda/board/config.h
  76. 38
      panda/board/drivers/adc.h
  77. 401
      panda/board/drivers/can.h
  78. 16
      panda/board/drivers/dac.h
  79. 141
      panda/board/drivers/drivers.h
  80. 35
      panda/board/drivers/llgpio.h
  81. 120
      panda/board/drivers/spi.h
  82. 7
      panda/board/drivers/timer.h
  83. 224
      panda/board/drivers/uart.h
  84. 705
      panda/board/drivers/usb.h
  85. 3
      panda/board/get_sdk.sh
  86. 5
      panda/board/get_sdk_mac.sh
  87. 450
      panda/board/gpio.h
  88. 1373
      panda/board/inc/cmsis_gcc.h
  89. 1763
      panda/board/inc/core_cm3.h
  90. 1937
      panda/board/inc/core_cm4.h
  91. 87
      panda/board/inc/core_cmFunc.h
  92. 87
      panda/board/inc/core_cmInstr.h
  93. 96
      panda/board/inc/core_cmSimd.h
  94. 7666
      panda/board/inc/stm32f205xx.h
  95. 209
      panda/board/inc/stm32f2xx.h
  96. 181
      panda/board/inc/stm32f2xx_hal_def.h
  97. 299
      panda/board/inc/stm32f2xx_hal_gpio_ex.h
  98. 14994
      panda/board/inc/stm32f413xx.h
  99. 271
      panda/board/inc/stm32f4xx.h
  100. 214
      panda/board/inc/stm32f4xx_hal_def.h
  101. Some files were not shown because too many files have changed in this diff Show More

9
.gitmodules vendored

@ -1,9 +0,0 @@
[submodule "panda"]
path = panda
url = https://github.com/commaai/panda.git
[submodule "opendbc"]
path = opendbc
url = https://github.com/commaai/opendbc.git
[submodule "pyextra"]
path = pyextra
url = https://github.com/commaai/openpilot-pyextra.git

@ -3,7 +3,7 @@ Welcome to openpilot
[openpilot](http://github.com/commaai/openpilot) is an open source driving agent.
Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas and Acuras. It's about on par with Tesla Autopilot at launch, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan).
Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas, Acuras and Toyotas. It's about on par with Tesla Autopilot at launch, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan).
The openpilot codebase has been written to be concise and enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier.
@ -29,13 +29,18 @@ Supported Cars
- Honda CR-V Touring 2015-2016
- Can only be enabled above 25 mph
- Toyota RAV-4 2016+ with TSS-P (alpha!)
- Toyota RAV-4 2016+ non-hybrid with TSS-P
- By default it uses stock Toyota ACC for longitudinal control
- openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Prius_.28for_openpilot.29) and can be enabled above 20 mph
- openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can be enabled above 20 mph
- Toyota Prius 2017 (alpha!)
- By default it uses stock Toyota ACC for longitudinal control
- openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29)
- openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Prius_.28for_openpilot.29)
- Lateral control needs improvements
- Toyota RAV-4 2017 hybrid (alpha!)
- By default it uses stock Toyota ACC for longitudinal control
- openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can do stop and go
In Progress Cars
------
@ -50,6 +55,12 @@ Community WIP Cars
- [Classic Tesla Model S (pre-AP)](https://github.com/commaai/openpilot/pull/145)
- [Honda Odyssey 2018 with Honda Sensing](https://github.com/commaai/openpilot/pull/155)
- [Honda Pilot 2017 with Honda Sensing](https://github.com/commaai/openpilot/pull/161)
- [Acura RDX 2018 with AcuraWatch Plus](https://github.com/commaai/openpilot/pull/162)
Directory structure
------

@ -1,3 +1,12 @@
Version 0.4.0.1 (2017-12-21)
==========================
* New UI to match chffrplus
* Improved lateral control tuning to fix oscillations on Civic
* Add alpha support for 2017 Toyota Rav4 Hybrid
* Reduced CPU usage
* Removed unnecessary utilization of fan at max speed
* Minor bug fixes
Version 0.3.9 (2017-11-21)
==========================
* Add alpha support for 2017 Toyota Prius

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

@ -0,0 +1,2 @@
src/*
out/*

Binary file not shown.

Binary file not shown.

@ -0,0 +1,122 @@
#!/usr/bin/env python2.7
import os
import sys
import glob
import shutil
import urllib2
import hashlib
import subprocess
EXTERNAL_PATH = os.path.dirname(os.path.abspath(__file__))
if os.path.exists("/init.qcom.rc"):
# android
APKPATCH = os.path.join(EXTERNAL_PATH, 'tools/apkpatch_android')
SIGNAPK = os.path.join(EXTERNAL_PATH, 'tools/signapk_android')
else:
APKPATCH = os.path.join(EXTERNAL_PATH, 'tools/apkpatch')
SIGNAPK = os.path.join(EXTERNAL_PATH, 'tools/signapk')
APKS = {
'com.waze': {
'src': 'https://apkcache.s3.amazonaws.com/com.waze_1021278.apk',
'src_sha256': 'f00957e93e2389f9e30502ac54994b98ac769314b0963c263d4e8baa625ab0c2',
'patch': 'com.waze.apkpatch',
'out_sha256': '9ec8b0ea3c78c666342865b1bfb66e368a3f5c911df2ad12835206ec8b19f444'
},
'com.spotify.music': {
'src': 'https://apkcache.s3.amazonaws.com/com.spotify.music_24382006.apk',
'src_sha256': '0610fea68ee7ba5f8e4e0732ad429d729dd6cbb8bc21222c4c99db6cb09fbff4',
'patch': 'com.spotify.music.apkpatch',
'out_sha256': '5a3d6f478c7e40403a98ccc8906d7e0ae12b06543b41f5df52149dd09c647c11'
},
}
def sha256_path(path):
with open(path, 'rb') as f:
return hashlib.sha256(f.read()).hexdigest()
def remove(path):
try:
os.remove(path)
except OSError:
pass
def process(download, patch):
# clean up any junk apks
for out_apk in glob.glob(os.path.join(EXTERNAL_PATH, 'out/*.apk')):
app = os.path.basename(out_apk)[:-4]
if app not in APKS:
print "remove junk", out_apk
remove(out_apk)
complete = True
for k,v in APKS.iteritems():
apk_path = os.path.join(EXTERNAL_PATH, 'out', k+'.apk')
print "checking", apk_path
if os.path.exists(apk_path) and sha256_path(apk_path) == v['out_sha256']:
# nothing to do
continue
complete = False
remove(apk_path)
src_path = os.path.join(EXTERNAL_PATH, 'src', v['src_sha256'])
if not os.path.exists(src_path) or sha256_path(src_path) != v['src_sha256']:
if not download:
continue
print "downloading", v['src'], "to", src_path
# download it
resp = urllib2.urlopen(v['src'])
data = resp.read()
with open(src_path, 'wb') as src_f:
src_f.write(data)
if sha256_path(src_path) != v['src_sha256']:
print "download was corrupted..."
continue
if not patch:
continue
# ignoring lots of TOCTTOU here...
apk_temp = "/tmp/"+k+".patched"
remove(apk_temp)
apk_temp2 = "/tmp/"+k+".signed"
remove(apk_temp2)
try:
print "patching", v['patch']
subprocess.check_call([APKPATCH, 'apply', src_path, apk_temp, os.path.join(EXTERNAL_PATH, v['patch'])])
print "signing", apk_temp
subprocess.check_call([SIGNAPK,
os.path.join(EXTERNAL_PATH, 'tools/certificate.pem'), os.path.join(EXTERNAL_PATH, 'tools/key.pk8'),
apk_temp, apk_temp2])
out_sha256 = sha256_path(apk_temp2) if os.path.exists(apk_temp2) else None
if out_sha256 == v['out_sha256']:
print "done", apk_path
shutil.move(apk_temp2, apk_path)
else:
print "patch was corrupted", apk_temp2, out_sha256
finally:
remove(apk_temp)
remove(apk_temp2)
return complete
if __name__ == "__main__":
ret = True
if len(sys.argv) == 2 and sys.argv[1] == "download":
ret = process(True, False)
elif len(sys.argv) == 2 and sys.argv[1] == "patch":
ret = process(False, True)
else:
ret = process(True, True)
sys.exit(0 if ret else 1)

Binary file not shown.

@ -0,0 +1,7 @@
#!/system/bin/sh
DIR="$(cd "$(dirname "$0")" && pwd)"
export LD_LIBRARY_PATH=/system/lib64
export CLASSPATH="$DIR"/ApkPatch.android.jar
exec app_process "$DIR" ApkPatch "$@"

@ -0,0 +1,17 @@
-----BEGIN CERTIFICATE-----
MIICtTCCAh4CCQDm79UqF+Dc5zANBgkqhkiG9w0BAQUFADCBnjELMAkGA1UEBhMC
SUQxEzARBgNVBAgTCkphd2EgQmFyYXQxEDAOBgNVBAcTB0JhbmR1bmcxEjAQBgNV
BAoTCUxvbmRhdGlnYTETMBEGA1UECxMKQW5kcm9pZERldjEaMBgGA1UEAxMRTG9y
ZW5zaXVzIFcuIEwuIFQxIzAhBgkqhkiG9w0BCQEWFGxvcmVuekBsb25kYXRpZ2Eu
bmV0MB4XDTEwMDUwNTA5MjEzOFoXDTEzMDEyODA5MjEzOFowgZ4xCzAJBgNVBAYT
AklEMRMwEQYDVQQIEwpKYXdhIEJhcmF0MRAwDgYDVQQHEwdCYW5kdW5nMRIwEAYD
VQQKEwlMb25kYXRpZ2ExEzARBgNVBAsTCkFuZHJvaWREZXYxGjAYBgNVBAMTEUxv
cmVuc2l1cyBXLiBMLiBUMSMwIQYJKoZIhvcNAQkBFhRsb3JlbnpAbG9uZGF0aWdh
Lm5ldDCBnzANBgkqhkiG9w0BAQEFAAOBjQAwgYkCgYEAy2oWtbdVXMHGiS6cA3qi
3VfZt5Vz9jTlux+TEcGx5h18ZKwclyo+z2B0L/p5bYdnrTdFEiD7IxvX+h3lu0JV
B9rdXZdyrzXNOw5YFrsn2k7hKvB8KEBaga1gZEwodlc6N14H3FbZdZkIA9V716Pu
e5CWBZ2VqU03lUJmKnpH8c8CAwEAATANBgkqhkiG9w0BAQUFAAOBgQBpNgXh8dw9
uMjZxzLUXovV5ptHd61jAcZlQlffqPsz6/2QNfIShVdGH9jkm0IudfKkbvvOKive
a77t9c4sDh2Sat2L/rx6BfTuS1+y9wFr1Ee8Rrr7wGHhRkx2qqGrXGVWqXn8aE3E
P6e7BTPF0ibS+tG8cdDPEisqGFxw36nTNQ==
-----END CERTIFICATE-----

Binary file not shown.

Binary file not shown.

@ -0,0 +1,7 @@
#!/system/bin/sh
DIR="$(cd "$(dirname "$0")" && pwd)"
export LD_LIBRARY_PATH=/system/lib64
export CLASSPATH="$DIR"/signapk.android.jar
exec app_process "$DIR" com.android.signapk.SignApk "$@"

@ -12,12 +12,13 @@ $Java.outerClassname("Car");
struct CarEvent @0x9b1657f34caf3ad3 {
name @0 :EventName;
enable @1 :Bool;
preEnable @7 :Bool;
noEntry @2 :Bool;
warning @3 :Bool;
userDisable @4 :Bool;
softDisable @5 :Bool;
immediateDisable @6 :Bool;
preEnable @7 :Bool;
permanent @8 :Bool;
enum EventName @0xbaa8c5d505f727de {
# TODO: copy from error list
@ -64,9 +65,10 @@ struct CarState {
events @13 :List(CarEvent);
# car speed
vEgo @1 :Float32; # best estimate of speed
aEgo @16 :Float32; # best estimate of acceleration
vEgoRaw @17 :Float32; # unfiltered speed
vEgo @1 :Float32; # best estimate of speed
aEgo @16 :Float32; # best estimate of acceleration
vEgoRaw @17 :Float32; # unfiltered speed from CAN sensors
yawRate @22 :Float32; # best estimate of yaw rate
standstill @18 :Bool;
wheelSpeeds @2 :WheelSpeeds;
@ -309,4 +311,5 @@ struct CarParams {
directAccelControl @31 :Bool; # Does the car have direct accel control or just gas/brake
stoppingControl @34 :Bool; # Does the car allows full control even at lows speeds when stopping
startAccel @35 :Float32; # Required acceleraton to overcome creep braking
steerRateCost @40 :Float32; # Lateral MPC cost on steering rate
}

@ -28,6 +28,7 @@ struct InitData {
version @4 :Text;
gitCommit @10 :Text;
gitBranch @11 :Text;
gitRemote @13 :Text;
androidBuildInfo @5 :AndroidBuildInfo;
androidSensors @6 :List(AndroidSensor);
@ -154,6 +155,8 @@ struct SensorEventData {
pressure @9 :SensorVec;
magneticUncalibrated @11 :SensorVec;
gyroUncalibrated @12 :SensorVec;
proximity @13: Float32;
light @14: Float32;
}
source @8 :SensorSource;
@ -242,8 +245,11 @@ struct ThermalData {
freeSpace @7 :Float32;
batteryPercent @8 :Int16;
batteryStatus @9 :Text;
usbOnline @12 :Bool;
fanSpeed @10 :UInt16;
started @11 :Bool;
startedTs @13 :UInt64;
}
struct HealthData {
@ -349,6 +355,7 @@ struct Live100Data {
jerkFactor @12 :Float32;
angleSteers @13 :Float32; # Steering angle in degrees.
angleSteersDes @29 :Float32;
curvature @37 :Float32; # path curvature from vehicle model
hudLeadDEPRECATED @14 :Int32;
cumLagMs @15 :Float32;
@ -361,6 +368,8 @@ struct Live100Data {
rearViewCam @23 :Bool;
alertText1 @24 :Text;
alertText2 @25 :Text;
alertStatus @38 :AlertStatus;
alertSize @39 :AlertSize;
awarenessStatus @26 :Float32;
angleOffset @27 :Float32;
@ -378,6 +387,20 @@ struct Live100Data {
stopping @2;
starting @3;
}
enum AlertStatus {
normal @0; # low priority alert for user's convenience
userPrompt @1; # mid piority alert that might require user intervention
critical @2; # high priority alert that needs immediate user intervention
}
enum AlertSize {
none @0; # don't display the alert
small @1; # small box
mid @2; # mid screen
full @3; # full screen
}
}
struct LiveEventData {
@ -600,6 +623,23 @@ struct NavUpdate {
}
}
struct NavStatus {
isNavigating @0 :Bool;
currentAddress @1 :Address;
struct Address {
title @0 :Text;
lat @1 :Float64;
lng @2 :Float64;
house @3 :Text;
address @4 :Text;
street @5 :Text;
city @6 :Text;
state @7 :Text;
country @8 :Text;
}
}
struct CellInfo {
timestamp @0 :UInt64;
repr @1 :Text; # android toString() for now
@ -1300,5 +1340,6 @@ struct Event {
clocks @35 :Clocks;
liveMpc @36 :LiveMpcData;
liveLongitudinalMpc @37 :LiveLongitudinalMpcData;
navStatus @38 :NavStatus;
}
}

@ -1,4 +1,4 @@
import os
BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")
BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../"))

@ -19,6 +19,9 @@ _FINGERPRINTS = {
"TOYOTA RAV4 2017": {
36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 552L: 4, 562L: 4, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 725L: 2, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 918L: 7, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 951L: 8, 955L: 4, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1008L: 2, 1014L: 8, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1593L: 8, 1595L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1656L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8
},
"TOYOTA RAV4 2017 HYBRID": {
36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 552L: 4, 562L: 4, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 725L: 2, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 918L: 7, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 951L: 8, 955L: 8, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1008L: 2, 1014L: 8, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1593L: 8, 1595L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1656L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8, 581L: 5, 296: 8, 552L: 8, 560L: 7, 552L: 4, 713L: 8, 550L: 8, 608L: 8, 37L: 8, 36L: 8, 950L: 8, 1198L: 8, 1197L: 8, 1199L: 8, 1212L: 8, 953L: 3, 1264L: 8, 1184L: 8, 1005L: 2, 1185L: 8, 1232L: 8, 1186L: 8
},
"TOYOTA PRIUS 2017": {
36L: 8, 37L: 8, 166L: 8, 170L: 8, 180L: 8, 295L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 6, 581L: 5, 608L: 8, 610L: 8, 614L: 8, 643L: 7, 658L: 8, 713L: 8, 740L: 5, 742L: 8, 743L: 8, 800L: 8, 810L: 2, 814L: 8, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 863L: 8, 869L: 7, 870L: 7, 871L: 2, 898L: 8, 900L: 6, 902L: 6, 905L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1279L: 8, 1552L: 8, 1553L: 8, 1556L: 8, 1557L: 8, 1568L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1595L: 8, 1777L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8
},

@ -35,7 +35,7 @@ class SensorReading:
# A generic sensor class that does no pre-processing of data
class SimpleSensor:
# obs_model can be
# a full obesrvation model matrix, or
# a full observation model matrix, or
# an integer or tuple of indices into ekf.state, indicating which variables are being directly observed
# covar can be
# a full covariance matrix
@ -129,7 +129,7 @@ class EKF:
print "covar:\n",self.covar
def update_scalar(self, reading):
# like update but knowing that measurment is a scalar
# like update but knowing that measurement is a scalar
# this avoids matrix inversions and speeds up (surprisingly) drived.py a lot
# innovation = reading.data - np.matmul(reading.obs_model, self.state)
@ -188,7 +188,7 @@ class EKF:
Current implementations calculate A and J as functions of state. Control input
can be added trivially by adding a control parameter to predict() and calc_tranfer_update(),
and using it during calcualtion of A and J
and using it during calculation of A and J
"""

@ -52,12 +52,14 @@ keys = {
"Version": TxType.PERSISTANT,
"GitCommit": TxType.PERSISTANT,
"GitBranch": TxType.PERSISTANT,
"GitRemote": TxType.PERSISTANT,
# written: baseui
# read: ui, controls
"IsMetric": TxType.PERSISTANT,
"IsRearViewMirror": TxType.PERSISTANT,
"IsFcwEnabled": TxType.PERSISTANT,
"HasAcceptedTerms": TxType.PERSISTANT,
"IsUploadVideoOverCellularEnabled": TxType.PERSISTANT,
# written: visiond
# read: visiond, controlsd
"CalibrationParams": TxType.PERSISTANT,
@ -69,6 +71,7 @@ keys = {
"CarParams": TxType.CLEAR_ON_CAR_START,
"Passive": TxType.PERSISTANT,
"DoUninstall": TxType.CLEAR_ON_MANAGER_START,
}
def fsync_dir(path):

@ -1,32 +1,47 @@
from common.realtime import sec_since_boot
import time
class Profiler(object):
def __init__(self, enabled=False):
self.enabled = enabled
self.cp = []
self.start_time = sec_since_boot()
self.cp = {}
self.cp_ignored = []
self.iter = 0
self.start_time = time.clock()
self.last_time = self.start_time
def checkpoint(self, name):
if not self.enabled:
return
tt = sec_since_boot()
self.cp.append((name, tt - self.last_time))
self.last_time = tt
self.tot = 0.
def reset(self, enabled=False):
self.enabled = enabled
self.cp = []
self.start_time = sec_since_boot()
self.cp = {}
self.cp_ignored = []
self.iter = 0
self.start_time = time.clock()
self.last_time = self.start_time
def checkpoint(self, name, ignore=False):
# ignore flag needed when benchmarking threads with ratekeeper
if not self.enabled:
return
tt = time.clock()
if name not in self.cp:
self.cp[name] = 0.
if ignore:
self.cp_ignored.append(name)
self.cp[name] += tt - self.last_time
if not ignore:
self.tot += tt - self.last_time
self.last_time = tt
def display(self):
if not self.enabled:
return
self.iter += 1
print "******* Profiling *******"
tot = 0.0
for n, ms in self.cp:
print "%30s: %7.2f" % (n, ms*1000.0)
tot += ms
print " TOTAL: %7.2f" % (tot*1000.0)
for n in self.cp:
ms = self.cp[n]
if n in self.cp_ignored:
print "%30s: %7.2f perc: %1.0f" % (n, ms*1000.0, ms/self.tot*100), " IGNORED"
else:
print "%30s: %7.2f perc: %1.0f" % (n, ms*1000.0, ms/self.tot*100)
print "Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)

@ -0,0 +1,39 @@
#!/usr/bin/bash
function launch {
# apply update
if [ "$(git rev-parse HEAD)" != "$(git rev-parse @{u})" ]; then
git reset --hard @{u} &&
git clean -xdf &&
exec "${BASH_SOURCE[0]}"
fi
# no cpu rationing for now
echo 0-3 > /dev/cpuset/background/cpus
echo 0-3 > /dev/cpuset/system-background/cpus
echo 0-3 > /dev/cpuset/foreground/boost/cpus
echo 0-3 > /dev/cpuset/foreground/cpus
echo 0-3 > /dev/cpuset/android/cpus
# wait for network
(cd selfdrive/ui/spinner && exec ./spinner 'waiting for network...') & spin_pid=$!
until ping -W 1 -c 1 8.8.8.8; do sleep 1; done
kill $spin_pid
# check if NEOS update is required
while [ "$(cat /VERSION)" -lt 4 ] && [ ! -e /data/media/0/noupdate ]; do
curl -o /tmp/updater https://neos.comma.ai/updater && chmod +x /tmp/updater && /tmp/updater
sleep 10
done
export PYTHONPATH="$PWD"
# start manager
cd selfdrive
./manager.py
# if broken, keep on screen error
while true; do sleep 1; done
}
launch

@ -1 +0,0 @@
Subproject commit 242698f80038bab677a4a6e58127309f9ed38d93

@ -0,0 +1,2 @@
*.pyc
.*.swp

@ -0,0 +1,49 @@
opendbc
======
The project to democratize access to the decoder ring of your car.
### DBC file basics
A DBC file encodes, in a humanly readable way, the information needed to understand a vehicle's CAN bus traffic. A vehicle might have multiple CAN buses and every CAN bus is represented by its own dbc file.
Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/index.php?title=DBC_Format) a good overview.
### How to start reverse engineering cars
[opendbc](https://github.com/commaai/opendbc) is integrated with [cabana](https://community.comma.ai/cabana/).
Use [panda](https://github.com/commaai/panda) to connect your car to a computer.
### Good practices for contributing to opendbc
- Comments: the best way to store comments is to add them directly to the DBC files. For example:
```
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
```
is a comment that refers to signal `LONG_ACCEL` in message `490`. Using comments is highly recommended, especially for doubts and uncertainties. [cabana](https://community.comma.ai/cabana/) can easily display/add/edit comments to signals and messages.
- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better.
For example:
```
SG_ VEHICLE_SPEED : 7|15@0+ (0.00278,0) [0|70] "m/s" PCM
```
is better than:
```
SG_ VEHICLE_SPEED : 7|15@0+ (0.00620,0) [0|115] "mph" PCM
```
However, the cleanest option is really:
```
SG_ VEHICLE_SPEED : 7|15@0+ (0.01,0) [0|250] "kph" PCM
```
- Signal's size: always use the smallest amount of bits possible. For example, let's say I'm reverse engineering the gas pedal position and I've determined that it's in a 3 bytes message. For 0% pedal position I read a message value of `0x00 0x00 0x00`, while for 100% of pedal position I read `0x64 0x00 0x00`: clearly, the gas pedal position is within the first byte of the message and I might be tempted to define the signal `GAS_POS` as:
```
SG_ GAS_POS : 7|8@0+ (1,0) [0|100] "%" PCM
```
However, I can't be sure that the very first bit of the message is referred to the pedal position: I haven't seen it changing! Therefore, a safer way of defining the signal is:
```
SG_ GAS_POS : 6|7@0+ (1,0) [0|100] "%" PCM
```
which leaves the first bit unallocated. This prevents from very erroneous reading of the gas pedal position, in case the first bit is indeed used for something else.

@ -0,0 +1,2 @@
import os
DBC_PATH = os.path.dirname(os.path.abspath(__file__))

@ -0,0 +1,323 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX
BO_ 57 XXX_1: 3 XXX
BO_ 145 XXX_2: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO
BO_ 228 STEERING_CONTROL: 5 ADAS
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS
BO_ 304 GAS_PEDAL2: 8 PCM
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
BO_ 316 GAS_PEDAL: 8 PCM
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 398 XXX_3: 3 XXX
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 419 GEARBOX: 8 PCM
SG_ GEAR : 7|8@0+ (1,0) [0|256] "" NEO
SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 422 SCM_BUTTONS: 8 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 428 XXX_4: 8 XXX
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 476 XXX_5: 4 XXX
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM
SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM
BO_ 512 GAS_COMMAND: 3 NEO
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 5 INTERCEPTOR
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
BO_ 542 XXX_6: 7 XXX
BO_ 545 XXX_7: 4 XXX
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO
BO_ 660 SCM_COMMANDS: 8 SCM
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 777 XXX_8: 8 XXX
BO_ 780 ACC_HUD: 8 ADAS
SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 800 XXX_9: 8 XXX
BO_ 804 CRUISE: 8 PCM
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 808 XXX_10: 8 XXX
BO_ 819 XXX_11: 7 XXX
BO_ 821 XXX_12: 5 XXX
BO_ 829 LKAS_HUD_2: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY
BO_ 882 XXX_13: 2 XXX
BO_ 884 XXX_14: 7 XXX
BO_ 887 XXX_15: 8 XXX
BO_ 888 XXX_16: 8 XXX
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO
BO_ 923 XXX_18: 2 XXX
BO_ 929 XXX_19: 4 XXX
BO_ 983 XXX_20: 8 XXX
BO_ 985 XXX_21: 3 XXX
BO_ 1024 XXX_22: 5 XXX
BO_ 1027 XXX_23: 5 XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1030 XXX_24: 5 VSA
BO_ 1034 XXX_25: 5 XXX
BO_ 1036 XXX_26: 8 XXX
BO_ 1039 XXX_27: 8 XXX
BO_ 1057 XXX_28: 5 EPS
BO_ 1064 XXX_29: 7 XXX
BO_ 1108 XXX_30: 8 XXX
BO_ 1365 XXX_31: 5 XXX
BO_ 1600 XXX_32: 5 XXX
BO_ 1601 XXX_33: 8 XXX
BO_TX_BU_ 228 : NEO,ADAS;
BO_TX_BU_ 506 : NEO,ADAS;
BO_TX_BU_ 780 : NEO,ADAS;
BO_TX_BU_ 829 : NEO,ADAS;
CM_ SG_ 419 GEAR "10 = reverse, 11 = transition";
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc...";
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ;
VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,185 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: ADAS RADAR NEO XXX
BO_ 768 VEHICLE_STATE: 8 ADAS
SG_ SET_ME_XF9 : 7|8@0+ (1,0) [0|255] "" Vector__XXX
SG_ VEHICLE_SPEED : 15|8@0+ (1,0) [0|255] "kph" Vector__XXX
BO_ 769 VEHICLE_STATE2: 8 ADAS
SG_ SET_ME_0F18510 : 7|28@0+ (1,0) [0|268435455] "" Vector__XXX
SG_ SET_ME_25A0000 : 27|28@0+ (1,0) [0|268435455] "" Vector__XXX
BO_ 1024 RADAR_DIAGNOSTIC: 8 RADAR
SG_ RADAR_STATE : 7|8@0+ (1,0) [0|255] "" NEO
BO_ 1040 XXX_101: 8 RADAR
BO_ 1041 XXX_102: 8 RADAR
BO_ 1042 XXX_103: 8 RADAR
BO_ 1043 XXX_104: 8 RADAR
BO_ 1044 XXX_105: 8 RADAR
BO_ 1045 XXX_106: 8 RADAR
BO_ 1046 XXX_107: 8 RADAR
BO_ 1047 XXX_108: 8 RADAR
BO_ 1056 XXX_109: 8 RADAR
BO_ 1057 XXX_110: 8 RADAR
BO_ 1058 XXX_111: 8 RADAR
BO_ 1059 XXX_112: 8 RADAR
BO_ 1060 XXX_113: 8 RADAR
BO_ 1072 TRACK_0: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1073 TRACK_1: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1074 TRACK_2: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1075 TRACK_3: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1076 TRACK_4: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1077 TRACK_5: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1078 TRACK_6: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1079 TRACK_7: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1080 TRACK_8: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1081 TRACK_9: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1088 TRACK_10: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1089 TRACK_11: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1090 TRACK_12: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1091 TRACK_13: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1092 TRACK_14: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1093 TRACK_15: 8 RADAR
SG_ LONG_DIST : 7|12@0+ (0.0625,0) [0|255.5] "m" NEO
SG_ NEW_TRACK : 11|1@0+ (1,0) [0|1] "" NEO
SG_ LAT_DIST : 9|10@0- (0.0625,0) [0|63.5] "m" NEO
SG_ REL_SPEED : 31|12@0- (0.03125,0) [0|127.5] "m/s" NEO
BO_ 1279 XXX_114: 8 RADAR
BO_ 1280 XXX_115: 8 RADAR
BO_ 1296 XXX_116: 8 RADAR
BO_ 1297 XXX_117: 8 RADAR
BO_TX_BU_ 768 : NEO,ADAS;
BO_TX_BU_ 769 : NEO,ADAS;
CM_ SG_ 1024 RADAR_STATE "need to find out more diagnostic values";
VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted";

@ -0,0 +1,315 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
BO_ 145 XXX_2: 8 XXX
BO_ 316 XXX_3: 8 PCM
BO_ 340 XXX_4: 8 PCM
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 392 GEARBOX: 6 XXX
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX
SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" NEO
SG_ GEAR : 36|5@0+ (1,0) [0|31] "" NEO
BO_ 398 XXX_5: 3 PCM
BO_ 399 STEER_STATUS: 6 EPS
SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
BO_ 404 STEERING_CONTROL: 4 NEO
SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS
SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 422 SCM_BUTTONS: 8 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO
SG_ PARKING_BREAK_LIGHT : 2|1@0+ (1,0) [0|1] "" NEO
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 426 XXX_6: 8 VSA
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 474 XXX_7: 5 VSA
BO_ 476 XXX_8: 5 XXX
BO_ 487 XXX_9: 4 VSA
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 493 XXX_10: 3 VSA
BO_ 506 BRAKE_COMMAND: 8 NEO
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM
SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM
SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM
SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
BO_ 507 XXX_11: 1 NEO
BO_ 542 XXX_12: 7 XXX
BO_ 545 XXX_13: 4 XXX
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 660 SCM_COMMANDS: 8 SCM
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 661 XXX_14: 4 XXX
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 777 XXX_15: 8 XXX
BO_ 780 ACC_HUD: 8 CAM
SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY
BO_ 800 XXX_16: 8 XXX
BO_ 804 CRUISE: 8 PCM
SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO
SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 808 XXX_17: 8 XXX
BO_ 829 LKAS_HUD_2: 5 CAM
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
BO_ 882 XXX_18: 2 XXX
BO_ 884 XXX_19: 7 XXX
BO_ 888 XXX_20: 8 XXX
BO_ 891 XXX_21: 8 XXX
BO_ 923 XXX_23: 2 XXX
BO_ 929 XXX_24: 8 XXX
BO_ 983 XXX_25: 8 XXX
BO_ 985 XXX_26: 3 XXX
BO_ 1024 XXX_27: 5 XXX
BO_ 1027 XXX_28: 5 XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 1033 XXX_29: 5 XXX
BO_ 1036 XXX_30: 8 XXX
BO_ 1039 XXX_31: 8 XXX
BO_ 1057 XXX_32: 5 XXX
BO_ 1064 XXX_32: 7 XXX
BO_ 1108 XXX_33: 8 XXX
BO_ 1125 XXX_34: 8 XXX
BO_ 1296 XXX_35: 8 XXX
BO_ 1365 XXX_36: 5 XXX
BO_ 1424 XXX_37: 5 XXX
BO_ 1600 XXX_38: 5 XXX
BO_ 1601 XXX_39: 8 XXX
BO_TX_BU_ 399 : NEO,CAM;
BO_TX_BU_ 506 : NEO,CAM;
BO_TX_BU_ 780 : NEO,CAM;
BO_TX_BU_ 829 : NEO,CAM;
CM_ SG_ 422 PARKING_BREAK_LIGHT "Believe this is just the dash light for the parking break";
VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ;
VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

@ -0,0 +1,75 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: K182_PACM K43_PSCM K17_EBCM NEO K124_ASCM
BO_ 823 PACMParkAssitCmd: 7 NEO
SG_ RollingCounter : 35|2@0+ (1,0) [0|0] "" NEO
SG_ SteeringWheelChecksum : 47|16@0+ (1,0) [0|0] "" NEO
SG_ SteeringWheelCmd : 23|16@0+ (1,0) [0|0] "" NEO
BO_ 560 EBCMRegen: 6 K17_EBCM
SG_ Regen : 1|10@0+ (1,0) [0|0] "" NEO
BO_ 368 EBCMFrictionBrakeStatus: 8 K17_EBCM
SG_ FrictionBrakePressure : 23|16@0+ (1,0) [0|0] "" NEO
BO_ 789 EBCMFrictionBrakeCmd: 5 K17_EBCM
SG_ RollingCounter : 33|2@0+ (1,0) [0|0] "" NEO
SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO
SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO
SG_ FirctionBrakeCmd : 3|12@0+ (1,0) [0|0] "" NEO
BO_TX_BU_ 823 : K43_PSCM,NEO;
BO_TX_BU_ 789 : NEO,K17_EBCM;
CM_ BU_ K182_PACM "Parking Assist Control Module";
CM_ BU_ K43_PSCM "Power Steering Control Module";
CM_ BU_ K17_EBCM "Electronic Brake Control Module";
CM_ BU_ NEO "Comma NEO";
CM_ BU_ K124_ASCM "Active Safety Control Module";
BA_DEF_ "UseGMParameterIDs" INT 0 0;
BA_DEF_ "ProtocolType" STRING ;
BA_DEF_ "BusType" STRING ;
BA_DEF_DEF_ "UseGMParameterIDs" 1;
BA_DEF_DEF_ "ProtocolType" "GMLAN";
BA_DEF_DEF_ "BusType" "";
BA_ "UseGMParameterIDs" 0;
BA_ "BusType" "CAN";
BA_ "ProtocolType" "GMLAN";

@ -0,0 +1,110 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: GMLAN NEO
VAL_TABLE_ GearShifter 3 "Park" 0 "Drive/Low" ;
VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ;
VAL_TABLE_ LKAGapButton 2 "???" 1 "??" 0 "None" ;
VAL_TABLE_ CruiseButtons 12 "Cancel" 10 "Enabled" 6 "Set" 4 "Resume" 2 "None" ;
VAL_TABLE_ CruiseControlActive 1 "Active" 0 "Inactive" ;
VAL_TABLE_ BlinkerStatus 1 "Active" 0 "Inactive" ;
BO_ 274923520 DriverDoorStatus: 1 GMLAN
SG_ DriverDoorOpened : 0|1@0+ (1,0) [0|0] "" NEO
BO_ 272629760 Chime: 5 NEO
SG_ ChimeType : 7|8@0+ (1,0) [0|0] "" GMLAN
SG_ ChimeRepeat : 23|8@0+ (1,0) [0|0] "" GMLAN
SG_ ChimeDuration : 15|8@0+ (1,0) [0|0] "" GMLAN
SG_ ChimeByte5 : 39|8@0+ (1,0) [0|0] "" GMLAN
SG_ ChimeByte4 : 31|8@0+ (1,0) [0|0] "" GMLAN
BO_ 270581760 BlinkerStatus: 5 GMLAN
SG_ RightBlinker : 6|1@0+ (1,0) [0|0] "" NEO
SG_ LeftBlinker : 7|1@0+ (1,0) [0|0] "" NEO
SG_ BlinkerLight : 25|1@0+ (1,0) [0|0] "" NEO
BO_ 270794752 SteeringWheelAngle: 8 GMLAN
SG_ SteeringWheelAngle : 39|16@0- (0.0625,0) [-540|540] "deg" NEO
BO_ 271368192 GearShifter: 8 GMLAN
SG_ GearShifter : 17|2@0+ (1,0) [0|3] "" NEO
BO_ 271360000 GasPedalRegenCruise: 8 GMLAN
SG_ CruiseControlActive : 56|1@0+ (1,0) [0|0] "" GMLAN
SG_ MaxRegen : 12|1@0+ (1,0) [0|1] "" GMLAN,NEO
SG_ GasPedal : 47|8@0+ (1,0) [0|254] "" GMLAN,NEO
SG_ GearShifter2NotUsed : 55|8@0+ (1,0) [0|255] "" GMLAN,NEO
BO_ 270860288 BrakePedal: 2 GMLAN
SG_ BrakeLevel : 2|2@0+ (1,0) [0|3] "" NEO
SG_ BrakeSensor : 15|8@0+ (1,0) [0|255] "" NEO
BO_ 275480576 WheelSpeed: 8 GMLAN
SG_ WheelSpeedFL : 7|16@0+ (0.01,0) [0|70] "yd/s" NEO
SG_ WheelSpeedFR : 39|16@0+ (0.01,0) [0|70] "yd/s" NEO
SG_ WheelSpeedRL : 23|16@0+ (0.01,0) [0|70] "yd/s" NEO
SG_ WheelSpeedRR : 55|16@0+ (0.01,0) [0|70] "yd/s" NEO
BO_ 270598144 VehicleSpeed: 8 GMLAN
SG_ VehicleSpeed1 : 7|16@0+ (0.01,0) [0|100] "mph" NEO
SG_ VehicleSpeed2 : 39|16@0+ (0.01,0) [0|100] "mph" NEO
BO_ 276135936 CruiseButtons: 3 GMLAN
SG_ CruiseButtons : 3|4@0+ (1,0) [0|12] "" NEO
BO_ 276127744 CruiseButtons2: 1 GMLAN
SG_ LKAGapButton : 1|2@0+ (1,0) [0|2] "" NEO
BA_DEF_ "UseGMParameterIDs" INT 0 0;
BA_DEF_ "ProtocolType" STRING ;
BA_DEF_ "BusType" STRING ;
BA_DEF_DEF_ "UseGMParameterIDs" 1;
BA_DEF_DEF_ "ProtocolType" "GMLAN";
BA_DEF_DEF_ "BusType" "";
BA_ "BusType" "CAN";
BA_ "ProtocolType" "GMLAN";
VAL_ 274923520 DriverDoorOpened 1 "Opened" 0 "Closed" ;
VAL_ 270581760 RightBlinker 1 "Active" 0 "Inactive" ;
VAL_ 270581760 LeftBlinker 1 "Active" 0 "Inactive" ;
VAL_ 270581760 BlinkerLight 1 "Active" 0 "Inactive" ;
VAL_ 271368192 GearShifter 3 "Park" 0 "Drive/Low" ;
VAL_ 271360000 CruiseControlActive 1 "Active" 0 "Inactive" ;
VAL_ 276135936 CruiseButtons 12 "Cancel" 10 "Enabled" 6 "Set" 4 "Resume" 2 "None" ;
VAL_ 276127744 LKAGapButton 2 "???" 1 "??" 0 "None" ;

File diff suppressed because it is too large Load Diff

@ -0,0 +1,255 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: K109_FCM B233B_LRR NEO K124_ASCM
VAL_TABLE_ RangeMode 1 "Active" 0 "Inactive" ;
VAL_TABLE_ TrkConf 3 "Confident" 2 "Speculative" 1 "Highly speculative" 0 "Invalid" ;
VAL_TABLE_ TrkMeasStatus 3 "Measured current cycle" 2 "Latent track not detected " 1 "New object" 0 "No object" ;
VAL_TABLE_ TrkDynProp 4 "Moving in opposite direction" 3 "Moving in same direction " 2 "Has moved but currenty stopped" 1 "Has never moved," 0 "Unkown" ;
BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX
SG_ Always12 : 0|8@0+ (1,0) [0|0] "" Vector__XXX
SG_ TimeStatusChecksum : 0|12@0+ (1,0) [0|0] "" Vector__XXX
BO_ 161 ASCMTimeStatus: 7 NEO
SG_ TimeStatus : 7|28@0+ (1,0) [0|0] "" B233B_LRR
SG_ RollingCounter : 27|2@0+ (1,0) [0|0] "" B233B_LRR
BO_ 774 ASCMSteeringStatus: 8 NEO
SG_ ASCMSterringStatusChecksum : 55|16@0+ (1,0) [0|0] "" B233B_LRR
SG_ AlwaysF0 : 15|8@0+ (1,0) [0|0] "" B233B_LRR
SG_ Always20 : 23|8@0+ (1,0) [0|0] "" B233B_LRR
SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" B233B_LRR
BO_ 784 ASCMHeadlight: 2 NEO
SG_ Always42 : 7|8@0+ (1,0) [0|0] "" B233B_LRR
SG_ Always4 : 15|8@0+ (1,0) [0|0] "" B233B_LRR
BO_ 776 ASCMAccSpeedStatus: 7 NEO
SG_ AccSpeedChecksum : 42|11@0+ (1,0) [0|0] "" B233B_LRR
SG_ RollingCounter : 46|2@0+ (1,0) [0|0] "" B233B_LRR
SG_ NearRangeMode : 43|1@0+ (1,0) [0|0] "" B233B_LRR
SG_ FarRangeMode : 44|1@0+ (1,0) [0|0] "" B233B_LRR
SG_ VehicleAcceleration : 19|12@0+ (1,0) [0|0] "" B233B_LRR
SG_ VehicleSpeed : 15|12@0+ (1,0) [0|0] "" B233B_LRR
SG_ AlwaysOne : 3|1@0+ (1,0) [0|0] "" B233B_LRR
BO_ 1120 LRRNumObjects: 8 B233B_LRR
SG_ LRRNumObjects : 20|5@0+ (1,0) [0|0] "" NEO
BO_ 1134 LRRObject14: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1132 LRRObject12: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1131 LRRObject11: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1130 LRRObject10: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1129 LRRObject09: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1128 LRRObject08: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1127 LRRObject07: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1126 LRRObject06: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1125 LRRObject05: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1124 LRRObject04: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1123 LRRObject03: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1140 LRRObject20: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1139 LRRObject19: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1138 LRRObject18: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1137 LRRObject17: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1136 LRRObject16: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1135 LRRObject15: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1133 LRRObject13: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1122 LRRObject02: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_ 1121 LRRObject01: 8 B233B_LRR
SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO
SG_ TrkRangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" NEO
SG_ TrkRangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" NEO
SG_ TrkAzimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" NEO
SG_ TrkWidth : 55|6@0+ (0.25,0) [0|15.75] "m" NEO
SG_ TrkObjectID : 61|6@0+ (1,0) [0|63] "" NEO
BO_TX_BU_ 161 : K124_ASCM,NEO;
BO_TX_BU_ 774 : K124_ASCM,NEO;
BO_TX_BU_ 784 : K124_ASCM,NEO;
BO_TX_BU_ 776 : K124_ASCM,NEO;
CM_ BU_ K109_FCM "Frontview Camera Module ";
CM_ BU_ B233B_LRR "Radar Sensor Module Long Range";
CM_ BU_ NEO "Comma NEO";
CM_ BU_ K124_ASCM "Active Safety Control Module";
CM_ BO_ 3221225472 "This is a message for not used signals, created by Vector CANdb++ DBC OLE DB Provider.";
BA_DEF_ "UseGMParameterIDs" INT 0 0;
BA_DEF_ "ProtocolType" STRING ;
BA_DEF_ "BusType" STRING ;
BA_DEF_DEF_ "UseGMParameterIDs" 1;
BA_DEF_DEF_ "ProtocolType" "GMLAN";
BA_DEF_DEF_ "BusType" "";
BA_ "BusType" "CAN";
BA_ "ProtocolType" "GMLAN";
BA_ "UseGMParameterIDs" 0;
VAL_ 776 NearRangeMode 1 "Active" 0 "Inactive" ;
VAL_ 776 FarRangeMode 1 "Active" 0 "Inactive" ;

@ -0,0 +1,216 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM
VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ;
VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ;
VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ;
VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ;
VAL_TABLE_ ACCGapButton 1 "Active" 0 "Inactive" ;
VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ;
VAL_TABLE_ ACCCancelButton 1 "Active" 0 "Inactive" ;
VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ;
VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ;
VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ;
VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ;
VAL_TABLE_ ACCButton 1 "Pressed" 0 "Depressed" ;
VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ;
VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ;
VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ;
VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ;
VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ;
BO_ 320 BCMTurnSignals: 3 K9_BCM
SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO
BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM
SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "°C" NEO
BO_ 1249 VIN_Part2: 8 K20_ECM
SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO
BO_ 1300 VIN_Part1: 8 K20_ECM
SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO
BO_ 481 ASCMSteeringButton: 7 K124_ASCM
SG_ ACCGapButton : 22|1@0+ (1,0) [0|0] "" NEO
SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO
SG_ ACCCancelButton : 7|1@0+ (1,0) [0|0] "" NEO
BO_ 1912 PSCM_778: 8 K43_PSCM
BO_ 328 PSCM_148: 1 K43_PSCM
BO_ 309 ECMPRDNL: 8 K20_ECM
SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO
BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC
SG_ GPSLongitude : 39|32@0+ (1,0) [0|0] "milliarcsecond" NEO
SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO
BO_ 1001 ECMVehicleSpeed: 8 K20_ECM
SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO
BO_ 298 BCMDoorStatus: 8 K9_BCM
SG_ DriverDoorStatus : 55|1@0+ (1,0) [0|0] "" NEO
BO_ 381 MSG_17D: 6 K20_ECM
SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO
BO_ 201 ECMEngineStatus: 8 K20_ECM
SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO
SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO
BO_ 209 EBCMBrakePedalTorque: 7 K17_EBCM
SG_ BrakePedalTorque : 3|12@0+ (1,0) [0|0] "" NEO
BO_ 384 ASCMLKASteeringCmd: 4 NEO
SG_ RollingCounter : 5|2@0+ (1,0) [0|0] "" NEO
SG_ LKASteeringCmdChecksum : 19|12@0+ (1,0) [0|0] "" NEO
SG_ LKASteeringCmdActive : 3|1@0+ (1,0) [0|0] "" NEO
SG_ LKASteeringCmd : 2|11@0+ (1,0) [0|0] "" NEO
BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM
SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX
SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX
SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX
SG_ ACCSpeedSetpoint : 19|12@0+ (1,0) [0|0] "km/h" NEO
SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO
SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO
SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO
BO_ 1930 ASCM_78A: 7 K124_ASCM
BO_ 1296 ASCM_510: 4 K124_ASCM
BO_ 1034 ASCM_40A: 7 K124_ASCM
BO_ 869 ASCM_365: 4 K124_ASCM
BO_ 717 ASCM_2CD: 5 K124_ASCM
BO_ 1033 ASCMKeepAlive: 7 NEO
SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO
BO_ 485 PSCMSteeringAngle: 8 K43_PSCM
SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-540|540] "deg" NEO
SG_ SteeringWheelRate : 27|12@0- (0.5,0) [-100|100] "deg/s" NEO
BO_ 388 PSCMStatus: 8 K43_PSCM
SG_ HandsOffSWDetectionMode : 20|2@0+ (1,0) [0|3] "" NEO
SG_ HandsOffSWlDetectionStatus : 21|1@0+ (1,0) [0|1] "" NEO
SG_ LKATorqueDeliveredStatus : 5|3@0+ (1,0) [0|7] "" NEO
SG_ LKADriverAppldTrq : 50|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO
SG_ LKATotalTorqueDelivered : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO
BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM
SG_ YawRate : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO
SG_ LateralAcceleration : 3|12@0- (0.0161,0) [-2047|2047] "m/s2" NEO
SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO
BO_ 189 EBCMRegenPaddle: 7 K17_EBCM
SG_ RegenPaddle : 7|4@0+ (1,0) [0|0] "" NEO
BO_ 190 ECMAcceleratorPos: 6 K20_ECM
SG_ AcceleratorPos : 23|8@0+ (1,0) [0|0] "" NEO
BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM
SG_ GasRegenAlwaysOne2 : 9|1@0+ (1,1) [1|1] "" NEO
SG_ GasRegenAlwaysOne : 14|1@0+ (1,1) [1|1] "" NEO
SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO
SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO
SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO
SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO
SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO
SG_ GasRegenCmd : 23|16@0+ (1,0) [0|0] "" NEO
BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM
SG_ FLWheelSpd : 7|16@0+ (0.0305,0) [0|255] "km/h" NEO
SG_ FRWheelSpd : 23|16@0+ (0.0305,0) [0|255] "km/h" NEO
BO_ 842 EBCMWheelSpdRear: 4 K17_EBCM
SG_ RLWheelSpd : 7|16@0+ (0.0305,0) [0|255] "km/h" NEO
SG_ RRWheelSpd : 23|16@0+ (0.0305,0) [0|255] "km/h" NEO
BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM
SG_ BrakePedalPosition : 15|8@0+ (0.392157,0) [0|255] "%" NEO
BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM
SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO
SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO
BO_TX_BU_ 384 : K124_ASCM,NEO;
BO_TX_BU_ 880 : NEO,K124_ASCM;
BO_TX_BU_ 1033 : K124_ASCM,NEO;
BO_TX_BU_ 715 : NEO,K124_ASCM;
CM_ BU_ K16_BECM "Battery Energy Control Module";
CM_ BU_ K73_TCIC "Telematics Communication Control Module";
CM_ BU_ K9_BCM "Body Control Module";
CM_ BU_ K43_PSCM "Power Steering Control Module";
CM_ BU_ K17_EBCM "Electronic Brake Control Module";
CM_ BU_ K20_ECM "Engine Control Module";
CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module";
CM_ BU_ NEO "Comma NEO";
CM_ BU_ K124_ASCM "Active Safety Control Module";
CM_ SG_ 381 MSG17D_AccPower "Need to investigate";
BA_DEF_ "UseGMParameterIDs" INT 0 0;
BA_DEF_ "ProtocolType" STRING ;
BA_DEF_ "BusType" STRING ;
BA_DEF_DEF_ "UseGMParameterIDs" 1;
BA_DEF_DEF_ "ProtocolType" "GMLAN";
BA_DEF_DEF_ "BusType" "";
BA_ "BusType" "CAN";
BA_ "ProtocolType" "GMLAN";
BA_ "UseGMParameterIDs" 0;
VAL_ 481 ACCGapButton 1 "Active" 0 "Inactive" ;
VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ;
VAL_ 481 ACCCancelButton 1 "Active" 0 "Inactive" ;
VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ;
VAL_ 298 DriverDoorStatus 1 "Opened" 0 "Closed" ;
VAL_ 384 LKASteeringCmdActive 1 "Active" 0 "Inactive" ;
VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ;
VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ;
VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ;
VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ;
VAL_ 388 HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ;
VAL_ 388 HandsOffSWlDetectionStatus 1 "Hands On" 0 "Hands Off" ;
VAL_ 388 LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ;
VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ;
VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ;
VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ;

@ -0,0 +1,396 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" NEO
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO
BO_ 145 XXX_2: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 316 GAS_PEDAL: 8 PCM
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ZEROS_BOH : 23|16@0+ (1,0) [0|15000] "" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 398 XXX_3: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX
BO_ 401 GEARBOX: 8 PCM
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO
SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 422 SCM_BUTTONS: 8 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 426 XXX_4: 8 VSA
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 476 XXX_5: 4 XXX
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX
BO_ 487 XXX_6: 4 VSA
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM
SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM
SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM
SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
BO_ 507 XXX_7: 1 XXX
BO_ 542 XXX_8: 7 XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
BO_ 545 XXX_9: 6 SCM
SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX
BO_ 660 SCM_COMMANDS: 8 SCM
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX
BO_ 661 XXX_10: 4 XXX
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX
BO_ 662 CRUISE_BUTTONS: 4 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" XXX
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 777 XXX_11: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 780 ACC_HUD: 8 ADAS
SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY
BO_ 800 XXX_12: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 804 CRUISE: 8 PCM
SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO
SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 808 XXX_13: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
BO_ 871 XXX_14: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 882 XXX_15: 2 XXX
SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX
BO_ 884 XXX_16: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 891 XXX_17: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 918 XXX_18: 7 XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
BO_ 923 XXX_19: 2 XXX
SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX
BO_ 927 ACC_HUD_2: 8 ADAS
SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY
SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY
SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY
SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY
SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY
SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 929 XXX_20: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 983 XXX_21: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 985 XXX_22: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX
BO_ 1024 XXX_23: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1027 XXX_24: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 1036 XXX_25: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1039 XXX_26: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1057 XXX_27: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1064 XXX_28: 7 XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
BO_ 1088 XXX_29: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1089 XXX_30: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1108 XXX_31: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1125 XXX_32: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1296 XXX_33: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" XXX
BO_ 1365 XXX_34: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1424 XXX_35: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1600 XXX_36: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1601 XXX_37: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1633 XXX_38: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_TX_BU_ 506 : NEO,ADAS;
BO_TX_BU_ 780 : NEO,ADAS;
BO_TX_BU_ 829 : NEO,ADAS;
BO_TX_BU_ 927 : NEO,ADAS;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,463 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: EBCM NEO CAM RADAR PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" NEO
BO_ 148 XXX_2: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 228 STEERING_CONTROL: 5 NEO
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
BO_ 232 XXX_3: 7 XXX
SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
BO_ 304 GAS_PEDAL: 8 PCM
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 330 STEERING_SENSORS: 8 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO
SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO
SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 340 XXX_4: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 401 GEARBOX: 8 PCM
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO
SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX
SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX
SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 427 XXX_5: 3 VSA
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 428 XXX_6: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 432 STANDSTILL: 7 VSA
SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 441 XXX_7: 5 VSA
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 446 XXX_7: 3 VSA
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB
SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO
SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 470 XXX_8: 2 XXX
SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX
BO_ 474 XXX_9: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 476 XXX_9: 7 XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 477 XXX_10: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 479 ACC_CONTROL: 8 NEO
SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM
SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX
SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX
SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM
SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX
SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 490 XXX_11: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 493 XXX_12: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 32|4@1+ (1,0) [0|15] "" XXX
BO_ 495 ACC_CONTROL_ON: 8 XXX
SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX
SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
BO_ 506 XXX_13: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 545 XXX_14: 6 SCM
SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX
SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 662 CRUISE_BUTTONS: 4 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 777 CAR_SPEED: 8 PCM
SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX
SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX
SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX
SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ BOH : 55|2@0+ (1,0) [0|255] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 780 ACC_HUD: 8 ADAS
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY
SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY
SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX
SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX
SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 795 XXX_15: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 800 XXX_16: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 804 TRIP: 8 PCM
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 806 SCM_FEEDBACK: 8 SCM
SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO
SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO
SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 808 XXX_17: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 814 XXX_18: 4 XXX
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 829 LKAS_HUD_2: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ ZEROS_BOH : 6|6@0+ (1,0) [0|63] "" XXX
SG_ SET_TO_1 : 0|1@0+ (1,0) [0|1] "" XXX
SG_ BOH_2 : 15|1@0+ (1,0) [0|1] "" XXX
SG_ SET_TO_ZERO : 20|3@0+ (1,0) [0|7] "" XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
BO_ 862 CAMERA_MESSAGES: 8 CAM
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 884 STALK_STATUS_1: 8 XXX
SG_ LIGHT_SWITCH_AUTO : 46|1@0+ (1,0) [0|1] "" XXX
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" XXX
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" XXX
SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 891 STALK_STATUS_2: 8 XXX
SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX
SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX
SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" NEO
BO_ 927 RADAR_HUD: 8 RADAR
SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY
SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY
SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX
SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY
SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY
SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 929 XXX_23: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 985 XXX_24: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 1024 XXX_25: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1027 XXX_26: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 1036 XXX_27: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1039 XXX_28: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1108 XXX_29: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1302 XXX_30: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1322 XXX_31: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1361 XXX_32: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1365 XXX_33: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1424 XXX_34: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1600 XXX_35: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1601 XXX_36: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1618 XXX_37: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1633 XXX_38: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1670 XXX_39: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
CM_ SG_ 344 DISTANCE_COUNTER "";
CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off";
CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled";
CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied";
CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas";
CM_ SG_ 479 ZEROS_BOH "Signed value, negative when braking, positive when applying gas";
CM_ SG_ 780 HUD_LEAD "0: blank, 1: no car, 2: car, 3: ACC Off";
CM_ SG_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
CM_ SG_ 806 CMBS_STATES "3: Pressed, 2: On, 0: Off";
CM_ SG_ 884 WIPER_SWITCH "0 = PARKED, 1 = INTERMITTENT, 2 = LOW, 3 = HIGH/QUICK WIPE";
CM_ SG_ 891 HIGH_BEAMS "FLASH TO PASS OR FULL ON";
CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,435 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO
BO_ 148 XXX_2: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO
SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
BO_ 228 STEERING_CONTROL: 5 ADAS
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
BO_ 304 GAS_PEDAL2: 8 PCM
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 330 STEERING_SENSORS: 8 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO
SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO
SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ TRIP_DISTANCE : 55|8@0+ (0.010588,0) [0|255] "km" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 401 GEARBOX: 8 PCM
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO
SG_ GEAR : 43|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 427 XXX_3: 3 VSA
SG_ CHECKSUM : 19|4@0+ (1,0) [0|6] "" NEO
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO
BO_ 428 XXX_4: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 432 STANDSTILL: 7 VSA
SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 450 XXX_5: 8 EPB
SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO
SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 470 XXX_6: 2 VSA
SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 8|4@0+ (1,0) [0|3] "" NEO
BO_ 476 XXX_7: 7 XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
BO_ 487 XXX_8: 4 VSA
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 493 XXX_9: 5 VSA
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM
SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM
SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM
SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM
BO_ 512 GAS_COMMAND: 3 NEO
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 5 INTERCEPTOR
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
BO_ 545 XXX_10: 6 XXX
SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" NEO
SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|6] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
BO_ 662 CRUISE_BUTTONS: 4 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" NEO
SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 777 XXX_11: 8 XXX
SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" NEO
SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 780 ACC_HUD: 8 ADAS
SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 795 XXX_12: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 800 XXX_13: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 804 CRUISE: 8 PCM
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 806 SCM_FEEDBACK: 8 SCM
SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" NEO
SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO
SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO
SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 808 XXX_14: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 829 LKAS_HUD_2: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY
BO_ 862 XXX_15: 8 ADAS
SG_ UI_ALERTS : 7|56@0+ (1,0) [0|127] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 884 STALK_STATUS: 8 XXX
SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" NEO
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" NEO
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" NEO
SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
BO_ 891 XXX_17: 8 XXX
SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
BO_ 927 XXX_19: 8 ADAS
SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY
SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY
SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY
SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY
SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY
SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 929 XXX_20: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 985 XXX_21: 3 XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO
BO_ 1024 XXX_22: 5 XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
BO_ 1027 XXX_23: 5 XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1036 XXX_24: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1039 XXX_25: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1108 XXX_26: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1302 XXX_27: 8 XXX
SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1322 XXX_28: 5 XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
BO_ 1361 XXX_29: 5 XXX
BO_ 1365 XXX_30: 5 XXX
BO_ 1424 XXX_31: 5 XXX
BO_ 1600 XXX_32: 5 XXX
BO_ 1601 XXX_33: 8 XXX
BO_ 1633 XXX_34: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_TX_BU_ 228 : NEO,ADAS;
BO_TX_BU_ 506 : NEO,ADAS;
BO_TX_BU_ 780 : NEO,ADAS;
BO_TX_BU_ 829 : NEO,ADAS;
BO_TX_BU_ 862 : NEO,ADAS;
BO_TX_BU_ 927 : NEO,ADAS;
CM_ SG_ 401 GEAR "10 = reverse, 11 = transition";
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light";
CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light";
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc...";
CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights";
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ;
VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ;
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
VAL_ 545 ECON_ON_2 0 "off" 3 "on" ;
VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ;
CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,423 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: EBCM NEO CAM RADAR PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" NEO
BO_ 148 XXX_2: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 228 STEERING_CONTROL: 5 NEO
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
BO_ 232 BRAKE_HOLD: 7 XXX
SG_ XMISSION_SPEED3 : 7|14@0- (1,0) [1|0] "" XXX
SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX
SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX
SG_ SET_TO_1 : 9|2@0- (1,0) [1|0] "" XXX
SG_ ZEROS_BOH2 : 28|5@0+ (1,0) [0|31] "" XXX
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
BO_ 304 GAS_PEDAL: 8 PCM
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 330 STEERING_SENSORS: 8 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO
SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO
SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 340 XXX_4: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 401 GEARBOX: 8 PCM
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO
SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX
SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX
SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ USER_BRAKE : 7|16@0+ (0.015625,-103) [0|1000] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 427 XXX_5: 3 VSA
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 441 XXX_6: 5 VSA
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 446 XXX_7: 3 VSA
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB
SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO
SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 474 XXX_9: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 477 XXX_10: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 479 ACC_CONTROL: 8 NEO
SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM
SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX
SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX
SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM
SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX
SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 490 XXX_12: 8 XXX
SG_ BOH : 7|32@0+ (1,0) [0|65535] "" XXX
SG_ BOH_2 : 23|16@0+ (1,0) [0|65535] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 495 ACC_CONTROL_ON: 8 XXX
SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX
SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX
SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
BO_ 545 XXX_14: 6 SCM
SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ WHEEL_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
BO_ 662 CRUISE_BUTTONS: 4 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 777 CAR_SPEED: 8 PCM
SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX
SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX
SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX
SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ BOH : 55|2@0+ (1,0) [0|255] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 780 ACC_HUD: 8 ADAS
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY
SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY
SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX
SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX
SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 800 XXX_16: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 804 TRIP: 8 PCM
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_TEMPERATURE : 0|8@0+ (1,0) [0|65535] "" XXX
SG_ BOH_2 : 32|23@0+ (1,0) [0|255] "" NEO
SG_ BOH : 15|8@0+ (1,0) [0|255] "" XXX
SG_ BOOLEAN : 55|1@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 806 SCM_FEEDBACK: 8 SCM
SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO
SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO
SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 808 XXX_17: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 814 XXX_18: 4 XXX
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 829 LKAS_HUD_2: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ ZEROS_BOH : 6|6@0+ (1,0) [0|63] "" XXX
SG_ SET_TO_1 : 0|1@0+ (1,0) [0|1] "" XXX
SG_ BOH_2 : 15|1@0+ (1,0) [0|1] "" XXX
SG_ SET_TO_ZERO : 20|3@0+ (1,0) [0|7] "" XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
BO_ 862 CAMERA_MESSAGES: 8 CAM
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
SG_ ZEROS_BOH_2 : 48|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 884 XXX_20: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 891 XXX_21: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 927 RADAR_HUD: 8 RADAR
SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY
SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY
SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX
SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY
SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY
SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 929 XXX_23: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 985 XXX_24: 3 XXX
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
BO_ 1024 XXX_25: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1027 XXX_26: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 1036 XXX_27: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1039 XXX_28: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1108 XXX_29: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1302 XXX_30: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1322 XXX_31: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1361 XXX_32: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1365 XXX_33: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1424 XXX_34: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1600 XXX_35: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1601 XXX_36: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1618 XXX_37: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
BO_ 1633 XXX_38: 8 XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 1670 XXX_39: 5 XXX
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX
CM_ SG_ 344 DISTANCE_COUNTER "";
CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off";
CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled";
CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied";
CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas";
CM_ SG_ 479 ZEROS_BOH "Signed value, negative when braking, positive when applying gas";
CM_ SG_ 780 HUD_LEAD "0: blank, 1: no car, 2: car, 3: ACC Off";
CM_ SG_ 806 CMBS_STATES "3: Pressed, 2: On, 0: Off";
CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,312 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB
BO_ 57 XXX_1: 3 XXX
BO_ 145 XXX_2: 8 XXX
BO_ 316 XXX_3: 8 PCM
BO_ 340 XXX_4: 8 PCM
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 398 XXX_5: 3 PCM
BO_ 399 STEER_STATUS: 6 EPS
SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO
SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 401 GEARBOX: 8 PCM
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO
SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 404 STEERING_CONTROL: 4 NEO
SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS
SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS
SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 422 SCM_BUTTONS: 8 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 426 XXX_6: 8 VSA
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 474 XXX_7: 5 VSA
BO_ 476 XXX_8: 5 XXX
BO_ 487 XXX_9: 4 VSA
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO
SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 493 XXX_10: 3 VSA
BO_ 506 BRAKE_COMMAND: 8 NEO
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM
SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM
SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM
SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
BO_ 507 XXX_11: 1 NEO
BO_ 542 XXX_12: 7 XXX
BO_ 545 XXX_13: 4 XXX
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" NEO
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 660 SCM_COMMANDS: 8 SCM
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 661 XXX_14: 4 XXX
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO
BO_ 777 XXX_15: 8 XXX
BO_ 780 ACC_HUD: 8 CAM
SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY
BO_ 800 XXX_16: 8 XXX
BO_ 804 CRUISE: 8 PCM
SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO
SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 808 XXX_17: 8 XXX
BO_ 829 LKAS_HUD_2: 5 CAM
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
BO_ 882 XXX_18: 2 XXX
BO_ 884 XXX_19: 7 XXX
BO_ 888 XXX_20: 8 XXX
BO_ 891 XXX_21: 8 XXX
BO_ 923 XXX_23: 2 XXX
BO_ 929 XXX_24: 8 XXX
BO_ 983 XXX_25: 8 XXX
BO_ 985 XXX_26: 3 XXX
BO_ 1024 XXX_27: 5 XXX
BO_ 1027 XXX_28: 5 XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO
BO_ 1033 XXX_29: 5 XXX
BO_ 1036 XXX_30: 8 XXX
BO_ 1039 XXX_31: 8 XXX
BO_ 1057 XXX_32: 5 XXX
BO_ 1064 XXX_32: 7 XXX
BO_ 1108 XXX_33: 8 XXX
BO_ 1125 XXX_34: 8 XXX
BO_ 1296 XXX_35: 8 XXX
BO_ 1365 XXX_36: 5 XXX
BO_ 1424 XXX_37: 5 XXX
BO_ 1600 XXX_38: 5 XXX
BO_ 1601 XXX_39: 8 XXX
BO_TX_BU_ 399 : NEO,CAM;
BO_TX_BU_ 506 : NEO,CAM;
BO_TX_BU_ 780 : NEO,CAM;
BO_TX_BU_ 829 : NEO,CAM;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,386 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: EBCM EON CAM PCM EPS VSA SCM BDY XXX
BO_ 57 XXX_1: 3 XXX
BO_ 148 XXX_2: 8 XXX
BO_ 228 STEERING_CONTROL: 5 CAM
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS
BO_ 229 XXX_3: 4 XXX
BO_ 316 GAS_PEDAL: 8 PCM
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
BO_ 411 XXX_4: 5 XXX
BO_ 419 GEARBOX: 8 PCM
SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON
SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX
SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX
BO_ 427 XXX_5: 3 XXX
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
BO_ 450 XXX_6: 8 XXX
SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX
SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX
SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
BO_ 463 XXX_7: 8 XXX
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 476 XXX_8: 4 XXX
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON
BO_ 506 BRAKE_COMMAND: 8 CAM
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM
SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM
BO_ 542 XXX_9: 7 XXX
BO_ 545 XXX_10: 4 XXX
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" EON
BO_ 662 CRUISE_BUTTONS: 4 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
BO_ 777 XXX_11: 8 XXX
BO_ 780 ACC_HUD: 8 CAM
SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 795 XXX_12: 8 XXX
BO_ 800 XXX_13: 8 XXX
BO_ 804 CRUISE: 8 PCM
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 806 SCM_FEEDBACK: 8 SCM
SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON
SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON
SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON
SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON
SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 808 XXX_14: 8 XXX
BO_ 817 XXX_15: 4 XXX
BO_ 819 XXX_16: 7 XXX
BO_ 821 XXX_17: 5 XXX
BO_ 825 XXX_18: 4 XXX
BO_ 829 LKAS_HUD: 5 CAM
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY
BO_ 837 XXX_19: 5 XXX
BO_ 856 XXX_20: 7 XXX
BO_ 862 XXX_21: 8 CAM
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
BO_ 871 XXX_22: 8 XXX
BO_ 881 XXX_23: 8 XXX
BO_ 882 XXX_24: 4 XXX
BO_ 884 XXX_25: 8 XXX
BO_ 891 XXX_26: 8 XXX
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
BO_ 905 XXX_27: 8 XXX
BO_ 923 XXX_28: 2 XXX
BO_ 927 ACC_HUD_2: 8 CAM
SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY
SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY
SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY
SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY
SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY
SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 929 XXX_29: 8 XXX
BO_ 963 XXX_30: 8 XXX
BO_ 965 XXX_31: 8 XXX
BO_ 966 XXX_32: 8 XXX
BO_ 967 XXX_33: 8 XXX
BO_ 983 XXX_34: 8 XXX
BO_ 985 XXX_35: 3 XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON
SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 1036 XXX_36: 8 XXX
BO_ 1052 XXX_37: 8 XXX
BO_ 1064 XXX_38: 7 XXX
BO_ 1088 XXX_39: 8 XXX
BO_ 1089 XXX_40: 8 XXX
BO_ 1092 XXX_41: 1 XXX
BO_ 1108 XXX_42: 8 XXX
BO_ 1110 XXX_43: 8 XXX
BO_ 1125 XXX_44: 8 XXX
BO_ 1296 XXX_45: 8 XXX
BO_ 1302 XXX_46: 8 XXX
BO_ 1600 XXX_47: 5 XXX
BO_ 1601 XXX_48: 8 XXX
BO_ 1612 XXX_49: 5 XXX
BO_ 1613 XXX_50: 5 XXX
BO_ 1614 XXX_51: 5 XXX
BO_ 1615 XXX_52: 8 XXX
BO_ 1616 XXX_53: 5 XXX
BO_ 1619 XXX_54: 5 XXX
BO_ 1623 XXX_55: 5 XXX
BO_ 1668 XXX_56: 5 XXX
BO_TX_BU_ 228 : EON,CAM;
BO_TX_BU_ 506 : EON,CAM;
BO_TX_BU_ 780 : EON,CAM;
BO_TX_BU_ 829 : EON,CAM;
BO_TX_BU_ 862 : EON,CAM;
BO_TX_BU_ 927 : EON,CAM;
CM_ SG_ 419 GEAR "10 = reverse, 11 = transition";
CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged";
CM_ SG_ 450 EPB_STATE "3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged"";
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc...";
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,322 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX
BO_ 57 XXX_1: 3 XXX
BO_ 145 XXX_2: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO
BO_ 228 STEERING_CONTROL: 5 ADAS
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS
BO_ 304 GAS_PEDAL2: 8 PCM
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
BO_ 316 GAS_PEDAL: 8 PCM
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO
BO_ 342 STEERING_SENSORS: 6 EPS
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO
BO_ 344 POWERTRAIN_DATA: 8 PCM
SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX
BO_ 380 POWERTRAIN_DATA2: 8 PCM
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 398 XXX_3: 3 XXX
BO_ 399 STEER_STATUS: 7 EPS
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 419 GEARBOX: 8 PCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" NEO
SG_ GEAR : 7|8@0+ (1,0) [0|255] "" NEO
BO_ 420 VSA_STATUS: 8 VSA
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 422 SCM_BUTTONS: 8 SCM
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 428 XXX_4: 8 XXX
BO_ 432 STANDSTILL: 7 VSA
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 464 WHEEL_SPEEDS: 8 VSA
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 476 XXX_5: 4 XXX
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO
BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM
SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM
BO_ 512 GAS_COMMAND: 3 NEO
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR
SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 5 INTERCEPTOR
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO
BO_ 542 XXX_6: 7 XXX
BO_ 545 XXX_7: 4 XXX
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO
SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO
BO_ 660 SCM_COMMANDS: 8 SCM
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO
BO_ 773 SEATBELT_STATUS: 7 BDY
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO
BO_ 777 XXX_8: 8 XXX
BO_ 780 ACC_HUD: 8 ADAS
SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY
SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY
SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
BO_ 800 XXX_9: 8 XXX
BO_ 804 CRUISE: 8 PCM
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 808 XXX_10: 8 XXX
BO_ 819 XXX_11: 7 XXX
BO_ 821 XXX_12: 5 XXX
BO_ 829 LKAS_HUD_2: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY
BO_ 882 XXX_13: 2 XXX
BO_ 884 XXX_14: 7 XXX
BO_ 887 XXX_15: 8 XXX
BO_ 888 XXX_16: 8 XXX
BO_ 892 CRUISE_PARAMS: 8 PCM
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO
BO_ 923 XXX_18: 2 XXX
BO_ 929 XXX_19: 4 XXX
BO_ 983 XXX_20: 8 XXX
BO_ 985 XXX_21: 3 XXX
BO_ 1024 XXX_22: 5 XXX
BO_ 1027 XXX_23: 5 XXX
BO_ 1029 DOORS_STATUS: 8 BDY
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO
BO_ 1030 XXX_24: 5 VSA
BO_ 1034 XXX_25: 5 XXX
BO_ 1036 XXX_26: 8 XXX
BO_ 1039 XXX_27: 8 XXX
BO_ 1057 XXX_28: 5 EPS
BO_ 1064 XXX_29: 7 XXX
BO_ 1108 XXX_30: 8 XXX
BO_ 1365 XXX_31: 5 XXX
BO_ 1600 XXX_32: 5 XXX
BO_ 1601 XXX_33: 8 XXX
BO_TX_BU_ 228 : NEO,ADAS;
BO_TX_BU_ 506 : NEO,ADAS;
BO_TX_BU_ 780 : NEO,ADAS;
BO_TX_BU_ 829 : NEO,ADAS;
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc...";
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ;
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ;
VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,549 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX
BO_ 128 EMS_DCT1: 8 XXX
SG_ PV_AV_CAN : 0|8@1+ (0.3906,0) [0|99.603] "%" XXX
SG_ TQ_STND : 8|6@1+ (10,0) [0|630] "Nm" XXX
SG_ F_N_ENG : 14|1@1+ (1,0) [0|1] "" XXX
SG_ F_SUB_TQI : 15|1@1+ (1,0) [0|1] "" XXX
SG_ N : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX
SG_ TQI_ACOR : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQI : 48|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ CF_Ems_Alive : 56|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Ems_ChkSum : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 129 EMS_DCT2: 8 XXX
SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5,0) [0|315] "Min" XXX
SG_ BRAKE_ACT : 6|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Ems_EngOperStat : 8|8@1+ (1,0) [0|255] "" XXX
SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "" XXX
SG_ CF_Ems_Alive2 : 56|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Ems_ChkSum2 : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 160 EngFrzFrm1: 8 XXX
SG_ PID_04h : 0|8@1+ (0.392157,0) [0|100] "%" XXX
SG_ PID_05h : 8|8@1+ (1,-40) [-40|215] "" XXX
SG_ PID_0Ch : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX
SG_ PID_0Dh : 32|8@1+ (1,0) [0|255] "km/h" XXX
SG_ PID_11h : 40|8@1+ (0.392157,0) [0|100] "%" XXX
SG_ PID_03h : 48|16@1+ (1,0) [0|65535] "" XXX
BO_ 161 EngFrzFrm2: 8 XXX
SG_ PID_06h : 0|8@1+ (0.78125,-100) [-100|99.22] "%" XXX
SG_ PID_07h : 8|8@1+ (0.78125,-100) [-100|99.22] "%" XXX
SG_ PID_08h : 16|8@1+ (0.78125,-100) [-100|99.22] "%" XXX
SG_ PID_09h : 24|8@1+ (0.78125,-100) [-100|99.22] "%" XXX
SG_ PID_0Bh : 32|8@1+ (1,0) [0|255] "kPa" XXX
SG_ PID_23h : 40|16@1+ (10,0) [0|655350] "kPa" XXX
BO_ 304 YRS1: 8 XXX
SG_ CR_Yrs_Yr : 0|16@1+ (0.005,-163.84) [-163.84|163.83] "" XXX
SG_ CF_Yrs_SnsStat1 : 16|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Yrs_YrStat : 20|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Yrs_LatAc : 32|16@1+ (0.000127465,-4.17677) [-4.17677|4.17652] "g" XXX
SG_ CR_Yrs_MsgCnt1 : 48|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Yrs_LatAcStat1 : 52|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Yrs_Crc1 : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 305 YRS3: 8 XXX
SG_ CR_Yrs_YawAcc : 0|16@1+ (0.125,-4096) [-4096|4095.75] "" XXX
SG_ CF_Yrs_YawAccStat : 20|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Yrs_Ax : 32|16@1+ (0.000127465,-4.17677) [-4.17677|4.17652] "g" XXX
SG_ CR_Yrs_MsgCnt3 : 48|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Yrs_AxStat : 52|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Yrs_Crc3 : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 320 YRS2: 8 XXX
SG_ CF_Yrs_McuStat : 0|8@1+ (1,0) [0|255] "" XXX
SG_ CF_Yrs_SnsStat2 : 8|8@1+ (1,0) [0|255] "" XXX
SG_ CF_Yrs_ExtSysStat : 32|8@1+ (1,0) [0|255] "" XXX
SG_ CR_Yrs_Diag : 40|8@1+ (1,0) [0|255] "" XXX
SG_ CR_Yrs_MsgCnt2 : 48|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Yrs_Type : 52|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Yrs_Crc2 : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 339 TCS1: 8 XXX
SG_ TCS_REQ : 0|1@1+ (1,0) [0|1] "" XXX
SG_ MSR_C_REQ : 1|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_PAS : 2|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_GSC : 3|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Esc_LimoInfo : 4|2@1+ (1,0) [0|3] "" XXX
SG_ ABS_DIAG : 6|1@1+ (1,0) [0|1] "" XXX
SG_ ABS_DEF : 7|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_DEF : 8|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_CTL : 9|1@1+ (1,0) [0|1] "" XXX
SG_ ABS_ACT : 10|1@1+ (1,0) [0|1] "" XXX
SG_ EBD_DEF : 11|1@1+ (1,0) [0|1] "" XXX
SG_ ESP_PAS : 12|1@1+ (1,0) [0|1] "" XXX
SG_ ESP_DEF : 13|1@1+ (1,0) [0|1] "" XXX
SG_ ESP_CTL : 14|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_MFRN : 15|1@1+ (1,0) [0|1] "" XXX
SG_ DBC_CTL : 16|1@1+ (1,0) [0|1] "" XXX
SG_ DBC_PAS : 17|1@1+ (1,0) [0|1] "" XXX
SG_ DBC_DEF : 18|1@1+ (1,0) [0|1] "" XXX
SG_ HAC_CTL : 19|1@1+ (1,0) [0|1] "" XXX
SG_ HAC_PAS : 20|1@1+ (1,0) [0|1] "" XXX
SG_ HAC_DEF : 21|1@1+ (1,0) [0|1] "" XXX
SG_ ESS_STAT : 22|2@1+ (1,0) [0|3] "" XXX
SG_ TQI_TCS : 24|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQI_MSR : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ CF_Esc_BrkCtl : 48|1@1+ (1,0) [0|1] "" XXX
SG_ ESC_OFF_STEP : 49|2@1+ (1,0) [0|3] "" XXX
SG_ _4WD_Status : 51|1@1+ (1,0) [0|1] "" XXX
SG_ AliveCounter_TCS1 : 52|4@1+ (1,0) [0|1] "" XXX
SG_ CheckSum_TCS1 : 56|8@1+ (1,0) [0|1] "" XXX
BO_ 356 VSM1: 8 XXX
SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" XXX
SG_ CF_Esc_Act : 12|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Esc_CtrMode : 13|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Esc_Def : 16|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Esc_AliveCnt : 48|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Esc_Chksum : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 357 VSM2: 8 XXX
SG_ CR_Mdps_StrTq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" XXX
SG_ CR_Mdps_OutTq : 12|12@1+ (0.1,-204.8) [-204.8|204.7] "" XXX
SG_ CF_Mdps_Def : 24|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Mdps_SErr : 25|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Mdps_AliveCnt : 48|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Mdps_Chksum : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 399 EMS_H2: 8 XXX
SG_ R_TqAcnApvC : 0|8@1+ (0.2,0) [0|51] "Nm" XXX
SG_ R_PAcnC : 8|8@1+ (125,0) [0|31875] "hPa" XXX
SG_ TQI_B : 16|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ SLD_VS : 24|8@1+ (1,0) [0|255] "km/h" XXX
SG_ CF_CdaStat : 32|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Ems_IsgStat : 35|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Ems_OilChg : 38|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1,0) [0|1] "" XXX
SG_ R_NEngIdlTgC : 40|8@1+ (10,0) [0|2550] "rpm" XXX
SG_ CF_Ems_UpTarGr : 48|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_DownTarGr : 49|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_DesCurGr : 50|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Ems_SldAct : 54|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_SldPosAct : 55|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_HPresStat : 56|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_IsgBuz : 57|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_FCopen : 59|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_ActEcoAct : 60|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_EngRunNorm : 61|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_IsgStat2 : 62|2@1+ (2,0) [0|3] "" XXX
BO_ 497 TCS5: 8 XXX
SG_ ABS_W_LAMP : 0|1@1+ (1,0) [0|1] "" XXX
SG_ EBD_W_LAMP : 1|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_OFF_LAMP : 2|1@1+ (1,0) [0|1] "" XXX
SG_ TCS_LAMP : 3|2@1+ (1,0) [0|3] "" XXX
SG_ DBC_W_LAMP : 5|1@1+ (1,0) [0|1] "" XXX
SG_ DBC_F_LAMP : 6|2@1+ (1,0) [0|3] "" XXX
SG_ ODOMETER_LEFT : 8|4@1+ (1,0) [0|15] "m" XXX
SG_ ODOMETER_RIGHT : 12|4@1+ (1,0) [0|15] "m" XXX
SG_ WHEEL_FL : 16|12@1+ (0.125,0) [0|511.875] "km/h" XXX
SG_ WHEEL_FR : 28|12@1+ (0.125,0) [0|511.875] "km/h" XXX
SG_ WHEEL_RL : 40|12@1+ (0.125,0) [0|511.875] "km/h" XXX
SG_ WHEEL_RR : 52|12@1+ (0.125,0) [0|511.875] "km/h" XXX
BO_ 544 ESP2: 8 XXX
SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" XXX
SG_ ESP2_AliveCounter_LSB : 11|3@1+ (1,0) [0|7] "" XXX
SG_ LAT_ACCEL_STAT : 14|1@1+ (1,0) [0|1] "" XXX
SG_ LAT_ACCEL_DIAG : 15|1@1+ (1,0) [0|1] "" XXX
SG_ LONG_ACCEL : 16|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" XXX
SG_ ESP2_AliveCounter_MSB : 27|1@1+ (1,0) [0|1] "" XXX
SG_ ESP2_Checksum_LSB : 28|2@1+ (1,0) [0|3] "" XXX
SG_ LONG_ACCEL_STAT : 30|1@1+ (1,0) [0|1] "" XXX
SG_ LONG_ACCEL_DIAG : 31|1@1+ (1,0) [0|1] "" XXX
SG_ CYL_PRES : 32|12@1+ (0.1,0) [0|409.5] "Bar" XXX
SG_ ESP12_Checksum_MSB : 44|2@1+ (1,0) [0|3] "" XXX
SG_ CYL_PRES_STAT : 46|1@1+ (1,0) [0|1] "" XXX
SG_ CYL_PRESS_DIAG : 47|1@1+ (1,0) [0|1] "" XXX
SG_ YAW_RATE : 48|13@1+ (0.01,-40.95) [-40.95|40.96] "" XXX
SG_ CYL_PRES_FLAG : 61|1@1+ (1,0) [0|1] "" XXX
SG_ YAW_RATE_STAT : 62|1@1+ (1,0) [0|1] "" XXX
SG_ YAW_RATE_DIAG : 63|1@1+ (1,0) [0|1] "" XXX
BO_ 608 EMS6: 8 XXX
SG_ TQI_MIN : 0|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQI : 8|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQI_TARGET : 16|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ GLOW_STAT : 24|1@1+ (1,0) [0|1] "" XXX
SG_ CRUISE_LAMP_M : 25|1@1+ (1,0) [0|1] "" XXX
SG_ CRUISE_LAMP_S : 26|1@1+ (1,0) [0|1] "" XXX
SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1,0) [0|1] "" XXX
SG_ ENG_STAT : 28|3@1+ (1,0) [0|7] "" XXX
SG_ SOAK_TIME_ERROR : 31|1@1+ (1,0) [0|1] "" XXX
SG_ SOAK_TIME : 32|8@1+ (1,0) [0|255] "Min" XXX
SG_ TQI_MAX : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60] "" XXX
SG_ Checksum : 56|4@1+ (1,0) [0|15] "" XXX
SG_ AliveCounter : 60|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Ems_AclAct : 62|2@1+ (1,0) [0|3] "" XXX
BO_ 672 EMS5: 8 XXX
SG_ ECGPOvrd : 0|1@1+ (1,0) [0|1] "" XXX
SG_ QECACC : 1|1@1+ (1,0) [0|1] "" XXX
SG_ ECFail : 2|1@1+ (1,0) [0|1] "" XXX
SG_ SwitchOffCondExt : 3|1@1+ (1,0) [0|1] "" XXX
SG_ BLECFail : 4|1@1+ (1,0) [0|1] "" XXX
SG_ AliveCounter : 5|2@1+ (1,0) [0|3] "" XXX
SG_ Byte0Parity : 7|1@1+ (1,0) [0|1] "" XXX
SG_ FA_PV_CAN : 8|8@1+ (0.3906,0) [0|99.2] "%" XXX
SG_ IntAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "" XXX
SG_ STATE_DC_OBD : 24|7@1+ (1,0) [0|127] "" XXX
SG_ INH_DC_OBD : 31|1@1+ (1,0) [0|1] "" XXX
SG_ CTR_IG_CYC_OBD : 32|16@1+ (1,0) [0|65535] "" XXX
SG_ CTR_CDN_OBD : 48|16@1+ (1,0) [0|65535] "" XXX
BO_ 688 SAS1: 8 XXX
SG_ SAS_Angle : 0|16@1+ (0.1,0) [-3276.8|3276.7] "Deg" XXX
SG_ SAS_Speed : 16|8@1+ (4,0) [0|1016] "" XXX
SG_ SAS_Stat : 24|8@1+ (1,0) [0|255] "" XXX
SG_ MsgCount : 32|4@1+ (1,0) [0|15] "" XXX
SG_ CheckSum : 36|4@1+ (1,0) [0|15] "" XXX
BO_ 790 EMS1: 8 XXX
SG_ SWI_IGK : 0|1@1+ (1,0) [0|1] "" XXX
SG_ F_N_ENG : 1|1@1+ (1,0) [0|1] "" XXX
SG_ ACK_TCS : 2|1@1+ (1,0) [0|1] "" XXX
SG_ PUC_STAT : 3|1@1+ (1,0) [0|1] "" XXX
SG_ TQ_COR_STAT : 4|2@1+ (1,0) [0|3] "" XXX
SG_ RLY_AC : 6|1@1+ (1,0) [0|1] "" XXX
SG_ F_SUB_TQI : 7|1@1+ (1,0) [0|1] "" XXX
SG_ TQI_ACOR : 8|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ N : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX
SG_ TQI : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ VS : 48|8@1+ (1,0) [0|254] "km/h" XXX
SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0) [0|2] "" XXX
BO_ 809 EMS2: 8 XXX
SG_ TQ_STND : 0|6@1+ (10,0) [0|630] "Nm" XXX
SG_ CAN_VERS : 0|6@1+ (1,0) [0|7.7] "" XXX
SG_ CONF_TCU : 0|6@1+ (1,0) [0|63] "" XXX
SG_ OBD_FRF_ACK : 0|6@1+ (1,0) [0|63] "" XXX
SG_ MUL_CODE : 6|2@1+ (1,0) [0|3] "" XXX
SG_ TEMP_ENG : 8|8@1+ (0.75,-48) [-48|143.25] "" XXX
SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0) [0|1.99155] "" XXX
SG_ VB_OFF_ACT : 24|1@1+ (1,0) [0|1] "" XXX
SG_ ACK_ES : 25|1@1+ (1,0) [0|1] "" XXX
SG_ CONF_MIL_FMY : 26|3@1+ (1,0) [0|7] "" XXX
SG_ OD_OFF_REQ : 29|1@1+ (1,0) [0|1] "" XXX
SG_ ACC_ACT : 30|1@1+ (1,0) [0|1] "" XXX
SG_ CLU_ACK : 31|1@1+ (1,0) [0|1] "" XXX
SG_ BRAKE_ACT : 32|2@1+ (1,0) [0|3] "" XXX
SG_ ENG_CHR : 34|4@1+ (1,0) [0|15] "" XXX
SG_ GP_CTL : 38|2@1+ (1,0) [0|3] "" XXX
SG_ TPS : 40|8@1+ (0.469484,-15.0235) [-15.0235|104.695] "%" XXX
SG_ PV_AV_CAN : 48|8@1+ (0.3906,0) [0|99.603] "%" XXX
SG_ ENG_VOL : 56|8@1+ (0.1,0) [0|25.5] "liter" XXX
BO_ 848 FATC: 8 XXX
SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0) [0|50.8] "Nm" XXX
SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_EcvFlt : 10|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_BlwrOn : 11|1@1+ (1,0) [0|1] "" XXX
SG_ CF_FATC_Iden : 12|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Fatc_BlwrMax : 14|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_EngStartReq : 15|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_CtrInf : 17|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Fatc_MsgCnt : 20|4@1+ (1,0) [0|15] "" XXX
SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40) [-40|60] "" XXX
SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40) [-40|60] "" XXX
SG_ CF_Fatc_Compload : 40|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Fatc_ActiveEco : 43|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_AutoActivation : 44|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_DefSw : 45|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Fatc_ChkSum : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 880 TCU3: 8 XXX
SG_ N_TGT_LUP : 0|8@1+ (10,500) [500|3040] "rpm" XXX
SG_ SLOPE_TCU : 8|6@1+ (0.5,-16) [-16|15.5] "%" XXX
SG_ CF_Tcu_InhCda : 14|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_IsgInhib : 15|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_NCStat : 18|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_TarGr : 20|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Tcu_ShfPatt : 24|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Tcu_InhVis : 28|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_PRelReq : 29|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_ITPhase : 30|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10,0) [0|2540] "Nm/s" XXX
SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20,0) [0|3500] "rpm" XXX
SG_ TQI_TCU_INC : 48|8@1+ (0.390625,0) [0|99.6094] "%" XXX
SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_SptRdy : 57|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_Alive3 : 58|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 898 EMS9: 8 XXX
SG_ CF_Ems_BrkReq : 0|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_DnShftReq : 1|4@1+ (1,0) [0|14] "" XXX
SG_ CF_Ems_RepModChk : 5|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_DecelReq : 8|12@1+ (0.001,-4.094) [-4.094|0] "m/s^2" XXX
SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0) [0|4094] "hPa" XXX
SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40) [0|254] "" XXX
SG_ CF_Ems_PumpTPres : 40|8@1+ (3.13725,0) [0|800] "kPa" XXX
SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41) [-40|60] "" XXX
SG_ CF_Ems_OPSFail : 56|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_ECTTRQLIM : 57|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 1075 EPB1: 8 XXX
SG_ EPB_I_LAMP : 0|4@1+ (1,0) [0|15] "" XXX
SG_ EPB_F_LAMP : 4|2@1+ (1,0) [0|3] "" XXX
SG_ EPB_ALARM : 6|2@1+ (1,0) [0|3] "" XXX
SG_ EPB_CLU : 8|8@1+ (1,0) [0|255] "" XXX
SG_ EPB_SWITCH : 16|2@1+ (1,0) [0|3] "" XXX
SG_ EPB_RBL : 18|1@1+ (1,0) [0|1] "" XXX
SG_ EPB_STATUS : 19|3@1+ (1,0) [0|7] "" XXX
SG_ EPB_FRC_ERR : 22|2@1+ (1,0) [0|3] "" XXX
SG_ EPB_DBF_STAT : 24|1@1+ (1,0) [0|1] "" XXX
SG_ ESP_ACK : 25|1@1+ (1,0) [0|1] "" XXX
SG_ EPB_DBF_REQ : 26|1@1+ (1,0) [0|1] "" XXX
SG_ EPB_FAIL : 29|3@1+ (1,0) [0|7] "" XXX
SG_ EPB_FORCE : 32|12@1+ (1,-1000) [-1000|3000] "" XXX
SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0) [0|2.54] "g" XXX
BO_ 1087 TCU1: 8 XXX
SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" XXX
SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" XXX
SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" XXX
SG_ FAN_CTRL_TCU : 24|2@1+ (1,0) [0|3] "" XXX
SG_ BRAKE_ACT_TCU : 26|2@1+ (1,0) [0|3] "" XXX
SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" XXX
SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" XXX
SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" XXX
SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" XXX
SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" XXX
SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" XXX
SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.992188] "km/h" XXX
BO_ 1088 TCU2: 8 XXX
SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" XXX
SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" XXX
SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" XXX
SG_ FAN_CTRL_TCU : 24|2@1+ (1,0) [0|3] "" XXX
SG_ BRAKE_ACT_TCU : 26|2@1+ (1,0) [0|3] "" XXX
SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" XXX
SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" XXX
SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" XXX
SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" XXX
SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" XXX
SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" XXX
SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.992188] "km/h" XXX
BO_ 1200 WHL_SPD: 8 XXX
SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0) [0|511.969] "km/h" XXX
SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0) [0|511.969] "km/h" XXX
SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0) [0|511.969] "km/h" XXX
SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0) [0|511.969] "km/h" XXX
BO_ 1201 WHL_PUL: 8 XXX
SG_ WHL_PUL_FL : 0|8@1+ (0.5,0) [0|127.5] "pulse count" XXX
SG_ WHL_PUL_FR : 8|8@1+ (0.5,0) [0|127.5] "pulse count" XXX
SG_ WHL_PUL_RL : 16|8@1+ (0.5,0) [0|127.5] "pulse count" XXX
SG_ WHL_PUL_RR : 24|8@1+ (0.5,0) [0|127.5] "pulse count" XXX
SG_ WHL_DIR_FL : 32|2@1+ (1,0) [0|3] "" XXX
SG_ WHL_DIR_FR : 34|2@1+ (1,0) [0|3] "" XXX
SG_ WHL_DIR_RL : 36|2@1+ (1,0) [0|3] "" XXX
SG_ WHL_DIR_RR : 38|2@1+ (1,0) [0|3] "" XXX
SG_ WHL_PUL_Chksum : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 1264 CLU1: 8 XXX
SG_ CF_Clu_CruiseSwState : 0|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Blr_MaxStat : 3|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_SldMainSW : 4|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_ParityBit1 : 5|1@1+ (1,0) [0|1] "pulse count" XXX
SG_ CF_Clu_SPEED_UNIT : 6|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_ParkBrakeSw : 7|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0) [0|255.5] "km/h or MPH" XXX
SG_ CF_Clu_AliveCounter : 17|7@1+ (1,0) [0|127] "" XXX
SG_ CF_Clu_CruiseSwMain : 24|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_VanzDecimal : 25|2@1+ (1,0) [0|0.375] "" XXX
SG_ VEHICLE_INFO : 27|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_StrRlyState : 30|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_SMKOption : 31|1@1+ (1,0) [0|1] "" XXX
SG_ R_TqAcnOutC : 32|8@1+ (1,0) [0|51] "Nm" XXX
SG_ CF_Clu_Odometer : 40|24@1+ (0.1,0) [0|1.67772e+006] "km" XXX
BO_ 1265 CLU3: 8 XXX
SG_ CF_Clu_AcnRqSwi : 0|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_AcnCltEnRq : 1|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_RefDetMod : 2|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_DefoggerRly : 5|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_LowfuelWarn : 16|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_SportsModeSwi : 18|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_ALightStat : 20|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_FrtFog : 21|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_DetentOut : 22|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HeadLampTail : 23|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_TrailerMode : 24|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_DTE : 25|10@1+ (1,0) [0|1023] "" XXX
SG_ CF_Clu_TripUnit : 35|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_IsaMainSW : 37|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_FlexSteerSW : 40|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_AvsmCur : 41|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudSpeedset : 42|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudTbtSet : 43|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudSccSet : 44|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudLdwsSet : 45|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudDisSet : 46|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HudFontSizeSet : 47|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_HudFontColorSet : 49|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_HudBrightSet : 51|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_HudHeightSet : 53|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_CluInfo : 55|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_RheostatLevel : 56|5@1+ (1,0) [0|31] "" XXX
SG_ CF_Clu_DrivinglampStat : 61|3@1+ (1,0) [0|7] "" XXX
BO_ 1349 EMS4: 8 XXX
SG_ IMMO_LAMP_STAT : 0|1@1+ (1,0) [0|1] "" XXX
SG_ L_MIL : 1|1@1+ (1,0) [0|1] "" XXX
SG_ IM_STAT : 2|1@1+ (1,0) [0|1] "" XXX
SG_ AMP_CAN : 3|5@1+ (10.7316,458.98) [458.98|791.66] "mmHg" XXX
SG_ FCO : 8|16@1+ (0.128,0) [0|8388.48] "ul" XXX
SG_ VB : 24|8@1+ (0.101563,0) [0|25.8984] "V" XXX
SG_ TEMP_FUEL : 48|8@1+ (0.75,-48) [-48|143.25] "" XXX
SG_ Split_Stat : 56|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Ems_IsaAct : 57|1@1+ (1,0) [0|1] "" XXX
BO_ 1435 TCU4: 8 XXX
SG_ CF_TCU_WarnMsg : 0|3@1+ (1,0) [0|7] "" XXX
SG_ CF_TCU_WarnImg : 3|1@1+ (1,0) [0|1] "" XXX
SG_ CF_TCU_WarnSnd : 4|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_EolStat : 5|1@1+ (1,0) [0|1] "" XXX
SG_ CR_Tcu_GearSelDisp2 : 8|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Tcu_StRelStat : 12|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_DrivingModeReq : 18|4@1+ (1,0) [0|0] "" XXX
SG_ CF_Tcu_DrivingModeDisp : 22|4@1+ (1,0) [0|0] "" XXX
SG_ CF_Tcu_SiCluster : 26|5@1+ (1,0) [0|0] "" XXX
SG_ CF_Tcu_DSmode_Inf : 31|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Tcu_Alive4 : 58|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Tcu_ChkSum4 : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 1508 MDPS1: 8 XXX
SG_ CF_Mdps_WLmp : 1|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Mdps_ALTRequest : 5|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Mdps_Flex : 8|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Mdps_FlexDisp : 11|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Mdps_CurrMode : 12|2@1+ (1,0) [0|3] "" XXX
BO_ 1680 CLU2: 8 XXX
SG_ CF_Clu_IGNSw : 0|3@1+ (1,0) [0|7] "" XXX
SG_ RKE_CMD : 3|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_DrvDrSw : 6|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_DrvKeyLockSw : 8|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_DrvKeyUnlockSw : 9|1@1+ (1,0) [0|1] "" XXX
SG_ PIC_Lock : 10|3@1+ (1,0) [0|7] "" XXX
SG_ PIC_Unlock : 13|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_DrvSeatBeltSw : 16|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_TrunkTgSw : 18|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_AstSeatBeltSw : 20|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_HoodSw : 22|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_TurnSigLh : 24|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_TurnSigRh : 25|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_LdwsLkasSW : 26|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_WiperIntT : 27|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_WiperIntSW : 30|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_WiperLow : 31|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_WiperHigh : 32|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_WiperAuto : 33|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_RainSnsStat : 34|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_HeadLampLow : 37|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HeadLampHigh : 38|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_AltLStatus : 39|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_SwiGearR : 43|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_SWL_Stat : 45|3@1+ (1,0) [0|7] "" XXX
SG_ CF_Clu_ActiveEcoSW : 48|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_HazardSW : 49|1@1+ (1,0) [0|1] "" XXX
SG_ CF_Clu_AliveCnt2 : 50|4@1+ (1,0) [0|15] "" XXX
SG_ CF_Clu_AstDrSw : 54|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_LkasDispMode : 56|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_AutoLightLevel : 58|2@1+ (1,0) [0|3] "" XXX
SG_ CF_Clu_SunRoofOpenState : 60|1@1+ (1,0) [0|1] "" XXX

@ -0,0 +1,62 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX
BO_ 3 NEW_MSG_1: 8 XXX
SG_ STEERING_ANGLE : 7|32@0- (1,0) [0|4294967295] "" XXX
SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX
BO_ 5 NEW_MSG_2: 8 XXX
SG_ BRAKE_POSITION : 23|16@0+ (1,0) [0|65535] "" XXX
SG_ BRAKE_PRESSED : 0|8@1+ (1,0) [0|17] "" XXX
BO_ 69 NEW_MSG_3: 8 XXX
SG_ TURN_SIGNAL_LEVER : 16|8@1+ (1,0) [0|255] "" XXX
SG_ CRUISE_CONTROL_LEVER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ NEW_SIGNAL_2 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX
SG_ STEERING_WHEEL_BUTTONS : 32|8@1+ (1,0) [0|255] "4 directional, 2 volume control, & 2 phone buttons" XXX
SG_ MORE_STEERING_WHEELS_BUTTONS : 40|8@1+ (1,0) [0|255] "" XXX
BO_ 1 NEW_MSG_4: 8 XXX
SG_ DOOR_LOCK_STATUS : 31|16@0+ (1,0) [0|65535] "" XXX
CM_ SG_ 5 BRAKE_PRESSED "appears to be boolean (brake pressed)";
CM_ SG_ 69 MORE_STEERING_WHEELS_BUTTONS "back, ok, voice assistance, and mute buttons";

@ -0,0 +1,73 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX
BO_ 884 DoorStatus: 8 XXX
SG_ DoorOpenFD : 24|1@0+ (1,0) [0|1] "" XXX
SG_ DoorOpenFP : 25|1@0+ (1,0) [0|1] "" XXX
SG_ DoorOpenRP : 26|1@0+ (1,0) [0|1] "" XXX
SG_ DoorOpenRD : 27|1@0+ (1,0) [0|1] "" XXX
SG_ DoorOpenHatch : 28|1@0+ (1,0) [0|1] "" XXX
BO_ 324 CruiseControl: 7 XXX
SG_ BrakeApplied : 8|1@0+ (1,0) [0|0] "" XXX
SG_ CruiseEnabled : 48|1@0+ (1,0) [0|0] "" XXX
SG_ BrakeStatus : 51|1@0+ (1,0) [0|0] "" XXX
SG_ CruiseButtons : 4|2@0+ (1,0) [0|3] "" XXX
BO_ 320 Throttle: 8 XXX
SG_ ThrottlePosition : 7|8@0+ (1,0) [0|255] "" XXX
BO_ 209 NEW_MSG_1: 8 XXX
SG_ BrakePosition : 23|8@0+ (1,0) [0|255] "" XXX
BO_ 2 Steering: 8 XXX
SG_ SteeringAngle : 7|16@0- (0.1,0) [-500|500] "degree" XXX
BO_ 642 NEW_MSG_2: 8 XXX
SG_ TurnSignal : 45|2@0+ (1,0) [0|3] "" XXX
CM_ "CHFFR_METRIC 2 STEER_ANGLE STEER_ANGLE 0.36 180";
VAL_ 324 BrakeApplied 1 "On" 0 "Off" ;
VAL_ 324 CruiseEnabled 1 "On" 0 "Off" ;
VAL_ 324 BrakeStatus 1 "On" 0 "Off" ;
VAL_ 324 CruiseButtons 2 "Set" 1 "Resume" ;
VAL_ 642 TurnSignal 2 "Left" 1 "Right" ;

@ -0,0 +1,420 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_:
NEO
MCU
GTW
EPAS
DI
ESP
SBW
STW
VAL_TABLE_ StW_AnglHP_Spd 16383 "SNA" ;
VAL_TABLE_ DI_aebFaultReason 15 "DI_AEB_FAULT_DAS_REQ_DI_UNAVAIL" 14 "DI_AEB_FAULT_ACCEL_REQ_INVALID" 13 "DI_AEB_FAULT_MIN_TIME_BTWN_EVENTS" 12 "DI_AEB_FAULT_ESP_MIA" 11 "DI_AEB_FAULT_ESP_FAULT" 10 "DI_AEB_FAULT_EPB_NOT_PARKED" 9 "DI_AEB_FAULT_ACCEL_OUT_OF_BOUNDS" 8 "DI_AEB_FAULT_PM_REQUEST" 7 "DI_AEB_FAULT_VEL_EST_ABNORMAL" 6 "DI_AEB_FAULT_DAS_SNA" 5 "DI_AEB_FAULT_DAS_CONTROL_MIA" 4 "DI_AEB_FAULT_SPEED_DELTA" 3 "DI_AEB_FAULT_EBR_FAULT" 2 "DI_AEB_FAULT_PM_MIA" 1 "DI_AEB_FAULT_EPB_MIA" 0 "DI_AEB_FAULT_NONE" ;
VAL_TABLE_ DI_aebLockState 3 "AEB_LOCK_STATE_SNA" 2 "AEB_LOCK_STATE_UNUSED" 1 "AEB_LOCK_STATE_UNLOCKED" 0 "AEB_LOCK_STATE_LOCKED" ;
VAL_TABLE_ DI_aebSmState 7 "DI_AEB_STATE_FAULT" 6 "DI_AEB_STATE_EXIT" 5 "DI_AEB_STATE_STANDSTILL" 4 "DI_AEB_STATE_STOPPING" 3 "DI_AEB_STATE_ENABLE" 2 "DI_AEB_STATE_ENABLE_INIT" 1 "DI_AEB_STATE_STANDBY" 0 "DI_AEB_STATE_UNAVAILABLE" ;
VAL_TABLE_ DI_aebState 7 "AEB_CAN_STATE_SNA" 4 "AEB_CAN_STATE_FAULT" 3 "AEB_CAN_STATE_STANDSTILL" 2 "AEB_CAN_STATE_ENABLED" 1 "AEB_CAN_STATE_STANDBY" 0 "AEB_CAN_STATE_UNAVAILABLE" ;
VAL_TABLE_ DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ;
VAL_TABLE_ DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ;
VAL_TABLE_ DI_gpoReason 8 "DI_GPO_NUMREASONS" 7 "DI_GPO_CAPACITOR_OVERTEMP" 6 "DI_GPO_NOT_ENOUGH_12V" 5 "DI_GPO_NO_BATTERY_POWER" 4 "DI_GPO_AMBIENT_OVERTEMP" 3 "DI_GPO_FLUID_DELTAT" 2 "DI_GPO_STATOR_OVERTEMP" 1 "DI_GPO_HEATSINK_OVERTEMP" 0 "DI_GPO_OUTLET_OVERTEMP" ;
VAL_TABLE_ DI_immobilizerCondition 1 "DI_IMM_CONDITION_LEARNED" 0 "DI_IMM_CONDITION_VIRGIN_SNA" ;
VAL_TABLE_ DI_immobilizerState 7 "DI_IMM_STATE_FAULT" 6 "DI_IMM_STATE_FAULTRETRY" 5 "DI_IMM_STATE_RESET" 4 "DI_IMM_STATE_LEARN" 3 "DI_IMM_STATE_DISARMED" 2 "DI_IMM_STATE_AUTHENTICATING" 1 "DI_IMM_STATE_REQUEST" 0 "DI_IMM_STATE_INIT_SNA" ;
VAL_TABLE_ DI_limpReason 24 "DI_LIMP_NUMREASONS" 23 "DI_LIMP_CAPACITOR_OVERTEMP" 22 "DI_LIMP_GTW_MIA" 21 "DI_LIMP_TRQCMD_VALIDITY_UNKNOWN" 20 "DI_LIMP_DI_MIA" 19 "DI_LIMP_CONFIG_MISMATCH" 18 "DI_LIMP_HEATSINK_TEMP" 17 "DI_LIMP_PMREQUEST" 16 "DI_LIMP_PMHEARTBEAT" 15 "DI_LIMP_TRQ_CROSS_CHECK" 14 "DI_LIMP_EXTERNAL_COMMAND" 13 "DI_LIMP_WRONG_CS_CALIBRATION" 12 "DI_LIMP_STATOR_TEMP" 11 "DI_LIMP_DELTAT_TOO_NEGATIVE" 10 "DI_LIMP_DELTAT_TOO_POSITIVE" 9 "DI_LIMP_AMBIENT_TEMP" 8 "DI_LIMP_OUTLET_TEMP" 7 "DI_LIMP_LOW_FLOW" 6 "DI_LIMP_BMS_MIA" 5 "DI_LIMP_12V_SUPPLY_UNDERVOLTAGE" 4 "DI_LIMP_NO_FLUID" 3 "DI_LIMP_NO_FUNC_HEATSINK_SENSOR" 2 "DI_LIMP_NO_FUNC_STATORT_SENSOR" 1 "DI_LIMP_BUSV_SENSOR_IRRATIONAL" 0 "DI_LIMP_PHASE_IMBALANCE" ;
VAL_TABLE_ DI_mode 2 "DI_MODE_DYNO" 1 "DI_MODE_DRIVE" 0 "DI_MODE_UNDEF" ;
VAL_TABLE_ DI_motorType 14 "DI_MOTOR_F2AE" 13 "DI_MOTOR_F2AD" 12 "DI_MOTOR_F2AC" 11 "DI_MOTOR_F2AB" 10 "DI_MOTOR_F1AC" 9 "DI_MOTOR_SSR1A" 8 "DI_MOTOR_F1A" 7 "DI_MOTOR_M7M6" 6 "DI_MOTOR_M8A" 5 "DI_MOTOR_M7M5" 4 "DI_MOTOR_M7M4" 3 "DI_MOTOR_M7M3" 2 "DI_MOTOR_ROADSTER_SPORT" 1 "DI_MOTOR_ROADSTER_BASE" 0 "DI_MOTOR_SNA" ;
VAL_TABLE_ DI_speedUnits 1 "DI_SPEED_KPH" 0 "DI_SPEED_MPH" ;
VAL_TABLE_ DI_state 4 "DI_STATE_ENABLE" 3 "DI_STATE_FAULT" 2 "DI_STATE_CLEAR_FAULT" 1 "DI_STATE_STANDBY" 0 "DI_STATE_PREAUTH" ;
VAL_TABLE_ DI_velocityEstimatorState 4 "VE_STATE_BACKUP_MOTOR" 3 "VE_STATE_BACKUP_WHEELS_B" 2 "VE_STATE_BACKUP_WHEELS_A" 1 "VE_STATE_WHEELS_NORMAL" 0 "VE_STATE_NOT_INITIALIZED" ;
BO_ 1160 DAS_steeringControl: 4 NEO
SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|0] "" EPAS
SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|0] "" EPAS
SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|0] "" EPAS
SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" EPAS
SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|0] "" EPAS
BO_ 257 GTW_epasControl: 3 NEO
SG_ GTW_epasControlChecksum : 23|8@0+ (1,0) [0|255] "" NEO
SG_ GTW_epasControlCounter : 11|4@0+ (1,0) [0|15] "" NEO
SG_ GTW_epasControlType : 15|2@0+ (1,0) [-1|4] "" NEO
SG_ GTW_epasEmergencyOn : 7|1@0+ (1,0) [-1|2] "" NEO
SG_ GTW_epasLDWEnabled : 12|1@0+ (1,0) [-1|2] "" NEO
SG_ GTW_epasPowerMode : 6|4@0+ (1,0) [4|14] "" NEO
SG_ GTW_epasTuneRequest : 2|3@0+ (1,0) [-1|8] "" NEO
BO_ 880 EPAS_sysStatus: 8 EPAS
SG_ EPAS_currentTuneMode : 7|4@0+ (1,0) [8|15] "" NEO
SG_ EPAS_eacErrorCode : 23|4@0+ (1,0) [-1|16] "" NEO
SG_ EPAS_eacStatus : 55|3@0+ (1,0) [5|7] "" NEO
SG_ EPAS_handsOnLevel : 39|2@0+ (1,0) [-1|4] "" NEO
SG_ EPAS_internalSAS : 37|14@0+ (0.1,-819.200012) [0|0] "deg" NEO
SG_ EPAS_steeringFault : 2|1@0+ (1,0) [-1|2] "" NEO
SG_ EPAS_steeringRackForce : 1|10@0+ (50,-25575) [0|0] "N" NEO
SG_ EPAS_steeringReduced : 3|1@0+ (1,0) [-1|2] "" NEO
SG_ EPAS_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" NEO
SG_ EPAS_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" NEO
SG_ EPAS_torsionBarTorque : 19|12@0+ (0.01,-20.5) [0|0] "Nm" NEO
BO_ 3 STW_ANGL_STAT: 8 STW
SG_ StW_Angl : 5|14@0+ (0.5,-2048) [0|0] "deg" NEO
SG_ StW_AnglSpd : 21|14@0+ (0.5,-2048) [0|0] "/s" NEO
SG_ StW_AnglSens_Stat : 33|2@0+ (1,0) [-1|4] "" NEO
SG_ StW_AnglSens_Id : 35|2@0+ (1,0) [3|3] "" NEO
SG_ MC_STW_ANGL_STAT : 55|4@0+ (1,0) [0|15] "" NEO
SG_ CRC_STW_ANGL_STAT : 63|8@0+ (1,0) [0|255] "" NEO
BO_ 14 STW_ANGLHP_STAT: 8 STW
SG_ StW_AnglHP : 5|14@0+ (0.1,-819.2) [-819.2|819] "deg" NEO
SG_ StW_AnglHP_Spd : 21|14@0+ (0.5,-4096) [-4096|4095.5] "deg/s" NEO
SG_ StW_AnglHP_Sens_Stat : 33|2@0+ (1,0) [0|0] "" NEO
SG_ StW_AnglHP_Sens_Id : 35|2@0+ (1,0) [0|0] "" NEO
SG_ MC_STW_ANGLHP_STAT : 55|4@0+ (1,0) [0|15] "" NEO
SG_ CRC_STW_ANGLHP_STAT : 63|8@0+ (1,0) [0|0] "" NEO
BO_ 264 DI_torque1: 8 DI
SG_ DI_torqueDriver : 0|13@1- (0.25,0) [-750|750] "Nm" NEO
SG_ DI_torque1Counter : 13|3@1+ (1,0) [0|0] "" NEO
SG_ DI_torqueMotor : 16|13@1- (0.25,0) [-750|750] "Nm" NEO
SG_ DI_soptState : 29|3@1+ (1,0) [0|0] "" NEO
SG_ DI_motorRPM : 32|16@1- (1,0) [-17000|17000] "RPM" NEO
SG_ DI_pedalPos : 48|8@1+ (0.4,0) [0|100] "%" NEO
SG_ DI_torque1Checksum : 56|8@1+ (1,0) [0|0] "" NEO
BO_ 280 DI_torque2: 6 DI
SG_ DI_torqueEstimate : 0|12@1- (0.5,0) [-750|750] "Nm" NEO
SG_ DI_gear : 12|3@1+ (1,0) [0|0] "" NEO
SG_ DI_brakePedal : 15|1@1+ (1,0) [0|0] "" NEO
SG_ DI_vehicleSpeed : 16|12@1+ (0.05,-25) [-25|179.75] "MPH" NEO
SG_ DI_gearRequest : 28|3@1+ (1,0) [0|0] "" NEO
SG_ DI_torqueInterfaceFailure : 31|1@1+ (1,0) [0|0] "" NEO
SG_ DI_torque2Counter : 32|4@1+ (1,0) [0|0] "" NEO
SG_ DI_brakePedalState : 36|2@1+ (1,0) [0|0] "" NEO
SG_ DI_epbParkRequest : 38|1@1+ (1,0) [0|0] "" NEO
SG_ DI_epbInterfaceReady : 39|1@1+ (1,0) [0|0] "" NEO
SG_ DI_torque2Checksum : 40|8@1+ (1,0) [0|0] "" NEO
BO_ 309 ESP_135h: 5 ESP
SG_ ESP_135hChecksum : 23|8@0+ (1,0) [0|255] "" NEO
SG_ ESP_135hCounter : 11|4@0+ (1,0) [0|15] "" NEO
SG_ ESP_absBrakeEvent : 2|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_brakeDiscWipingActive : 4|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_brakeLamp : 3|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_espFaultLamp : 6|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_espLampFlash : 7|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_hillStartAssistActive : 1|2@0+ (1,0) [-1|4] "" NEO
SG_ ESP_messagePumpService : 24|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_messagePumpFailure : 25|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_messageEBDFailure : 26|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_absFaultLamp : 27|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_tcDisabledByFault : 28|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_messageDynoModeActive : 29|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_hydraulicBoostEnabled : 30|1@0+ (1,0) [0|1] "" NEO
SG_ ESP_espOffLamp : 31|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_stabilityControlSts : 14|3@0+ (1,0) [6|7] "" NEO
SG_ ESP_tcLampFlash : 5|1@0+ (1,0) [-1|2] "" NEO
SG_ ESP_tcOffLamp : 15|1@0+ (1,0) [0|1] "" NEO BO_ 341 ESP_B: 8 ESP
SG_ ESP_BChecksum : 39|8@0+ (1,0) [0|255] "" NEO,EPAS
SG_ ESP_BCounter : 62|4@0+ (1,0) [1|15] "" NEO,EPAS
SG_ ESP_vehicleSpeed : 47|16@0+ (0.00999999978,0) [0|0] "kph" NEO,EPAS
SG_ ESP_vehicleSpeedQF : 57|2@0+ (1,0) [1|2] "" NEO,EPAS
SG_ ESP_wheelPulseCountFrL : 7|8@0+ (1,0) [0|254] "" NEO,EPAS
SG_ ESP_wheelPulseCountFrR : 15|8@0+ (1,0) [0|254] "" NEO,EPAS
SG_ ESP_wheelPulseCountReL : 23|8@0+ (1,0) [0|254] "" NEO,EPAS
SG_ ESP_wheelPulseCountReR : 31|8@0+ (1,0) [0|254] "" NEO,EPAS
BO_ 532 EPB_epasControl: 3 EPB
SG_ EPB_epasControlChecksum : 23|8@0+ (1,0) [0|255] "" NEO,EPAS
SG_ EPB_epasControlCounter : 11|4@0+ (1,0) [0|15] "" NEO,EPAS
SG_ EPB_epasEACAllow : 2|3@0+ (1,0) [4|7] "" NEO,EPAS
BO_ 792 GTW_carState: 8 GTW
SG_ BOOT_STATE : 47|2@0+ (1,0) [-1|4] "" NEO
SG_ CERRD : 7|1@0+ (1,0) [-1|2] "" NEO
SG_ DAY : 36|5@0+ (1,0) [2|31] "" NEO
SG_ DOOR_STATE_FL : 13|2@0+ (1,0) [-1|4] "" NEO
SG_ DOOR_STATE_FR : 15|2@0+ (1,0) [-1|4] "" NEO
SG_ DOOR_STATE_FrontTrunk : 51|2@0+ (1,0) [-1|4] "" NEO
SG_ DOOR_STATE_RL : 23|2@0+ (1,0) [-1|4] "" NEO
SG_ DOOR_STATE_RR : 30|2@0+ (1,0) [-1|4] "" NEO
SG_ GTW_updateInProgress : 49|2@0+ (1,0) [-1|4] "" NEO
SG_ Hour : 28|5@0+ (1,0) [0|29] "h" NEO
SG_ MCU_factoryMode : 52|1@0+ (1,0) [-1|2] "" NEO
SG_ MCU_transportModeOn : 53|1@0+ (1,0) [1|1] "" NEO
SG_ MINUTE : 45|6@0+ (1,0) [0|61] "min" NEO
SG_ MONTH : 11|4@0+ (1,0) [0|14] "Month" NEO
SG_ SECOND : 21|6@0+ (1,0) [0|61] "s" NEO
SG_ YEAR : 6|7@0+ (1,2000) [2000|2125] "Year" NEO
BO_ 872 DI_state: 8 DI
SG_ DI_systemState : 0|3@1+ (1,0) [0|0] "" NEO
SG_ DI_vehicleHoldState : 3|3@1+ (1,0) [0|0] "" NEO
SG_ DI_proximity : 6|1@1+ (1,0) [0|0] "" NEO
SG_ DI_driveReady : 7|1@1+ (1,0) [0|0] "" NEO
SG_ DI_regenLight : 8|1@1+ (1,0) [0|0] "" NEO
SG_ DI_state : 9|3@1+ (1,0) [0|0] "" NEO
SG_ DI_cruiseState : 12|4@1+ (1,0) [0|0] "" NEO
SG_ DI_analogSpeed : 16|12@1+ (0.1,0) [0|150] "speed" NEO
SG_ DI_immobilizerState : 28|3@1+ (1,0) [0|0] "" NEO
SG_ DI_speedUnits : 31|1@1+ (1,0) [0|1] "" NEO
SG_ DI_cruiseSet : 32|9@1+ (0.5,0) [0|255.5] "speed" NEO
SG_ DI_aebState : 41|3@1+ (1,0) [0|0] "" NEO
SG_ DI_stateCounter : 44|4@1+ (1,0) [0|0] "" NEO
SG_ DI_digitalSpeed : 48|8@1+ (1,0) [0|250] "" NEO
SG_ DI_stateChecksum : 56|8@1+ (1,0) [0|0] "" NEO
BO_ 109 SBW_RQ_SCCM: 4 STW
SG_ StW_Sw_Stat3 : 0|3@1+ (1,0) [0|0] "" NEO
SG_ MsgTxmtId : 6|2@1+ (1,0) [0|0] "" NEO
SG_ TSL_RND_Posn_StW : 8|4@1+ (1,0) [0|0] "" NEO
SG_ TSL_P_Psd_StW : 12|2@1+ (1,0) [0|0] "" NEO
SG_ MC_SBW_RQ_SCCM : 20|4@1+ (1,0) [0|15] "" NEO
SG_ CRC_SBW_RQ_SCCM : 24|8@1+ (1,0) [0|0] "" NEO
BO_ 69 STW_ACTN_RQ: 8 STW
SG_ SpdCtrlLvr_Stat : 0|6@1+ (1,0) [0|0] "" NEO
SG_ VSL_Enbl_Rq : 6|1@1+ (1,0) [0|0] "" NEO
SG_ SpdCtrlLvrStat_Inv : 7|1@1+ (1,0) [0|0] "" NEO
SG_ DTR_Dist_Rq : 8|8@1+ (1,0) [0|200] "" NEO
SG_ TurnIndLvr_Stat : 16|2@1+ (1,0) [0|0] "" NEO
SG_ HiBmLvr_Stat : 18|2@1+ (1,0) [0|0] "" NEO
SG_ WprWashSw_Psd : 20|2@1+ (1,0) [0|0] "" NEO
SG_ WprWash_R_Sw_Posn_V2 : 22|2@1+ (1,0) [0|0] "" NEO
SG_ StW_Lvr_Stat : 24|3@1+ (1,0) [0|0] "" NEO
SG_ StW_Cond_Flt : 27|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Cond_Psd : 28|2@1+ (1,0) [0|0] "" NEO
SG_ HrnSw_Psd : 30|2@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw00_Psd : 32|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw01_Psd : 33|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw02_Psd : 34|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw03_Psd : 35|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw04_Psd : 36|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw05_Psd : 37|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw06_Psd : 38|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw07_Psd : 39|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw08_Psd : 40|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw09_Psd : 41|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw10_Psd : 42|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw11_Psd : 43|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw12_Psd : 44|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw13_Psd : 45|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw14_Psd : 46|1@1+ (1,0) [0|0] "" NEO
SG_ StW_Sw15_Psd : 47|1@1+ (1,0) [0|0] "" NEO
SG_ WprSw6Posn : 48|3@1+ (1,0) [0|0] "" NEO
SG_ MC_STW_ACTN_RQ : 52|4@1+ (1,0) [0|15] "" NEO
SG_ CRC_STW_ACTN_RQ : 56|8@1+ (1,0) [0|0] "" NEO
BO_ 643 BODY_R1: 8 GTW
SG_ AirTemp_Insd : 47|8@0+ (0.25,0) [0|63.5] "C" NEO
SG_ AirTemp_Outsd : 63|8@0+ (0.5,-40) [-40|86.5] "C" NEO
SG_ Bckl_Sw_RL_Stat_SAM_R : 49|2@0+ (1,0) [-1|4] "" NEO
SG_ Bckl_Sw_RM_Stat_SAM_R : 53|2@0+ (1,0) [-1|4] "" NEO
SG_ Bckl_Sw_RR_Stat_SAM_R : 51|2@0+ (1,0) [-1|4] "" NEO
SG_ DL_RLtch_Stat : 9|2@0+ (1,0) [-1|4] "" NEO
SG_ DrRLtch_FL_Stat : 1|2@0+ (1,0) [-1|4] "" NEO
SG_ DrRLtch_FR_Stat : 3|2@0+ (1,0) [-1|4] "" NEO
SG_ DrRLtch_RL_Stat : 5|2@0+ (1,0) [-1|4] "" NEO
SG_ DrRLtch_RR_Stat : 7|2@0+ (1,0) [-1|4] "" NEO
SG_ EngHd_Stat : 11|2@0+ (1,0) [-1|4] "" NEO
SG_ LoBm_On_Rq : 32|1@0+ (1,0) [0|1] "" NEO
SG_ HiBm_On : 33|1@0+ (1,0) [0|1] "" NEO
SG_ Hrn_On : 26|1@0+ (1,0) [0|1] "" NEO
SG_ IrLmp_D_Lt_Flt : 34|1@0+ (1,0) [0|1] "" NEO
SG_ IrLmp_P_Rt_Flt : 35|1@0+ (1,0) [0|1] "" NEO
SG_ LgtSens_Twlgt : 18|3@0+ (1,0) [0|7] "Steps" NEO
SG_ LgtSens_SNA : 19|1@0+ (1,0) [0|1] "" NEO
SG_ LgtSens_Tunnel : 20|1@0+ (1,0) [0|1] "" NEO
SG_ LgtSens_Flt : 21|1@0+ (1,0) [0|1] "" NEO
SG_ LgtSens_Night : 22|1@0+ (1,0) [-1|2] "" NEO
SG_ ADL_LoBm_On_Rq : 23|1@0+ (1,0) [0|1] "" NEO
SG_ LoBm_D_Lt_Flt : 36|1@0+ (1,0) [0|1] "" NEO
SG_ LoBm_P_Rt_Flt : 37|1@0+ (1,0) [0|1] "" NEO
SG_ MPkBrk_Stat : 28|1@0+ (1,0) [-1|2] "" NEO
SG_ RevGr_Engg : 39|2@0+ (1,0) [-1|4] "" NEO
SG_ StW_Cond_Stat : 55|2@0+ (1,0) [-1|4] "" NEO
SG_ Term54_Actv : 27|1@0+ (1,0) [0|1] "" NEO
SG_ Trlr_Stat : 25|2@0+ (1,0) [-1|4] "" NEO
SG_ VTA_Alm_Actv : 13|1@0+ (1,0) [0|1] "" NEO
SG_ WprOutsdPkPosn : 29|1@0+ (1,0) [0|1] "" NEO
BO_ 760 MCU_gpsVehicleSpeed: 8 MCU
SG_ MCU_gpsHDOP : 0|8@1+ (0.1,0) [0|25.5] "1" NEO
SG_ MCU_gpsVehicleHeading : 8|16@1+ (0.00781,0) [0|511.82835] "deg" NEO
SG_ MCU_gpsVehicleSpeed : 24|16@1+ (0.00391,0) [0|256.24185] "km/hr" NEO
SG_ MCU_mppSpeedLimit : 51|5@1+ (5,0) [0|155] "kph/mph" NEO
SG_ MCU_speedLimitUnits : 41|1@1+ (1,0) [-1|2] "" NEO
SG_ MCU_userSpeedOffset : 42|6@1+ (1,-30) [-30|33] "kph/mph" NEO
SG_ MCU_userSpeedOffsetUnits : 40|1@1+ (1,0) [-1|2] "" NEO
BO_ 904 MCU_clusterBacklightRequest: 3 NEO
SG_ MCU_clusterBacklightOn : 7|1@1+ (1,0) [0|1] "" NEO
SG_ MCU_clusterBrightnessLevel : 8|8@1+ (0.5,0) [0|127.5] "%" NEO
SG_ MCU_clusterReadyForDrive : 6|1@1+ (1,0) [-1|2] "" NEO
SG_ MCU_clusterReadyForPowerOff : 5|1@1+ (1,0) [0|1] "" NEO
BO_ 984 MCU_locationStatus: 8 MCU
SG_ MCU_gpsAccuracy : 56|7@1+ (0.200000003,0) [0|25.200000378] "m" NEO
SG_ MCU_latitude : 0|28@1- (1E-006,0) [-134.217727597347|134.217726597347] "deg" NEO
SG_ MCU_longitude : 28|28@1- (1E-006,0) [-268.435455194694|268.435454194694] "deg" NEO
BO_ 840 GTW_status: 8 GTW
SG_ GTW_accGoingDown : 6|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_accRailReq : 8|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_brakePressed : 1|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_driveGoingDown : 7|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_driveRailReq : 0|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_driverIsLeaving : 5|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_driverPresent : 2|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_hvacGoingDown : 11|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_hvacRailReq : 9|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_icPowerOff : 4|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_notEnough12VForDrive : 3|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_preconditionRequest : 10|1@0+ (1,0) [0|1] "" NEO
SG_ GTW_statusChecksum : 63|8@0+ (1,0) [0|255] "" NEO
SG_ GTW_statusCounter : 51|4@0+ (1,0) [0|15] "" NEO
VAL_ 3 StW_Angl 16383 "SNA" ;
VAL_ 3 StW_AnglSens_Id 2 "MUST" 0 "PSBL" 1 "SELF" ;
VAL_ 3 StW_AnglSens_Stat 2 "ERR" 3 "ERR_INI" 1 "INI" 0 "OK" ;
VAL_ 3 StW_AnglSpd 16383 "SNA" ;
VAL_ 14 StW_AnglHP 16383 "SNA" ;
VAL_ 14 StW_AnglHP_Spd 16383 "SNA" ;
VAL_ 14 StW_AnglHP_Sens_Stat 3 "SNA" 2 "ERR" 1 "INI" 0 "OK" ;
VAL_ 14 StW_AnglHP_Sens_Id 3 "SNA" 2 "KOSTAL" 1 "DELPHI" 0 "TEST" ;
VAL_ 69 SpdCtrlLvr_Stat 32 "DN_1ST" 16 "UP_1ST" 8 "DN_2ND" 4 "UP_2ND" 2 "RWD" 1 "FWD" 0 "IDLE" ;
VAL_ 69 DTR_Dist_Rq 255 "SNA" 200 "ACC_DIST_7" 166 "ACC_DIST_6" 133 "ACC_DIST_5" 100 "ACC_DIST_4" 66 "ACC_DIST_3" 33 "ACC_DIST_2" 0 "ACC_DIST_1" ;
VAL_ 69 TurnIndLvr_Stat 3 "SNA" 2 "RIGHT" 1 "LEFT" 0 "IDLE" ;
VAL_ 69 HiBmLvr_Stat 3 "SNA" 2 "HIBM_FLSH_ON_PSD" 1 "HIBM_ON_PSD" 0 "IDLE" ;
VAL_ 69 WprWashSw_Psd 3 "SNA" 2 "WASH" 1 "TIPWIPE" 0 "NPSD" ;
VAL_ 69 WprWash_R_Sw_Posn_V2 3 "SNA" 2 "WASH" 1 "INTERVAL" 0 "OFF" ;
VAL_ 69 StW_Lvr_Stat 4 "STW_BACK" 3 "STW_FWD" 2 "STW_DOWN" 1 "STW_UP" 0 "NPSD" ;
VAL_ 69 StW_Cond_Psd 3 "SNA" 2 "DOWN" 1 "UP" 0 "NPSD" ;
VAL_ 69 HrnSw_Psd 3 "SNA" 2 "NDEF2" 1 "PSD" 0 "NPSD" ;
VAL_ 69 StW_Sw00_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ;
VAL_ 69 StW_Sw01_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ;
VAL_ 69 StW_Sw03_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ;
VAL_ 69 StW_Sw04_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ;
VAL_ 69 WprSw6Posn 7 "SNA" 6 "STAGE2" 5 "STAGE1" 4 "INTERVAL4" 3 "INTERVAL3" 2 "INTERVAL2" 1 "INTERVAL1" 0 "OFF" ;VAL_ 257 GTW_epasControlType 0 "WITHOUT" 1 "WITH_ANGLE" 3 "WITH_BOTH" 2 "WITH_TORQUE" ;
VAL_ 109 StW_Sw_Stat3 7 "SNA" 6 "NDEF6" 5 "NDEF5" 4 "NDEF4" 3 "PLUS_MINUS" 2 "MINUS" 1 "PLUS" 0 "NPSD" ;
VAL_ 109 MsgTxmtId 3 "NDEF3" 2 "NDEF2" 1 "SCCM" 0 "EWM" ;
VAL_ 109 TSL_RND_Posn_StW 15 "SNA" 8 "D" 6 "INI" 4 "N_DOWN" 2 "N_UP" 1 "R" 0 "IDLE" ;
VAL_ 109 TSL_P_Psd_StW 3 "SNA" 2 "INI" 1 "PSD" 0 "IDLE" ;
VAL_ 257 GTW_epasEmergencyOn 1 "EMERGENCY_POWER" 0 "NONE" ;
VAL_ 257 GTW_epasLDWEnabled 1 "ALLOWED" 0 "INHIBITED" ;
VAL_ 257 GTW_epasPowerMode 0 "DRIVE_OFF" 1 "DRIVE_ON" 3 "LOAD_SHED" 2 "SHUTTING_DOWN" 15 "SNA" ;
VAL_ 257 GTW_epasTuneRequest 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "SNA" ;
VAL_ 264 DI_torqueDriver -4096 "SNA" ;
VAL_ 264 DI_torqueMotor -4096 "SNA" ;
VAL_ 264 DI_soptState 7 "SOPT_TEST_SNA" 4 "SOPT_TEST_NOT_RUN" 3 "SOPT_TEST_PASSED" 2 "SOPT_TEST_FAILED" 1 "SOPT_TEST_IN_PROGRESS" 0 "SOPT_PRE_TEST" ;
VAL_ 264 DI_motorRPM -32768 "SNA" ;
VAL_ 264 DI_pedalPos 255 "SNA" ;
VAL_ 280 DI_torqueEstimate -2048 "SNA" ;
VAL_ 280 DI_gear 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ;
VAL_ 280 DI_brakePedal 1 "Applied" 0 "Not_applied" ;
VAL_ 280 DI_vehicleSpeed 4095 "SNA" ;
VAL_ 280 DI_gearRequest 7 "DI_GEAR_SNA" 4 "DI_GEAR_D" 3 "DI_GEAR_N" 2 "DI_GEAR_R" 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" ;
VAL_ 280 DI_torqueInterfaceFailure 1 "TORQUE_INTERFACE_FAILED" 0 "TORQUE_INTERFACE_NORMAL" ;
VAL_ 280 DI_brakePedalState 3 "SNA" 2 "INVALID" 1 "ON" 0 "OFF" ;
VAL_ 280 DI_epbParkRequest 1 "Park_requested" 0 "No_request" ;
VAL_ 280 DI_epbInterfaceReady 1 "EPB_INTERFACE_READY" 0 "EPB_INTERFACE_NOT_READY" ;
VAL_ 309 ESP_absBrakeEvent 1 "ACTIVE" 0 "NOT_ACTIVE" ;
VAL_ 309 ESP_brakeDiscWipingActive 1 "ACTIVE" 0 "INACTIVE" ;
VAL_ 309 ESP_brakeLamp 0 "OFF" 1 "ON" ;
VAL_ 309 ESP_espFaultLamp 0 "OFF" 1 "ON" ;
VAL_ 309 ESP_espLampFlash 1 "FLASH" 0 "OFF" ;
VAL_ 309 ESP_hillStartAssistActive 1 "ACTIVE" 0 "INACTIVE" 2 "NOT_AVAILABLE" 3 "SNA" ;
VAL_ 309 ESP_absFaultLamp 0 "OFF" 1 "ON" ;
VAL_ 309 ESP_espOffLamp 0 "OFF" 1 "ON" ;
VAL_ 309 ESP_stabilityControlSts 2 "ENGAGED" 3 "FAULTED" 5 "INIT" 4 "NOT_CONFIGURED" 0 "OFF" 1 "ON" ;
VAL_ 309 ESP_tcLampFlash 1 "FLASH" 0 "OFF" ;
VAL_ 760 MCU_speedLimitUnits 1 "KPH" 0 "MPH" ;
VAL_ 760 MCU_userSpeedOffsetUnits 1 "KPH" 0 "MPH" ;
VAL_ 643 AirTemp_Insd 255 "SNA" ;
VAL_ 643 AirTemp_Outsd 254 "INIT" 255 "SNA" ;
VAL_ 643 Bckl_Sw_RL_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ;
VAL_ 643 Bckl_Sw_RM_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ;
VAL_ 643 Bckl_Sw_RR_Stat_SAM_R 2 "FLT" 1 "NOT" 0 "OK" 3 "SNA" ;
VAL_ 643 DL_RLtch_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 DrRLtch_FL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 DrRLtch_FR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 DrRLtch_RL_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 DrRLtch_RR_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 EngHd_Stat 1 "CLS" 0 "NDEF0" 2 "OPN" 3 "SNA" ;
VAL_ 643 LgtSens_Night 0 "DAY" 1 "NIGHT" ;
VAL_ 643 MPkBrk_Stat 1 "ENGG" 0 "RELS" ;
VAL_ 643 RevGr_Engg 0 "DISENGG" 1 "ENGG" 2 "NDEF2" 3 "SNA" ;
VAL_ 643 StW_Cond_Stat 3 "BLINK" 1 "NDEF1" 0 "OFF" 2 "ON" ;
VAL_ 643 Trlr_Stat 2 "NDEF2" 0 "NONE" 1 "OK" 3 "SNA" ;
VAL_ 792 BOOT_STATE 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 CERRD 1 "CAN error detect" 0 "no Can error detected" ;
VAL_ 792 DAY 1 "Init" 0 "SNA" ;
VAL_ 792 DOOR_STATE_FL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 DOOR_STATE_FR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 DOOR_STATE_FrontTrunk 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 DOOR_STATE_RL 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 DOOR_STATE_RR 2 "Init" 3 "SNA" 0 "closed" 1 "open" ;
VAL_ 792 GTW_updateInProgress 1 "IN_PROGRESS" 2 "IN_PROGRESS_NOT_USED" 3 "IN_PROGRESS_SNA" 0 "NOT_IN_PROGRESS" ;
VAL_ 792 Hour 30 "Init" 31 "SNA" ;
VAL_ 792 MCU_factoryMode 1 "FACTORY_MODE" 0 "NORMAL_MODE" ;
VAL_ 792 MCU_transportModeOn 0 "NORMAL_MODE" ;
VAL_ 792 MINUTE 62 "Init" 63 "SNA" ;
VAL_ 792 MONTH 1 "Init" 15 "SNA" ;
VAL_ 792 SECOND 62 "Init" 63 "SNA" ;
VAL_ 792 YEAR 126 "Init" 127 "SNA" ;
VAL_ 872 DI_aebState 2 "ENABLED" 4 "FAULT" 7 "SNA" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ;
VAL_ 872 DI_analogSpeed 4095 "SNA" ;
VAL_ 872 DI_cruiseState 2 "ENABLED" 5 "FAULT" 0 "OFF" 4 "OVERRIDE" 7 "PRE_CANCEL" 6 "PRE_FAULT" 1 "STANDBY" 3 "STANDSTILL" ;
VAL_ 872 DI_digitalSpeed 255 "SNA" ;
VAL_ 872 DI_immobilizerState 2 "AUTHENTICATING" 3 "DISARMED" 6 "FAULT" 4 "IDLE" 0 "INIT_SNA" 1 "REQUEST" 5 "RESET" ;
VAL_ 872 DI_speedUnits 1 "KPH" 0 "MPH" ;
VAL_ 872 DI_state 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ;
VAL_ 872 DI_systemState 3 "ABORT" 4 "ENABLE" 2 "FAULT" 1 "STANDBY" 0 "UNAVAILABLE" ;
VAL_ 872 DI_vehicleHoldState 2 "BLEND_IN" 4 "BLEND_OUT" 6 "FAULT" 7 "INIT" 5 "PARK" 1 "STANDBY" 3 "STANDSTILL" 0 "UNAVAILABLE" ;
VAL_ 880 EPAS_currentTuneMode 1 "DM_COMFORT" 3 "DM_SPORT" 2 "DM_STANDARD" 0 "FAIL_SAFE_DEFAULT" 4 "RWD_COMFORT" 6 "RWD_SPORT" 5 "RWD_STANDARD" 7 "UNAVAILABLE" ;
VAL_ 880 EPAS_eacErrorCode 14 "EAC_ERROR_EPB_INHIBIT" 3 "EAC_ERROR_HANDS_ON" 7 "EAC_ERROR_HIGH_ANGLE_RATE_REQ" 9 "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY" 6 "EAC_ERROR_HIGH_ANGLE_REQ" 8 "EAC_ERROR_HIGH_ANGLE_SAFETY" 10 "EAC_ERROR_HIGH_MMOT_SAFETY" 11 "EAC_ERROR_HIGH_TORSION_SAFETY" 0 "EAC_ERROR_IDLE" 12 "EAC_ERROR_LOW_ASSIST" 2 "EAC_ERROR_MAX_SPEED" 1 "EAC_ERROR_MIN_SPEED" 13 "EAC_ERROR_PINION_VEL_DIFF" 4 "EAC_ERROR_TMP_FAULT" 5 "EAR_ERROR_MAX_STEER_DELTA" 15 "SNA" ;
VAL_ 880 EPAS_eacStatus 2 "EAC_ACTIVE" 1 "EAC_AVAILABLE" 3 "EAC_FAULT" 0 "EAC_INHIBITED" 4 "SNA" ;
VAL_ 880 EPAS_handsOnLevel 0 "0" 1 "1" 2 "2" 3 "3" ;
VAL_ 880 EPAS_steeringFault 1 "FAULT" 0 "NO_FAULT" ;
VAL_ 880 EPAS_steeringRackForce 1022 "NOT_IN_SPEC" 1023 "SNA" ;
VAL_ 880 EPAS_steeringReduced 0 "NORMAL_ASSIST" 1 "REDUCED_ASSIST" ;
VAL_ 880 EPAS_torsionBarTorque 0 "SEE_SPECIFICATION" 4095 "SNA" 4094 "UNDEFINABLE_DATA" ;
VAL_ 904 MCU_clusterReadyForDrive 0 "NO_SNA" 1 "YES" ;
VAL_ 1160 DAS_steeringAngleRequest 16384 "ZERO_ANGLE" ;
VAL_ 1160 DAS_steeringControlType 1 "ANGLE_CONTROL" 3 "DISABLED" 0 "NONE" 2 "RESERVED" ;
VAL_ 1160 DAS_steeringHapticRequest 1 "ACTIVE" 0 "IDLE" ;
CM_ "CHFFR_METRIC 1160 DAS_steeringAngleRequest STEER_ANGLE 0.1098666 180; CHFFR_METRIC 264 DI_motorRPM ENGINE_RPM 1 0";

@ -0,0 +1,197 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX
BO_ 1552 CONTAINS_LRES_SPEED: 8 XXX
SG_ SPEED_LOWRES : 16|8@1+ (1,0) [0|255] "km/h?" XXX
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
BO_ 452 ENGINE: 8 XXX
SG_ ENGINE_RPM : 7|16@0+ (1,0) [0|65535] "rpm" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
SG_ DIFFERENT_EACH_RIDE : 23|8@0+ (1,0) [0|255] "" XXX
SG_ A_DECREASING_VALUE : 39|8@0+ (1,0) [0|255] "" XXX
BO_ 37 STEERING: 8 XXX
SG_ STEER_DIRECTION : 3|1@0+ (1,0) [0|1] "" XXX
SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|255] "" XXX
SG_ NEW_SIGNAL_4 : 42|2@0- (1,0) [0|3] "" XXX
SG_ NEW_SIGNAL_2 : 44|2@0- (1,0) [0|255] "" XXX
SG_ NEW_SIGNAL_3 : 46|2@0- (1,0) [0|3] "" XXX
SG_ STEER_ANGLE : 2|11@0- (1,0) [-350|350] "" XXX
BO_ 36 ACCELERATIONS: 8 XXX
SG_ ACC_LAT_CLEAN : 2|11@0- (1,0) [0|255] "" XXX
SG_ ACC_LATERAL : 63|8@0- (1,0) [0|255] "" XXX
SG_ ACC_FRONT_BACK_1 : 31|8@0- (1,0) [0|255] "" XXX
SG_ ACC_FRONT_BACK_2 : 47|8@0- (1,0) [0|255] "" XXX
BO_ 947 LOW_RES_INDICATORS: 8 XXX
SG_ LOW_RES_ACC_PEDAL : 23|7@0+ (1,0) [0|63] "" XXX
SG_ LOW_RES_RPM : 7|16@0+ (1,0) [0|255] "rpm" XXX
BO_ 955 BRAKING_PLUS_OTHER: 8 XXX
SG_ IS_BRAKING_2 : 0|1@0+ (1,0) [0|1] "" XXX
SG_ ENGINE_TEMPERATURE : 23|8@0+ (1,0) [0|255] "" XXX
SG_ MAYBE_CLUTCH : 13|1@0+ (1,0) [0|1] "" XXX
BO_ 1595 CONTAINS_TIME: 8 XXX
SG_ TIME_ON : 55|16@0+ (0.1,0) [0|65535] "s" XXX
SG_ BETWEEN_RIDES : 7|32@0+ (1,0) [0|4294967295] "" XXX
BO_ 170 WHEELS_SPEEDS: 8 XXX
SG_ FRONT_LEFT_WHEEL_SPEED : 23|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX
SG_ REAR_RIGHT_WHEEL_SPEED : 39|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX
SG_ REAR_LEFT_WHEEL_SPEED : 55|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX
SG_ FRONT_RIGHT_WHEEL_SPEED : 7|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX
BO_ 180 VEHICLE_DYNAMICS: 8 XXX
SG_ WIERD_STUFF : 8|2@1+ (1,0) [0|3] "" XXX
SG_ VEHICLE_SPEED : 47|16@0+ (0.01,0) [0|255] "km/h" XXX
SG_ SPEED_MOD_256 : 63|8@0- (1,0) [0|255] "" XXX
SG_ MAYBE_DISTANCE_MOD_256 : 39|8@0+ (1,0) [0|255] "" XXX
BO_ 186 NEW_MSG_9: 8 XXX
SG_ NEW_SIGNAL_2 : 31|8@0+ (1,0) [0|255] "" XXX
BO_ 426 NEW_MSG_5: 8 XXX
SG_ CONSTANT : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 906 BOOLS: 8 XXX
SG_ MAY_CONTAIN_LIGHTS : 7|4@0+ (1,0) [0|127] "" XXX
SG_ NEW_SIGNAL_1 : 3|1@0+ (1,0) [0|1] "" XXX
SG_ NEW_SIGNAL_2 : 2|1@0+ (1,0) [0|1] "" XXX
SG_ NEW_SIGNAL_3 : 1|1@0+ (1,0) [0|1] "" XXX
SG_ MOVEMENT_START_TRIGGER : 0|1@0+ (1,0) [0|1] "" XXX
BO_ 979 LOW_RES_ACCELERATOR: 8 XXX
SG_ VERY_LRES_ACC : 7|16@0+ (1,0) [0|65535] "" XXX
BO_ 1600 SLOW_VARIABLE_INFOS: 8 XXX
SG_ CHANGES_EACH_RIDE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ INCREASING_VALUE_FUEL : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 1568 DOORS: 8 XXX
SG_ KEY_ACC : 36|1@0+ (1,0) [0|1] "" XXX
SG_ KEY_ON : 37|1@0+ (1,0) [0|1] "" XXX
SG_ KEY_INSERT : 46|1@0+ (1,0) [0|1] "" XXX
SG_ NOT_ON : 63|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_RIGHT : 44|1@0+ (1,0) [0|3] "" XXX
SG_ DOOR_TRUNK : 41|1@1+ (1,0) [0|3] "" XXX
SG_ DOOR_LEFT : 45|1@0+ (1,0) [0|255] "" XXX
SG_ HANDBRAKE : 60|1@0+ (1,0) [0|3] "" XXX
SG_ NEW_SIGNAL_1 : 4|1@0+ (1,0) [0|1] "" XXX
SG_ DRIVER_SEATBELT : 62|1@0+ (1,0) [0|1] "" XXX
SG_ TRIGGER_BOOL : 15|1@0+ (1,0) [0|1] "" XXX
BO_ 705 COMMAND: 8 XXX
SG_ NOT_ACCELERATING_PEDAL : 3|1@1+ (1,0) [0|1] "" XXX
SG_ ACC_PEDAL_SENSOR : 55|16@0+ (1,0) [0|65535] "" XXX
SG_ ACC_COMMAND : 31|16@0- (1,0) [0|7] "" XXX
SG_ ACC_PEDAL_MEAN : 15|16@0- (1,0) [0|255] "" XXX
SG_ NEGATIVE_COMMAND_OFFSET : 47|8@0- (1,0) [0|255] "" XXX
BO_ 928 STEER2_MAYBE: 8 XXX
SG_ NEW_SIGNAL_1 : 13|6@0+ (1,0) [0|63] "" XXX
SG_ NEW_SIGNAL_2 : 60|5@0+ (1,0) [0|31] "" XXX
SG_ NEW_SIGNAL_4 : 5|6@0+ (1,0) [0|255] "" XXX
SG_ NEW_SIGNAL_3 : 46|7@0+ (1,0) [0|15] "" XXX
BO_ 896 LONG_TERM_2: 8 XXX
SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX
BO_ 944 LONG_TERM_MSG: 8 XXX
SG_ LONG_TERM_SIGN : 31|8@0+ (1,0) [0|255] "" XXX
BO_ 1553 TOTAL_DIST: 8 XXX
SG_ TOTAL_DISTANCE : 55|16@0+ (1,0) [0|65535] "" XXX
BO_ 1572 WHY_THESE_VALUES: 8 XXX
BO_ 1555 BETWEEN_RIDES_CHANGE_1: 8 XXX
SG_ BETWEEN_RIDES : 23|1@0+ (1,0) [0|1] "" XXX
BO_ 1090 ASYNC_MSG_ACK: 8 XXX
SG_ NEW_SIGNAL_1 : 13|2@0+ (1,0) [0|1] "" XXX
SG_ NEW_SIGNAL_2 : 23|1@0+ (1,0) [0|1] "" XXX
BO_ 1592 NEW_MSG_14: 8 XXX
SG_ DOORS_LOCKED2 : 20|1@0+ (1,0) [0|1] "" XXX
SG_ DOORS_LOCKED1 : 16|1@0+ (1,0) [0|1] "" XXX
BO_ 608 NEW_MSG_6: 8 XXX
SG_ VERY_SMALL_SIGNAL2 : 56|1@0+ (1,0) [0|255] "" XXX
SG_ VERY_SMALL_SIGNAL1 : 0|1@0+ (1,0) [0|1] "" XXX
BO_ 945 BETWEEN_RIDES_CHANGES_2: 8 XXX
SG_ BETWEEN_RIDES : 24|1@0+ (1,0) [0|65535] "" XXX
CM_ SG_ 1552 SPEED_LOWRES "Negative values to check";
CM_ SG_ 452 CHECKSUM "Follows path of RPMs but more precise & 1 byte only";
CM_ SG_ 452 A_DECREASING_VALUE "stabilizes to 62 after ~10 mins";
CM_ SG_ 37 STEER_DIRECTION "Could be intended as 12 bit steering angle";
CM_ SG_ 37 STEER_ANGLE "can convert to degrees (imprecise) or percentage of max amplitude";
CM_ SG_ 36 ACC_FRONT_BACK_1 "more likely up-down";
CM_ SG_ 36 ACC_FRONT_BACK_2 "more likely front-back";
CM_ SG_ 947 LOW_RES_ACC_PEDAL "Follows rather closely other acceleration commands";
CM_ SG_ 947 LOW_RES_RPM "Mabe used for onboard display?";
CM_ SG_ 955 MAYBE_CLUTCH "might be related to shifting gears";
CM_ SG_ 1595 TIME_ON "Time since last ignition, tenth of seconds";
CM_ SG_ 1595 BETWEEN_RIDES "the fourth byte (at least) changes between rides";
CM_ SG_ 180 WIERD_STUFF "Might be a signed value on the whole two bytes (sometimes all set)";
CM_ SG_ 180 VEHICLE_SPEED "Roughly 2 seconds before wheel speeds";
CM_ SG_ 180 SPEED_MOD_256 "One byte speed, a bit before vehicle speed";
CM_ SG_ 180 MAYBE_DISTANCE_MOD_256 "Looks like measure for distance or wheel angle";
CM_ SG_ 906 MOVEMENT_START_TRIGGER "trigger of when speed becomes != 0";
CM_ SG_ 979 VERY_LRES_ACC "Power used by engine? moves alongside speed, very low res, goes from 0 to 9 max?";
CM_ SG_ 1600 CHANGES_EACH_RIDE "Small decrementation during some rides, possibly long term fuel";
CM_ SG_ 1600 INCREASING_VALUE_FUEL "Fuel/distance? Average fuel consumption?";
CM_ SG_ 705 NOT_ACCELERATING_PEDAL "Looks like opposite of accelerating bit";
CM_ SG_ 705 ACC_PEDAL_SENSOR "similar to pedal sensor maybe checksum.";
CM_ SG_ 705 ACC_COMMAND "Similar to other pedal indicator., cleaner, must be sent back to engine";
CM_ SG_ 705 ACC_PEDAL_MEAN "Actual sensor for pedal (works when engine off)";
CM_ SG_ 705 NEGATIVE_COMMAND_OFFSET "Mysterious for now";
CM_ SG_ 928 NEW_SIGNAL_1 "Very slow changing noisy value, 45-49 in 10 min";
CM_ SG_ 928 NEW_SIGNAL_2 "Other very slow changing 24-26 in 10 min";
CM_ SG_ 928 NEW_SIGNAL_4 "Inconsistent across rides";
CM_ SG_ 896 NEW_SIGNAL_1 "there is a difference at the beginning of 2017-10-31--12-04-05";
CM_ SG_ 1553 TOTAL_DISTANCE "Probably also contains the previous/two previous bytes but can't confirm";
CM_ SG_ 945 BETWEEN_RIDES "Might be others in the same message. at least this one";
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 452 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 955 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";

@ -0,0 +1,261 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX
BO_ 528 TRACK_A_0: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 529 TRACK_A_1: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 530 TRACK_A_2: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 531 TRACK_A_3: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 532 TRACK_A_4: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 533 TRACK_A_5: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 534 TRACK_A_6: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 535 TRACK_A_7: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 536 TRACK_A_8: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 537 TRACK_A_9: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 538 TRACK_A_10: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 539 TRACK_A_11: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 540 TRACK_A_12: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 541 TRACK_A_13: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 542 TRACK_A_14: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 543 TRACK_A_15: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ LAT_DIST : 31|11@0- (0.04,0) [-50|50] "m" XXX
SG_ LONG_DIST : 15|13@0+ (0.04,0) [0|300] "m" XXX
SG_ NEW_TRACK : 36|1@0+ (1,0) [0|1] "" XXX
SG_ REL_SPEED : 47|12@0- (0.025,0) [-100|100] "m/s" XXX
SG_ VALID : 48|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 544 TRACK_B_0: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 545 TRACK_B_1: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 546 TRACK_B_2: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 547 TRACK_B_3: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 548 TRACK_B_4: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 549 TRACK_B_5: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 550 TRACK_B_6: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 551 TRACK_B_7: 8 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 552 TRACK_B_8: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 553 TRACK_B_9: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 554 TRACK_B_10: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 555 TRACK_B_11: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 556 TRACK_B_12: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 557 TRACK_B_13: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 558 TRACK_B_14: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX
BO_ 559 TRACK_B_15: 6 XXX
SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX
SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX
SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX

@ -0,0 +1,206 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX DSU HCU EPS IPAS
BO_ 36 KINEMATICS: 8 XXX
SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX
SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX
SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX
BO_ 166 BRAKE: 8 XXX
SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX
SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX
BO_ 170 WHEEL_SPEEDS: 8 XXX
SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX
BO_ 180 SPEED: 8 XXX
SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX
BO_ 295 GEAR_PACKET: 8 XXX
SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX
SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX
BO_ 466 PCM_CRUISE: 8 XXX
SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX
SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX
SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 550 BRAKE_MODULE: 8 XXX
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
BO_ 552 ACCELEROMETER: 8 XXX
SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX
SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX
BO_ 560 BRAKE_MODULE2: 7 XXX
SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX
BO_ 581 GAS_PEDAL: 8 XXX
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 610 EPS_STATUS: 8 EPS
SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 614 STEERING_IPAS: 8 IPAS
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 643 PRE_COLLISION: 8 XXX
BO_ 740 STEERING_LKA: 8 XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX
SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX
SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX
BO_ 742 LEAD_INFO: 8 DSU
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU
SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU
SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
BO_ 37 STEER_ANGLE_SENSOR: 8 XXX
SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX
SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX
SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX
BO_ 467 PCM_CRUISE_2: 8 XXX
SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX
SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 921 PCM_CRUISE_SM: 8 XXX
SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX
SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX
SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX
BO_ 951 ESP_CONTROL: 8 ESP
SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX
SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
BO_ 1042 LKAS_HUD: 8 XXX
SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX
SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX
SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX
SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX
SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX
SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX
SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
BO_ 1568 SEATS_DOORS: 8 XXX
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX
CM_ SG_ 36 ACCEL_Y "unit is tbd";
CM_ SG_ 36 YAW_RATE "verify";
CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd";
CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors";
CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force";
CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?";
CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered";
CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque";
CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value";
CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active";
CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set";
CM_ SG_ 37 STEER_RATE "factor is tbd";
CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect";
CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph";
CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit";
CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces";
CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts";
VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ;
VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ;
VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
VAL_ 610 LKA_STATE 50 "temporary_fault";
VAL_ 614 STATE 3 "enabled" 1 "disabled";
VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left";
VAL_ 1553 UNITS 1 "km" 2 "miles";
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ;
VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none";
VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none";
VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted";
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";

@ -0,0 +1,204 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX DSU HCU EPS IPAS
BO_ 36 KINEMATICS: 8 XXX
SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX
SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX
SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX
BO_ 166 BRAKE: 8 XXX
SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX
SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX
BO_ 170 WHEEL_SPEEDS: 8 XXX
SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX
BO_ 180 SPEED: 8 XXX
SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX
BO_ 466 PCM_CRUISE: 8 XXX
SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX
SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX
SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 548 BRAKE_MODULE: 8 XXX
SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX
SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX
BO_ 552 ACCELEROMETER: 8 XXX
SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX
SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX
BO_ 560 BRAKE_MODULE2: 7 XXX
SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX
BO_ 705 GAS_PEDAL: 8 XXX
SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX
SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 610 EPS_STATUS: 5 EPS
SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
BO_ 614 STEERING_IPAS: 8 IPAS
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 643 PRE_COLLISION: 8 XXX
BO_ 740 STEERING_LKA: 8 XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX
SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX
SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX
BO_ 742 LEAD_INFO: 8 DSU
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU
SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU
SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
BO_ 37 STEER_ANGLE_SENSOR: 8 XXX
SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX
SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX
SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX
BO_ 467 PCM_CRUISE_2: 8 XXX
SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX
SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 921 PCM_CRUISE_SM: 8 XXX
SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX
SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX
SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX
BO_ 951 ESP_CONTROL: 8 ESP
SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX
SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX
BO_ 956 GEAR_PACKET: 8 XXX
SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
BO_ 1042 LKAS_HUD: 8 XXX
SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX
SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX
SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX
SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX
SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX
SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX
SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
BO_ 1568 SEATS_DOORS: 8 XXX
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX
CM_ SG_ 36 ACCEL_Y "unit is tbd";
CM_ SG_ 36 YAW_RATE "verify";
CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd";
CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors";
CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force";
CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
CM_ SG_ 560 BRAKE_PRESSED "another brake press?";
CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered";
CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque";
CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value";
CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active";
CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set";
CM_ SG_ 37 STEER_RATE "factor is tbd";
CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect";
CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph";
CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit";
CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces";
CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ;
VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ;
VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
VAL_ 610 LKA_STATE 50 "temporary_fault";
VAL_ 614 STATE 3 "enabled" 1 "disabled";
VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left";
VAL_ 1553 UNITS 1 "km" 2 "miles";
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ;
VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none";
VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none";
VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted";
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";

@ -0,0 +1,203 @@
VERSION ""
NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_
BS_:
BU_: XXX DSU HCU EPS IPAS
BO_ 36 KINEMATICS: 8 XXX
SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX
SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX
SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX
BO_ 166 BRAKE: 8 XXX
SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX
SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX
BO_ 170 WHEEL_SPEEDS: 8 XXX
SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX
SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX
BO_ 180 SPEED: 8 XXX
SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX
BO_ 466 PCM_CRUISE: 8 XXX
SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX
SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX
SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 550 BRAKE_MODULE: 8 XXX
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
BO_ 552 ACCELEROMETER: 8 XXX
SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX
SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX
BO_ 560 BRAKE_MODULE2: 7 XXX
SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX
BO_ 581 GAS_PEDAL: 8 XXX
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 610 EPS_STATUS: 5 EPS
SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
BO_ 614 STEERING_IPAS: 8 IPAS
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 643 PRE_COLLISION: 8 XXX
BO_ 740 STEERING_LKA: 8 XXX
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX
SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX
SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX
SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX
BO_ 742 LEAD_INFO: 8 DSU
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU
SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU
SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
BO_ 37 STEER_ANGLE_SENSOR: 8 XXX
SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX
SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX
SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX
BO_ 467 PCM_CRUISE_2: 8 XXX
SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX
SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 921 PCM_CRUISE_SM: 8 XXX
SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX
SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX
SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX
BO_ 951 ESP_CONTROL: 8 ESP
SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX
SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX
BO_ 956 GEAR_PACKET: 8 XXX
SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
BO_ 1042 LKAS_HUD: 8 XXX
SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX
SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX
SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX
SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX
SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX
SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX
SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX
SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX
SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
BO_ 1568 SEATS_DOORS: 8 XXX
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX
SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX
CM_ SG_ 36 ACCEL_Y "unit is tbd";
CM_ SG_ 36 YAW_RATE "verify";
CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd";
CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors";
CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force";
CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?";
CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered";
CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque";
CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value";
CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active";
CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set";
CM_ SG_ 37 STEER_RATE "factor is tbd";
CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect";
CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph";
CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit";
CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces";
CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts";
VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ;
VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ;
VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
VAL_ 610 LKA_STATE 50 "temporary_fault";
VAL_ 614 STATE 3 "enabled" 1 "disabled";
VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
VAL_ 1553 UNITS 1 "km" 2 "miles";
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ;
VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none";
VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none";
VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted";
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

@ -1 +0,0 @@
Subproject commit 3cab37297566962fd6e48a674db3e1f6de8fa4da

12
panda/.gitignore vendored

@ -0,0 +1,12 @@
*.pyc
.*.swp
.*.swo
*.o
a.out
*~
.#*
dist/
pandacan.egg-info/
board/obj/
examples/output.csv
.DS_Store

@ -0,0 +1,20 @@
language: python
cache:
directories:
- build/commaai/panda/boardesp/esp-open-sdk/crosstool-NG
addons:
apt:
packages:
- gcc-arm-none-eabi
- libnewlib-arm-none-eabi
- gperf
- texinfo
- help2man
script:
- python setup.py install
- pushd board && make bin && popd
- pushd boardesp && git clone --recursive https://github.com/pfalcon/esp-open-sdk.git && pushd esp-open-sdk && git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec && LD_LIBRARY_PATH="" make STANDALONE=y && popd && popd
- pushd boardesp && make user1.bin && popd

@ -0,0 +1,7 @@
Copyright (c) 2016, Comma.ai, Inc.
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

@ -0,0 +1,89 @@
Welcome to panda
======
[panda](http://github.com/commaai/panda) is the nicest universal car interface ever.
<a href="https://panda.comma.ai"><img src="https://github.com/commaai/panda/blob/master/panda.png">
<img src="https://github.com/commaai/panda/blob/master/buy.png"></a>
It supports 3x CAN, 2x LIN, and 1x GMLAN. It also charges a phone. On the computer side, it has both USB and Wi-Fi.
It uses an [STM32F413](http://www.st.com/en/microcontrollers/stm32f413-423.html?querycriteria=productId=LN2004) for low level stuff and an [ESP8266](https://en.wikipedia.org/wiki/ESP8266) for Wi-Fi. They are connected over high speed SPI, so the panda is actually capable of dumping the full contents of the busses over Wi-Fi, unlike every other dongle on amazon. ELM327 is weak, panda is strong.
It is 2nd gen hardware, reusing code and parts from the [NEO](https://github.com/commaai/neo) interface board.
[![Build Status](https://travis-ci.org/commaai/panda.svg?branch=master)](https://travis-ci.org/commaai/panda)
Usage
------
To install the library:
```
# pip install pandacan
```
See [this class](https://github.com/commaai/panda/blob/master/python/__init__.py#L80) for how to interact with the panda.
For example, to receive CAN messages:
```
>>> from panda import Panda
>>> panda = Panda()
>>> panda.can_recv()
```
And to send one on bus 0:
```
>>> panda.can_send(0x1aa, "message", 0)
```
More examples coming soon
Software interface support
------
As a universal car interface, it should support every reasonable software interface.
- User space ([done](https://github.com/commaai/panda/tree/master/python))
- socketcan in kernel ([alpha](https://github.com/commaai/panda/tree/master/drivers/linux))
- ELM327 ([done](https://github.com/commaai/panda/blob/master/boardesp/elm327.c))
- Windows J2534 ([alpha](https://github.com/commaai/panda/tree/master/drivers/windows))
Directory structure
------
- board -- Code that runs on the STM32
- boardesp -- Code that runs on the ESP8266
- drivers -- Drivers (not needed for use with python)
- python   -- Python userspace library for interfacing with the panda
- tests -- Tests and helper programs for panda
Programming (over USB)
------
[Programming the Board (STM32)](board/README.md)
[Programming the ESP](boardesp/README.md)
Debugging
------
To print out the serial console from the STM32, run tests/debug_console.py
To print out the serial console from the ESP8266, run PORT=1 tests/debug_console.py
Safety Model
------
When a panda powers up, by default it's in "SAFETY_NOOUTPUT" mode. While in no output mode, the buses are also forced to be silent. In order to send messages, you have to select a safety mode. Currently, setting safety modes is only supported over USB.
Safety modes can also optionally support "controls_allowed", which allows or blocks a subset of messages based on a piece of state in the board.
Hardware
------
Check out the hardware [guide](https://github.com/commaai/panda/blob/master/docs/guide.pdf)
Licensing
------
panda software is released under the MIT license unless otherwise specified.

@ -0,0 +1,31 @@
** Projects **
== ELM327 Emulator ==
Write an elm327 emulator in boardesp/elm327.c and make it work with Torque
You'll find a start at this in the "elm327" branch.
== socketcan Kernel Driver ==
Write a kernel driver version of lib/panda.py that exposes the Panda on socketcan and makes it work with those tools.
You may want to switch to interrupt endpoint first. Should LIN be exposed as a serial interface?
== Windows J2534 DLL ==
Write a Windows DLL that exposes the J2534 API.
Will make the Panda work with car diagnostic software.
** Refactors **
== USB Interrupt Endpoint ==
Switch USB to use an interrupt endpoint instead of a bulk endpoint for can recv
== WebSocket Support ==
Add CAN streaming over WebSocket to the ELM code in addition to the UDP pipe.

@ -0,0 +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))
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.)

@ -0,0 +1 @@
v1.0.3

@ -0,0 +1 @@
from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st

@ -0,0 +1,8 @@
PROJ_NAME = panda
CFLAGS = -g -Wall
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m4
CFLAGS += -mhard-float -DSTM32F4 -DSTM32F413xx
STARTUP_FILE = startup_stm32f413xx
include build.mk

@ -0,0 +1,9 @@
# :set noet
PROJ_NAME = comma
CFLAGS = -g -Wall
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx
STARTUP_FILE = startup_stm32f205xx
include build.mk

@ -0,0 +1,41 @@
Dependencies
--------
**Mac**
```
./get_sdk_mac.sh
```
**Debian / Ubuntu**
```
./get_sdk.sh
```
Programming
----
**Panda**
```
make
```
**NEO**
```
make -f Makefile.legacy
```
Troubleshooting
----
If your panda will not flash and is quickly blinking a single Green LED, use:
```
make recover
```
[dfu-util](http://github.com/dsigma/dfu-util.git) for flashing

@ -0,0 +1,91 @@
#define BOOTSTUB
#include "config.h"
#include "obj/gitversion.h"
#ifdef STM32F4
#define PANDA
#include "stm32f4xx.h"
#include "stm32f4xx_hal_gpio_ex.h"
#else
#include "stm32f2xx.h"
#include "stm32f2xx_hal_gpio_ex.h"
#endif
#include "libc.h"
#include "provision.h"
#include "drivers/drivers.h"
#include "drivers/llgpio.h"
#include "gpio.h"
#include "drivers/spi.h"
#include "drivers/usb.h"
//#include "drivers/uart.h"
int puts(const char *a) { return 0; }
void puth(unsigned int i) {}
#include "crypto/rsa.h"
#include "crypto/sha.h"
#include "obj/cert.h"
#include "spi_flasher.h"
void __initialize_hardware_early() {
early();
}
void fail() {
soft_flasher_start();
}
// know where to sig check
extern void *_app_start[];
int main() {
__disable_irq();
clock_init();
detect();
if (revision == PANDA_REV_C) {
set_usb_power_mode(USB_POWER_CLIENT);
}
if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) {
enter_bootloader_mode = 0;
soft_flasher_start();
}
// validate length
int len = (int)_app_start[0];
if ((len < 8) || (len > (0x1000000 - 0x4000 - 4 - RSANUMBYTES))) goto fail;
// compute SHA hash
uint8_t digest[SHA_DIGEST_SIZE];
SHA_hash(&_app_start[1], len-4, digest);
// verify RSA signature
if (RSA_verify(&release_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) {
goto good;
}
// allow debug if built from source
#ifdef ALLOW_DEBUG
if (RSA_verify(&debug_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) {
goto good;
}
#endif
// here is a failure
fail:
fail();
return 0;
good:
// jump to flash
((void(*)()) _app_start[1])();
return 0;
}

@ -0,0 +1,59 @@
CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O0
CFLAGS += -Tstm32_flash.ld
CC = arm-none-eabi-gcc
OBJCOPY = arm-none-eabi-objcopy
OBJDUMP = arm-none-eabi-objdump
ifeq ($(RELEASE),1)
CERT = ../../pandaextra/certs/release
else
# enable the debug cert
CERT = ../certs/debug
CFLAGS += "-DALLOW_DEBUG"
endif
DFU_UTIL = "dfu-util"
# this no longer pushes the bootstub
flash: obj/$(PROJ_NAME).bin
PYTHONPATH=../ python -c "from panda import Panda; Panda().flash('obj/$(PROJ_NAME).bin')"
ota: obj/$(PROJ_NAME).bin
curl http://192.168.0.10/stupdate --upload-file $<
bin: obj/$(PROJ_NAME).bin
# this flashes everything
recover: obj/bootstub.$(PROJ_NAME).bin obj/$(PROJ_NAME).bin
-PYTHONPATH=../ python -c "from panda import Panda; Panda().reset(enter_bootloader=True)"
sleep 1.0
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.$(PROJ_NAME).bin
include ../common/version.mk
obj/cert.h: ../crypto/getcertheader.py
../crypto/getcertheader.py ../certs/debug.pub ../certs/release.pub > $@
obj/%.$(PROJ_NAME).o: %.c obj/cert.h obj/gitversion.h config.h drivers/*.h gpio.h libc.h provision.h safety.h safety/*.h spi_flasher.h
$(CC) $(CFLAGS) -o $@ -c $<
obj/%.$(PROJ_NAME).o: ../crypto/%.c
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(STARTUP_FILE).o: $(STARTUP_FILE).s
$(CC) $(CFLAGS) -o $@ -c $<
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o
# hack
$(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
$(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin
SETLEN=1 ../crypto/sign.py obj/code.bin $@ $(CERT)
obj/bootstub.$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/bootstub.$(PROJ_NAME).o obj/sha.$(PROJ_NAME).o obj/rsa.$(PROJ_NAME).o
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
clean:
@rm -f obj/*

@ -0,0 +1,40 @@
#ifndef PANDA_CONFIG_H
#define PANDA_CONFIG_H
//#define DEBUG
//#define DEBUG_USB
//#define DEBUG_SPI
#ifdef STM32F4
#define PANDA
#include "stm32f4xx.h"
#else
#include "stm32f2xx.h"
#endif
#define USB_VID 0xbbaa
#ifdef BOOTSTUB
#define USB_PID 0xddee
#else
#define USB_PID 0xddcc
#endif
#include <stdbool.h>
#define NULL ((void*)0)
#define COMPILE_TIME_ASSERT(pred) switch(0){case 0:case pred:;}
#define min(a,b) \
({ __typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
_a < _b ? _a : _b; })
#define max(a,b) \
({ __typeof__ (a) _a = (a); \
__typeof__ (b) _b = (b); \
_a > _b ? _a : _b; })
#define MAX_RESP_LEN 0x40
#endif

@ -0,0 +1,38 @@
// ACCEL1 = ADC10
// ACCEL2 = ADC11
// VOLT_S = ADC12
// CURR_S = ADC13
#define ADCCHAN_ACCEL0 10
#define ADCCHAN_ACCEL1 11
#define ADCCHAN_VOLTAGE 12
#define ADCCHAN_CURRENT 13
void adc_init() {
// global setup
ADC->CCR = ADC_CCR_TSVREFE | ADC_CCR_VBATE;
//ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_EOCS | ADC_CR2_DDS;
ADC1->CR2 = ADC_CR2_ADON;
// long
//ADC1->SMPR1 = ADC_SMPR1_SMP10 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13;
ADC1->SMPR1 = ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13;
}
uint32_t adc_get(int channel) {
// includes length
//ADC1->SQR1 = 0;
// select channel
ADC1->JSQR = channel << 15;
//ADC1->CR1 = ADC_CR1_DISCNUM_0;
//ADC1->CR1 = ADC_CR1_EOCIE;
ADC1->SR &= ~(ADC_SR_JEOC);
ADC1->CR2 |= ADC_CR2_JSWSTART;
while (!(ADC1->SR & ADC_SR_JEOC));
return ADC1->JDR1;
}

@ -0,0 +1,401 @@
// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE, CAN2_TX, CAN2_RX0, CAN2_SCE, CAN3_TX, CAN3_RX0, CAN3_SCE
#define ALL_CAN_SILENT 0xFF
#define ALL_CAN_BUT_MAIN_SILENT 0xFE
#define ALL_CAN_LIVE 0
int can_live = 0, pending_can_live = 0, can_loopback = 0, can_silent = ALL_CAN_SILENT;
// ********************* instantiate queues *********************
#define can_buffer(x, size) \
CAN_FIFOMailBox_TypeDef elems_##x[size]; \
can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x };
can_buffer(rx_q, 0x1000)
can_buffer(tx1_q, 0x100)
can_buffer(tx2_q, 0x100)
#ifdef PANDA
can_buffer(tx3_q, 0x100)
can_buffer(txgmlan_q, 0x100)
can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q};
#else
can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q};
#endif
// ********************* interrupt safe queue *********************
int can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
int ret = 0;
enter_critical_section();
if (q->w_ptr != q->r_ptr) {
*elem = q->elems[q->r_ptr];
if ((q->r_ptr + 1) == q->fifo_size) q->r_ptr = 0;
else q->r_ptr += 1;
ret = 1;
}
exit_critical_section();
return ret;
}
int can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) {
int ret = 0;
uint32_t next_w_ptr;
enter_critical_section();
if ((q->w_ptr + 1) == q->fifo_size) next_w_ptr = 0;
else next_w_ptr = q->w_ptr + 1;
if (next_w_ptr != q->r_ptr) {
q->elems[q->w_ptr] = *elem;
q->w_ptr = next_w_ptr;
ret = 1;
}
exit_critical_section();
if (ret == 0) puts("can_push failed!\n");
return ret;
}
void can_clear(can_ring *q) {
enter_critical_section();
q->w_ptr = 0;
q->r_ptr = 0;
exit_critical_section();
}
// assign CAN numbering
// bus num: Can bus number on ODB connector. Sent to/from USB
// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1)
// cans: Look up MCU can interface from bus number
// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc);
// bus_lookup: Translates from 'can number' to 'bus number'.
// can_num_lookup: Translates from 'bus number' to 'can number'.
// can_forwarding: Given a bus num, lookup bus num to forward to. -1 means no forward.
int can_rx_cnt = 0;
int can_tx_cnt = 0;
int can_txd_cnt = 0;
int can_err_cnt = 0;
// NEO: Bus 1=CAN1 Bus 2=CAN2
// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3
#ifdef PANDA
CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3};
uint8_t bus_lookup[] = {0,1,2};
uint8_t can_num_lookup[] = {0,1,2,-1};
int8_t can_forwarding[] = {-1,-1,-1,-1};
uint32_t can_speed[] = {5000, 5000, 5000, 333};
#define CAN_MAX 3
#else
CAN_TypeDef *cans[] = {CAN1, CAN2};
uint8_t bus_lookup[] = {1,0};
uint8_t can_num_lookup[] = {1,0};
int8_t can_forwarding[] = {-1,-1};
uint32_t can_speed[] = {5000, 5000};
#define CAN_MAX 2
#endif
#define CANIF_FROM_CAN_NUM(num) (cans[num])
#define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num])
#define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num])
// other option
/*#define CAN_QUANTA 16
#define CAN_SEQ1 13
#define CAN_SEQ2 2*/
// this is needed for 1 mbps support
#define CAN_QUANTA 8
#define CAN_SEQ1 6 // roundf(quanta * 0.875f) - 1;
#define CAN_SEQ2 1 // roundf(quanta * 0.125f);
#define CAN_PCLK 24000
// 333 = 33.3 kbps
// 5000 = 500 kbps
#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10 / (x))
void process_can(uint8_t can_number);
void can_init(uint8_t can_number) {
if (can_number == 0xff) return;
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number);
set_can_enable(CAN, 1);
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ;
while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK);
// set time quanta from defines
CAN->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) |
(CAN_BTR_TS2_0 * (CAN_SEQ2-1)) |
(can_speed_to_prescaler(can_speed[BUS_NUM_FROM_CAN_NUM(can_number)]) - 1);
// silent loopback mode for debugging
if (can_loopback) {
CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM;
}
if (can_silent & (1 << can_number)) {
CAN->BTR |= CAN_BTR_SILM;
}
// reset
CAN->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM;
#define CAN_TIMEOUT 1000000
int tmp = 0;
while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++;
if (tmp == CAN_TIMEOUT) {
puts("CAN init FAILED!!!!!\n");
puth(can_number); puts(" ");
puth(BUS_NUM_FROM_CAN_NUM(can_number)); puts("\n");
}
// accept all filter
CAN->FMR |= CAN_FMR_FINIT;
// no mask
CAN->sFilterRegister[0].FR1 = 0;
CAN->sFilterRegister[0].FR2 = 0;
CAN->sFilterRegister[14].FR1 = 0;
CAN->sFilterRegister[14].FR2 = 0;
CAN->FA1R |= 1 | (1 << 14);
CAN->FMR &= ~(CAN_FMR_FINIT);
// enable certain CAN interrupts
CAN->IER = CAN_IER_TMEIE | CAN_IER_FMPIE0;
switch (can_number) {
case 0:
NVIC_EnableIRQ(CAN1_TX_IRQn);
NVIC_EnableIRQ(CAN1_RX0_IRQn);
NVIC_EnableIRQ(CAN1_SCE_IRQn);
break;
case 1:
NVIC_EnableIRQ(CAN2_TX_IRQn);
NVIC_EnableIRQ(CAN2_RX0_IRQn);
NVIC_EnableIRQ(CAN2_SCE_IRQn);
break;
#ifdef CAN3
case 2:
NVIC_EnableIRQ(CAN3_TX_IRQn);
NVIC_EnableIRQ(CAN3_RX0_IRQn);
NVIC_EnableIRQ(CAN3_SCE_IRQn);
break;
#endif
}
// in case there are queued up messages
process_can(can_number);
}
void can_init_all() {
for (int i=0; i < CAN_MAX; i++) {
can_init(i);
}
}
void can_set_gmlan(int bus) {
if (bus == -1 || bus != can_num_lookup[3]) {
// GMLAN OFF
switch (can_num_lookup[3]) {
case 1:
puts("disable GMLAN on CAN2\n");
set_can_mode(1, 0);
bus_lookup[1] = 1;
can_num_lookup[1] = 1;
can_num_lookup[3] = -1;
can_init(1);
break;
case 2:
puts("disable GMLAN on CAN3\n");
set_can_mode(2, 0);
bus_lookup[2] = 2;
can_num_lookup[2] = 2;
can_num_lookup[3] = -1;
can_init(2);
break;
}
}
if (bus == 1) {
puts("GMLAN on CAN2\n");
// GMLAN on CAN2
set_can_mode(1, 1);
bus_lookup[1] = 3;
can_num_lookup[1] = -1;
can_num_lookup[3] = 1;
can_init(1);
} else if (bus == 2 && revision == PANDA_REV_C) {
puts("GMLAN on CAN3\n");
// GMLAN on CAN3
set_can_mode(2, 1);
bus_lookup[2] = 3;
can_num_lookup[2] = -1;
can_num_lookup[3] = 2;
can_init(2);
}
}
// CAN error
void can_sce(CAN_TypeDef *CAN) {
can_err_cnt += 1;
#ifdef DEBUG
if (CAN==CAN1) puts("CAN1: ");
if (CAN==CAN2) puts("CAN2: ");
#ifdef CAN3
if (CAN==CAN3) puts("CAN3: ");
#endif
puts("MSR:");
puth(CAN->MSR);
puts(" TSR:");
puth(CAN->TSR);
puts(" RF0R:");
puth(CAN->RF0R);
puts(" RF1R:");
puth(CAN->RF1R);
puts(" ESR:");
puth(CAN->ESR);
puts("\n");
#endif
// clear current send
CAN->TSR |= CAN_TSR_ABRQ0;
CAN->MSR = CAN->MSR;
}
// ***************************** CAN *****************************
void process_can(uint8_t can_number) {
if (can_number == 0xff) return;
enter_critical_section();
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
#ifdef DEBUG
puts("process CAN TX\n");
#endif
// check for empty mailbox
CAN_FIFOMailBox_TypeDef to_send;
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
// add successfully transmitted message to my fifo
if ((CAN->TSR & CAN_TSR_RQCP0) == CAN_TSR_RQCP0) {
can_txd_cnt += 1;
if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) {
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sTxMailBox[0].TIR;
to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) | ((CAN_BUS_RET_FLAG | bus_number) << 4);
to_push.RDLR = CAN->sTxMailBox[0].TDLR;
to_push.RDHR = CAN->sTxMailBox[0].TDHR;
can_push(&can_rx_q, &to_push);
}
if ((CAN->TSR & CAN_TSR_TERR0) == CAN_TSR_TERR0) {
#ifdef DEBUG
puts("CAN TX ERROR!\n");
#endif
}
if ((CAN->TSR & CAN_TSR_ALST0) == CAN_TSR_ALST0) {
#ifdef DEBUG
puts("CAN TX ARBITRATION LOST!\n");
#endif
}
// clear interrupt
// careful, this can also be cleared by requesting a transmission
CAN->TSR |= CAN_TSR_RQCP0;
}
if (can_pop(can_queues[bus_number], &to_send)) {
can_tx_cnt += 1;
// only send if we have received a packet
CAN->sTxMailBox[0].TDLR = to_send.RDLR;
CAN->sTxMailBox[0].TDHR = to_send.RDHR;
CAN->sTxMailBox[0].TDTR = to_send.RDTR;
CAN->sTxMailBox[0].TIR = to_send.RIR;
}
}
exit_critical_section();
}
// CAN receive handlers
// blink blue when we are receiving CAN messages
void can_rx(uint8_t can_number) {
CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number);
uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number);
while (CAN->RF0R & CAN_RF0R_FMP0) {
can_rx_cnt += 1;
// can is live
pending_can_live = 1;
// add to my fifo
CAN_FIFOMailBox_TypeDef to_push;
to_push.RIR = CAN->sFIFOMailBox[0].RIR;
to_push.RDTR = CAN->sFIFOMailBox[0].RDTR;
to_push.RDLR = CAN->sFIFOMailBox[0].RDLR;
to_push.RDHR = CAN->sFIFOMailBox[0].RDHR;
// forwarding (panda only)
#ifdef PANDA
if (can_forwarding[bus_number] != -1) {
CAN_FIFOMailBox_TypeDef to_send;
to_send.RIR = to_push.RIR | 1; // TXRQ
to_send.RDTR = to_push.RDTR;
to_send.RDLR = to_push.RDLR;
to_send.RDHR = to_push.RDHR;
can_send(&to_send, can_forwarding[bus_number]);
}
#endif
// modify RDTR for our API
to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4);
safety_rx_hook(&to_push);
#ifdef PANDA
set_led(LED_BLUE, 1);
#endif
can_push(&can_rx_q, &to_push);
// next
CAN->RF0R |= CAN_RF0R_RFOM0;
}
}
void CAN1_TX_IRQHandler() { process_can(0); }
void CAN1_RX0_IRQHandler() { can_rx(0); }
void CAN1_SCE_IRQHandler() { can_sce(CAN1); }
void CAN2_TX_IRQHandler() { process_can(1); }
void CAN2_RX0_IRQHandler() { can_rx(1); }
void CAN2_SCE_IRQHandler() { can_sce(CAN2); }
#ifdef CAN3
void CAN3_TX_IRQHandler() { process_can(2); }
void CAN3_RX0_IRQHandler() { can_rx(2); }
void CAN3_SCE_IRQHandler() { can_sce(CAN3); }
#endif
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) {
if (safety_tx_hook(to_push)) {
if (bus_number < BUS_MAX) {
// add CAN packet to send queue
// bus number isn't passed through
to_push->RDTR &= 0xF;
can_push(can_queues[bus_number], to_push);
process_can(CAN_NUM_FROM_BUS_NUM(bus_number));
}
}
}
void can_set_forwarding(int from, int to) {
can_forwarding[from] = to;
}

@ -0,0 +1,16 @@
void dac_init() {
// no buffers required since we have an opamp
//DAC->CR = DAC_CR_EN1 | DAC_CR_BOFF1 | DAC_CR_EN2 | DAC_CR_BOFF2;
DAC->DHR12R1 = 0;
DAC->DHR12R2 = 0;
DAC->CR = DAC_CR_EN1 | DAC_CR_EN2;
}
void dac_set(int channel, uint32_t value) {
if (channel == 0) {
DAC->DHR12R1 = value;
} else if (channel == 1) {
DAC->DHR12R2 = value;
}
}

@ -0,0 +1,141 @@
#ifndef PANDA_DRIVERS_H
#define PANDA_DRIVERS_H
// ********************* LLGPIO *********************
#define MODE_INPUT 0
#define MODE_OUTPUT 1
#define MODE_ALTERNATE 2
#define MODE_ANALOG 3
#define PULL_NONE 0
#define PULL_UP 1
#define PULL_DOWN 2
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode);
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val);
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode);
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode);
int get_gpio_input(GPIO_TypeDef *GPIO, int pin);
// ********************* USB *********************
// IRQs: OTG_FS
typedef union {
uint16_t w;
struct BW {
uint8_t msb;
uint8_t lsb;
}
bw;
}
uint16_t_uint8_t;
typedef union _USB_Setup {
uint32_t d8[2];
struct _SetupPkt_Struc
{
uint8_t bmRequestType;
uint8_t bRequest;
uint16_t_uint8_t wValue;
uint16_t_uint8_t wIndex;
uint16_t_uint8_t wLength;
} b;
}
USB_Setup_TypeDef;
void usb_init();
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired);
int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired);
void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired);
void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired);
void usb_cb_enumeration_complete();
// ********************* UART *********************
// IRQs: USART1, USART2, USART3, UART5
#define FIFO_SIZE 0x100
typedef struct uart_ring {
uint8_t w_ptr_tx;
uint8_t r_ptr_tx;
uint8_t elems_tx[FIFO_SIZE];
uint8_t w_ptr_rx;
uint8_t r_ptr_rx;
uint8_t elems_rx[FIFO_SIZE];
USART_TypeDef *uart;
void (*callback)(struct uart_ring*);
} uart_ring;
void uart_init(USART_TypeDef *u, int baud);
int getc(uart_ring *q, char *elem);
int putc(uart_ring *q, char elem);
int puts(const char *a);
void puth(unsigned int i);
void hexdump(const void *a, int l);
// ********************* ADC *********************
void adc_init();
uint32_t adc_get(int channel);
// ********************* DAC *********************
void dac_init();
uint32_t dac_set(int channel, uint32_t value);
// ********************* TIMER *********************
void timer_init(TIM_TypeDef *TIM, int psc);
// ********************* SPI *********************
// IRQs: DMA2_Stream2, DMA2_Stream3, EXTI4
void spi_init();
int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out);
// ********************* CAN *********************
// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE
// CAN2_TX, CAN2_RX0, CAN2_SCE
// CAN3_TX, CAN3_RX0, CAN3_SCE
typedef struct {
uint32_t w_ptr;
uint32_t r_ptr;
uint32_t fifo_size;
CAN_FIFOMailBox_TypeDef *elems;
} can_ring;
#define CAN_BUS_RET_FLAG 0x80
#define CAN_BUS_NUM_MASK 0x7F
#ifdef PANDA
#define BUS_MAX 4
#else
#define BUS_MAX 2
#endif
extern int can_live, pending_can_live;
// must reinit after changing these
extern int can_loopback, can_silent;
extern uint32_t can_speed[];
void can_set_forwarding(int from, int to);
void can_init(uint8_t can_number);
void can_init_all();
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number);
int can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem);
#endif

@ -0,0 +1,35 @@
void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode) {
uint32_t tmp = GPIO->MODER;
tmp &= ~(3 << (pin*2));
tmp |= (mode << (pin*2));
GPIO->MODER = tmp;
}
void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val) {
if (val) {
GPIO->ODR |= (1 << pin);
} else {
GPIO->ODR &= ~(1 << pin);
}
set_gpio_mode(GPIO, pin, MODE_OUTPUT);
}
void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode) {
uint32_t tmp = GPIO->AFR[pin>>3];
tmp &= ~(0xF << ((pin&7)*4));
tmp |= mode << ((pin&7)*4);
GPIO->AFR[pin>>3] = tmp;
set_gpio_mode(GPIO, pin, MODE_ALTERNATE);
}
void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode) {
uint32_t tmp = GPIO->PUPDR;
tmp &= ~(3 << (pin*2));
tmp |= (mode << (pin*2));
GPIO->PUPDR = tmp;
}
int get_gpio_input(GPIO_TypeDef *GPIO, int pin) {
return (GPIO->IDR & (1 << pin)) == (1 << pin);
}

@ -0,0 +1,120 @@
// IRQs: DMA2_Stream2, DMA2_Stream3, EXTI4
#define SPI_BUF_SIZE 256
uint8_t spi_buf[SPI_BUF_SIZE];
int spi_buf_count = 0;
int spi_total_count = 0;
void spi_init() {
//puts("SPI init\n");
SPI1->CR1 = SPI_CR1_SPE;
// enable SPI interrupts
//SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE;
SPI1->CR2 = SPI_CR2_RXNEIE;
NVIC_EnableIRQ(DMA2_Stream2_IRQn);
NVIC_EnableIRQ(DMA2_Stream3_IRQn);
//NVIC_EnableIRQ(SPI1_IRQn);
// reset handshake back to pull up
set_gpio_mode(GPIOB, 0, MODE_INPUT);
set_gpio_pullup(GPIOB, 0, PULL_UP);
// setup interrupt on falling edge of SPI enable (on PA4)
SYSCFG->EXTICR[2] = SYSCFG_EXTICR2_EXTI4_PA;
EXTI->IMR = (1 << 4);
EXTI->FTSR = (1 << 4);
NVIC_EnableIRQ(EXTI4_IRQn);
}
void spi_tx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_TXDMAEN;
DMA2_Stream3->CR &= ~DMA_SxCR_EN;
// DMA2, stream 3, channel 3
DMA2_Stream3->M0AR = (uint32_t)addr;
DMA2_Stream3->NDTR = len;
DMA2_Stream3->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, memory -> periph, enable
DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN;
DMA2_Stream3->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_TXDMAEN;
// signal data is ready by driving low
// esp must be configured as input by this point
set_gpio_output(GPIOB, 0, 0);
}
void spi_rx_dma(void *addr, int len) {
// disable DMA
SPI1->CR2 &= ~SPI_CR2_RXDMAEN;
DMA2_Stream2->CR &= ~DMA_SxCR_EN;
// drain the bus
volatile uint8_t dat = SPI1->DR;
(void)dat;
// DMA2, stream 2, channel 3
DMA2_Stream2->M0AR = (uint32_t)addr;
DMA2_Stream2->NDTR = len;
DMA2_Stream2->PAR = (uint32_t)&(SPI1->DR);
// channel3, increment memory, periph -> memory, enable
DMA2_Stream2->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_EN;
DMA2_Stream2->CR |= DMA_SxCR_TCIE;
SPI1->CR2 |= SPI_CR2_RXDMAEN;
}
// ***************************** SPI IRQs *****************************
// can't go on the stack cause it's DMAed
uint8_t spi_tx_buf[0x44];
// SPI RX
void DMA2_Stream2_IRQHandler(void) {
int *resp_len = (int*)spi_tx_buf;
memset(spi_tx_buf, 0xaa, 0x44);
*resp_len = spi_cb_rx(spi_buf, 0x14, spi_tx_buf+4);
#ifdef DEBUG_SPI
puts("SPI write: ");
puth(*resp_len);
puts("\n");
#endif
spi_tx_dma(spi_tx_buf, *resp_len + 4);
// ack
DMA2->LIFCR = DMA_LIFCR_CTCIF2;
}
// SPI TX
void DMA2_Stream3_IRQHandler(void) {
#ifdef DEBUG_SPI
puts("SPI handshake\n");
#endif
// reset handshake back to pull up
set_gpio_mode(GPIOB, 0, MODE_INPUT);
set_gpio_pullup(GPIOB, 0, PULL_UP);
// ack
DMA2->LIFCR = DMA_LIFCR_CTCIF3;
}
void EXTI4_IRQHandler(void) {
volatile int pr = EXTI->PR;
#ifdef DEBUG_SPI
puts("exti4\n");
#endif
// SPI CS falling
if (pr & (1 << 4)) {
spi_total_count = 0;
spi_rx_dma(spi_buf, 0x14);
}
EXTI->PR = pr;
}

@ -0,0 +1,7 @@
void timer_init(TIM_TypeDef *TIM, int psc) {
TIM->PSC = psc-1;
TIM->DIER = TIM_DIER_UIE;
TIM->CR1 = TIM_CR1_CEN;
TIM->SR = 0;
}

@ -0,0 +1,224 @@
// IRQs: USART1, USART2, USART3, UART5
// ***************************** serial port queues *****************************
// esp = USART1
uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART1 };
// lin1, K-LINE = UART5
// lin2, L-LINE = USART3
uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = UART5 };
uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART3 };
// debug = USART2
void debug_ring_callback(uart_ring *ring);
uart_ring debug_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0,
.w_ptr_rx = 0, .r_ptr_rx = 0,
.uart = USART2,
.callback = debug_ring_callback};
uart_ring *get_ring_by_number(int a) {
switch(a) {
case 0:
return &debug_ring;
case 1:
return &esp_ring;
case 2:
return &lin1_ring;
case 3:
return &lin2_ring;
default:
return NULL;
}
}
// ***************************** serial port *****************************
void uart_ring_process(uart_ring *q) {
enter_critical_section();
// TODO: check if external serial is connected
int sr = q->uart->SR;
if (q->w_ptr_tx != q->r_ptr_tx) {
if (sr & USART_SR_TXE) {
q->uart->DR = q->elems_tx[q->r_ptr_tx];
q->r_ptr_tx += 1;
} else {
// push on interrupt later
q->uart->CR1 |= USART_CR1_TXEIE;
}
} else {
// nothing to send
q->uart->CR1 &= ~USART_CR1_TXEIE;
}
if (sr & USART_SR_RXNE) {
uint8_t c = q->uart->DR; // TODO: can drop packets
uint8_t next_w_ptr = q->w_ptr_rx + 1;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = c;
q->w_ptr_rx = next_w_ptr;
if (q->callback) q->callback(q);
}
}
exit_critical_section();
}
// interrupt boilerplate
void USART1_IRQHandler(void) { uart_ring_process(&esp_ring); }
void USART2_IRQHandler(void) { uart_ring_process(&debug_ring); }
void USART3_IRQHandler(void) { uart_ring_process(&lin2_ring); }
void UART5_IRQHandler(void) { uart_ring_process(&lin1_ring); }
int getc(uart_ring *q, char *elem) {
int ret = 0;
enter_critical_section();
if (q->w_ptr_rx != q->r_ptr_rx) {
*elem = q->elems_rx[q->r_ptr_rx];
q->r_ptr_rx += 1;
ret = 1;
}
exit_critical_section();
return ret;
}
int injectc(uart_ring *q, char elem) {
int ret = 0;
uint8_t next_w_ptr;
enter_critical_section();
next_w_ptr = q->w_ptr_rx + 1;
if (next_w_ptr != q->r_ptr_rx) {
q->elems_rx[q->w_ptr_rx] = elem;
q->w_ptr_rx = next_w_ptr;
ret = 1;
}
exit_critical_section();
return ret;
}
int putc(uart_ring *q, char elem) {
int ret = 0;
uint8_t next_w_ptr;
enter_critical_section();
next_w_ptr = q->w_ptr_tx + 1;
if (next_w_ptr != q->r_ptr_tx) {
q->elems_tx[q->w_ptr_tx] = elem;
q->w_ptr_tx = next_w_ptr;
ret = 1;
}
exit_critical_section();
uart_ring_process(q);
return ret;
}
void clear_uart_buff(uart_ring *q) {
enter_critical_section();
q->w_ptr_tx = 0;
q->r_ptr_tx = 0;
q->w_ptr_rx = 0;
q->r_ptr_rx = 0;
exit_critical_section();
}
// ***************************** start UART code *****************************
#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_)))
#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100)
#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100)
#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F))
void uart_set_baud(USART_TypeDef *u, int baud) {
if (u == USART1) {
// USART1 is on APB2
u->BRR = __USART_BRR(48000000, baud);
} else {
u->BRR = __USART_BRR(24000000, baud);
}
}
void uart_init(USART_TypeDef *u, int baud) {
// enable uart and tx+rx mode
u->CR1 = USART_CR1_UE;
uart_set_baud(u, baud);
u->CR1 |= USART_CR1_TE | USART_CR1_RE;
//u->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1;
//u->CR2 = USART_CR2_STOP_0;
// ** UART is ready to work **
// enable interrupts
u->CR1 |= USART_CR1_RXNEIE;
if (u == USART1) {
NVIC_EnableIRQ(USART1_IRQn);
} else if (u == USART2) {
NVIC_EnableIRQ(USART2_IRQn);
} else if (u == USART3) {
NVIC_EnableIRQ(USART3_IRQn);
} else if (u == UART5) {
NVIC_EnableIRQ(UART5_IRQn);
}
}
void putch(const char a) {
if (has_external_debug_serial) {
/*while ((debug_ring.uart->SR & USART_SR_TXE) == 0);
debug_ring.uart->DR = a;*/
// assuming debugging is important if there's external serial connected
while (!putc(&debug_ring, a));
//putc(&debug_ring, a);
} else {
injectc(&debug_ring, a);
}
}
int puts(const char *a) {
for (;*a;a++) {
if (*a == '\n') putch('\r');
putch(*a);
}
return 0;
}
void puth(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 28; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void puth2(unsigned int i) {
int pos;
char c[] = "0123456789abcdef";
for (pos = 4; pos != -4; pos -= 4) {
putch(c[(i >> pos) & 0xF]);
}
}
void hexdump(const void *a, int l) {
int i;
for (i=0;i<l;i++) {
if (i != 0 && (i&0xf) == 0) puts("\n");
puth2(((const unsigned char*)a)[i]);
puts(" ");
}
puts("\n");
}

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

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

@ -0,0 +1,5 @@
#!/bin/bash
# Need formula for gcc
brew tap ArmMbed/homebrew-formulae
brew install python dfu-util arm-none-eabi-gcc
pip2 install libusb1

@ -0,0 +1,450 @@
#ifdef STM32F4
#include "stm32f4xx_hal_gpio_ex.h"
#else
#include "stm32f2xx_hal_gpio_ex.h"
#endif
// ********************* dynamic configuration detection *********************
#define PANDA_REV_AB 0
#define PANDA_REV_C 1
#define PULL_EFFECTIVE_DELAY 10
int has_external_debug_serial = 0;
int is_giant_panda = 0;
int is_entering_bootmode = 0;
int revision = PANDA_REV_AB;
int detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) {
set_gpio_mode(GPIO, pin, MODE_INPUT);
set_gpio_pullup(GPIO, pin, mode);
for (volatile int i=0; i<PULL_EFFECTIVE_DELAY; i++);
int ret = get_gpio_input(GPIO, pin);
set_gpio_pullup(GPIO, pin, PULL_NONE);
return ret;
}
// must call again from main because BSS is zeroed
void detect() {
// detect has_external_debug_serial
has_external_debug_serial = detect_with_pull(GPIOA, 3, PULL_DOWN);
#ifdef PANDA
// detect is_giant_panda
is_giant_panda = detect_with_pull(GPIOB, 1, PULL_DOWN);
// detect panda REV C.
// A13 floats in REV AB. In REV C, A13 is pulled up to 5V with a 10K
// resistor and attached to the USB power control chip CTRL
// line. Pulling A13 down with an internal 50k resistor in REV C
// will produce a voltage divider that results in a high logic
// level. Checking if this pin reads high with a pull down should
// differentiate REV AB from C.
revision = detect_with_pull(GPIOA, 13, PULL_DOWN) ? PANDA_REV_C : PANDA_REV_AB;
// check if the ESP is trying to put me in boot mode
is_entering_bootmode = !detect_with_pull(GPIOB, 0, PULL_UP);
#else
// need to do this for early detect
is_giant_panda = 0;
revision = PANDA_REV_AB;
is_entering_bootmode = 0;
#endif
}
// ********************* bringup *********************
void clock_init() {
// enable external oscillator
RCC->CR |= RCC_CR_HSEON;
while ((RCC->CR & RCC_CR_HSERDY) == 0);
// divide shit
RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4;
#ifdef PANDA
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE;
#else
RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE;
#endif
// start PLL
RCC->CR |= RCC_CR_PLLON;
while ((RCC->CR & RCC_CR_PLLRDY) == 0);
// Configure Flash prefetch, Instruction cache, Data cache and wait state
// *** without this, it breaks ***
FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS;
// switch to PLL
RCC->CFGR |= RCC_CFGR_SW_PLL;
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL);
// *** running on PLL ***
}
void periph_init() {
// enable GPIOB, UART2, CAN, USB clock
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN;
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
#ifdef PANDA
RCC->APB1ENR |= RCC_APB1ENR_UART5EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
#ifdef CAN3
RCC->APB1ENR |= RCC_APB1ENR_CAN3EN;
#endif
RCC->APB1ENR |= RCC_APB1ENR_DACEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
//RCC->APB1ENR |= RCC_APB1ENR_TIM4EN;
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// needed?
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
}
// ********************* setters *********************
void set_can_enable(CAN_TypeDef *CAN, int enabled) {
// enable CAN busses
if (CAN == CAN1) {
#ifdef PANDA
// CAN1_EN
set_gpio_output(GPIOC, 1, !enabled);
#else
// CAN1_EN
set_gpio_output(GPIOB, 3, enabled);
#endif
} else if (CAN == CAN2) {
#ifdef PANDA
// CAN2_EN
set_gpio_output(GPIOC, 13, !enabled);
#else
// CAN2_EN
set_gpio_output(GPIOB, 4, enabled);
#endif
#ifdef CAN3
} else if (CAN == CAN3) {
// CAN3_EN
set_gpio_output(GPIOA, 0, !enabled);
#endif
}
}
#ifdef PANDA
#define LED_RED 9
#define LED_GREEN 7
#define LED_BLUE 6
#else
#define LED_RED 10
#define LED_GREEN 11
#define LED_BLUE -1
#endif
void set_led(int led_num, int on) {
if (led_num == -1) return;
#ifdef PANDA
set_gpio_output(GPIOC, led_num, !on);
#else
set_gpio_output(GPIOB, led_num, !on);
#endif
}
void set_can_mode(int can, int use_gmlan) {
// connects to CAN2 xcvr or GMLAN xcvr
if (use_gmlan) {
if (can == 1) {
// B5,B6: disable normal mode
set_gpio_mode(GPIOB, 5, MODE_INPUT);
set_gpio_mode(GPIOB, 6, MODE_INPUT);
// B12,B13: gmlan mode
set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2);
#ifdef CAN3
} else if (revision == PANDA_REV_C && can == 2) {
// A8,A15: disable normal mode
set_gpio_mode(GPIOA, 8, MODE_INPUT);
set_gpio_mode(GPIOA, 15, MODE_INPUT);
// B3,B4: enable gmlan mode
set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3);
#endif
}
} else {
if (can == 1) {
// B12,B13: disable gmlan mode
set_gpio_mode(GPIOB, 12, MODE_INPUT);
set_gpio_mode(GPIOB, 13, MODE_INPUT);
// B5,B6: normal mode
set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2);
set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2);
#ifdef CAN3
} else if (can == 2) {
if(revision == PANDA_REV_C){
// B3,B4: disable gmlan mode
set_gpio_mode(GPIOB, 3, MODE_INPUT);
set_gpio_mode(GPIOB, 4, MODE_INPUT);
}
// A8,A15: normal mode
set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3);
set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3);
#endif
}
}
}
#define USB_POWER_NONE 0
#define USB_POWER_CLIENT 1
#define USB_POWER_CDP 2
#define USB_POWER_DCP 3
int usb_power_mode = USB_POWER_NONE;
void set_usb_power_mode(int mode) {
switch (mode) {
case USB_POWER_CLIENT:
// B2,A13: set client mode
set_gpio_output(GPIOB, 2, 0);
set_gpio_output(GPIOA, 13, 1);
break;
case USB_POWER_CDP:
// B2,A13: set CDP mode
set_gpio_output(GPIOB, 2, 1);
set_gpio_output(GPIOA, 13, 1);
break;
case USB_POWER_DCP:
// B2,A13: set DCP mode on the charger (breaks USB!)
set_gpio_output(GPIOB, 2, 0);
set_gpio_output(GPIOA, 13, 0);
break;
}
usb_power_mode = mode;
}
#define ESP_DISABLED 0
#define ESP_ENABLED 1
#define ESP_BOOTMODE 2
void set_esp_mode(int mode) {
switch (mode) {
case ESP_DISABLED:
// ESP OFF
set_gpio_output(GPIOC, 14, 0);
set_gpio_output(GPIOC, 5, 0);
break;
case ESP_ENABLED:
// ESP ON
set_gpio_output(GPIOC, 14, 1);
set_gpio_output(GPIOC, 5, 1);
break;
case ESP_BOOTMODE:
set_gpio_output(GPIOC, 14, 1);
set_gpio_output(GPIOC, 5, 0);
break;
}
}
// ********************* big init function *********************
// board specific
void gpio_init() {
// pull low to hold ESP in reset??
// enable OTG out tied to ground
GPIOA->ODR = 0;
GPIOB->ODR = 0;
GPIOA->PUPDR = 0;
//GPIOC->ODR = 0;
GPIOB->AFR[0] = 0;
GPIOB->AFR[1] = 0;
// C2,C3: analog mode, voltage and current sense
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
// C8: FAN aka TIM3_CH4
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
// turn off LEDs and set mode
set_led(LED_RED, 0);
set_led(LED_GREEN, 0);
set_led(LED_BLUE, 0);
// A11,A12: USB
set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS);
set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS);
GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12;
#ifdef PANDA
// enable started_alt on the panda
set_gpio_pullup(GPIOA, 1, PULL_UP);
// A2,A3: USART 2 for debugging
set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2);
set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2);
// A9,A10: USART 1 for talking to the ESP
set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1);
set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1);
// B12: GMLAN, ignition sense, pull up
set_gpio_pullup(GPIOB, 12, PULL_UP);
// A4,A5,A6,A7: setup SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1);
#endif
// B8,B9: CAN 1
#ifdef STM32F4
set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1);
set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1);
#else
set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1);
set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1);
#endif
set_can_enable(CAN1, 1);
// B5,B6: CAN 2
set_can_mode(1, 0);
set_can_enable(CAN2, 1);
// A8,A15: CAN 3
#ifdef CAN3
set_can_mode(2, 0);
set_can_enable(CAN3, 1);
#endif
/* GMLAN mode pins:
M0(B15) M1(B14) mode
=======================
0 0 sleep
1 0 100kbit
0 1 high voltage wakeup
1 1 33kbit (normal)
*/
// put gmlan transceiver in normal mode
set_gpio_output(GPIOB, 14, 1);
set_gpio_output(GPIOB, 15, 1);
#ifdef PANDA
// K-line enable moved from B4->B7 to make room for GMLAN on CAN3
if (revision == PANDA_REV_C) {
set_gpio_output(GPIOB, 7, 1); // REV C
} else {
set_gpio_output(GPIOB, 4, 1); // REV AB
}
// C12,D2: K-Line setup on UART 5
set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5);
set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5);
set_gpio_pullup(GPIOD, 2, PULL_UP);
// L-line enable
set_gpio_output(GPIOA, 14, 1);
// C10,C11: L-Line setup on USART 3
set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3);
set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3);
set_gpio_pullup(GPIOC, 11, PULL_UP);
#endif
if (revision == PANDA_REV_C) {
set_usb_power_mode(USB_POWER_CLIENT);
}
}
// ********************* early bringup *********************
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
#define ENTER_SOFTLOADER_MAGIC 0xdeadc0de
#define BOOT_NORMAL 0xdeadb111
extern void *g_pfnVectors;
extern uint32_t enter_bootloader_mode;
void jump_to_bootloader() {
// do enter bootloader
enter_bootloader_mode = 0;
void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004));
// jump to bootloader
bootloader();
// reset on exit
enter_bootloader_mode = BOOT_NORMAL;
NVIC_SystemReset();
}
void early() {
// after it's been in the bootloader, things are initted differently, so we reset
if (enter_bootloader_mode != BOOT_NORMAL &&
enter_bootloader_mode != ENTER_BOOTLOADER_MAGIC &&
enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC) {
enter_bootloader_mode = BOOT_NORMAL;
NVIC_SystemReset();
}
// if wrong chip, reboot
volatile unsigned int id = DBGMCU->IDCODE;
#ifdef STM32F4
if ((id&0xFFF) != 0x463) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
#else
if ((id&0xFFF) != 0x411) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
#endif
// setup interrupt table
SCB->VTOR = (uint32_t)&g_pfnVectors;
// early GPIOs float everything
RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN;
GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0;
GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0;
GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0;
detect();
#ifdef PANDA
// enable the ESP, disable ESP boot mode
// unless we are on a giant panda, then there's no ESP
if (is_giant_panda) {
set_esp_mode(ESP_DISABLED);
} else {
set_esp_mode(ESP_ENABLED);
}
#endif
if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) {
set_esp_mode(ESP_DISABLED);
set_led(LED_GREEN, 1);
jump_to_bootloader();
}
if (is_entering_bootmode) {
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
}
}

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

@ -0,0 +1,87 @@
/**************************************************************************//**
* @file core_cmFunc.h
* @brief CMSIS Cortex-M Core Function Access Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMFUNC_H
#define __CORE_CMFUNC_H
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CORE_CMFUNC_H */

@ -0,0 +1,87 @@
/**************************************************************************//**
* @file core_cmInstr.h
* @brief CMSIS Cortex-M Core Instruction Access Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMINSTR_H
#define __CORE_CMINSTR_H
/* ########################## Core Instruction Access ######################### */
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
Access to dedicated instructions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
#endif /* __CORE_CMINSTR_H */

@ -0,0 +1,96 @@
/**************************************************************************//**
* @file core_cmSimd.h
* @brief CMSIS Cortex-M SIMD Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMSIMD_H
#define __CORE_CMSIMD_H
#ifdef __cplusplus
extern "C" {
#endif
/* ################### Compiler specific Intrinsics ########################### */
/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
Access to dedicated SIMD instructions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@} end of group CMSIS_SIMD_intrinsics */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_CMSIMD_H */

File diff suppressed because it is too large Load Diff

@ -0,0 +1,209 @@
/**
******************************************************************************
* @file stm32f2xx.h
* @author MCD Application Team
* @version V2.1.2
* @date 29-June-2016
* @brief CMSIS STM32F2xx Device Peripheral Access Layer Header File.
*
* The file is the unique include file that the application programmer
* is using in the C source code, usually in main.c. This file contains:
* - Configuration section that allows to select:
* - The STM32F2xx device used in the target application
* - To use or not the peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* "#define USE_HAL_DRIVER"
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f2xx
* @{
*/
#ifndef __STM32F2xx_H
#define __STM32F2xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Library_configuration_section
* @{
*/
/**
* @brief STM32 Family
*/
#if !defined (STM32F2)
#define STM32F2
#endif /* STM32F2 */
/* Uncomment the line below according to the target STM32 device used in your
application
*/
#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx)
/* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF,
STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC,
STM32F205RB and STM32F205VB Devices */
/* #define STM32F215xx */ /*!< STM32F215RG, STM32F215VG, STM32F215ZG, STM32F215RE, STM32F215VE and STM32F215ZE Devices */
/* #define STM32F207xx */ /*!< STM32F207VG, STM32F207ZG, STM32F207IG, STM32F207VF, STM32F207ZF, STM32F207IF,
STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */
/* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE Devices */
#endif
/* Tip: To avoid modifying this file each time you need to switch between these
devices, you can define the device in your toolchain compiler preprocessor.
*/
#if !defined (USE_HAL_DRIVER)
/**
* @brief Comment the line below if you will not use the peripherals drivers.
In this case, these drivers will not be included and the application code will
be based on direct access to peripherals registers
*/
/*#define USE_HAL_DRIVER */
#endif /* USE_HAL_DRIVER */
/**
* @brief CMSIS Device version number V2.1.2
*/
#define __STM32F2xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */
#define __STM32F2xx_CMSIS_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */
#define __STM32F2xx_CMSIS_VERSION_SUB2 (0x02U) /*!< [15:8] sub2 version */
#define __STM32F2xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */
#define __STM32F2xx_CMSIS_VERSION ((__STM32F2xx_CMSIS_VERSION_MAIN << 24)\
|(__STM32F2xx_CMSIS_VERSION_SUB1 << 16)\
|(__STM32F2xx_CMSIS_VERSION_SUB2 << 8 )\
|(__STM32F2xx_CMSIS_VERSION))
/**
* @}
*/
/** @addtogroup Device_Included
* @{
*/
#if defined(STM32F205xx)
#include "stm32f205xx.h"
#elif defined(STM32F215xx)
#include "stm32f215xx.h"
#elif defined(STM32F207xx)
#include "stm32f207xx.h"
#elif defined(STM32F217xx)
#include "stm32f217xx.h"
#else
#error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)"
#endif
/**
* @}
*/
/** @addtogroup Exported_types
* @{
*/
typedef enum
{
RESET = 0,
SET = !RESET
} FlagStatus, ITStatus;
typedef enum
{
DISABLE = 0,
ENABLE = !DISABLE
} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum
{
ERROR = 0,
SUCCESS = !ERROR
} ErrorStatus;
/**
* @}
*/
/** @addtogroup Exported_macro
* @{
*/
#define SET_BIT(REG, BIT) ((REG) |= (BIT))
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
#define READ_BIT(REG, BIT) ((REG) & (BIT))
#define CLEAR_REG(REG) ((REG) = (0x0))
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
/**
* @}
*/
#if defined (USE_HAL_DRIVER)
#include "stm32f2xx_hal.h"
#endif /* USE_HAL_DRIVER */
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* __STM32F2xx_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

@ -0,0 +1,181 @@
/**
******************************************************************************
* @file stm32f2xx_hal_def.h
* @author MCD Application Team
* @version V1.1.3
* @date 29-June-2016
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F2xx_HAL_DEF
#define __STM32F2xx_HAL_DEF
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f2xx.h"
//#include "Legacy/stm32_hal_legacy.h"
//#include <stdio.h>
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00U,
HAL_ERROR = 0x01U,
HAL_BUSY = 0x02U,
HAL_TIMEOUT = 0x03U
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
*/
typedef enum
{
HAL_UNLOCKED = 0x00U,
HAL_LOCKED = 0x01U
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
#define HAL_MAX_DELAY 0xFFFFFFFFU
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET)
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET)
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD_, __DMA_HANDLE_) \
do{ \
(__HANDLE__)->__PPP_DMA_FIELD_ = &(__DMA_HANDLE_); \
(__DMA_HANDLE_).Parent = (__HANDLE__); \
} while(0)
#define UNUSED(x) ((void)(x))
/** @brief Reset the Handle's State field.
* @param __HANDLE__: specifies the Peripheral Handle.
* @note This macro can be used for the following purpose:
* - When the Handle is declared as local variable; before passing it as parameter
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro
* to set to 0 the Handle's "State" field.
* Otherwise, "State" field may have any random value and the first time the function
* HAL_PPP_Init() is called, the low level hardware initialization will be missed
* (i.e. HAL_PPP_MspInit() will not be executed).
* - When there is a need to reconfigure the low level hardware: instead of calling
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
* In this later function, when the Handle's "State" field is set to 0, it will execute the function
* HAL_PPP_MspInit() which will reconfigure the low level hardware.
* @retval None
*/
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
#if (USE_RTOS == 1)
/* Reserved for future use */
#error " USE_RTOS should be 0 in the current HAL release "
#else
#define __HAL_LOCK(__HANDLE__) \
do{ \
if((__HANDLE__)->Lock == HAL_LOCKED) \
{ \
return HAL_BUSY; \
} \
else \
{ \
(__HANDLE__)->Lock = HAL_LOCKED; \
} \
}while (0)
#define __HAL_UNLOCK(__HANDLE__) \
do{ \
(__HANDLE__)->Lock = HAL_UNLOCKED; \
}while (0)
#endif /* USE_RTOS */
#if defined ( __GNUC__ )
#ifndef __weak
#define __weak __attribute__((weak))
#endif /* __weak */
#ifndef __packed
#define __packed __attribute__((__packed__))
#endif /* __packed */
#endif /* __GNUC__ */
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
#if defined (__GNUC__) /* GNU Compiler */
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#endif /* __CC_ARM */
#endif /* __ALIGN_BEGIN */
#endif /* __GNUC__ */
/**
* @brief __NOINLINE definition
*/
#if defined ( __CC_ARM ) || defined ( __GNUC__ )
/* ARM & GNUCompiler
----------------
*/
#define __NOINLINE __attribute__ ( (noinline) )
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
*/
#define __NOINLINE _Pragma("optimize = no_inline")
#endif
#ifdef __cplusplus
}
#endif
#endif /* ___STM32F2xx_HAL_DEF */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

@ -0,0 +1,299 @@
/**
******************************************************************************
* @file stm32f2xx_hal_gpio_ex.h
* @author MCD Application Team
* @version V1.1.3
* @date 29-June-2016
* @brief Header file of GPIO HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F2xx_HAL_GPIO_EX_H
#define __STM32F2xx_HAL_GPIO_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f2xx_hal_def.h"
/** @addtogroup STM32F2xx_HAL_Driver
* @{
*/
/** @defgroup GPIOEx GPIOEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants
* @{
*/
/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection
* @{
*/
/**
* @brief AF 0 selection
*/
#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */
#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */
#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */
#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */
#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */
/**
* @brief AF 1 selection
*/
#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */
#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */
/**
* @brief AF 2 selection
*/
#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */
#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */
#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */
/**
* @brief AF 3 selection
*/
#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */
#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */
#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */
#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */
/**
* @brief AF 4 selection
*/
#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */
#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */
#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */
/**
* @brief AF 5 selection
*/
#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */
#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */
/**
* @brief AF 6 selection
*/
#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */
/**
* @brief AF 7 selection
*/
#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */
#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */
#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */
/**
* @brief AF 8 selection
*/
#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */
#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */
#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */
/**
* @brief AF 9 selection
*/
#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */
#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */
#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */
#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */
#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */
/**
* @brief AF 10 selection
*/
#define GPIO_AF10_OTG_FS ((uint8_t)0xAU) /* OTG_FS Alternate Function mapping */
#define GPIO_AF10_OTG_HS ((uint8_t)0xAU) /* OTG_HS Alternate Function mapping */
/**
* @brief AF 11 selection
*/
#if defined(STM32F207xx) || defined(STM32F217xx)
#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */
#endif /* STM32F207xx || STM32F217xx */
/**
* @brief AF 12 selection
*/
#define GPIO_AF12_FSMC ((uint8_t)0xCU) /* FSMC Alternate Function mapping */
#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xCU) /* OTG HS configured in FS, Alternate Function mapping */
#define GPIO_AF12_SDIO ((uint8_t)0xCU) /* SDIO Alternate Function mapping */
/**
* @brief AF 13 selection
*/
#if defined(STM32F207xx) || defined(STM32F217xx)
#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */
#endif /* STM32F207xx || STM32F217xx */
/**
* @brief AF 15 selection
*/
#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros
* @{
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions
* @{
*/
/**
* @}
*/
/* Private types -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private constants ---------------------------------------------------------*/
/** @defgroup GPIOEx_Private_Constants GPIO Private Constants
* @{
*/
/**
* @}
*/
/* Private macros ------------------------------------------------------------*/
/** @defgroup GPIOEx_Private_Macros GPIO Private Macros
* @{
*/
/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index
* @{
*/
#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\
((__GPIOx__) == (GPIOB))? 1U :\
((__GPIOx__) == (GPIOC))? 2U :\
((__GPIOx__) == (GPIOD))? 3U :\
((__GPIOx__) == (GPIOE))? 4U :\
((__GPIOx__) == (GPIOF))? 5U :\
((__GPIOx__) == (GPIOG))? 6U :\
((__GPIOx__) == (GPIOH))? 7U :\
((__GPIOx__) == (GPIOI))? 8U : 9U)
/**
* @}
*/
/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function
* @{
*/
#if defined(STM32F207xx) || defined(STM32F217xx)
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \
((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \
((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \
((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \
((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \
((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \
((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \
((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \
((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \
((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \
((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \
((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \
((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \
((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \
((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \
((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \
((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT))
#else /* STM32F207xx || STM32F217xx */
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \
((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \
((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \
((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \
((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \
((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \
((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \
((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \
((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \
((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \
((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \
((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \
((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \
((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \
((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \
((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT))
#endif /* STM32F207xx || STM32F217xx */
/**
* @}
*/
/**
* @}
*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup GPIOEx_Private_Functions GPIO Private Functions
* @{
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32F2xx_HAL_GPIO_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

@ -0,0 +1,271 @@
/**
******************************************************************************
* @file stm32f4xx.h
* @author MCD Application Team
* @version V2.6.0
* @date 04-November-2016
* @brief CMSIS STM32F4xx Device Peripheral Access Layer Header File.
*
* The file is the unique include file that the application programmer
* is using in the C source code, usually in main.c. This file contains:
* - Configuration section that allows to select:
* - The STM32F4xx device used in the target application
* - To use or not the peripherals drivers in application code(i.e.
* code will be based on direct access to peripherals registers
* rather than drivers API), this option is controlled by
* "#define USE_HAL_DRIVER"
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx
* @{
*/
#ifndef __STM32F4xx_H
#define __STM32F4xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Library_configuration_section
* @{
*/
/**
* @brief STM32 Family
*/
#if !defined (STM32F4)
#define STM32F4
#endif /* STM32F4 */
/* Uncomment the line below according to the target STM32 device used in your
application
*/
#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \
!defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \
!defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F410Tx) && !defined (STM32F410Cx) && \
!defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \
!defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \
!defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx)
/* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */
/* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */
/* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */
/* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */
/* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */
/* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */
/* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG,
STM32F439NI, STM32F429IG and STM32F429II Devices */
/* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG,
STM32F439NI, STM32F439IG and STM32F439II Devices */
/* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */
/* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */
/* #define STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */
/* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */
/* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */
/* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */
/* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC,
and STM32F446ZE Devices */
/* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG,
STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */
/* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG
and STM32F479NG Devices */
/* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */
/* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */
/* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */
/* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */
/* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG,
STM32F413RG, STM32F413VG and STM32F413ZG Devices */
/* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH Devices */
#endif
/* Tip: To avoid modifying this file each time you need to switch between these
devices, you can define the device in your toolchain compiler preprocessor.
*/
#if !defined (USE_HAL_DRIVER)
/**
* @brief Comment the line below if you will not use the peripherals drivers.
In this case, these drivers will not be included and the application code will
be based on direct access to peripherals registers
*/
/*#define USE_HAL_DRIVER */
#endif /* USE_HAL_DRIVER */
/**
* @brief CMSIS version number V2.6.0
*/
#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */
#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */
#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x00U) /*!< [15:8] sub2 version */
#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */
#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\
|(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\
|(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\
|(__STM32F4xx_CMSIS_VERSION))
/**
* @}
*/
/** @addtogroup Device_Included
* @{
*/
#if defined(STM32F405xx)
#include "stm32f405xx.h"
#elif defined(STM32F415xx)
#include "stm32f415xx.h"
#elif defined(STM32F407xx)
#include "stm32f407xx.h"
#elif defined(STM32F417xx)
#include "stm32f417xx.h"
#elif defined(STM32F427xx)
#include "stm32f427xx.h"
#elif defined(STM32F437xx)
#include "stm32f437xx.h"
#elif defined(STM32F429xx)
#include "stm32f429xx.h"
#elif defined(STM32F439xx)
#include "stm32f439xx.h"
#elif defined(STM32F401xC)
#include "stm32f401xc.h"
#elif defined(STM32F401xE)
#include "stm32f401xe.h"
#elif defined(STM32F410Tx)
#include "stm32f410tx.h"
#elif defined(STM32F410Cx)
#include "stm32f410cx.h"
#elif defined(STM32F410Rx)
#include "stm32f410rx.h"
#elif defined(STM32F411xE)
#include "stm32f411xe.h"
#elif defined(STM32F446xx)
#include "stm32f446xx.h"
#elif defined(STM32F469xx)
#include "stm32f469xx.h"
#elif defined(STM32F479xx)
#include "stm32f479xx.h"
#elif defined(STM32F412Cx)
#include "stm32f412cx.h"
#elif defined(STM32F412Zx)
#include "stm32f412zx.h"
#elif defined(STM32F412Rx)
#include "stm32f412rx.h"
#elif defined(STM32F412Vx)
#include "stm32f412vx.h"
#elif defined(STM32F413xx)
#include "stm32f413xx.h"
#elif defined(STM32F423xx)
#include "stm32f423xx.h"
#else
#error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)"
#endif
/**
* @}
*/
/** @addtogroup Exported_types
* @{
*/
typedef enum
{
RESET = 0U,
SET = !RESET
} FlagStatus, ITStatus;
typedef enum
{
DISABLE = 0U,
ENABLE = !DISABLE
} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum
{
ERROR = 0U,
SUCCESS = !ERROR
} ErrorStatus;
/**
* @}
*/
/** @addtogroup Exported_macro
* @{
*/
#define SET_BIT(REG, BIT) ((REG) |= (BIT))
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
#define READ_BIT(REG, BIT) ((REG) & (BIT))
#define CLEAR_REG(REG) ((REG) = (0x0))
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
/**
* @}
*/
#if defined (USE_HAL_DRIVER)
#include "stm32f4xx_hal.h"
#endif /* USE_HAL_DRIVER */
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* __STM32F4xx_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

@ -0,0 +1,214 @@
/**
******************************************************************************
* @file stm32f4xx_hal_def.h
* @author MCD Application Team
* @version V1.6.0
* @date 04-November-2016
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_HAL_DEF
#define __STM32F4xx_HAL_DEF
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
//#include "Legacy/stm32_hal_legacy.h"
//#include <stdio.h>
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00U,
HAL_ERROR = 0x01U,
HAL_BUSY = 0x02U,
HAL_TIMEOUT = 0x03U
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
*/
typedef enum
{
HAL_UNLOCKED = 0x00U,
HAL_LOCKED = 0x01U
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
#define HAL_MAX_DELAY 0xFFFFFFFFU
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET)
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET)
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
do{ \
(__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
(__DMA_HANDLE__).Parent = (__HANDLE__); \
} while(0)
#define UNUSED(x) ((void)(x))
/** @brief Reset the Handle's State field.
* @param __HANDLE__: specifies the Peripheral Handle.
* @note This macro can be used for the following purpose:
* - When the Handle is declared as local variable; before passing it as parameter
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro
* to set to 0 the Handle's "State" field.
* Otherwise, "State" field may have any random value and the first time the function
* HAL_PPP_Init() is called, the low level hardware initialization will be missed
* (i.e. HAL_PPP_MspInit() will not be executed).
* - When there is a need to reconfigure the low level hardware: instead of calling
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
* In this later function, when the Handle's "State" field is set to 0, it will execute the function
* HAL_PPP_MspInit() which will reconfigure the low level hardware.
* @retval None
*/
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
#if (USE_RTOS == 1)
/* Reserved for future use */
#error "USE_RTOS should be 0 in the current HAL release"
#else
#define __HAL_LOCK(__HANDLE__) \
do{ \
if((__HANDLE__)->Lock == HAL_LOCKED) \
{ \
return HAL_BUSY; \
} \
else \
{ \
(__HANDLE__)->Lock = HAL_LOCKED; \
} \
}while (0)
#define __HAL_UNLOCK(__HANDLE__) \
do{ \
(__HANDLE__)->Lock = HAL_UNLOCKED; \
}while (0)
#endif /* USE_RTOS */
#if defined ( __GNUC__ )
#ifndef __weak
#define __weak __attribute__((weak))
#endif /* __weak */
#ifndef __packed
#define __packed __attribute__((__packed__))
#endif /* __packed */
#endif /* __GNUC__ */
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
#if defined (__GNUC__) /* GNU Compiler */
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#endif /* __CC_ARM */
#endif /* __ALIGN_BEGIN */
#endif /* __GNUC__ */
/**
* @brief __RAM_FUNC definition
*/
#if defined ( __CC_ARM )
/* ARM Compiler
------------
RAM functions are defined using the toolchain options.
Functions that are executed in RAM should reside in a separate source module.
Using the 'Options for File' dialog you can simply change the 'Code / Const'
area of a module to a memory space in physical RAM.
Available memory areas are declared in the 'Target' tab of the 'Options for Target'
dialog.
*/
#define __RAM_FUNC HAL_StatusTypeDef
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
RAM functions are defined using a specific toolchain keyword "__ramfunc".
*/
#define __RAM_FUNC __ramfunc HAL_StatusTypeDef
#elif defined ( __GNUC__ )
/* GNU Compiler
------------
RAM functions are defined using a specific toolchain attribute
"__attribute__((section(".RamFunc")))".
*/
#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc")))
#endif
/**
* @brief __NOINLINE definition
*/
#if defined ( __CC_ARM ) || defined ( __GNUC__ )
/* ARM & GNUCompiler
----------------
*/
#define __NOINLINE __attribute__ ( (noinline) )
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
*/
#define __NOINLINE _Pragma("optimize = no_inline")
#endif
#ifdef __cplusplus
}
#endif
#endif /* ___STM32F4xx_HAL_DEF */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save