diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md
new file mode 100644
index 0000000000..2357509eee
--- /dev/null
+++ b/CONTRIBUTING.md
@@ -0,0 +1,18 @@
+# How to contribute
+
+Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use.
+
+Most open source development activity is coordinated through our [slack](https://slack.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/)
+
+## Getting Started
+
+ * Join our slack [slack.comma.ai](https://slack.comma.ai)
+ * Make sure you have a [GitHub account](https://github.com/signup/free)
+ * Fork the repository on GitHub
+
+## Car Ports (openpilot)
+
+We've released a guide for porting to Toyota cars [here](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6)
+
+If you port openpilot to a substantially new car, you might be eligible for a bounty. See our bounties at [comma.ai/bounties.html](https://comma.ai/bounties.html)
+
diff --git a/LICENSE.openpilot b/LICENSE
similarity index 96%
rename from LICENSE.openpilot
rename to LICENSE
index 8a6c6976b7..7dafa9443b 100644
--- a/LICENSE.openpilot
+++ b/LICENSE
@@ -1,4 +1,4 @@
-Copyright (c) 2016, Comma.ai, Inc.
+Copyright (c) 2018, 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:
diff --git a/README.md b/README.md
index 7af20f07b3..6c53015e7a 100644
--- a/README.md
+++ b/README.md
@@ -22,7 +22,7 @@ Supported Cars
- Acura ILX 2016 with AcuraWatch Plus
- Due to use of the cruise control for gas, it can only be enabled above 25 mph
-- Honda Civic 2016-2017 with Honda Sensing
+- Honda Civic 2016-2018 with Honda Sensing
- Due to limitations in steering firmware, steering is disabled below 12 mph
- Note that the hatchback model is not supported
@@ -34,6 +34,9 @@ Supported Cars
- Acura RDX 2018 with AcuraWatch Plus (alpha!)
- Can only be enabled above 25 mph
+
+- Honda Pilot 2017 with Honda Sensing (alpha!)
+ - Can only be enabled above 27 mph
- Toyota RAV-4 2016+ non-hybrid with TSS-P
- By default it uses stock Toyota ACC for longitudinal control
@@ -72,8 +75,6 @@ Community WIP Cars
- [Classic Tesla Model S (pre-AP)](https://github.com/commaai/openpilot/pull/145)
-- [Honda Pilot 2017 with Honda Sensing](https://github.com/commaai/openpilot/pull/161)
-
Directory structure
------
diff --git a/README_chffrplus.md b/README_chffrplus.md
new file mode 100644
index 0000000000..dc13e8c3f2
--- /dev/null
+++ b/README_chffrplus.md
@@ -0,0 +1,36 @@
+Welcome to chffrplus
+======
+
+[chffrplus](https://github.com/commaai/chffrplus) is an open source dashcam.
+
+This is the shipping reference software for the comma EON Dashcam DevKit. It keeps many of the niceities of [openpilot](https://github.com/commaai/openpilot), like high quality sensors, great camera, and good autostart and stop. Though unlike openpilot, it cannot control your car. chffrplus can interface with your car through a [panda](https://shop.comma.ai/products/panda-obd-ii-dongle), but just like our dashcam app [chffr](https://getchffr.com/), it is read only.
+
+It integrates with the rest of the comma ecosystem, so you can view your drives on the [chffr](https://getchffr.com/) app for Android or iOS, and reverse engineer your car with [cabana](https://community.comma.ai/cabana/?demo=1).
+
+
+Hardware
+------
+
+Right now chffrplus supports the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit) for hardware to run on.
+
+Install chffrplus on a EON device by entering ``https://chffrplus.comma.ai`` during NEOS setup.
+
+
+User Data / chffr Account / Crash Reporting
+------
+
+By default chffrplus creates an account and includes a client for chffr, our dashcam app.
+
+It's open source software, so you are free to disable it if you wish.
+
+It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs.
+It does not log the user facing camera or the microphone.
+
+By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data.
+
+
+Licensing
+------
+
+chffrplus is released under the MIT license.
+
diff --git a/RELEASES.md b/RELEASES.md
index 1acd4fc8fb..23c0e27f7e 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,3 +1,21 @@
+Version 0.4.3.1 (2018-03-19)
+============================
+ * Improve autofocus
+ * Add check for MPC solution error
+ * Make first distracted warning visual only
+
+Version 0.4.3 (2018-03-13)
+==========================
+ * Add HDR and autofocus
+ * Update UI aesthetic
+ * Grey panda works in Waze
+ * Add alpha support for 2017 Honda Pilot
+ * Slight increase in acceleration response from stop
+ * Switch CAN sending to use CANPacker
+ * Fix pulsing acceleration regression on Honda
+ * Fix openpilot bugs when stock system is in use
+ * Change starting logic for chffrplus to use battery voltage
+
Version 0.4.2 (2018-02-05)
==========================
* Add alpha support for 2017 Lexus RX Hybrid
diff --git a/apk/ai.comma.plus.frame.apk b/apk/ai.comma.plus.frame.apk
index 06fcf2a513..b7ac55c976 100644
Binary files a/apk/ai.comma.plus.frame.apk and b/apk/ai.comma.plus.frame.apk differ
diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk
index bb9d467913..c3bcf538a5 100644
Binary files a/apk/ai.comma.plus.offroad.apk and b/apk/ai.comma.plus.offroad.apk differ
diff --git a/apk/external/com.waze.apkpatch b/apk/external/com.waze.apkpatch
index 799c102311..31e86c5645 100644
Binary files a/apk/external/com.waze.apkpatch and b/apk/external/com.waze.apkpatch differ
diff --git a/apk/external/patcher.py b/apk/external/patcher.py
index bb5e6e7130..2666e5eeb4 100755
--- a/apk/external/patcher.py
+++ b/apk/external/patcher.py
@@ -24,7 +24,7 @@ APKS = {
'src': 'https://apkcache.s3.amazonaws.com/com.waze_1021278.apk',
'src_sha256': 'f00957e93e2389f9e30502ac54994b98ac769314b0963c263d4e8baa625ab0c2',
'patch': 'com.waze.apkpatch',
- 'out_sha256': '9ec8b0ea3c78c666342865b1bfb66e368a3f5c911df2ad12835206ec8b19f444'
+ 'out_sha256': 'fee880a91a44c738442cd05fd1b6d9b5817cbf755aa61c86325ada2bc443d5cf'
},
'com.spotify.music': {
'src': 'https://apkcache.s3.amazonaws.com/com.spotify.music_24382006.apk',
diff --git a/cereal/Makefile b/cereal/Makefile
index b384b4904e..dcf4cc2214 100644
--- a/cereal/Makefile
+++ b/cereal/Makefile
@@ -1,6 +1,6 @@
PWD := $(shell pwd)
-SRCS := log.capnp car.capnp
+SRCS := log.capnp car.capnp map.capnp
GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++
diff --git a/cereal/car.capnp b/cereal/car.capnp
index be31f6628d..beb6e8a783 100644
--- a/cereal/car.capnp
+++ b/cereal/car.capnp
@@ -54,6 +54,7 @@ struct CarEvent @0x9b1657f34caf3ad3 {
parkBrake @29;
manualRestart @30;
lowSpeedLockout @31;
+ plannerError @32;
}
}
@@ -207,6 +208,7 @@ struct CarControl {
brake @1: Float32;
# range from -1.0 - 1.0
steer @2: Float32;
+ steerAngle @3: Float32;
}
struct CruiseControl {
@@ -286,6 +288,8 @@ struct CarParams {
honda @1;
toyota @2;
elm327 @3;
+ gm @4;
+ hondaBosch @5;
}
# things about the car in the manual
@@ -301,8 +305,12 @@ struct CarParams {
tireStiffnessRear @14 :Float32; # [N/rad] rear tire coeff of stiff
# Kp and Ki for the lateral control
- steerKp @15 :Float32;
- steerKi @16 :Float32;
+ steerKpBP @42 :List(Float32);
+ steerKpV @43 :List(Float32);
+ steerKiBP @44 :List(Float32);
+ steerKiV @45 :List(Float32);
+ steerKpDEPRECATED @15 :Float32;
+ steerKiDEPRECATED @16 :Float32;
steerKf @25 :Float32;
# Kp and Ki for the longitudinal control
diff --git a/cereal/log.capnp b/cereal/log.capnp
index f6df60cd5a..a4bd57c810 100644
--- a/cereal/log.capnp
+++ b/cereal/log.capnp
@@ -117,6 +117,10 @@ struct FrameData {
frameLength @3 :Int32;
integLines @4 :Int32;
globalGain @5 :Int32;
+ lensPos @11 :Int32;
+ lensSag @12 :Float32;
+ lensErr @13 :Float32;
+ lensTruePos @14 :Float32;
image @6 :Data;
frameType @7 :FrameType;
@@ -515,6 +519,7 @@ struct Plan {
aCruise @17 :Float32;
vTarget @3 :Float32;
vTargetFuture @14 :Float32;
+ vMax @20 :Float32;
aTargetMinDEPRECATED @4 :Float32;
aTargetMaxDEPRECATED @5 :Float32;
aTarget @18 :Float32;
@@ -576,12 +581,14 @@ struct LiveLocationData {
source @14 :SensorSource;
# if we are fixing a location in the past
fixMonoTime @15 :UInt64;
-
+
gpsWeek @16 :Int32;
timeOfWeek @17 :Float64;
positionECEF @18 :List(Float64);
poseQuatECEF @19 :List(Float32);
+ pitchCalibration @20 :Float32;
+ yawCalibration @21 :Float32;
struct Accuracy {
pNEDError @0 :List(Float32);
@@ -599,6 +606,7 @@ struct LiveLocationData {
kalman @1;
orbslam @2;
timing @3;
+ dummy @4;
}
}
@@ -1283,6 +1291,11 @@ struct UbloxGnss {
fitInterval @35 :Float64;
toc @36 :Float64;
+
+ ionoCoeffsValid @37 :Bool;
+ ionoAlpha @38 :List(Float64);
+ ionoBeta @39 :List(Float64);
+
}
struct IonoData {
@@ -1314,6 +1327,7 @@ struct LiveMpcData {
delta @3 :List(Float32);
qpIterations @4 :UInt32;
calculationTime @5 :UInt64;
+ cost @6 :Float64;
}
struct LiveLongitudinalMpcData {
@@ -1327,21 +1341,31 @@ struct LiveLongitudinalMpcData {
qpIterations @7 :UInt32;
mpcId @8 :UInt32;
calculationTime @9 :UInt64;
+ cost @10 :Float64;
}
-struct ECEFPoint {
+struct ECEFPointDEPRECATED @0xe10e21168db0c7f7 {
x @0 :Float32;
y @1 :Float32;
z @2 :Float32;
}
+struct ECEFPoint @0xc25bbbd524983447 {
+ x @0 :Float64;
+ y @1 :Float64;
+ z @2 :Float64;
+}
+
struct GPSPlannerPoints {
- curPos @0 :ECEFPoint;
- points @1 :List(ECEFPoint);
+ curPosDEPRECATED @0 :ECEFPointDEPRECATED;
+ pointsDEPRECATED @1 :List(ECEFPointDEPRECATED);
+ curPos @6 :ECEFPoint;
+ points @7 :List(ECEFPoint);
valid @2 :Bool;
trackName @3 :Text;
- instructionProgress @4 :Float32;
+ speedLimit @4 :Float32;
+ accelTarget @5 :Float32;
}
struct GPSPlannerPlan {
@@ -1349,22 +1373,30 @@ struct GPSPlannerPlan {
poly @1 :List(Float32);
trackName @2 :Text;
speed @3 :Float32;
+ acceleration @4 :Float32;
+ pointsDEPRECATED @5 :List(ECEFPointDEPRECATED);
+ points @6 :List(ECEFPoint);
}
-struct TrafficSigns {
+struct TrafficEvent @0xacfa74a094e62626 {
type @0 :Type;
distance @1 :Float32;
action @2 :Action;
resuming @3 :Bool;
enum Type {
- light @0;
+ stopSign @0;
+ lightRed @1;
+ lightYellow @2;
+ lightGreen @3;
+ stopLight @4;
}
enum Action {
none @0;
yield @1;
stop @2;
+ resumeReady @3;
}
}
@@ -1378,6 +1410,98 @@ struct OrbslamCorrection {
numInliers @5 :UInt32;
}
+struct OrbObservation {
+ observationMonoTime @0 :UInt64;
+ normalizedCoordinates @1 :List(Float32);
+ locationECEF @2 :List(Float64);
+ matchDistance @3: UInt32;
+}
+
+struct UiNavigationEvent {
+ type @0: Type;
+ status @1: Status;
+ distanceTo @2: Float32;
+ endRoadPointDEPRECATED @3: ECEFPointDEPRECATED;
+ endRoadPoint @4: ECEFPoint;
+
+ enum Type {
+ none @0;
+ laneChangeLeft @1;
+ laneChangeRight @2;
+ mergeLeft @3;
+ mergeRight @4;
+ turnLeft @5;
+ turnRight @6;
+ }
+
+ enum Status {
+ none @0;
+ passive @1;
+ approaching @2;
+ active @3;
+ }
+}
+
+struct UiLayoutState {
+ activeApp @0 :App;
+ sidebarCollapsed @1 :Bool;
+ mapEnabled @2 :Bool;
+
+ enum App {
+ home @0;
+ music @1;
+ nav @2;
+ }
+}
+
+struct Joystick {
+ # convenient for debug and live tuning
+ axes @0: List(Float32);
+ buttons @1: List(Bool);
+}
+
+struct OrbOdometry {
+ # timing first
+ startMonoTime @0 :UInt64;
+ endMonoTime @1 :UInt64;
+
+ # fundamental matrix and error
+ f @2: List(Float64);
+ err @3: Float64;
+
+ # number of inlier points
+ inliers @4: Int32;
+
+ # for debug only
+ # indexed by endMonoTime features
+ # value is startMonoTime feature match
+ # -1 if no match
+ matches @5: List(Int16);
+}
+
+struct OrbFeatures {
+ timestampEof @0 :UInt64;
+ # transposed arrays of normalized image coordinates
+ # len(xs) == len(ys) == len(descriptors) * 32
+ xs @1 :List(Float32);
+ ys @2 :List(Float32);
+ descriptors @3 :Data;
+ octaves @4 :List(Int8);
+}
+
+struct OrbKeyFrame {
+ # this is a globally unique id for the KeyFrame
+ id @0: UInt64;
+
+ # this is the location of the KeyFrame
+ pos @1: ECEFPoint;
+
+ # these are the features in the world
+ # len(dpos) == len(descriptors) * 32
+ dpos @2 :List(ECEFPoint);
+ descriptors @3 :Data;
+}
+
struct Event {
# in nanoseconds?
logMonoTime @0 :UInt64;
@@ -1425,9 +1549,20 @@ struct Event {
gpsPlannerPoints @40 :GPSPlannerPoints;
gpsPlannerPlan @41 :GPSPlannerPlan;
applanixRaw @42 :Data;
- trafficSigns @43 :List(TrafficSigns);
+ trafficEvents @43 :List(TrafficEvent);
liveLocationTiming @44 :LiveLocationData;
- orbslamCorrection @45 :OrbslamCorrection;
+ orbslamCorrectionDEPRECATED @45 :OrbslamCorrection;
liveLocationCorrected @46 :LiveLocationData;
+ orbObservation @47 :List(OrbObservation);
+ gpsLocationExternal @48 :GpsLocationData;
+ location @49 :LiveLocationData;
+ uiNavigationEvent @50 :UiNavigationEvent;
+ liveLocationKalman @51 :LiveLocationData;
+ testJoystick @52 :Joystick;
+ orbOdometry @53 :OrbOdometry;
+ orbFeatures @54 :OrbFeatures;
+ applanixLocation @55 :LiveLocationData;
+ orbKeyFrame @56 :OrbKeyFrame;
+ uiLayoutState @57 :UiLayoutState;
}
}
diff --git a/common/fingerprints.py b/common/fingerprints.py
index 1e0c71da47..ee10abd038 100644
--- a/common/fingerprints.py
+++ b/common/fingerprints.py
@@ -4,6 +4,7 @@ class HONDA:
CRV = "HONDA CR-V 2016 TOURING"
ODYSSEY = "HONDA ODYSSEY 2018 EX-L"
ACURA_RDX = "ACURA RDX 2018 ACURAWATCH PLUS"
+ PILOT = "HONDA PILOT 2017 TOURING"
class TOYOTA:
@@ -13,35 +14,43 @@ class TOYOTA:
COROLLA = "TOYOTA COROLLA 2017"
LEXUS_RXH = "LEXUS RX HYBRID 2017"
+_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes
_FINGERPRINTS = {
- HONDA.ACURA_ILX: {
- 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5,
+ HONDA.ACURA_ILX: [{
+ 1024L: 5, 513L: 6, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5,
# sent messages
- 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5,
- },
- HONDA.ACURA_RDX: {
+ 0xe4: 5, 0x1fa: 8, 0x200: 6, 0x30c: 8, 0x33d: 5,
+ }],
+ HONDA.ACURA_RDX: [{
57L: 3, 145L: 8, 229L: 4, 308L: 5, 316L: 8, 342L: 6, 344L: 8, 380L: 8, 392L: 6, 398L: 3, 399L: 6, 404L: 4, 420L: 8, 422L: 8, 426L: 8, 432L: 7, 464L: 8, 474L: 5, 476L: 4, 487L: 4, 490L: 8, 506L: 8, 542L: 7, 545L: 4, 597L: 8, 660L: 8, 773L: 7, 777L: 8, 780L: 8, 800L: 8, 804L: 8, 808L: 8, 819L: 7, 821L: 5, 829L: 5, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 892L: 8, 923L: 2, 929L: 4, 963L: 8, 965L: 8, 966L: 8, 967L: 8, 983L: 8, 985L: 3, 1024L: 5, 1027L: 5, 1029L: 8, 1033L: 5, 1034L: 5, 1036L: 8, 1039L: 8, 1057L: 5, 1064L: 7, 1108L: 8, 1365L: 5, 1424L: 5, 1729L: 1
- },
- HONDA.CIVIC: {
- 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5,
+ }],
+ HONDA.CIVIC: [{
+ 1024L: 5, 513L: 6, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5,
# sent messages
- 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8,
- },
- HONDA.CRV: {
+ 0xe4: 5, 0x1fa: 8, 0x200: 6, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8,
+ }],
+ HONDA.CRV: [{
57L: 3, 145L: 8, 316L: 8, 340L: 8, 342L: 6, 344L: 8, 380L: 8, 398L: 3, 399L: 6, 401L: 8, 420L: 8, 422L: 8, 426L: 8, 432L: 7, 464L: 8, 474L: 5, 476L: 4, 487L: 4, 490L: 8, 493L: 3, 507L: 1, 542L: 7, 545L: 4, 597L: 8, 660L: 8, 661L: 4, 773L: 7, 777L: 8, 800L: 8, 804L: 8, 808L: 8, 882L: 2, 884L: 7, 888L: 8, 891L: 8, 892L: 8, 923L: 2, 929L: 8, 983L: 8, 985L: 3, 1024L: 5, 1027L: 5, 1029L: 8, 1033L: 5, 1036L: 8, 1039L: 8, 1057L: 5, 1064L: 7, 1108L: 8, 1125L: 8, 1296L: 8, 1365L: 5, 1424L: 5, 1600L: 5, 1601L: 8,
# sent messages
0x194: 4, 0x1fa: 8, 0x30c: 8, 0x33d: 5,
- },
- HONDA.ODYSSEY: {
+ }],
+ HONDA.ODYSSEY: [{
57L: 3, 148L: 8, 228L: 5, 229L: 4, 316L: 8, 342L: 6, 344L: 8, 380L: 8, 399L: 7, 411L: 5, 419L: 8, 420L: 8, 427L: 3, 432L: 7, 450L: 8, 463L: 8, 464L: 8, 476L: 4, 490L: 8, 506L: 8, 542L: 7, 545L: 6, 597L: 8, 662L: 4, 773L: 7, 777L: 8, 780L: 8, 795L: 8, 800L: 8, 804L: 8, 806L: 8, 808L: 8, 817L: 4, 819L: 7, 821L: 5, 825L: 4, 829L: 5, 837L: 5, 856L: 7, 862L: 8, 871L: 8, 881L: 8, 882L: 4, 884L: 8, 891L: 8, 892L: 8, 905L: 8, 923L: 2, 927L: 8, 929L: 8, 963L: 8, 965L: 8, 966L: 8, 967L: 8, 983L: 8, 985L: 3, 1029L: 8, 1036L: 8, 1052L: 8, 1064L: 7, 1088L: 8, 1089L: 8, 1092L: 1, 1108L: 8, 1110L: 8, 1125L: 8, 1296L: 8, 1302L: 8, 1600L: 5, 1601L: 8, 1612L: 5, 1613L: 5, 1614L: 5, 1615L: 8, 1616L: 5, 1619L: 5, 1623L: 5, 1668L: 5
},
- TOYOTA.RAV4: {
+ # Odyssey Elite
+ {
+ 57L: 3, 148L: 8, 228L: 5, 229L: 4, 304L: 8, 342L: 6, 344L: 8, 380L: 8, 399L: 7, 411L: 5, 419L: 8, 420L: 8, 427L: 3, 432L: 7, 440L: 8, 450L: 8, 463L: 8, 464L: 8, 476L: 4, 490L: 8, 506L: 8, 507L: 1, 542L: 7, 545L: 6, 597L: 8, 662L: 4, 773L: 7, 777L: 8, 780L: 8, 795L: 8, 800L: 8, 804L: 8, 806L: 8, 808L: 8, 817L: 4, 819L: 7, 821L: 5, 825L: 4, 829L: 5, 837L: 5, 856L: 7, 862L: 8, 871L: 8, 881L: 8, 882L: 4, 884L: 8, 891L: 8, 892L: 8, 905L: 8, 923L: 2, 927L: 8, 929L: 8, 963L: 8, 965L: 8, 966L: 8, 967L: 8, 983L: 8, 985L: 3, 1029L: 8, 1036L: 8, 1052L: 8, 1064L: 7, 1088L: 8, 1089L: 8, 1092L: 1, 1108L: 8, 1110L: 8, 1125L: 8, 1296L: 8, 1302L: 8, 1600L: 5, 1601L: 8, 1612L: 5, 1613L: 5, 1614L: 5, 1616L: 5, 1619L: 5, 1623L: 5, 1668L: 5
+ }],
+ HONDA.PILOT: [{
+ 1600L: 5, 1027L: 5, 1668L: 5, 1029L: 8, 1601L: 8, 777L: 8, 891L: 8, 1036L: 8, 399L: 7, 1424L: 5, 145L: 8, 660L: 8, 985L: 3, 1616L: 5, 538L: 3, 795L: 8, 542L: 7, 773L: 7, 800L: 8, 545L: 5, 546L: 3, 419L: 8, 420L: 8, 422L: 8, 1064L: 7, 425L: 8, 426L: 8, 427L: 3, 432L: 7, 819L: 7, 308L: 5, 821L: 5, 57L: 3, 965L: 8, 316L: 8, 829L: 5, 1088L: 8, 1089L: 8, 963L: 8, 837L: 5, 966L: 8, 929L: 8, 780L: 8, 923L: 2, 1613L: 5, 334L: 8, 463L: 8, 464L: 8, 1618L: 5, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 856L: 7, 804L: 8, 1612L: 5, 476L: 4, 1125L: 8, 344L: 8, 1296L: 8, 379L: 8, 228L: 5, 229L: 4, 871L: 8, 892L: 8, 490L: 8, 808L: 8, 882L: 2, 884L: 7, 967L: 8, 506L: 8, 507L: 1, 380L: 8,
+ }],
+ TOYOTA.RAV4: [{
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, 1005L: 2, 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, 1264L: 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.RAV4H: {
- 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, 560L: 7, 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.RAV4H: [{
+ 36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 296L: 8, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 4, 581L: 5, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 713L: 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, 950L: 8, 951L: 8, 953L: 3, 955L: 8, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1005L: 2, 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, 1184L: 8, 1185L: 8, 1186L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1197L: 8, 1198L: 8, 1199L: 8, 1212L: 8, 1227L: 8, 1228L: 8, 1232L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1264L: 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.PRIUS: [{
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
},
@@ -52,14 +61,13 @@ _FINGERPRINTS = {
# Taiwanese Prius Prime
{
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, 824L: 2, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 845L: 5, 863L: 8, 869L: 7, 870L: 7, 871L: 2,898L: 8, 900L: 6, 902L: 6, 905L: 8, 913L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 974L: 8, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1005L: 2, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1076L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1164L: 8, 1165L: 8, 1166L: 8, 1167L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1264L: 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
- }
- ],
- TOYOTA.COROLLA: {
+ }],
+ TOYOTA.COROLLA: [{
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- },
- TOYOTA.LEXUS_RXH: {
+ }],
+ TOYOTA.LEXUS_RXH: [{
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8
- },
+ }],
}
# support additional internal only fingerprints
@@ -88,10 +96,10 @@ def eliminate_incompatible_cars(msg, candidate_cars):
compatible_cars = []
for car_name in candidate_cars:
car_fingerprints = _FINGERPRINTS[car_name]
- if not isinstance(car_fingerprints, list):
- car_fingerprints = [car_fingerprints]
for fingerprint in car_fingerprints:
+ fingerprint.update(_DEBUG_ADDRESS) # add alien debug address
+
if is_valid_for_fingerprint(msg, fingerprint):
compatible_cars.append(car_name)
break
diff --git a/common/profiler.py b/common/profiler.py
index 83e5672e04..953f5737d8 100644
--- a/common/profiler.py
+++ b/common/profiler.py
@@ -6,7 +6,7 @@ class Profiler(object):
self.cp = {}
self.cp_ignored = []
self.iter = 0
- self.start_time = time.clock()
+ self.start_time = time.time()
self.last_time = self.start_time
self.tot = 0.
@@ -15,14 +15,14 @@ class Profiler(object):
self.cp = {}
self.cp_ignored = []
self.iter = 0
- self.start_time = time.clock()
+ self.start_time = time.time()
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()
+ tt = time.time()
if name not in self.cp:
self.cp[name] = 0.
if ignore:
@@ -37,11 +37,10 @@ class Profiler(object):
return
self.iter += 1
print "******* Profiling *******"
- for n in self.cp:
- ms = self.cp[n]
+ for n, ms in sorted(self.cp.items(), key=lambda x: -x[1]):
if n in self.cp_ignored:
- print "%30s: %7.2f perc: %1.0f" % (n, ms*1000.0, ms/self.tot*100), " IGNORED"
+ print "%30s: %7.2f percent: %3.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 "%30s: %7.2f percent: %3.0f" % (n, ms*1000.0, ms/self.tot*100)
print "Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)
diff --git a/common/transformations/__init__.py b/common/transformations/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py
new file mode 100644
index 0000000000..0b0bd839ad
--- /dev/null
+++ b/common/transformations/coordinates.py
@@ -0,0 +1,106 @@
+import numpy as np
+"""
+Coordinate transformation module. All methods accept arrays as input
+with each row as a position.
+"""
+
+
+
+a = 6378137
+b = 6356752.3142
+esq = 6.69437999014 * 0.001
+e1sq = 6.73949674228 * 0.001
+
+
+def geodetic2ecef(geodetic):
+ geodetic = np.array(geodetic)
+ input_shape = geodetic.shape
+ geodetic = np.atleast_2d(geodetic)
+ lat = (np.pi/180)*geodetic[:,0]
+ lon = (np.pi/180)*geodetic[:,1]
+ alt = geodetic[:,2]
+
+ xi = np.sqrt(1 - esq * np.sin(lat)**2)
+ x = (a / xi + alt) * np.cos(lat) * np.cos(lon)
+ y = (a / xi + alt) * np.cos(lat) * np.sin(lon)
+ z = (a / xi * (1 - esq) + alt) * np.sin(lat)
+ ecef = np.array([x, y, z]).T
+ return ecef.reshape(input_shape)
+
+
+def ecef2geodetic(ecef):
+ """
+ Convert ECEF coordinates to geodetic using ferrari's method
+ """
+ def ferrari(x, y, z):
+ # ferrari's method
+ r = np.sqrt(x * x + y * y)
+ Esq = a * a - b * b
+ F = 54 * b * b * z * z
+ G = r * r + (1 - esq) * z * z - esq * Esq
+ C = (esq * esq * F * r * r) / (pow(G, 3))
+ S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C))
+ P = F / (3 * pow((S + 1 / S + 1), 2) * G * G)
+ Q = np.sqrt(1 + 2 * esq * esq * P)
+ r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \
+ P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r)
+ U = np.sqrt(pow((r - esq * r_0), 2) + z * z)
+ V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z)
+ Z_0 = b * b * z / (a * V)
+ h = U * (1 - b * b / (a * V))
+ lat = (180/np.pi)*np.arctan((z + e1sq * Z_0) / r)
+ lon = (180/np.pi)*np.arctan2(y, x)
+ return lat, lon, h
+
+ geodetic = []
+ ecef = np.array(ecef)
+ input_shape = ecef.shape
+ ecef = np.atleast_2d(ecef)
+ for p in ecef:
+ geodetic.append(ferrari(*p))
+ geodetic = np.array(geodetic)
+ return geodetic.reshape(input_shape)
+
+
+
+class LocalCoord(object):
+ """
+ Allows conversions to local frames. In this case NED.
+ That is: North East Down from the start position in
+ meters.
+ """
+ def __init__(self, init_geodetic, init_ecef):
+ self.init_ecef = init_ecef
+ lat, lon, _ = (np.pi/180)*init_geodetic
+ self.ned2ecef_matrix = np.array([[-np.sin(lat)*np.cos(lon), -np.sin(lon), -np.cos(lat)*np.cos(lon)],
+ [-np.sin(lat)*np.sin(lon), np.cos(lon), -np.cos(lat)*np.sin(lon)],
+ [np.cos(lat), 0, -np.sin(lat)]])
+ self.ecef2ned_matrix = self.ned2ecef_matrix.T
+
+ @classmethod
+ def from_geodetic(self, init_geodetic):
+ init_ecef = geodetic2ecef(init_geodetic)
+ return LocalCoord(init_geodetic, init_ecef)
+
+ @classmethod
+ def from_ecef(self, init_ecef):
+ init_geodetic = ecef2geodetic(init_ecef)
+ return LocalCoord(init_geodetic, init_ecef)
+
+
+ def ecef2ned(self, ecef):
+ ecef = np.array(ecef)
+ return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T
+
+ def ned2ecef(self, ned):
+ ned = np.array(ned)
+ # Transpose so that init_ecef will broadcast correctly for 1d or 2d ned.
+ return (np.dot(self.ned2ecef_matrix, ned.T).T + self.init_ecef)
+
+ def geodetic2ned(self, geodetic):
+ ecef = geodetic2ecef(geodetic)
+ return self.ecef2ned(ecef)
+
+ def ned2geodetic(self, ned):
+ ecef = self.ned2ecef(ned)
+ return ecef2geodetic(ecef)
diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh
new file mode 100755
index 0000000000..3959c58de1
--- /dev/null
+++ b/launch_chffrplus.sh
@@ -0,0 +1,44 @@
+#!/usr/bin/bash
+
+if [ -z "$PASSIVE" ]; then
+ export PASSIVE="1"
+fi
+
+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
+
+ # check if NEOS update is required
+ while [ "$(cat /VERSION)" -lt 4 ] && [ ! -e /data/media/0/noupdate ]; do
+ # 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
+
+ # update NEOS
+ 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
diff --git a/launch_openpilot.sh b/launch_openpilot.sh
index 2e7b163c8c..1525e1715f 100755
--- a/launch_openpilot.sh
+++ b/launch_openpilot.sh
@@ -1,39 +1,5 @@
#!/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
+export PASSIVE="0"
+exec ./launch_chffrplus.sh
- # 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
diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc
index 204a25c923..868d8ba4f5 100644
--- a/opendbc/acura_ilx_2016_can_generated.dbc
+++ b/opendbc/acura_ilx_2016_can_generated.dbc
@@ -1,4 +1,24 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
+CM_ "Imported file _comma.dbc starts here"
+BO_ 512 GAS_COMMAND: 6 EON
+ SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
+ SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR
+
+BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
+ SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
+
+VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +56,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +97,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +116,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +144,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +162,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +179,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -217,6 +228,8 @@ VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "acura_ilx_2016_can.dbc starts here"
+
+
BO_ 145 KINEMATICS: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
diff --git a/opendbc/acura_ilx_2016_nidec.dbc b/opendbc/acura_ilx_2016_nidec.dbc
index e2810b40ac..4d8738a0aa 100644
--- a/opendbc/acura_ilx_2016_nidec.dbc
+++ b/opendbc/acura_ilx_2016_nidec.dbc
@@ -1,185 +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";
+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";
diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc
index 1e85eb4132..2eedb6fc4b 100644
--- a/opendbc/acura_rdx_2018_can_generated.dbc
+++ b/opendbc/acura_rdx_2018_can_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +38,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +79,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +98,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +126,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +144,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +161,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -217,6 +210,7 @@ VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "acura_rdx_2018_can.dbc starts here"
+
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
diff --git a/opendbc/chrysler_pacifica_2017_hybrid.dbc b/opendbc/chrysler_pacifica_2017_hybrid.dbc
new file mode 100644
index 0000000000..7cd13b745f
--- /dev/null
+++ b/opendbc/chrysler_pacifica_2017_hybrid.dbc
@@ -0,0 +1,107 @@
+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_ 258 STEERING: 8 XXX
+ SG_ STEER_ANGLE : 4|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX
+ SG_ STEERING_RATE : 20|13@0+ (1,-4096) [0|8191] "" XXX
+
+BO_ 514 SPEED: 4 XXX
+ SG_ SPEED_LEFT : 7|16@0+ (0.07,0) [0|65535] "m/s" XXX
+ SG_ SPEED_RIGHT : 23|16@0+ (0.07,0) [0|1023] "m/s" XXX
+
+BO_ 653 BRAKE_MODULE: 2 XXX
+ SG_ BRAKE_PRESSURE : 15|8@0+ (1,0) [0|255] "" XXX
+ SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|4] "" XXX
+
+BO_ 820 DOORS: 8 XXX
+ SG_ DOOR_OPEN_FR : 18|1@0+ (1,0) [0|1] "" XXX
+ SG_ DOOR_OPEN_RL : 19|1@0+ (1,0) [0|1] "" XXX
+ SG_ DOOR_OPEN_RR : 20|1@0+ (1,0) [0|1] "" XXX
+ SG_ DOOR_OPEN_TRUNK : 22|1@0+ (1,0) [0|1] "" XXX
+ SG_ DOOR_OPEN_FL : 17|1@0+ (1,0) [0|1] "" XXX
+ SG_ TURN_LIGHT_LEFT : 31|1@0+ (1,0) [0|1] "" XXX
+ SG_ TURN_LIGHT_RIGHT : 30|1@0+ (1,0) [0|1] "" XXX
+ SG_ HIGH_BEAM_DISPLAY : 58|1@1+ (1,0) [0|1] "" XXX
+
+BO_ 746 GEAR: 5 XXX
+ SG_ PRNDL : 0|3@1+ (1,0) [0|7] "" XXX
+
+BO_ 284 NEW_MSG_1: 8 XXX
+ SG_ BRAKE_RELATED : 3|12@0+ (1,0) [0|255] "" XXX
+ SG_ BRAKE_RELATED_2 : 17|10@0+ (1,0) [0|255] "" XXX
+ SG_ SPEED : 37|14@0+ (1,0) [0|255] "" XXX
+
+BO_ 320 NEW_MSG_2: 8 XXX
+ SG_ SPEED_RELATED : 47|8@0+ (1,0) [0|63] "" XXX
+ SG_ BRAKE_PRESSED : 2|3@0+ (1,0) [0|7] "" XXX
+
+BO_ 736 TRIP: 8 XXX
+ SG_ DISTANCE_COUNTER : 7|16@0+ (0,0) [0|65535] "Meters" XXX
+ SG_ DISTANCE_COUNTER_2 : 23|16@0+ (1,0) [0|65535] "Meters" XXX
+
+BO_ 344 WHEEL_SPEEDS: 8 XXX
+ SG_ WHEEL_SPEED_FL : 1|10@0+ (1,0) [0|65535] "" XXX
+ SG_ WHEEL_SPEED_FR : 17|10@0+ (1,0) [0|255] "" XXX
+ SG_ WHEEL_SPEED_RL : 33|10@0+ (1,0) [0|3] "" XXX
+ SG_ WHEEL_SPEED_RR : 49|10@0+ (1,0) [0|255] "" XXX
+
+BO_ 792 STEERING_LEVERS: 8 XXX
+ SG_ TURN_SIGNALS : 1|2@0+ (1,0) [0|3] "" XXX
+ SG_ HIGH_BEAM_PUSHED_IN : 2|1@1+ (1,0) [0|3] "" XXX
+ SG_ HIGH_BEAM_FLASH : 3|1@1+ (1,0) [0|3] "" XXX
+
+BO_ 264 ACCEL_PEDAL_MSG: 8 XXX
+ SG_ ACCEL_PEDAL : 32|4@1+ (1,-7) [0|15] "" XXX
+
+
+
+
+CM_ SG_ 258 STEER_ANGLE "positive is left (counter-clockwise)";
+CM_ SG_ 514 SPEED_LEFT "TODO find upper limit";
+CM_ SG_ 653 BRAKE_PRESSURE "max seems to be 148";
+CM_ SG_ 820 TURN_LIGHT_LEFT "oscillates with the light blinking";
+CM_ SG_ 820 TURN_LIGHT_RIGHT "hazard blinks both right and left lights";
+CM_ SG_ 746 PRNDL "4=D, 3=N, 2=R, 1=P";
+CM_ SG_ 284 BRAKE_RELATED "Correlates with braking";
+CM_ SG_ 284 SPEED "Another Speed Signal, Maybe RPMs?";
+CM_ SG_ 320 BRAKE_PRESSED "Value is 5 when brake is pressed";
+CM_ SG_ 792 TURN_SIGNALS "1=Left, 2=Right";
+CM_ SG_ 792 HIGH_BEAM_FLASH "use this for genericToggle";
+CM_ SG_ 264 ACCEL_PEDAL "not in ACC so seems to be actual pedal. Use for gasPressed";
+VAL_ 746 PRNDL 4 "Drive" 3 "Neutral" 2 "Reverse" 1 "Park" ;
+VAL_ 792 TURN_SIGNALS 2 "Right" 1 "Left" ;
diff --git a/opendbc/generator/generator.py b/opendbc/generator/generator.py
index 81e3b1ce9b..e5f69e40bb 100755
--- a/opendbc/generator/generator.py
+++ b/opendbc/generator/generator.py
@@ -17,14 +17,16 @@ for dir_name, _, _ in os.walk(cur_path):
print filename
dbc_file = open(os.path.join(dir_name, filename)).read()
- include = re.search(r'CM_ "IMPORT (.*?)"', dbc_file)
- if include is not None:
- dbc_file = dbc_file.replace(include.group(0), '\nCM_ "%s starts here"' % filename)
+ dbc_file = '\nCM_ "%s starts here"\n' % filename + dbc_file
+
+ includes = re.finditer(r'CM_ "IMPORT (.*?)"', dbc_file)
+ for include in includes:
+ dbc_file = dbc_file.replace(include.group(0), '')
include_path = os.path.join(dir_name, include.group(1))
# Load included file
include_file = open(include_path).read()
- include_file = 'CM_ "Imported file %s starts here"\n' % include.group(1) + include_file
+ include_file = '\n\nCM_ "Imported file %s starts here"\n' % include.group(1) + include_file
dbc_file = include_file + dbc_file
dbc_file = 'CM_ "AUTOGENERATED FILE, DO NOT EDIT"\n' + dbc_file
diff --git a/opendbc/generator/honda/_bosch_2018.dbc b/opendbc/generator/honda/_bosch_2018.dbc
new file mode 100644
index 0000000000..a1c5071167
--- /dev/null
+++ b/opendbc/generator/honda/_bosch_2018.dbc
@@ -0,0 +1,265 @@
+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_
+
+BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB
+
+BO_ 228 STEERING_CONTROL: 5 EON
+ 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_SPEED : 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_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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|15] "" EON
+
+BO_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 344 ENGINE_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_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 380 POWERTRAIN_DATA: 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] "" EON
+ SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" EON
+
+BO_ 420 VSA_STATUS: 8 VSA
+ SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
+ SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
+ SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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|15] "" EON
+
+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|15] "" EON
+
+BO_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ 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.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 479 ACC_CONTROL: 8 EON
+ 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_ 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_16: 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" 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 : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
+ SG_ LONG_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_ 773 SEATBELT_STATUS: 7 BDY
+ SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_ON : 15|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 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_ LOCK_STATUS : 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_ 804 CRUISE: 8 PCM
+ SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 806 SCM_FEEDBACK: 8 SCM
+ 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_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON
+ 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_ 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 : 51|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 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 STALK_STATUS_2: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ 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_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/generator/honda/_comma.dbc b/opendbc/generator/honda/_comma.dbc
new file mode 100644
index 0000000000..0be2275381
--- /dev/null
+++ b/opendbc/generator/honda/_comma.dbc
@@ -0,0 +1,15 @@
+BO_ 512 GAS_COMMAND: 6 EON
+ SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
+ SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR
+
+BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
+ SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
+
+VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
diff --git a/opendbc/generator/honda/_honda_2017.dbc b/opendbc/generator/honda/_honda_2017.dbc
index 30cda98536..49664a0dca 100644
--- a/opendbc/generator/honda/_honda_2017.dbc
+++ b/opendbc/generator/honda/_honda_2017.dbc
@@ -34,9 +34,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -75,7 +75,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -94,17 +94,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -133,9 +122,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -152,6 +140,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -167,6 +157,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
diff --git a/opendbc/generator/honda/acura_ilx_2016_can.dbc b/opendbc/generator/honda/acura_ilx_2016_can.dbc
index df5b543fc8..5acfc3169d 100644
--- a/opendbc/generator/honda/acura_ilx_2016_can.dbc
+++ b/opendbc/generator/honda/acura_ilx_2016_can.dbc
@@ -1,4 +1,5 @@
CM_ "IMPORT _honda_2017.dbc"
+CM_ "IMPORT _comma.dbc"
BO_ 145 KINEMATICS: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
diff --git a/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc b/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc
new file mode 100644
index 0000000000..5a5f46d83d
--- /dev/null
+++ b/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc
@@ -0,0 +1,54 @@
+CM_ "IMPORT _bosch_2018.dbc"
+
+BO_ 419 GEARBOX: 8 PCM
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
+
+BO_ 446 BRAKE_MODULE: 3 VSA
+ SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 19|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_ 662 SCM_BUTTONS: 8 SCM
+ SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
+ SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+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_ 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_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX
+ SG_ BOH_2 : 30|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_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ;
+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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc
new file mode 100644
index 0000000000..ef4f6a4e93
--- /dev/null
+++ b/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc
@@ -0,0 +1,54 @@
+CM_ "IMPORT _bosch_2018.dbc"
+
+BO_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ 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] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 662 SCM_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_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON
+
+BO_ 892 CRUISE_PARAMS: 8 PCM
+ SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON
+
+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_ 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|15] "" EON
+
+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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc
index 85643cbe2f..9e795fbae3 100644
--- a/opendbc/generator/honda/honda_civic_touring_2016_can.dbc
+++ b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc
@@ -1,142 +1,143 @@
-CM_ "IMPORT _honda_2017.dbc"
-
-BO_ 148 KINEMATICS: 8 XXX
- SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
- SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-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_PEDAL_2: 8 PCM
- SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
- SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
- SG_ CAR_GAS : 39|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_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
- SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" 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_ 401 GEARBOX: 8 PCM
- SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
- SG_ GEAR : 43|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_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
- SG_ BRAKE_HOLD_ENABLED : 45|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_ 450 EPB_STATUS: 8 EPB
- SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
- SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
-
-BO_ 487 BRAKE_PRESSURE: 4 VSA
- SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
- SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
- SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
-
-BO_ 545 ECON_STATUS: 6 XXX
- SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON
- SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON
- SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
-
-BO_ 662 SCM_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_ 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_ 862 HIGHBEAM_CONTROL: 8 ADAS
- SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
- SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
- SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
- SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 884 STALK_STATUS: 8 XXX
- SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
- SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
- SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
- SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-BO_ 891 WIPERS: 8 XXX
- SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-BO_ 927 RADAR_HUD: 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_ 1302 ODOMETER: 8 XXX
- SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
-
-CM_ SG_ 401 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_ 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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
-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";
+CM_ "IMPORT _honda_2017.dbc"
+CM_ "IMPORT _comma.dbc"
+
+BO_ 148 KINEMATICS: 8 XXX
+ SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
+ SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+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_PEDAL_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" 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_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 43|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_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 487 BRAKE_PRESSURE: 4 VSA
+ SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
+ SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+
+BO_ 545 ECON_STATUS: 6 XXX
+ SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON
+ SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
+
+BO_ 662 SCM_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_ 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_ 862 HIGHBEAM_CONTROL: 8 ADAS
+ SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
+ SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
+ SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
+ SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 884 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 WIPERS: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 927 RADAR_HUD: 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_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+CM_ SG_ 401 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_ 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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+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";
diff --git a/opendbc/generator/honda/honda_crv_ex_2017_can.dbc b/opendbc/generator/honda/honda_crv_ex_2017_can.dbc
new file mode 100644
index 0000000000..46afb90bd6
--- /dev/null
+++ b/opendbc/generator/honda/honda_crv_ex_2017_can.dbc
@@ -0,0 +1,71 @@
+CM_ "IMPORT _bosch_2018.dbc"
+
+BO_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ 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] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 446 BRAKE_MODULE: 3 VSA
+ SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 19|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_ 662 SCM_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_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON
+
+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_ 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|15] "" EON
+
+BO_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+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";
+
+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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc b/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc
new file mode 100644
index 0000000000..29b6e44dd0
--- /dev/null
+++ b/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc
@@ -0,0 +1,61 @@
+CM_ "IMPORT _honda_2017.dbc"
+
+BO_ 145 KINEMATICS: 8 XXX
+ SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
+
+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_ 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_ 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_ 419 GEARBOX: 8 PCM
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" 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
+
+BO_ 422 SCM_BUTTONS: 8 SCM
+ SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
+ SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
+ SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 660 SCM_FEEDBACK: 8 SCM
+ SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON
+ SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON
+
+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" ;
+
+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";
diff --git a/opendbc/generator/toyota/_toyota_2017.dbc b/opendbc/generator/toyota/_toyota_2017.dbc
index 25120828c2..5679ecf399 100644
--- a/opendbc/generator/toyota/_toyota_2017.dbc
+++ b/opendbc/generator/toyota/_toyota_2017.dbc
@@ -71,10 +71,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -95,6 +96,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -121,17 +127,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
diff --git a/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc b/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc
index 2c0a480991..601066dbfa 100644
--- a/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc
+++ b/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc
@@ -15,7 +15,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -25,6 +25,6 @@ BO_ 956 GEAR_PACKET: 8 XXX
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_ 581 GAS_PEDAL "it seems slightly filtered";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
diff --git a/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc
new file mode 100644
index 0000000000..130e619d48
--- /dev/null
+++ b/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc
@@ -0,0 +1,33 @@
+CM_ "IMPORT _toyota_2017.dbc"
+
+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_ 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_ 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_ IPAS_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
+
+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_ 581 GAS_PEDAL "it seems slightly filtered";
+VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/generator/toyota/toyota_chr_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_2018_pt.dbc
new file mode 100644
index 0000000000..5082c37e85
--- /dev/null
+++ b/opendbc/generator/toyota/toyota_chr_2018_pt.dbc
@@ -0,0 +1,30 @@
+CM_ "IMPORT _toyota_2017.dbc"
+
+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_ 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.73,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_ IPAS_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_ 956 GEAR_PACKET: 8 XXX
+ SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
+
+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";
+VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc
index bf29cbc314..15fbc3494f 100644
--- a/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc
+++ b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc
@@ -15,7 +15,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -25,5 +25,5 @@ BO_ 956 GEAR_PACKET: 8 XXX
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";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/generator/toyota/toyota_prius_2017_pt.dbc b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc
index 7f00b34e7e..130e619d48 100644
--- a/opendbc/generator/toyota/toyota_prius_2017_pt.dbc
+++ b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc
@@ -21,7 +21,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -29,5 +29,5 @@ 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_ 581 GAS_PEDAL "it seems slightly filtered";
VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc
index fe98779c43..a598ccb52d 100644
--- a/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc
+++ b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc
@@ -15,7 +15,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -25,5 +25,5 @@ BO_ 956 GEAR_PACKET: 8 XXX
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";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc
index 2c0a480991..601066dbfa 100644
--- a/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc
+++ b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc
@@ -15,7 +15,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -25,6 +25,6 @@ BO_ 956 GEAR_PACKET: 8 XXX
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_ 581 GAS_PEDAL "it seems slightly filtered";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
diff --git a/opendbc/gm_global_a_chassis.dbc b/opendbc/gm_global_a_chassis.dbc
index 5408e00a8c..bbc2ccd588 100644
--- a/opendbc/gm_global_a_chassis.dbc
+++ b/opendbc/gm_global_a_chassis.dbc
@@ -1,75 +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";
-
+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";
+
diff --git a/opendbc/gm_global_a_lowspeed.dbc b/opendbc/gm_global_a_lowspeed.dbc
index 9fc4f86e23..9ea4d1da3d 100644
--- a/opendbc/gm_global_a_lowspeed.dbc
+++ b/opendbc/gm_global_a_lowspeed.dbc
@@ -1,110 +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" ;
-
+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 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "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|3@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 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ;
+VAL_ 276127744 LKAGapButton 2 "???" 1 "??" 0 "None" ;
+
diff --git a/opendbc/gm_global_a_object.dbc b/opendbc/gm_global_a_object.dbc
index c1a50ad94d..b4aa31a3e1 100644
--- a/opendbc/gm_global_a_object.dbc
+++ b/opendbc/gm_global_a_object.dbc
@@ -1,255 +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" ;
-
+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" ;
+
diff --git a/opendbc/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain.dbc
index 9a7fb34dac..7c35d9b970 100644
--- a/opendbc/gm_global_a_powertrain.dbc
+++ b/opendbc/gm_global_a_powertrain.dbc
@@ -1,217 +1,233 @@
-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_ GasRegenAlwaysOne3 : 23|1@0+ (1,0) [0|1] "" NEO
- SG_ GasRegenCmd : 22|12@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" ;
-
+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_ DistanceButton 1 "Active" 0 "Inactive" ;
+VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ;
+VAL_TABLE_ ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ;
+VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ;
+VAL_TABLE_ DoorStatus 1 "Opened" 0 "Closed" ;
+VAL_TABLE_ SeatBeltStatus 1 "Latched" 0 "Unlatched" ;
+VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ;
+VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ;
+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_ DistanceButton : 22|1@0+ (1,0) [0|0] "" NEO
+ SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO
+ SG_ ACCButtons : 46|3@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 BCMDoorBeltStatus: 8 K9_BCM
+ SG_ RearLeftDoor : 8|1@0+ (1,0) [0|0] "" NEO
+ SG_ FrontLeftDoor : 9|1@0+ (1,0) [0|0] "" NEO
+ SG_ FrontRightDoor : 10|1@0+ (1,0) [0|0] "" NEO
+ SG_ RearRightDoor : 23|1@0+ (1,0) [0|0] "" NEO
+ SG_ LeftSeatBelt : 12|1@0+ (1,0) [0|0] "" NEO
+ SG_ RightSeatBelt : 53|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_ BrakePedalPos : 15|8@0+ (1,0) [0|0] "sticky" NEO
+ SG_ GasPedalAndAcc : 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_ GasRegenAlwaysOne3 : 23|1@0+ (1,0) [0|1] "" NEO
+ SG_ GasRegenCmd : 22|12@0+ (1,0) [0|0] "" NEO
+
+BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM
+ SG_ FLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO
+ SG_ FRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO
+
+BO_ 842 EBCMWheelSpdRear: 4 K17_EBCM
+ SG_ RLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO
+ SG_ RRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO
+
+BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM
+ SG_ BrakePedalPosition : 15|8@0+ (1,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_ 417 AcceleratorPedal: 8 XXX
+ SG_ AcceleratorPedal : 55|8@0+ (1,0) [0|0] "" NEO
+
+BO_ 451 GasAndAcc: 8 XXX
+ SG_ GasPedalAndAcc2 : 55|8@0+ (1,0) [0|0] "" NEO
+
+BO_ 452 AcceleratorPedal2: 8 XXX
+ SG_ AcceleratorPedal2 : 47|8@0+ (1,0) [0|0] "" 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";
+CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62";
+CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62";
+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 DistanceButton 1 "Active" 0 "Inactive" ;
+VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ;
+VAL_ 481 ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ;
+VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ;
+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" ;
+
diff --git a/opendbc/honda_accord_s2t_2018_can_generated.dbc b/opendbc/honda_accord_s2t_2018_can_generated.dbc
new file mode 100644
index 0000000000..77035ee1d8
--- /dev/null
+++ b/opendbc/honda_accord_s2t_2018_can_generated.dbc
@@ -0,0 +1,322 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+CM_ "Imported file _bosch_2018.dbc starts here"
+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_
+
+BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB
+
+BO_ 228 STEERING_CONTROL: 5 EON
+ 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_SPEED : 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_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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|15] "" EON
+
+BO_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 344 ENGINE_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_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 380 POWERTRAIN_DATA: 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] "" EON
+ SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" EON
+
+BO_ 420 VSA_STATUS: 8 VSA
+ SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
+ SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
+ SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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|15] "" EON
+
+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|15] "" EON
+
+BO_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ 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.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 479 ACC_CONTROL: 8 EON
+ 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_ 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_16: 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" 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 : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
+ SG_ LONG_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_ 773 SEATBELT_STATUS: 7 BDY
+ SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_ON : 15|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 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_ LOCK_STATUS : 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_ 804 CRUISE: 8 PCM
+ SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 806 SCM_FEEDBACK: 8 SCM
+ 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_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON
+ 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_ 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 : 51|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 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 STALK_STATUS_2: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ 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_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+CM_ "honda_accord_s2t_2018_can.dbc starts here"
+
+BO_ 419 GEARBOX: 8 PCM
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
+
+BO_ 446 BRAKE_MODULE: 3 VSA
+ SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 19|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_ 662 SCM_BUTTONS: 8 SCM
+ SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
+ SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+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_ 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_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX
+ SG_ BOH_2 : 30|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_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ;
+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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/honda_accord_touring_2016_can.dbc b/opendbc/honda_accord_touring_2016_can.dbc
index d615a19a96..d26ccd6a13 100644
--- a/opendbc/honda_accord_touring_2016_can.dbc
+++ b/opendbc/honda_accord_touring_2016_can.dbc
@@ -1,396 +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 : 59|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 : 59|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";
+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 : 59|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 : 59|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";
diff --git a/opendbc/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/honda_civic_hatchback_ex_2017_can.dbc
deleted file mode 100644
index 73a7758d32..0000000000
--- a/opendbc/honda_civic_hatchback_ex_2017_can.dbc
+++ /dev/null
@@ -1,459 +0,0 @@
-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_2: 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 ENGINE_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_DATA: 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_8: 3 VSA
- SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
- SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
-
-BO_ 450 EPB_STATUS: 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_9: 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_10: 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_11: 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_12: 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_13: 8 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_ 506 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_ 545 XXX_16: 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 SCM_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_17: 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_18: 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_ 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_19: 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_20: 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: 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: 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_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|3] "" XXX
- SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" 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_ 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_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_ 1108 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_ 1302 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_ 1322 XXX_29: 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_30: 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_31: 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_32: 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_33: 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_34: 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_35: 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_36: 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_37: 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";
diff --git a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc
new file mode 100644
index 0000000000..f0433d590f
--- /dev/null
+++ b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc
@@ -0,0 +1,322 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+CM_ "Imported file _bosch_2018.dbc starts here"
+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_
+
+BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB
+
+BO_ 228 STEERING_CONTROL: 5 EON
+ 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_SPEED : 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_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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|15] "" EON
+
+BO_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 344 ENGINE_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_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 380 POWERTRAIN_DATA: 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] "" EON
+ SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" EON
+
+BO_ 420 VSA_STATUS: 8 VSA
+ SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
+ SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
+ SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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|15] "" EON
+
+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|15] "" EON
+
+BO_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ 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.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 479 ACC_CONTROL: 8 EON
+ 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_ 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_16: 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" 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 : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
+ SG_ LONG_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_ 773 SEATBELT_STATUS: 7 BDY
+ SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_ON : 15|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 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_ LOCK_STATUS : 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_ 804 CRUISE: 8 PCM
+ SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 806 SCM_FEEDBACK: 8 SCM
+ 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_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON
+ 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_ 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 : 51|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 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 STALK_STATUS_2: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ 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_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+CM_ "honda_civic_hatchback_ex_2017_can.dbc starts here"
+
+BO_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ 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] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 662 SCM_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_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON
+
+BO_ 892 CRUISE_PARAMS: 8 PCM
+ SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON
+
+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_ 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|15] "" EON
+
+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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc
index 677f34bb66..63db4e9f4f 100644
--- a/opendbc/honda_civic_touring_2016_can_generated.dbc
+++ b/opendbc/honda_civic_touring_2016_can_generated.dbc
@@ -1,4 +1,24 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
+CM_ "Imported file _comma.dbc starts here"
+BO_ 512 GAS_COMMAND: 6 EON
+ SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
+ SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR
+
+BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
+ SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
+
+VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +56,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +97,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +116,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +144,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +162,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +179,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -215,145 +226,147 @@ 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_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
-CM_ "honda_civic_touring_2016_can.dbc starts here"
-
-BO_ 148 KINEMATICS: 8 XXX
- SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
- SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-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_PEDAL_2: 8 PCM
- SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
- SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
- SG_ CAR_GAS : 39|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_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
- SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" 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_ 401 GEARBOX: 8 PCM
- SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
- SG_ GEAR : 43|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_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
- SG_ BRAKE_HOLD_ENABLED : 45|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_ 450 EPB_STATUS: 8 EPB
- SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
- SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
-
-BO_ 487 BRAKE_PRESSURE: 4 VSA
- SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
- SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
- SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
-
-BO_ 545 ECON_STATUS: 6 XXX
- SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON
- SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON
- SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
-
-BO_ 662 SCM_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_ 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_ 862 HIGHBEAM_CONTROL: 8 ADAS
- SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
- SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
- SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
- SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 884 STALK_STATUS: 8 XXX
- SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
- SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
- SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
- SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-BO_ 891 WIPERS: 8 XXX
- SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
-
-BO_ 927 RADAR_HUD: 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_ 1302 ODOMETER: 8 XXX
- SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
- SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
-
-CM_ SG_ 401 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_ 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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
-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";
+CM_ "honda_civic_touring_2016_can.dbc starts here"
+
+
+
+BO_ 148 KINEMATICS: 8 XXX
+ SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
+ SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+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_PEDAL_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" 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_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 43|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_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 487 BRAKE_PRESSURE: 4 VSA
+ SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
+ SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+
+BO_ 545 ECON_STATUS: 6 XXX
+ SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON
+ SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON
+ SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
+
+BO_ 662 SCM_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_ 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_ 862 HIGHBEAM_CONTROL: 8 ADAS
+ SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
+ SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
+ SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
+ SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 884 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 WIPERS: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 927 RADAR_HUD: 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_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+CM_ SG_ 401 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_ 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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+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";
diff --git a/opendbc/honda_crv_ex_2017_can.dbc b/opendbc/honda_crv_ex_2017_can.dbc
deleted file mode 100644
index 1e8b4031f6..0000000000
--- a/opendbc/honda_crv_ex_2017_can.dbc
+++ /dev/null
@@ -1,423 +0,0 @@
-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_2: 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 ENGINE_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_DATA: 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 EPB_STATUS: 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 SCM_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 CRUISE: 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: 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";
diff --git a/opendbc/honda_crv_ex_2017_can_generated.dbc b/opendbc/honda_crv_ex_2017_can_generated.dbc
new file mode 100644
index 0000000000..7d712555ba
--- /dev/null
+++ b/opendbc/honda_crv_ex_2017_can_generated.dbc
@@ -0,0 +1,339 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+CM_ "Imported file _bosch_2018.dbc starts here"
+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_
+
+BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB
+
+BO_ 228 STEERING_CONTROL: 5 EON
+ 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_SPEED : 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_2: 8 PCM
+ SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
+ SG_ CAR_GAS : 39|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|15] "" EON
+
+BO_ 330 STEERING_SENSORS: 8 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_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
+ SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 344 ENGINE_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_ DISTANCE_COUNTER : 55|8@0+ (10,0) [0|2550] "Meters" XXX
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 380 POWERTRAIN_DATA: 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] "" EON
+ SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
+ SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" EON
+
+BO_ 420 VSA_STATUS: 8 VSA
+ SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
+ SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
+ SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_HOLD_ENABLED : 45|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|15] "" EON
+
+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|15] "" EON
+
+BO_ 450 EPB_STATUS: 8 EPB
+ SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
+ SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
+ 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.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 479 ACC_CONTROL: 8 EON
+ 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_ 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_16: 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" 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 : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
+ SG_ LONG_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_ 773 SEATBELT_STATUS: 7 BDY
+ SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_ON : 15|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 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_ LOCK_STATUS : 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_ 804 CRUISE: 8 PCM
+ SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 806 SCM_FEEDBACK: 8 SCM
+ 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_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON
+ 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_ 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 : 51|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 STALK_STATUS: 8 XXX
+ SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
+ SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+BO_ 891 STALK_STATUS_2: 8 XXX
+ SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
+ 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_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+CM_ "honda_crv_ex_2017_can.dbc starts here"
+
+BO_ 401 GEARBOX: 8 PCM
+ SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
+ 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] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+
+BO_ 446 BRAKE_MODULE: 3 VSA
+ SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
+ SG_ CHECKSUM : 19|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_ 662 SCM_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_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON
+
+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_ 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|15] "" EON
+
+BO_ 1302 ODOMETER: 8 XXX
+ SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+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";
+
+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_ 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_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
+VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
+VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+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";
diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc
index 92665dbb22..53e1291ea2 100644
--- a/opendbc/honda_crv_touring_2016_can_generated.dbc
+++ b/opendbc/honda_crv_touring_2016_can_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +38,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +79,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +98,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +126,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +144,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +161,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -217,6 +210,7 @@ VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "honda_crv_touring_2016_can.dbc starts here"
+
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
diff --git a/opendbc/honda_odyssey_exl_2018_generated.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc
index 8639f48444..e14906293a 100644
--- a/opendbc/honda_odyssey_exl_2018_generated.dbc
+++ b/opendbc/honda_odyssey_exl_2018_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +38,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +79,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +98,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +126,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +144,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +161,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -217,6 +210,7 @@ VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "honda_odyssey_exl_2018.dbc starts here"
+
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
diff --git a/opendbc/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc
index 360b362d7a..b2d901e0c5 100644
--- a/opendbc/honda_pilot_touring_2017_can_generated.dbc
+++ b/opendbc/honda_pilot_touring_2017_can_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _honda_2017.dbc starts here"
VERSION ""
@@ -36,9 +38,9 @@ NS_ :
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
BO_ 344 ENGINE_DATA: 8 PCM
- SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" 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_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
@@ -77,7 +79,7 @@ BO_ 490 VEHICLE_DYNAMICS: 8 VSA
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
BO_ 506 BRAKE_COMMAND: 8 ADAS
- SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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
@@ -96,17 +98,6 @@ BO_ 506 BRAKE_COMMAND: 8 ADAS
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
-BO_ 512 GAS_COMMAND: 3 EON
- 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] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
- SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON
-
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
@@ -135,9 +126,8 @@ BO_ 777 LOCK_STATUS: 8 XXX
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
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_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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
@@ -154,6 +144,8 @@ BO_ 780 ACC_HUD: 8 ADAS
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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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
@@ -169,6 +161,7 @@ BO_ 804 CRUISE: 8 PCM
BO_ 829 LKAS_HUD: 5 ADAS
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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
@@ -217,6 +210,7 @@ VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
CM_ "honda_pilot_touring_2017_can.dbc starts here"
+
BO_ 145 KINEMATICS: 8 XXX
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
diff --git a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc
new file mode 100644
index 0000000000..5c7d88a113
--- /dev/null
+++ b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc
@@ -0,0 +1,272 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
+CM_ "Imported file _honda_2017.dbc starts here"
+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_
+
+BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
+
+BO_ 344 ENGINE_DATA: 8 PCM
+ SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON
+ SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
+ SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
+ SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
+
+BO_ 380 POWERTRAIN_DATA: 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_ 432 STANDSTILL: 7 VSA
+ SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON
+ 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_ 464 WHEEL_SPEEDS: 8 VSA
+ SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 490 VEHICLE_DYNAMICS: 8 VSA
+ SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 506 BRAKE_COMMAND: 8 ADAS
+ SG_ COMPUTER_BRAKE : 7|10@0+ (1,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|2@0+ (1,0) [0|3] "" 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_ 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 : 39|8@0+ (1,0) [0|255] "" EON
+ SG_ SET_TO_X55_2 : 47|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|15] "" EON
+
+BO_ 773 SEATBELT_STATUS: 7 BDY
+ SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
+ SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
+ SG_ PASS_AIRBAG_ON : 15|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 LOCK_STATUS: 8 XXX
+ SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON
+ SG_ DOORS_LOCKED : 55|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_ 780 ACC_HUD: 8 ADAS
+ SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
+ SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" 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_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
+ SG_ SET_ME_X01 : 48|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_ 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_ 829 LKAS_HUD: 5 ADAS
+ SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
+ SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" 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_ 892 CRUISE_PARAMS: 8 PCM
+ SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+
+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
+
+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...";
+
+
+VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
+VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
+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_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
+
+CM_ "honda_ridgeline_black_edition_2017_can.dbc starts here"
+
+
+BO_ 145 KINEMATICS: 8 XXX
+ SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
+
+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_ 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_ 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_ 419 GEARBOX: 8 PCM
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" 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
+
+BO_ 422 SCM_BUTTONS: 8 SCM
+ SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
+ SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
+ SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
+ SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
+ SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
+ SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
+
+BO_ 660 SCM_FEEDBACK: 8 SCM
+ SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON
+ SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON
+ SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON
+
+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" ;
+
+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";
diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
index abc28528dc..9ad275556c 100644
--- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
+++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _toyota_2017.dbc starts here"
VERSION ""
@@ -73,10 +75,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -97,6 +100,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -123,17 +131,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
@@ -180,6 +196,7 @@ CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
CM_ "lexus_rx_hybrid_2017_pt.dbc starts here"
+
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
@@ -195,7 +212,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -205,6 +222,6 @@ BO_ 956 GEAR_PACKET: 8 XXX
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_ 581 GAS_PEDAL "it seems slightly filtered";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
new file mode 100644
index 0000000000..680a7ebd8f
--- /dev/null
+++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
@@ -0,0 +1,230 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
+CM_ "Imported file _toyota_2017.dbc starts here"
+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_ 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_ 614 STEERING_IPAS: 8 IPAS
+ SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
+ SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" 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: 5 XXX
+ SG_ LKA_STATE : 31|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
+ SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" 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
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
+
+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
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@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
+
+BO_ 1570 LIGHT_STALK: 8 SCM
+ SG_ AUTO_HIGH_BEAM : 37|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_ 560 BRAKE_PRESSED "another brake pressed?";
+CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
+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_ 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";
+
+CM_ "toyota_camry_hybrid_2018_pt.dbc starts here"
+
+
+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_ 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_ 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_ IPAS_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
+
+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_ 581 GAS_PEDAL "it seems slightly filtered";
+VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/toyota_chr_2018_pt_generated.dbc b/opendbc/toyota_chr_2018_pt_generated.dbc
new file mode 100644
index 0000000000..ae5d16da3c
--- /dev/null
+++ b/opendbc/toyota_chr_2018_pt_generated.dbc
@@ -0,0 +1,227 @@
+CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
+CM_ "Imported file _toyota_2017.dbc starts here"
+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_ 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_ 614 STEERING_IPAS: 8 IPAS
+ SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
+ SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" 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: 5 XXX
+ SG_ LKA_STATE : 31|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
+ SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" 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
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
+
+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
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@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
+
+BO_ 1570 LIGHT_STALK: 8 SCM
+ SG_ AUTO_HIGH_BEAM : 37|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_ 560 BRAKE_PRESSED "another brake pressed?";
+CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
+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_ 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";
+
+CM_ "toyota_chr_2018_pt.dbc starts here"
+
+
+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_ 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.73,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_ IPAS_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_ 956 GEAR_PACKET: 8 XXX
+ SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
+
+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";
+VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc
index c1be02aada..a83f80b2fe 100644
--- a/opendbc/toyota_corolla_2017_pt_generated.dbc
+++ b/opendbc/toyota_corolla_2017_pt_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _toyota_2017.dbc starts here"
VERSION ""
@@ -73,10 +75,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -97,6 +100,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -123,17 +131,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
@@ -180,6 +196,7 @@ CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
CM_ "toyota_corolla_2017_pt.dbc starts here"
+
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
@@ -195,7 +212,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -205,5 +222,5 @@ BO_ 956 GEAR_PACKET: 8 XXX
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";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc
index ec72752baa..0e92e6678e 100644
--- a/opendbc/toyota_prius_2017_pt_generated.dbc
+++ b/opendbc/toyota_prius_2017_pt_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _toyota_2017.dbc starts here"
VERSION ""
@@ -73,10 +75,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -97,6 +100,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -123,17 +131,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
@@ -180,6 +196,7 @@ CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
CM_ "toyota_prius_2017_pt.dbc starts here"
+
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
@@ -201,7 +218,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -209,5 +226,5 @@ 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_ 581 GAS_PEDAL "it seems slightly filtered";
VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc
index 3301bc0c6d..9382a0e0ca 100644
--- a/opendbc/toyota_rav4_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_2017_pt_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _toyota_2017.dbc starts here"
VERSION ""
@@ -73,10 +75,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -97,6 +100,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -123,17 +131,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
@@ -180,6 +196,7 @@ CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
CM_ "toyota_rav4_2017_pt.dbc starts here"
+
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
@@ -195,7 +212,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -205,5 +222,5 @@ BO_ 956 GEAR_PACKET: 8 XXX
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";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
index cca97d041d..bf6a40cae5 100644
--- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
@@ -1,4 +1,6 @@
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
+
+
CM_ "Imported file _toyota_2017.dbc starts here"
VERSION ""
@@ -73,10 +75,11 @@ BO_ 560 BRAKE_MODULE2: 7 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_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" 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_X40 : 47|8@0+ (1,0) [0|255] "" XXX
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
@@ -97,6 +100,11 @@ BO_ 742 LEAD_INFO: 8 DSU
BO_ 835 ACC_CONTROL: 8 DSU
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
+ SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
+ SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
+ SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
+ SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
+ SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
BO_ 1556 STEERING_LEVERS: 8 XXX
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
@@ -123,17 +131,25 @@ BO_ 951 ESP_CONTROL: 8 ESP
BO_ 1041 ACC_HUD: 8 DSU
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X80 : 55|8@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_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
+ SG_ SET_ME_X01_2 : 11|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
+ SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
+ SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
BO_ 1553 UI_SEETING: 8 XXX
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
@@ -180,6 +196,7 @@ CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
CM_ "toyota_rav4_hybrid_2017_pt.dbc starts here"
+
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
@@ -195,7 +212,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 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_ IPAS_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
@@ -205,6 +222,6 @@ BO_ 956 GEAR_PACKET: 8 XXX
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_ 581 GAS_PEDAL "it seems slightly filtered";
-VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled";
-VAL_ 610 LKA_STATE 50 "temporary_fault";
+VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
+VAL_ 610 LKA_STATE 50 "temporary_fault" 10 "active" 2 "standby";
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
diff --git a/panda/README.md b/panda/README.md
index 75424f9ce6..85de25c905 100644
--- a/panda/README.md
+++ b/panda/README.md
@@ -45,7 +45,7 @@ As a universal car interface, it should support every reasonable software interf
- 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))
+- Windows J2534 ([done](https://github.com/commaai/panda/tree/master/drivers/windows))
Directory structure
------
diff --git a/panda/VERSION b/panda/VERSION
index ef6a92d304..992977ad20 100644
--- a/panda/VERSION
+++ b/panda/VERSION
@@ -1 +1 @@
-v1.0.7
\ No newline at end of file
+v1.1.0
\ No newline at end of file
diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c
index 147d75a010..4e516110c5 100644
--- a/panda/board/bootstub.c
+++ b/panda/board/bootstub.c
@@ -24,6 +24,12 @@
#include "drivers/usb.h"
//#include "drivers/uart.h"
+#ifdef PEDAL
+#define CUSTOM_CAN_INTERRUPTS
+#include "safety.h"
+#include "drivers/can.h"
+#endif
+
int puts(const char *a) { return 0; }
void puth(unsigned int i) {}
diff --git a/panda/board/build.mk b/panda/board/build.mk
index 069a00e1a0..d662f6b141 100644
--- a/panda/board/build.mk
+++ b/panda/board/build.mk
@@ -1,4 +1,4 @@
-CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O0
+CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -O2
CFLAGS += -Tstm32_flash.ld
CC = arm-none-eabi-gcc
diff --git a/panda/board/drivers/can.h b/panda/board/drivers/can.h
index 422da965cf..b094d2b4ce 100644
--- a/panda/board/drivers/can.h
+++ b/panda/board/drivers/can.h
@@ -199,6 +199,7 @@ void can_init_all() {
}
void can_set_gmlan(int bus) {
+ #ifdef PANDA
if (bus == -1 || bus != can_num_lookup[3]) {
// GMLAN OFF
switch (can_num_lookup[3]) {
@@ -238,6 +239,7 @@ void can_set_gmlan(int bus) {
can_num_lookup[3] = 2;
can_init(2);
}
+ #endif
}
// CAN error
@@ -346,13 +348,14 @@ void can_rx(uint8_t can_number) {
// forwarding (panda only)
#ifdef PANDA
- if (can_forwarding[bus_number] != -1) {
+ int bus_fwd_num = can_forwarding[bus_number] != -1 ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push);
+ if (bus_fwd_num != -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]);
+ can_send(&to_send, bus_fwd_num);
}
#endif
@@ -370,6 +373,8 @@ void can_rx(uint8_t can_number) {
}
}
+#ifndef CUSTOM_CAN_INTERRUPTS
+
void CAN1_TX_IRQHandler() { process_can(0); }
void CAN1_RX0_IRQHandler() { can_rx(0); }
void CAN1_SCE_IRQHandler() { can_sce(CAN1); }
@@ -384,6 +389,8 @@ void CAN3_RX0_IRQHandler() { can_rx(2); }
void CAN3_SCE_IRQHandler() { can_sce(CAN3); }
#endif
+#endif
+
void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) {
if (safety_tx_hook(to_push)) {
if (bus_number < BUS_MAX) {
diff --git a/panda/board/drivers/drivers.h b/panda/board/drivers/drivers.h
index ce1e860ceb..d3409d6099 100644
--- a/panda/board/drivers/drivers.h
+++ b/panda/board/drivers/drivers.h
@@ -88,7 +88,7 @@ uint32_t adc_get(int channel);
// ********************* DAC *********************
void dac_init();
-uint32_t dac_set(int channel, uint32_t value);
+void dac_set(int channel, uint32_t value);
// ********************* TIMER *********************
diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h
index 14c2ae7cdf..c43a8ce400 100644
--- a/panda/board/drivers/usb.h
+++ b/panda/board/drivers/usb.h
@@ -71,12 +71,15 @@ uint8_t resp[MAX_RESP_LEN];
#define ENDPOINT_TYPE_BULK 2
#define ENDPOINT_TYPE_INT 3
+// This is an arbitrary value used in bRequest
+#define MS_VENDOR_CODE 0x20
+
//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
+ DSCR_DEVICE_LEN, DSCR_DEVICE_TYPE, 0x00, 0x02, //Length, Type, bcdUSB
0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size
TOUSBORDER(USB_VID), // idVendor
TOUSBORDER(USB_PID), // idProduct
@@ -165,9 +168,47 @@ uint16_t string_3_desc[] = {
'n', 'o', 'n', 'e'
};
+#ifdef PANDA
+// WCID (auto install WinUSB driver)
+// https://github.com/pbatard/libwdi/wiki/WCID-Devices
+// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file
+uint8_t string_238_desc[] = {
+ 0x12, 0x03, // bLength, bDescriptorType
+ 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100)
+ MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad
+};
+uint8_t winusb_ext_compatid_os_desc[] = {
+ 0x28, 0x00, 0x00, 0x00, // dwLength
+ 0x00, 0x01, // bcdVersion
+ 0x04, 0x00, // wIndex
+ 0x01, // bCount
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved
+ 0x00, // bFirstInterfaceNumber
+ 0x00, // Reserved
+ 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB)
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none)
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved
+};
+uint8_t winusb_ext_prop_os_desc[] = {
+ 0x8e, 0x00, 0x00, 0x00, // dwLength
+ 0x00, 0x01, // bcdVersion
+ 0x05, 0x00, // wIndex
+ 0x01, 0x00, // wCount
+ // first property
+ 0x84, 0x00, 0x00, 0x00, // dwSize
+ 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType
+ 0x28, 0x00, // wPropertyNameLength
+ 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID)
+ 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength
+ '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9})
+};
+#endif
+
// current packet
USB_Setup_TypeDef setup;
uint8_t usbdata[0x100];
+uint8_t* ep0_txdata = NULL;
+uint16_t ep0_txlen = 0;
// Store the current interface alt setting.
int current_int0_alt_setting = 0;
@@ -206,6 +247,26 @@ void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) {
}
}
+// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest)
+// so use TX FIFO empty interrupt to send larger amounts of data
+void USB_WritePacket_EP0(uint8_t *src, uint16_t len) {
+ #ifdef DEBUG_USB
+ puts("writing ");
+ hexdump(src, len);
+ #endif
+
+ uint16_t wplen = min(len, 0x40);
+ USB_WritePacket(src, wplen, 0);
+
+ if (wplen < len) {
+ ep0_txdata = src + wplen;
+ ep0_txlen = len - wplen;
+ USBx_DEVICE->DIEPEMPMSK |= 1;
+ } else {
+ USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
+ }
+}
+
void usb_reset() {
// unmask endpoint interrupts, so many sets
USBx_DEVICE->DAINT = 0xFFFFFFFF;
@@ -345,6 +406,11 @@ void usb_setup() {
USB_WritePacket((const uint8_t *)string_3_desc, min(sizeof(string_3_desc), setup.b.wLength.w), 0);
#endif
break;
+ #ifdef PANDA
+ case 238:
+ USB_WritePacket((uint8_t*)string_238_desc, min(sizeof(string_238_desc), setup.b.wLength.w), 0);
+ break;
+ #endif
default:
// nothing
USB_WritePacket(0, 0, 0);
@@ -372,6 +438,22 @@ void usb_setup() {
USB_WritePacket(0, 0, 0);
USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
break;
+ #ifdef PANDA
+ case MS_VENDOR_CODE:
+ switch (setup.b.wIndex.w) {
+ // Extended Compat ID OS Descriptor
+ case 4:
+ USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, min(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w));
+ break;
+ // Extended Properties OS Descriptor
+ case 5:
+ USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, min(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w));
+ break;
+ default:
+ USB_WritePacket_EP0(0, 0);
+ }
+ break;
+ #endif
default:
resp_len = usb_cb_control_msg(&setup, resp, 1);
USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0);
@@ -682,6 +764,24 @@ void usb_irqhandler(void) {
break;
}
+ if (USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) {
+ #ifdef DEBUG_USB
+ puts(" IN PACKET QUEUE\n");
+ #endif
+
+ if (ep0_txlen != 0 && (USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40) {
+ uint16_t len = min(ep0_txlen, 0x40);
+ USB_WritePacket(ep0_txdata, len, 0);
+ ep0_txdata += len;
+ ep0_txlen -= len;
+ if (ep0_txlen == 0) {
+ ep0_txdata = NULL;
+ USBx_DEVICE->DIEPEMPMSK &= ~1;
+ USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK;
+ }
+ }
+ }
+
// clear interrupts
USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0?
USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT;
diff --git a/panda/board/get_sdk.sh b/panda/board/get_sdk.sh
index 2248d1b9ec..7b8d1f9154 100755
--- a/panda/board/get_sdk.sh
+++ b/panda/board/get_sdk.sh
@@ -1,3 +1,3 @@
#!/bin/bash
sudo apt-get install gcc-arm-none-eabi python-pip
-sudo pip2 install libusb1
+sudo pip2 install libusb1 pycrypto requests
diff --git a/panda/board/get_sdk_mac.sh b/panda/board/get_sdk_mac.sh
index 1c4c74ff8c..a6f641dce1 100644
--- a/panda/board/get_sdk_mac.sh
+++ b/panda/board/get_sdk_mac.sh
@@ -2,4 +2,4 @@
# Need formula for gcc
brew tap ArmMbed/homebrew-formulae
brew install python dfu-util arm-none-eabi-gcc
-pip2 install libusb1
+pip2 install libusb1 pycrypto requests
diff --git a/panda/board/gpio.h b/panda/board/gpio.h
index 775a88df54..7b2812e7b4 100644
--- a/panda/board/gpio.h
+++ b/panda/board/gpio.h
@@ -72,8 +72,15 @@ void clock_init() {
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;
+ #ifdef PEDAL
+ // comma pedal has a 16mhz crystal
+ RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
+ RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE;
+ #else
+ // NEO board has a 8mhz crystal
+ RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 |
+ RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE;
+ #endif
#endif
// start PLL
@@ -132,8 +139,13 @@ void set_can_enable(CAN_TypeDef *CAN, int enabled) {
// CAN1_EN
set_gpio_output(GPIOC, 1, !enabled);
#else
- // CAN1_EN
- set_gpio_output(GPIOB, 3, enabled);
+ #ifdef PEDAL
+ // CAN1_EN (not flipped)
+ set_gpio_output(GPIOB, 3, !enabled);
+ #else
+ // CAN1_EN
+ set_gpio_output(GPIOB, 3, enabled);
+ #endif
#endif
} else if (CAN == CAN2) {
#ifdef PANDA
@@ -285,6 +297,14 @@ void gpio_init() {
set_gpio_mode(GPIOC, 2, MODE_ANALOG);
set_gpio_mode(GPIOC, 3, MODE_ANALOG);
+#ifdef PEDAL
+ // comma pedal has inputs on C0 and C1
+ set_gpio_mode(GPIOC, 0, MODE_ANALOG);
+ set_gpio_mode(GPIOC, 1, MODE_ANALOG);
+ // DAC outputs on A4 and A5
+ // apparently they don't need GPIO setup
+#endif
+
// C8: FAN aka TIM3_CH4
set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3);
@@ -443,9 +463,10 @@ void early() {
if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) {
+ #ifdef PANDA
set_esp_mode(ESP_DISABLED);
+ #endif
set_led(LED_GREEN, 1);
-
jump_to_bootloader();
}
diff --git a/panda/board/pedal/.gitignore b/panda/board/pedal/.gitignore
new file mode 100644
index 0000000000..94053f2925
--- /dev/null
+++ b/panda/board/pedal/.gitignore
@@ -0,0 +1 @@
+obj/*
diff --git a/panda/board/pedal/Makefile b/panda/board/pedal/Makefile
new file mode 100644
index 0000000000..9917e38150
--- /dev/null
+++ b/panda/board/pedal/Makefile
@@ -0,0 +1,59 @@
+# :set noet
+PROJ_NAME = comma
+
+CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL
+CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
+CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx
+CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib
+CFLAGS += -T../stm32_flash.ld
+
+STARTUP_FILE = startup_stm32f205xx
+
+CC = arm-none-eabi-gcc
+OBJCOPY = arm-none-eabi-objcopy
+OBJDUMP = arm-none-eabi-objdump
+DFU_UTIL = "dfu-util"
+
+# pedal only uses the debug cert
+CERT = ../../certs/debug
+CFLAGS += "-DALLOW_DEBUG"
+
+canflash: obj/$(PROJ_NAME).bin
+ ../../tests/pedal/enter_canloader.py $<
+
+usbflash: obj/$(PROJ_NAME).bin
+ ../../tests/pedal/enter_canloader.py; sleep 0.5
+ PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)"
+
+recover: obj/bootstub.bin obj/$(PROJ_NAME).bin
+ ../../tests/pedal/enter_canloader.py --recover; sleep 0.5
+ $(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.bin
+
+obj/main.o: main.c ../*.h
+ mkdir -p obj
+ $(CC) $(CFLAGS) -o $@ -c $<
+
+obj/bootstub.o: ../bootstub.c ../*.h
+ mkdir -p obj
+ $(CC) $(CFLAGS) -o $@ -c $<
+
+obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s
+ $(CC) $(CFLAGS) -o $@ -c $<
+
+obj/%.o: ../../crypto/%.c
+ $(CC) $(CFLAGS) -o $@ -c $<
+
+obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.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.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o
+ $(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
+ $(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
+
+clean:
+ rm -f obj/*
+
diff --git a/panda/board/pedal/README b/panda/board/pedal/README
new file mode 100644
index 0000000000..cf779db258
--- /dev/null
+++ b/panda/board/pedal/README
@@ -0,0 +1,28 @@
+This is the firmware for the comma pedal. It borrows a lot from panda.
+
+The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal.
+
+This is the open source software. Note that it is not ready to use yet.
+
+== Test Plan ==
+
+* Startup
+** Confirm STATE_FAULT_STARTUP
+* Timeout
+** Send value
+** Confirm value is output
+** Stop sending messages
+** Confirm value is passthru after 100ms
+** Confirm STATE_FAULT_TIMEOUT
+* Random values
+** Send random 6 byte messages
+** Confirm random values cause passthru
+** Confirm STATE_FAULT_BAD_CHECKSUM
+* Same message lockout
+** Send same message repeated
+** Confirm timeout behavior
+* Don't set enable
+** Confirm no output
+* Set enable and values
+** Confirm output
+
diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c
new file mode 100644
index 0000000000..5d5264791c
--- /dev/null
+++ b/panda/board/pedal/main.c
@@ -0,0 +1,295 @@
+//#define DEBUG
+//#define CAN_LOOPBACK_MODE
+//#define USE_INTERNAL_OSC
+
+#include "../config.h"
+
+#include "drivers/drivers.h"
+#include "drivers/llgpio.h"
+#include "gpio.h"
+
+#define CUSTOM_CAN_INTERRUPTS
+
+#include "libc.h"
+#include "safety.h"
+#include "drivers/adc.h"
+#include "drivers/uart.h"
+#include "drivers/dac.h"
+#include "drivers/can.h"
+#include "drivers/timer.h"
+
+#define CAN CAN1
+
+//#define PEDAL_USB
+
+#ifdef PEDAL_USB
+ #include "drivers/usb.h"
+#endif
+
+#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
+uint32_t enter_bootloader_mode;
+
+void __initialize_hardware_early() {
+ early();
+}
+
+// ********************* serial debugging *********************
+
+void debug_ring_callback(uart_ring *ring) {
+ char rcv;
+ while (getc(ring, &rcv)) {
+ putc(ring, rcv);
+ }
+}
+
+#ifdef PEDAL_USB
+
+int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; }
+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() {}
+
+int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
+ int resp_len = 0;
+ uart_ring *ur = NULL;
+ switch (setup->b.bRequest) {
+ // **** 0xe0: uart read
+ case 0xe0:
+ ur = get_ring_by_number(setup->b.wValue.w);
+ if (!ur) break;
+ if (ur == &esp_ring) uart_dma_drain();
+ // read
+ while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) &&
+ getc(ur, (char*)&resp[resp_len])) {
+ ++resp_len;
+ }
+ break;
+ }
+ return resp_len;
+}
+
+#endif
+
+// ***************************** honda can checksum *****************************
+
+int can_cksum(uint8_t *dat, int len, int addr, int idx) {
+ int i;
+ int s = 0;
+ for (i = 0; i < len; i++) {
+ s += (dat[i] >> 4);
+ s += dat[i] & 0xF;
+ }
+ s += (addr>>0)&0xF;
+ s += (addr>>4)&0xF;
+ s += (addr>>8)&0xF;
+ s += idx;
+ s = 8-s;
+ return s&0xF;
+}
+
+// ***************************** can port *****************************
+
+// addresses to be used on CAN
+#define CAN_GAS_INPUT 0x200
+#define CAN_GAS_OUTPUT 0x201
+
+void CAN1_TX_IRQHandler() {
+ // clear interrupt
+ CAN->TSR |= CAN_TSR_RQCP0;
+}
+
+// two independent values
+uint16_t gas_set_0 = 0;
+uint16_t gas_set_1 = 0;
+
+#define MAX_TIMEOUT 10
+uint32_t timeout = 0;
+uint32_t current_index = 0;
+
+#define NO_FAULT 0
+#define FAULT_BAD_CHECKSUM 1
+#define FAULT_SEND 2
+#define FAULT_SCE 3
+#define FAULT_STARTUP 4
+#define FAULT_TIMEOUT 5
+#define FAULT_INVALID 6
+uint8_t state = FAULT_STARTUP;
+
+void CAN1_RX0_IRQHandler() {
+ while (CAN->RF0R & CAN_RF0R_FMP0) {
+ #ifdef DEBUG
+ puts("CAN RX\n");
+ #endif
+ uint32_t address = CAN->sFIFOMailBox[0].RIR>>21;
+ if (address == CAN_GAS_INPUT) {
+ // softloader entry
+ if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) {
+ if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) {
+ enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
+ NVIC_SystemReset();
+ } else if (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) {
+ enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
+ NVIC_SystemReset();
+ }
+ }
+
+ // normal packet
+ uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
+ uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
+ uint16_t value_0 = (dat[0] << 8) | dat[1];
+ uint16_t value_1 = (dat[2] << 8) | dat[3];
+ uint8_t enable = (dat2[0] >> 7) & 1;
+ uint8_t index = (dat2[1] >> 4) & 3;
+ if (can_cksum(dat, 5, CAN_GAS_INPUT, index) == (dat2[1] & 0xF)) {
+ if (((current_index+1)&3) == index) {
+ #ifdef DEBUG
+ puts("setting gas ");
+ puth(value);
+ puts("\n");
+ #endif
+ if (enable) {
+ gas_set_0 = value_0;
+ gas_set_1 = value_1;
+ } else {
+ // clear the fault state if values are 0
+ if (value_0 == 0 && value_1 == 0) {
+ state = NO_FAULT;
+ } else {
+ state = FAULT_INVALID;
+ }
+ gas_set_0 = gas_set_1 = 0;
+ }
+ // clear the timeout
+ timeout = 0;
+ }
+ current_index = index;
+ } else {
+ // wrong checksum = fault
+ state = FAULT_BAD_CHECKSUM;
+ }
+ }
+ // next
+ CAN->RF0R |= CAN_RF0R_RFOM0;
+ }
+}
+
+void CAN1_SCE_IRQHandler() {
+ state = FAULT_SCE;
+ can_sce(CAN);
+}
+
+int pdl0 = 0, pdl1 = 0;
+int pkt_idx = 0;
+
+int led_value = 0;
+
+void TIM3_IRQHandler() {
+ #ifdef DEBUG
+ puth(TIM3->CNT);
+ puts(" ");
+ puth(pdl0);
+ puts(" ");
+ puth(pdl1);
+ puts("\n");
+ #endif
+
+ // check timer for sending the user pedal and clearing the CAN
+ if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
+ uint8_t dat[8];
+ dat[0] = (pdl0>>8)&0xFF;
+ dat[1] = (pdl0>>0)&0xFF;
+ dat[2] = (pdl1>>8)&0xFF;
+ dat[3] = (pdl1>>0)&0xFF;
+ dat[4] = state;
+ dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT, pkt_idx) | (pkt_idx<<4);
+ CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24);
+ CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8);
+ CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5
+ CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1;
+ ++pkt_idx;
+ pkt_idx &= 3;
+ } else {
+ // old can packet hasn't sent!
+ state = FAULT_SEND;
+ #ifdef DEBUG
+ puts("CAN MISS\n");
+ #endif
+ }
+
+ // blink the LED
+ set_led(LED_GREEN, led_value);
+ led_value = !led_value;
+
+ TIM3->SR = 0;
+
+ // up timeout for gas set
+ if (timeout == MAX_TIMEOUT) {
+ state = FAULT_TIMEOUT;
+ } else {
+ timeout += 1;
+ }
+}
+
+// ***************************** main code *****************************
+
+void pedal() {
+ // read/write
+ pdl0 = adc_get(ADCCHAN_ACCEL0);
+ pdl1 = adc_get(ADCCHAN_ACCEL1);
+
+ // write the pedal to the DAC
+ if (state == NO_FAULT) {
+ dac_set(0, max(gas_set_0, pdl0));
+ dac_set(1, max(gas_set_1, pdl1));
+ } else {
+ dac_set(0, pdl0);
+ dac_set(1, pdl1);
+ }
+
+ // feed the watchdog
+ IWDG->KR = 0xAAAA;
+}
+
+int main() {
+ __disable_irq();
+
+ // init devices
+ clock_init();
+ periph_init();
+ gpio_init();
+
+#ifdef PEDAL_USB
+ // enable USB
+ usb_init();
+#endif
+
+ // pedal stuff
+ dac_init();
+ adc_init();
+
+ // init can
+ can_silent = ALL_CAN_LIVE;
+ can_init(0);
+
+ // 48mhz / 65536 ~= 732
+ timer_init(TIM3, 15);
+ NVIC_EnableIRQ(TIM3_IRQn);
+
+ // setup watchdog
+ IWDG->KR = 0x5555;
+ IWDG->PR = 0; // divider /4
+ // 0 = 0.125 ms, let's have a 50ms watchdog
+ IWDG->RLR = 400 - 1;
+ IWDG->KR = 0xCCCC;
+
+ puts("**** INTERRUPTS ON ****\n");
+ __enable_irq();
+
+ // main pedal loop
+ while (1) {
+ pedal();
+ }
+
+ return 0;
+}
+
diff --git a/panda/board/safety.h b/panda/board/safety.h
index 8842141544..3e0b0cf38a 100644
--- a/panda/board/safety.h
+++ b/panda/board/safety.h
@@ -6,12 +6,14 @@ typedef void (*safety_hook_init)(int16_t param);
typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push);
typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send);
typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len);
+typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd);
typedef struct {
safety_hook_init init;
rx_hook rx;
tx_hook tx;
tx_lin_hook tx_lin;
+ fwd_hook fwd;
} safety_hooks;
// This can be set by the safety hooks.
@@ -21,6 +23,7 @@ int controls_allowed = 0;
#include "safety/safety_defaults.h"
#include "safety/safety_honda.h"
#include "safety/safety_toyota.h"
+#include "safety/safety_gm.h"
#include "safety/safety_elm327.h"
const safety_hooks *current_hooks = &nooutput_hooks;
@@ -37,6 +40,10 @@ int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){
return current_hooks->tx_lin(lin_num, data, len);
}
+int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return current_hooks->fwd(bus_num, to_fwd);
+}
+
typedef struct {
uint16_t id;
const safety_hooks *hooks;
@@ -46,14 +53,18 @@ typedef struct {
#define SAFETY_HONDA 1
#define SAFETY_TOYOTA 2
#define SAFETY_TOYOTA_NOLIMITS 0x1336
+#define SAFETY_GM 3
+#define SAFETY_HONDA_BOSCH 4
#define SAFETY_ALLOUTPUT 0x1337
#define SAFETY_ELM327 0xE327
const safety_hook_config safety_hook_registry[] = {
{SAFETY_NOOUTPUT, &nooutput_hooks},
{SAFETY_HONDA, &honda_hooks},
+ {SAFETY_HONDA_BOSCH, &honda_bosch_hooks},
{SAFETY_TOYOTA, &toyota_hooks},
{SAFETY_TOYOTA_NOLIMITS, &toyota_nolimits_hooks},
+ {SAFETY_GM, &gm_hooks},
{SAFETY_ALLOUTPUT, &alloutput_hooks},
{SAFETY_ELM327, &elm327_hooks},
};
diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h
index b7b4d37295..2411a41628 100644
--- a/panda/board/safety/safety_defaults.h
+++ b/panda/board/safety/safety_defaults.h
@@ -14,11 +14,16 @@ static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) {
return false;
}
+static int nooutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
+}
+
const safety_hooks nooutput_hooks = {
.init = nooutput_init,
.rx = default_rx_hook,
.tx = nooutput_tx_hook,
.tx_lin = nooutput_tx_lin_hook,
+ .fwd = nooutput_fwd_hook,
};
// *** all output safety mode ***
@@ -35,10 +40,15 @@ static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) {
return true;
}
+static int alloutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
+}
+
const safety_hooks alloutput_hooks = {
.init = alloutput_init,
.rx = default_rx_hook,
.tx = alloutput_tx_hook,
.tx_lin = alloutput_tx_lin_hook,
+ .fwd = alloutput_fwd_hook,
};
diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h
index b9af35ebdc..3a0efe6e6b 100644
--- a/panda/board/safety/safety_elm327.h
+++ b/panda/board/safety/safety_elm327.h
@@ -31,9 +31,14 @@ static void elm327_init(int16_t param) {
controls_allowed = 1;
}
+static int elm327_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
+}
+
const safety_hooks elm327_hooks = {
.init = elm327_init,
.rx = elm327_rx_hook,
.tx = elm327_tx_hook,
.tx_lin = elm327_tx_lin_hook,
+ .fwd = elm327_fwd_hook,
};
diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h
new file mode 100644
index 0000000000..f5fbbfe8fe
--- /dev/null
+++ b/panda/board/safety/safety_gm.h
@@ -0,0 +1,186 @@
+// board enforces
+// in-state
+// accel set/resume
+// out-state
+// cancel button
+// regen paddle
+// accel rising edge
+// brake rising edge
+// brake > 0mph
+
+// gm_: poor man's namespacing
+int gm_brake_prev = 0;
+int gm_gas_prev = 0;
+int gm_speed = 0;
+
+// silence everything if stock ECUs are still online
+int gm_ascm_detected = 0;
+
+static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
+
+ uint32_t addr;
+ if (to_push->RIR & 4) {
+ // Extended
+ // Not looked at, but have to be separated
+ // to avoid address collision
+ addr = to_push->RIR >> 3;
+ } else {
+ // Normal
+ addr = to_push->RIR >> 21;
+ }
+
+ // sample speed, really only care if car is moving or not
+ // rear left wheel speed
+ if (addr == 842) {
+ gm_speed = to_push->RDLR & 0xFFFF;
+ }
+
+ // check if stock ASCM ECU is still online
+ int bus_number = (to_push->RDTR >> 4) & 0xFF;
+ if (bus_number == 0 && addr == 715) {
+ gm_ascm_detected = 1;
+ controls_allowed = 0;
+ }
+
+ // ACC steering wheel buttons
+ if (addr == 481) {
+ int buttons = (to_push->RDHR >> 12) & 0x7;
+ // res/set - enable, cancel button - disable
+ if (buttons == 2 || buttons == 3) {
+ controls_allowed = 1;
+ } else if (buttons == 6) {
+ controls_allowed = 0;
+ }
+ }
+
+ // exit controls on rising edge of brake press or on brake press when
+ // speed > 0
+ if (addr == 241) {
+ int brake = (to_push->RDLR & 0xFF00) >> 8;
+ // Brake pedal's potentiometer returns near-zero reading
+ // even when pedal is not pressed
+ if (brake < 10) {
+ brake = 0;
+ }
+ if (brake && (!gm_brake_prev || gm_speed)) {
+ controls_allowed = 0;
+ }
+ gm_brake_prev = brake;
+ }
+
+ // exit controls on rising edge of gas press
+ if (addr == 417) {
+ int gas = to_push->RDHR & 0xFF0000;
+ if (gas && !gm_gas_prev) {
+ controls_allowed = 0;
+ }
+ gm_gas_prev = gas;
+ }
+
+ // exit controls on regen paddle
+ if (addr == 189) {
+ int regen = to_push->RDLR & 0x20;
+ if (regen) {
+ controls_allowed = 0;
+ }
+ }
+}
+
+// all commands: gas/regen, friction brake and steering
+// if controls_allowed and no pedals pressed
+// allow all commands up to limit
+// else
+// block all commands that produce actuation
+
+static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
+
+ // There can be only one! (ASCM)
+ if (gm_ascm_detected) {
+ return 0;
+ }
+
+ // disallow actuator commands if gas or brake (with vehicle moving) are pressed
+ // and the the latching controls_allowed flag is True
+ int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_speed);
+ int current_controls_allowed = controls_allowed && !pedal_pressed;
+
+ uint32_t addr;
+ if (to_send->RIR & 4) {
+ // Extended
+ addr = to_send->RIR >> 3;
+ } else {
+ // Normal
+ addr = to_send->RIR >> 21;
+ }
+
+ // BRAKE: safety check
+ if (addr == 789) {
+ int rdlr = to_send->RDLR;
+ int brake = ((rdlr & 0xF) << 8) + ((rdlr & 0xFF00) >> 8);
+ brake = (0x1000 - brake) & 0xFFF;
+ if (current_controls_allowed) {
+ if (brake > 255) return 0;
+ } else {
+ if (brake != 0) return 0;
+ }
+ }
+
+ // LKA STEER: safety check
+ if (addr == 384) {
+ int rdlr = to_send->RDLR;
+ int steer = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8);
+ int max_steer = 255;
+ if (current_controls_allowed) {
+ // Signed arithmetic
+ if (steer & 0x400) {
+ if (steer < (0x800 - max_steer)) return 0;
+ } else {
+ if (steer > max_steer) return 0;
+ }
+ } else {
+ if (steer != 0) return 0;
+ }
+ }
+
+ // PARK ASSIST STEER: unlimited torque, no thanks
+ if (addr == 823) return 0;
+
+ // GAS/REGEN: safety check
+ if (addr == 715) {
+ int rdlr = to_send->RDLR;
+ int gas_regen = ((rdlr & 0x7F0000) >> 11) + ((rdlr & 0xF8000000) >> 27);
+ int apply = rdlr & 1;
+ if (current_controls_allowed) {
+ if (gas_regen > 3072) return 0;
+ } else {
+ // Disabled message is !engaed with gas
+ // value that corresponds to max regen.
+ if (apply || gas_regen != 1404) return 0;
+ }
+ }
+
+ // 1 allows the message through
+ return true;
+}
+
+static int gm_tx_lin_hook(int lin_num, uint8_t *data, int len) {
+ // LIN is not used in Volt
+ return false;
+}
+
+static void gm_init(int16_t param) {
+ controls_allowed = 0;
+}
+
+static int gm_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
+}
+
+const safety_hooks gm_hooks = {
+ .init = gm_init,
+ .rx = gm_rx_hook,
+ .tx = gm_tx_hook,
+ .tx_lin = gm_tx_lin_hook,
+ .fwd = gm_fwd_hook,
+};
+
diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h
index bf30d84707..5fe3ebf7c9 100644
--- a/panda/board/safety/safety_honda.h
+++ b/panda/board/safety/safety_honda.h
@@ -8,11 +8,14 @@
// brake > 0mph
// these are set in the Honda safety hooks...this is the wrong place
+const int gas_interceptor_threshold = 328;
int gas_interceptor_detected = 0;
int brake_prev = 0;
int gas_prev = 0;
int gas_interceptor_prev = 0;
int ego_speed = 0;
+// TODO: auto-detect bosch hardware based on CAN messages?
+bool bosch_hardware = false;
static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
@@ -33,22 +36,28 @@ static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
}
}
+ // user brake signal is different for nidec vs bosch hardware
+ // nidec hardware: 0x17C bit 53
+ // bosch hardware: 0x1BE bit 4
+ #define IS_USER_BRAKE_MSG(to_push) (!bosch_hardware ? to_push->RIR>>21 == 0x17C : to_push->RIR>>21 == 0x1BE)
+ #define USER_BRAKE_VALUE(to_push) (!bosch_hardware ? to_push->RDHR & 0x200000 : to_push->RDLR & 0x10)
// exit controls on rising edge of brake press or on brake press when
// speed > 0
- if ((to_push->RIR>>21) == 0x17C) {
- // bit 53
- int brake = to_push->RDHR & 0x200000;
+ if (IS_USER_BRAKE_MSG(to_push)) {
+ int brake = USER_BRAKE_VALUE(to_push);
if (brake && (!(brake_prev) || ego_speed)) {
controls_allowed = 0;
}
brake_prev = brake;
}
- // exit controls on rising edge of gas press if interceptor
- if ((to_push->RIR>>21) == 0x201) {
+ // exit controls on rising edge of gas press if interceptor (0x201 w/ len = 6)
+ // length check because bosch hardware also uses this id (0x201 w/ len = 8)
+ if ((to_push->RIR>>21) == 0x201 && (to_push->RDTR & 0xf) == 6) {
gas_interceptor_detected = 1;
int gas_interceptor = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8);
- if ((gas_interceptor > 328) && (gas_interceptor_prev <= 328)) {
+ if ((gas_interceptor > gas_interceptor_threshold) &&
+ (gas_interceptor_prev <= gas_interceptor_threshold)) {
controls_allowed = 0;
}
gas_interceptor_prev = gas_interceptor;
@@ -76,7 +85,8 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
// disallow actuator commands if gas or brake (with vehicle moving) are pressed
// and the the latching controls_allowed flag is True
- int pedal_pressed = gas_prev || gas_interceptor_prev || (brake_prev && ego_speed);
+ int pedal_pressed = gas_prev || (gas_interceptor_prev > gas_interceptor_threshold) ||
+ (brake_prev && ego_speed);
int current_controls_allowed = controls_allowed && !(pedal_pressed);
// BRAKE: safety check
@@ -117,6 +127,11 @@ static int honda_tx_lin_hook(int lin_num, uint8_t *data, int len) {
static void honda_init(int16_t param) {
controls_allowed = 0;
+ bosch_hardware = false;
+}
+
+static int honda_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
}
const safety_hooks honda_hooks = {
@@ -124,5 +139,26 @@ const safety_hooks honda_hooks = {
.rx = honda_rx_hook,
.tx = honda_tx_hook,
.tx_lin = honda_tx_lin_hook,
+ .fwd = honda_fwd_hook,
};
+static void honda_bosch_init(int16_t param) {
+ controls_allowed = 0;
+ bosch_hardware = true;
+}
+
+static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ if (bus_num == 1 || bus_num == 2) {
+ int addr = to_fwd->RIR>>21;
+ return addr != 0xE4 && addr != 0x33D ? (uint8_t)(~bus_num & 0x3) : -1;
+ }
+ return -1;
+}
+
+const safety_hooks honda_bosch_hooks = {
+ .init = honda_bosch_init,
+ .rx = honda_rx_hook,
+ .tx = honda_tx_hook,
+ .tx_lin = honda_tx_lin_hook,
+ .fwd = honda_bosch_fwd_hook,
+};
diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h
index 9ddaf172bb..78aaa36973 100644
--- a/panda/board/safety/safety_toyota.h
+++ b/panda/board/safety/safety_toyota.h
@@ -32,10 +32,10 @@ uint32_t ts_last = 0;
static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
// get eps motor torque (0.66 factor in dbc)
if ((to_push->RIR>>21) == 0x260) {
- int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF));
+ int16_t torque_meas_new_16 = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF));
// increase torque_meas by 1 to be conservative on rounding
- torque_meas_new = (torque_meas_new * dbc_eps_torque_factor / 100) + (torque_meas_new > 0 ? 1 : -1);
+ int torque_meas_new = ((int)(torque_meas_new_16) * dbc_eps_torque_factor / 100) + (torque_meas_new_16 > 0 ? 1 : -1);
// shift the array
for (int i = sizeof(torque_meas)/sizeof(torque_meas[0]) - 1; i > 0; i--) {
@@ -161,11 +161,16 @@ static void toyota_init(int16_t param) {
dbc_eps_torque_factor = param;
}
+static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
+ return -1;
+}
+
const safety_hooks toyota_hooks = {
.init = toyota_init,
.rx = toyota_rx_hook,
.tx = toyota_tx_hook,
.tx_lin = toyota_tx_lin_hook,
+ .fwd = toyota_fwd_hook,
};
static void toyota_nolimits_init(int16_t param) {
@@ -179,4 +184,5 @@ const safety_hooks toyota_nolimits_hooks = {
.rx = toyota_rx_hook,
.tx = toyota_tx_hook,
.tx_lin = toyota_tx_lin_hook,
+ .fwd = toyota_fwd_hook,
};
diff --git a/panda/board/spi_flasher.h b/panda/board/spi_flasher.h
index 5d979a09d2..179a095b97 100644
--- a/panda/board/spi_flasher.h
+++ b/panda/board/spi_flasher.h
@@ -130,6 +130,120 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) {
return resp_len;
}
+#ifdef PEDAL
+
+#define CAN CAN1
+
+#define CAN_BL_INPUT 0x1
+#define CAN_BL_OUTPUT 0x2
+
+void CAN1_TX_IRQHandler() {
+ // clear interrupt
+ CAN->TSR |= CAN_TSR_RQCP0;
+}
+
+#define ISOTP_BUF_SIZE 0x110
+
+uint8_t isotp_buf[ISOTP_BUF_SIZE];
+uint8_t *isotp_buf_ptr = NULL;
+int isotp_buf_remain = 0;
+
+uint8_t isotp_buf_out[ISOTP_BUF_SIZE];
+uint8_t *isotp_buf_out_ptr = NULL;
+int isotp_buf_out_remain = 0;
+int isotp_buf_out_idx = 0;
+
+void bl_can_send(uint8_t *odat) {
+ // wait for send
+ while (!(CAN->TSR & CAN_TSR_TME0));
+
+ // send continue
+ CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0];
+ CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1];
+ CAN->sTxMailBox[0].TDTR = 8;
+ CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1;
+}
+
+void CAN1_RX0_IRQHandler() {
+ while (CAN->RF0R & CAN_RF0R_FMP0) {
+ if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) {
+ uint8_t dat[8];
+ ((uint32_t*)dat)[0] = CAN->sFIFOMailBox[0].RDLR;
+ ((uint32_t*)dat)[1] = CAN->sFIFOMailBox[0].RDHR;
+ uint8_t odat[8];
+ uint8_t type = dat[0] & 0xF0;
+ if (type == 0x30) {
+ // continue
+ while (isotp_buf_out_remain > 0) {
+ // wait for send
+ while (!(CAN->TSR & CAN_TSR_TME0));
+
+ odat[0] = 0x20 | isotp_buf_out_idx;
+ memcpy(odat+1, isotp_buf_out_ptr, 7);
+ isotp_buf_out_remain -= 7;
+ isotp_buf_out_ptr += 7;
+ isotp_buf_out_idx++;
+
+ bl_can_send(odat);
+ }
+ } else if (type == 0x20) {
+ if (isotp_buf_remain > 0) {
+ memcpy(isotp_buf_ptr, dat+1, 7);
+ isotp_buf_ptr += 7;
+ isotp_buf_remain -= 7;
+ }
+ if (isotp_buf_remain <= 0) {
+ int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain;
+
+ // call the function
+ memset(isotp_buf_out, 0, ISOTP_BUF_SIZE);
+ isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out);
+ isotp_buf_out_ptr = isotp_buf_out;
+ isotp_buf_out_idx = 0;
+
+ // send initial
+ if (isotp_buf_out_remain <= 7) {
+ odat[0] = isotp_buf_out_remain;
+ memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain);
+ } else {
+ odat[0] = 0x10 | (isotp_buf_out_remain>>8);
+ odat[1] = isotp_buf_out_remain & 0xFF;
+ memcpy(odat+2, isotp_buf_out_ptr, 6);
+ isotp_buf_out_remain -= 6;
+ isotp_buf_out_ptr += 6;
+ isotp_buf_out_idx++;
+ }
+
+ bl_can_send(odat);
+ }
+ } else if (type == 0x10) {
+ int len = ((dat[0]&0xF)<<8) | dat[1];
+
+ // setup buffer
+ isotp_buf_ptr = isotp_buf;
+ memcpy(isotp_buf_ptr, dat+2, 6);
+
+ if (len < (ISOTP_BUF_SIZE-0x10)) {
+ isotp_buf_ptr += 6;
+ isotp_buf_remain = len-6;
+ }
+
+ memset(odat, 0, 8);
+ odat[0] = 0x30;
+ bl_can_send(odat);
+ }
+ }
+ // next
+ CAN->RF0R |= CAN_RF0R_RFOM0;
+ }
+}
+
+void CAN1_SCE_IRQHandler() {
+ can_sce(CAN);
+}
+
+#endif
+
void soft_flasher_start() {
puts("\n\n\n************************ FLASHER START ************************\n");
@@ -140,6 +254,20 @@ void soft_flasher_start() {
RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN;
RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
+// pedal has the canloader
+#ifdef PEDAL
+ RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
+
+ // B8,B9: CAN 1
+ set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1);
+ set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1);
+ set_can_enable(CAN1, 1);
+
+ // init can
+ can_silent = ALL_CAN_LIVE;
+ can_init(0);
+#endif
+
// A4,A5,A6,A7: setup SPI
set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1);
set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1);
diff --git a/panda/boardesp/proxy.c b/panda/boardesp/proxy.c
index 02e3473a53..35493869fd 100644
--- a/panda/boardesp/proxy.c
+++ b/panda/boardesp/proxy.c
@@ -20,6 +20,9 @@
_a > _b ? _a : _b; })
char ssid[32];
+char password[] = "testing123";
+int wifi_secure_mode = 0;
+
static const int pin = 2;
// Structure holding the TCP connection information.
@@ -218,11 +221,50 @@ void ICACHE_FLASH_ATTR inter_recv_cb(void *arg, char *pusrdata, unsigned short l
}
}
+void ICACHE_FLASH_ATTR wifi_configure(int secure) {
+ wifi_secure_mode = secure;
+
+ // start wifi AP
+ wifi_set_opmode(SOFTAP_MODE);
+ struct softap_config config = {0};
+ wifi_softap_get_config(&config);
+ strcpy(config.ssid, ssid);
+ if (wifi_secure_mode == 0) strcat(config.ssid, "-pair");
+ strcpy(config.password, password);
+ config.ssid_len = strlen(config.ssid);
+ config.authmode = wifi_secure_mode ? AUTH_WPA2_PSK : AUTH_OPEN;
+ config.beacon_interval = 100;
+ config.max_connection = 4;
+ wifi_softap_set_config(&config);
+
+ if (wifi_secure_mode) {
+ // setup tcp server
+ tcp_proto.local_port = 1337;
+ tcp_conn.type = ESPCONN_TCP;
+ tcp_conn.state = ESPCONN_NONE;
+ tcp_conn.proto.tcp = &tcp_proto;
+ espconn_regist_connectcb(&tcp_conn, tcp_connect_cb);
+ espconn_accept(&tcp_conn);
+ espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections
+
+ // setup inter server
+ inter_proto.local_port = 1338;
+ const char udp_remote_ip[4] = {255, 255, 255, 255};
+ os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4);
+ inter_proto.remote_port = 1338;
+
+ inter_conn.type = ESPCONN_UDP;
+ inter_conn.proto.udp = &inter_proto;
+
+ espconn_regist_recvcb(&inter_conn, inter_recv_cb);
+ espconn_create(&inter_conn);
+ }
+}
+
void ICACHE_FLASH_ATTR wifi_init() {
// default ssid and password
memset(ssid, 0, 32);
os_sprintf(ssid, "panda-%08x-BROKEN", system_get_chip_id());
- char password[] = "testing123";
// fetch secure ssid and password
// update, try 20 times, for 1 second
@@ -242,19 +284,7 @@ void ICACHE_FLASH_ATTR wifi_init() {
os_delay_us(50000);
}
- // start wifi AP
- wifi_set_opmode(SOFTAP_MODE);
- struct softap_config config;
- wifi_softap_get_config(&config);
- strcpy(config.ssid, ssid);
- strcpy(config.password, password);
- config.ssid_len = strlen(ssid);
- config.authmode = AUTH_WPA2_PSK;
- config.beacon_interval = 100;
- config.max_connection = 4;
- wifi_softap_set_config(&config);
-
- //set IP
+ // set IP
wifi_softap_dhcps_stop(); //stop DHCP before setting static IP
struct ip_info ip_config;
IP4_ADDR(&ip_config.ip, 192, 168, 0, 10);
@@ -265,27 +295,7 @@ void ICACHE_FLASH_ATTR wifi_init() {
wifi_softap_set_dhcps_offer_option(OFFER_ROUTER, &stupid_gateway);
wifi_softap_dhcps_start();
- // setup tcp server
- tcp_proto.local_port = 1337;
- tcp_conn.type = ESPCONN_TCP;
- tcp_conn.state = ESPCONN_NONE;
- tcp_conn.proto.tcp = &tcp_proto;
- espconn_regist_connectcb(&tcp_conn, tcp_connect_cb);
- espconn_accept(&tcp_conn);
- espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections
-
- // setup inter server
- inter_proto.local_port = 1338;
- const char udp_remote_ip[4] = {255, 255, 255, 255};
- os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4);
- inter_proto.remote_port = 1338;
-
- inter_conn.type = ESPCONN_UDP;
- inter_conn.proto.udp = &inter_proto;
-
- espconn_regist_recvcb(&inter_conn, inter_recv_cb);
-
- espconn_create(&inter_conn);
+ wifi_configure(0);
}
#define LOOP_PRIO 2
diff --git a/panda/boardesp/webserver.c b/panda/boardesp/webserver.c
index 66b1185fef..9266b08f70 100644
--- a/panda/boardesp/webserver.c
+++ b/panda/boardesp/webserver.c
@@ -40,6 +40,7 @@ char OK_header[] = "HTTP/1.0 200 OK\nContent-Type: text/html\n\n";
static struct espconn web_conn;
static esp_tcp web_proto;
extern char ssid[];
+extern int wifi_secure_mode;
char *st_firmware;
int real_content_length, content_length = 0;
@@ -205,6 +206,12 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
} else {
ets_strcat(resp, "\nesp flash file: user1.bin");
}
+
+ if (wifi_secure_mode) {
+ ets_strcat(resp, "\nin secure mode");
+ } else {
+ ets_strcat(resp, "\nin INSECURE mode...secure it");
+ }
ets_strcat(resp,"\nSet USB Mode:"
""
@@ -215,8 +222,9 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
-
- } else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0) {
+ } else if (memcmp(data, "GET /secure", 11) == 0 && !wifi_secure_mode) {
+ wifi_configure(1);
+ } else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0 && wifi_secure_mode) {
char mode_value = data[27] - '0';
if (mode_value >= '\x00' && mode_value <= '\x02') {
memset(resp, 0, MAX_RESP);
@@ -228,7 +236,7 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
espconn_send_string(&web_conn, resp);
espconn_disconnect(conn);
}
- } else if (memcmp(data, "PUT /stupdate ", 14) == 0) {
+ } else if (memcmp(data, "PUT /stupdate ", 14) == 0 && wifi_secure_mode) {
os_printf("init st firmware\n");
char *cl = strstr(data, "Content-Length: ");
if (cl != NULL) {
@@ -244,8 +252,8 @@ static void ICACHE_FLASH_ATTR web_rx_cb(void *arg, char *data, uint16_t len) {
state = RECEIVING_ST_FIRMWARE;
}
- } else if ((memcmp(data, "PUT /espupdate1 ", 16) == 0) ||
- (memcmp(data, "PUT /espupdate2 ", 16) == 0)) {
+ } else if (((memcmp(data, "PUT /espupdate1 ", 16) == 0) ||
+ (memcmp(data, "PUT /espupdate2 ", 16) == 0)) && wifi_secure_mode) {
// 0x1000 = user1.bin
// 0x81000 = user2.bin
// 0x3FE000 = blank.bin
diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim.h b/panda/drivers/windows/ECUsim DLL/ECUsim.h
index 7378e2c581..2f5fe0f7ad 100644
--- a/panda/drivers/windows/ECUsim DLL/ECUsim.h
+++ b/panda/drivers/windows/ECUsim DLL/ECUsim.h
@@ -1,7 +1,7 @@
#pragma once
#include
-#include "panda\panda.h"
+#include "panda_shared/panda.h"
#include
// The following ifdef block is the standard way of creating macros which make exporting
diff --git a/panda/drivers/windows/README.md b/panda/drivers/windows/README.md
index 7219abda24..c36e6abdc8 100644
--- a/panda/drivers/windows/README.md
+++ b/panda/drivers/windows/README.md
@@ -56,10 +56,8 @@ features.
# Building the Project:
-This project was developed with Visual Studio 2015, the Windows SDK,
-and the Windows Driver Kit (WDK). At the time of writing, there is not
-a stable WDK for Visual Studio 2017, but this project should build
-with the new WDK and Visual Studio when it is available.
+This project is developed with Visual Studio 2017, the Windows SDK,
+and the Windows Driver Kit (WDK).
The WDK is only required for creating the signed WinUSB inf file. The
WDK may also provide the headers for WinUSB.
@@ -102,50 +100,18 @@ A simple tool for testing J2534 drivers is DrewTech's 'J2534-1 Bus Analysis
Tool' available in the 'Other Support Applications' section of their
[Download Page](http://www.drewtech.com/downloads/).
-# Dealing with self signed drivers:
+# Installing WinUSB driver:
-Installation would be straightforward were it not for the USB Driver
-that needs to be setup. The driver itself is only a WinUSB inf file
-(no actual driver), but it still needs to be signed.
+Installation automatically happens for Windows 8 and Windows 10 because the panda
+firmware contains the USB descriptors necessary to auto-install the WinUSB driver.
-Driver signing is a requirement of Windows starting in 8 (64 bit
-versions only for some reason). If your Windows refuses to install
-the driver, there are three choices:
+Windows 7 will not auto-install the WinUSB driver. You can use Zadig to install
+the WinUSB driver. This software is not tested on anything before 7.
-- Self Sign the Driver.
-- Disable Driver Signature Verification
-- Purchase a certificate signed by a trusted authority.
-
-Since self signed certificates have no chain of trust to a known
-certificate authority, if you self sign, you will have to add your
-cert to the root certificate store of your Windows' installation. This
-is dangerous because it means anything signed with your cert will be
-trusted. If you make your own cert, add a password so someone can't
-copy it and screw with your computer's trust.
-
-Disabling Signature Verification allows you to temporarily install
-drivers without a trusted signature. Once you reboot, new drivers will
-need to be verified again, but any installed drivers will stay where
-they are. This option is irritating if you are installing and
-uninstalling the inf driver multiple times, but overall, is safer than
-the custom root certificate described above.
-
-Purchasing a signed certificate is the best long term option, but it
-is not useful for open source contributors, since the certificate will
-be kept safe by the comma.ai team. Developers should use one of the
-other two options.
-
-**Note that certificate issues apply no matter if you are building
- from source or running an insaller .exe file.**
-
-Some people have reported that the driver installs without needing to
-disable driver signing, or that visual studio correctly sets up a
-temporary signing key for them. I call witchcraft because I have not
-had that happen to me. The signed certificate is still the correct
-thing to do in the end.
-
-Windows 7 will not force driver signing. This software is not tested
-on anything before 7.
+More details here:
+[WinUSB (Winusb.sys) Installation](https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation)
+[WCID Devices](https://github.com/pbatard/libwdi/wiki/WCID-Devices)
+[Zadig for installing libusb compatible driver](https://github.com/pbatard/libwdi/wiki/Zadig)
# Developing:
@@ -154,8 +120,6 @@ on anything before 7.
# ToDo Items:
-- Get official signing key for WinUSB driver inf file.
-- Implement TxClear and RxClear. (Requires reading vague specifications).
- Apply a style-guide and consistent naming convention for Classes/Functions/Variables.
- Send multiple messages (each with a different address) from a given connection at the same time.
- Implement ISO14230/KWP2000 FAST (LIN communication is already supported with the raw panda USB driver).
@@ -173,5 +137,14 @@ on anything before 7.
relaxed to allow serialization of messages based on their address
(making multiple queues, effectively one queue per address).
+# Troubleshooting:
+troubleshooting:
+1. Install DrewTech J2534-1 Bus Analysis Tool
+http://www.drewtech.com/downloads/tools/Drew%20Technologies%20Tool%20for%20J2534-1%20API%20v1.07.msi
+2. Open DrewTech tool and make sure it shows "panda" as a device listed (this means registry settings are correct)
+3. When DrewTech tool attempts to load the driver it will show an error if it fails
+4. To figure out why the driver fails to load install Process Monitor and filter by the appropriate process name
+https://docs.microsoft.com/en-us/sysinternals/downloads/procmon
+
# Other:
Panda head ASCII art by dcau
\ No newline at end of file
diff --git a/panda/drivers/windows/panda.sln b/panda/drivers/windows/panda.sln
index a74e4022bf..39c8a63e28 100644
--- a/panda/drivers/windows/panda.sln
+++ b/panda/drivers/windows/panda.sln
@@ -1,90 +1,92 @@
-
-Microsoft Visual Studio Solution File, Format Version 12.00
-# Visual Studio 14
-VisualStudioVersion = 14.0.25420.1
-MinimumVisualStudioVersion = 10.0.40219.1
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}"
- ProjectSection(ProjectDependencies) = postProject
- {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
- EndProjectSection
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}"
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}"
- ProjectSection(ProjectDependencies) = postProject
- {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
- EndProjectSection
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}"
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}"
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}"
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}"
-EndProject
-Global
- GlobalSection(SolutionConfigurationPlatforms) = preSolution
- Debug|x64 = Debug|x64
- Debug|x86 = Debug|x86
- Release|x64 = Release|x64
- Release|x86 = Release|x86
- EndGlobalSection
- GlobalSection(ProjectConfigurationPlatforms) = postSolution
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32
- {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32
- {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32
- {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64
- {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64
- {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32
- {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32
- {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64
- {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64
- {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32
- {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.Build.0 = Release|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Build.0 = Debug|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.Deploy.0 = Debug|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Build.0 = Release|Win32
- {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.Deploy.0 = Release|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32
- {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.Build.0 = Release|Win32
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32
- {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.Build.0 = Release|Win32
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32
- {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.Build.0 = Release|Win32
- EndGlobalSection
- GlobalSection(SolutionProperties) = preSolution
- HideSolutionNode = FALSE
- EndGlobalSection
-EndGlobal
+
+Microsoft Visual Studio Solution File, Format Version 12.00
+# Visual Studio 15
+VisualStudioVersion = 15.0.27130.2027
+MinimumVisualStudioVersion = 10.0.40219.1
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}"
+ ProjectSection(ProjectDependencies) = postProject
+ {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531}
+ EndProjectSection
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}"
+EndProject
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_shared", "panda_shared\panda_shared.vcxitems", "{0C843279-68C7-4679-AE51-9BC463D50D1C}"
+EndProject
+Global
+ GlobalSection(SharedMSBuildProjectFiles) = preSolution
+ panda_shared\panda_shared.vcxitems*{0c843279-68c7-4679-ae51-9bc463d50d1c}*SharedItemsImports = 9
+ panda_shared\panda_shared.vcxitems*{5528aefb-638d-49af-b9d4-965154e7d531}*SharedItemsImports = 4
+ panda_shared\panda_shared.vcxitems*{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}*SharedItemsImports = 4
+ EndGlobalSection
+ GlobalSection(SolutionConfigurationPlatforms) = preSolution
+ Debug|x64 = Debug|x64
+ Debug|x86 = Debug|x86
+ Release|x64 = Release|x64
+ Release|x86 = Release|x86
+ EndGlobalSection
+ GlobalSection(ProjectConfigurationPlatforms) = postSolution
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32
+ {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32
+ {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64
+ {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32
+ {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32
+ {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32
+ {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32
+ {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32
+ {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32
+ {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32
+ {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32
+ {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32
+ {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64
+ {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64
+ {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32
+ EndGlobalSection
+ GlobalSection(SolutionProperties) = preSolution
+ HideSolutionNode = FALSE
+ EndGlobalSection
+ GlobalSection(ExtensibilityGlobals) = postSolution
+ SolutionGuid = {8AF3826E-406A-4F1C-BA80-B4D7FD4B52E1}
+ EndGlobalSection
+ GlobalSection(Performance) = preSolution
+ HasPerformanceSessions = true
+ EndGlobalSection
+EndGlobal
diff --git a/panda/drivers/windows/panda/panda.vcxproj b/panda/drivers/windows/panda/panda.vcxproj
index a84b2fcce2..22879c7cae 100644
--- a/panda/drivers/windows/panda/panda.vcxproj
+++ b/panda/drivers/windows/panda/panda.vcxproj
@@ -55,6 +55,7 @@
+
@@ -151,14 +152,10 @@
-
-
-
-
false
@@ -173,7 +170,6 @@
-
Create
Create
diff --git a/panda/drivers/windows/panda/panda.vcxproj.filters b/panda/drivers/windows/panda/panda.vcxproj.filters
index cded701a31..afddad6e8b 100644
--- a/panda/drivers/windows/panda/panda.vcxproj.filters
+++ b/panda/drivers/windows/panda/panda.vcxproj.filters
@@ -1,58 +1,43 @@
-
-
-
-
- {4FC737F1-C7A5-4376-A066-2A32D752A2FF}
- cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx
-
-
- {93995380-89BD-4b04-88EB-625FBE52EBFB}
- h;hh;hpp;hxx;hm;inl;inc;xsd
-
-
- {67DA6AB6-F800-4c08-8B7A-83BB121AAD01}
- rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms
-
-
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
- Header Files
-
-
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
- Source Files
-
-
-
-
- Resource Files
-
-
-
-
- Resource Files
-
-
+
+
+
+
+ {4FC737F1-C7A5-4376-A066-2A32D752A2FF}
+ cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx
+
+
+ {93995380-89BD-4b04-88EB-625FBE52EBFB}
+ h;hh;hpp;hxx;hm;inl;inc;xsd
+
+
+ {67DA6AB6-F800-4c08-8B7A-83BB121AAD01}
+ rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms
+
+
+
+
+ Header Files
+
+
+ Header Files
+
+
+
+
+ Source Files
+
+
+ Source Files
+
+
+
+
+ Resource Files
+
+
+
+
+ Resource Files
+
+
\ No newline at end of file
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp
index 1effc49145..8a9161475c 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp
@@ -1,7 +1,7 @@
#include "stdafx.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "Timer.h"
#include "ECUsim DLL\ECUsim.h"
#include "TestHelpers.h"
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp
index 62096d1181..1281eb9d61 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp
@@ -2,7 +2,7 @@
#include "TestHelpers.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "Timer.h"
using namespace Microsoft::VisualStudio::CppUnitTestFramework;
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h
index 17dcee5f54..9df59d7b5e 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h
+++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h
@@ -1,7 +1,7 @@
#pragma once
#include "stdafx.h"
#include "pandaJ2534DLL/J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
using namespace Microsoft::VisualStudio::CppUnitTestFramework;
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp
index 774b8ed31c..674569accc 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp
@@ -1,7 +1,7 @@
#include "stdafx.h"
#include "Loader4.h"
#include "pandaJ2534DLL/J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "Timer.h"
#include "ECUsim DLL\ECUsim.h"
#include "TestHelpers.h"
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj
index d415b1fd79..f19c743461 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj
+++ b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj
@@ -115,9 +115,6 @@
{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}
-
- {5528aefb-638d-49af-b9d4-965154e7d531}
-
diff --git a/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp
index 65e549c50c..51b0bfcf2f 100644
--- a/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp
@@ -1,5 +1,5 @@
#include "stdafx.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "TestHelpers.h"
#include
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp
index 358158bcb4..aa364b0f8a 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp
@@ -33,6 +33,7 @@ long J2534Connection::PassThruReadMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMs
messageRxBuff_mutex.unlock();
if (Timeout == 0)
break;
+ Sleep(2);
continue;
}
@@ -146,16 +147,35 @@ long J2534Connection::PassThruIoctl(unsigned long IoctlID, void *pInput, void *p
return STATUS_NOERROR;
}
-long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return STATUS_NOERROR; }
-long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return STATUS_NOERROR; }
-long J2534Connection::clearTXBuff() { return STATUS_NOERROR; }
+long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return ERR_FAILED; }
+long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return ERR_FAILED; }
+long J2534Connection::clearTXBuff() {
+ if (auto panda_ps = this->panda_dev.lock()) {
+ synchronized(staged_writes_lock) {
+ this->txbuff = {};
+ panda_ps->panda->can_clear(panda::PANDA_CAN1_TX);
+ }
+ }
+ return STATUS_NOERROR;
+}
long J2534Connection::clearRXBuff() {
- synchronized(messageRxBuff_mutex) {
- this->messageRxBuff = {};
+ if (auto panda_ps = this->panda_dev.lock()) {
+ synchronized(messageRxBuff_mutex) {
+ this->messageRxBuff = {};
+ panda_ps->panda->can_clear(panda::PANDA_CAN_RX);
+ }
}
return STATUS_NOERROR;
}
-long J2534Connection::clearPeriodicMsgs() { return STATUS_NOERROR; }
+long J2534Connection::clearPeriodicMsgs() {
+ for (int i = 0; i < this->periodicMessages.size(); i++) {
+ if (periodicMessages[i] == nullptr) continue;
+ this->periodicMessages[i]->cancel();
+ this->periodicMessages[i] = nullptr;
+ }
+
+ return STATUS_NOERROR;
+}
long J2534Connection::clearMsgFilters() {
for (auto& filter : this->filters) filter = nullptr;
return STATUS_NOERROR;
@@ -202,6 +222,7 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo
switch (Parameter) {
case DATA_RATE: // 5-500000
this->setBaud(Value);
+ break;
case LOOPBACK: // 0 (OFF), 1 (ON) [0]
this->loopback = (Value != 0);
break;
@@ -236,6 +257,11 @@ void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned lo
default:
printf("Got unknown SET code %X\n", Parameter);
}
+
+ // reserved parameters usually mean special equiptment is required
+ if (Parameter >= 0x20) {
+ throw ERR_NOT_SUPPORTED;
+ }
}
unsigned long J2534Connection::processIOCTLGetConfig(unsigned long Parameter) {
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h
index cdb215018b..70f25a1063 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h
@@ -1,5 +1,5 @@
#pragma once
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "J2534_v0404.h"
#include "synchronize.h"
#include "J2534Frame.h"
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h
index 4dd950b390..3971351eea 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h
@@ -1,7 +1,7 @@
#pragma once
#include "J2534Connection.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#define val_is_29bit(num) check_bmask(num, CAN_29BIT_ID)
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp
index 2b9d97cb64..a83f6f4331 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp
@@ -43,7 +43,7 @@ std::shared_ptr J2534Connection_ISO15765::parseMessageTx(PASSTHRU_MSG
void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) {
if (msg.ProtocolID != CAN) return;
- int fid = get_matching_in_fc_filter_id(msg);
+ int fid = get_matching_in_fc_filter_id(msg, this->Flags);
if (fid == -1) return;
auto filter = this->filters[fid];
@@ -136,6 +136,9 @@ void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) {
if (flowfilter.size() > 4)
flowstrlresp += flowfilter[4];
flowstrlresp += std::string("\x30\x00\x00", 3);
+ if (check_bmask(filter->flags, ISO15765_FRAME_PAD)) {
+ flowstrlresp += std::string(8 - flowstrlresp.size(), '\x00');
+ }
if (auto panda_dev_sp = this->panda_dev.lock()) {
panda_dev_sp->panda->can_send(flow_addr, val_is_29bit(msg.RxStatus), (const uint8_t *)flowstrlresp.c_str(), (uint8_t)flowstrlresp.size(), panda::PANDA_CAN1);
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h
index ddbf2dc2aa..beb9f012e0 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h
@@ -25,7 +25,7 @@ public:
int get_matching_out_fc_filter_id(const std::string & msgdata, unsigned long flags, unsigned long flagmask);
- int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask = CAN_29BIT_ID);
+ int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask);
virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg);
diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h
index 5c991c5082..2549216b6f 100644
--- a/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h
+++ b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h
@@ -1,6 +1,6 @@
#pragma once
#include "J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
/*A move convenient container for J2534 Messages than the static buffer provided by default.*/
class J2534Frame {
@@ -10,7 +10,7 @@ public:
J2534Frame(const panda::PANDA_CAN_MSG& msg_in) {
ProtocolID = CAN;
- ExtraDataIndex = 0;
+ ExtraDataIndex = msg_in.len + 4;
Data.reserve(msg_in.len + 4);
Data += msg_in.addr >> 24;
Data += (msg_in.addr >> 16) & 0xFF;
diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp
index abcf3f6a47..023088d3c6 100644
--- a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp
@@ -95,7 +95,7 @@ BOOL MessageTx_ISO15765::checkTxReceipt(J2534Frame frame) {
J2534Frame outframe(ISO15765);
outframe.Timestamp = frame.Timestamp;
- outframe.RxStatus = TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID));
+ outframe.RxStatus = TX_MSG_TYPE | TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID));
outframe.Data = frame.Data.substr(0, addressLength());
conn_sp->addMsgToRxQueue(outframe);
diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp
index 6a78271fdc..1b961579e0 100644
--- a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp
@@ -8,11 +8,15 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr new_panda) : tx
this->panda->set_esp_power(FALSE);
this->panda->set_safety_mode(panda::SAFETY_ALLOUTPUT);
this->panda->set_can_loopback(FALSE);
- this->panda->set_alt_setting(1);
+ this->panda->set_alt_setting(0);
- DWORD canListenThreadID;
this->thread_kill_event = CreateEvent(NULL, TRUE, FALSE, NULL);
- this->can_thread_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID);
+
+ DWORD canListenThreadID;
+ this->can_recv_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID);
+
+ DWORD canProcessThreadID;
+ this->can_process_handle = CreateThread(NULL, 0, _can_process_threadBootstrap, (LPVOID)this, 0, &canProcessThreadID);
DWORD flowControlSendThreadID;
this->flow_control_wakeup_event = CreateEvent(NULL, TRUE, FALSE, NULL);
@@ -21,8 +25,11 @@ PandaJ2534Device::PandaJ2534Device(std::unique_ptr new_panda) : tx
PandaJ2534Device::~PandaJ2534Device() {
SetEvent(this->thread_kill_event);
- DWORD res = WaitForSingleObject(this->can_thread_handle, INFINITE);
- CloseHandle(this->can_thread_handle);
+ DWORD res = WaitForSingleObject(this->can_recv_handle, INFINITE);
+ CloseHandle(this->can_recv_handle);
+
+ res = WaitForSingleObject(this->can_process_handle, INFINITE);
+ CloseHandle(this->can_process_handle);
res = WaitForSingleObject(this->flow_control_thread_handle, INFINITE);
CloseHandle(this->flow_control_thread_handle);
@@ -67,11 +74,28 @@ DWORD PandaJ2534Device::addChannel(std::shared_ptr& conn, unsig
}
DWORD PandaJ2534Device::can_recv_thread() {
- DWORD err = TRUE;
- while (err) {
- std::vector msg_recv;
- err = this->panda->can_recv_async(this->thread_kill_event, msg_recv);
- for (auto msg_in : msg_recv) {
+ this->panda->can_clear(panda::PANDA_CAN_RX);
+ this->panda->can_rx_q_push(this->thread_kill_event);
+
+ return 0;
+}
+
+DWORD PandaJ2534Device::can_process_thread() {
+ panda::PANDA_CAN_MSG msg_recv[CAN_RX_MSG_LEN];
+
+ while (true) {
+ if (!WaitForSingleObject(this->thread_kill_event, 0)) {
+ break;
+ }
+
+ int count = 0;
+ this->panda->can_rx_q_pop(msg_recv, count);
+ if (count == 0) {
+ continue;
+ }
+
+ for (int i = 0; i < count; i++) {
+ auto msg_in = msg_recv[i];
J2534Frame msg_out(msg_in);
if (msg_in.is_receipt) {
diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h
index 3e5880c955..32004ffba5 100644
--- a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h
+++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h
@@ -5,7 +5,7 @@
#include
#include
#include "J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "synchronize.h"
#include "Action.h"
#include "MessageTx.h"
@@ -55,12 +55,18 @@ public:
private:
HANDLE thread_kill_event;
- HANDLE can_thread_handle;
+ HANDLE can_recv_handle;
static DWORD WINAPI _can_recv_threadBootstrap(LPVOID This) {
return ((PandaJ2534Device*)This)->can_recv_thread();
}
DWORD can_recv_thread();
+ HANDLE can_process_handle;
+ static DWORD WINAPI _can_process_threadBootstrap(LPVOID This) {
+ return ((PandaJ2534Device*)This)->can_process_thread();
+ }
+ DWORD can_process_thread();
+
HANDLE flow_control_wakeup_event;
HANDLE flow_control_thread_handle;
static DWORD WINAPI _msg_tx_threadBootstrap(LPVOID This) {
diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp
index 2e706f507d..096e441988 100644
--- a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp
+++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp
@@ -5,7 +5,7 @@
#include "stdafx.h"
#include "J2534_v0404.h"
-#include "panda/panda.h"
+#include "panda_shared/panda.h"
#include "J2534Connection.h"
#include "J2534Connection_CAN.h"
#include "J2534Connection_ISO15765.h"
@@ -57,7 +57,7 @@ long ret_code(long code) {
return code;
}
-#define EXTRACT_DID(CID) (CID & 0xFFFF)
+#define EXTRACT_DID(CID) ((CID & 0xFFFF) - 1)
#define EXTRACT_CID(CID) ((CID >> 16) & 0xFFFF)
long check_valid_DeviceID(unsigned long DeviceID) {
@@ -68,7 +68,7 @@ long check_valid_DeviceID(unsigned long DeviceID) {
}
long check_valid_ChannelID(unsigned long ChannelID) {
- uint16_t dev_id = EXTRACT_DID(ChannelID);;
+ uint16_t dev_id = EXTRACT_DID(ChannelID);
uint16_t con_id = EXTRACT_CID(ChannelID);
if (pandas.size() <= dev_id || pandas[dev_id] == nullptr)
@@ -117,7 +117,7 @@ PANDAJ2534DLL_API long PTAPI PassThruOpen(void *pName, unsigned long *pDevice
panda_index = pandas.size()-1;
}
- *pDeviceID = panda_index;
+ *pDeviceID = panda_index + 1; // TIS doesn't like it when ID == 0
return ret_code(STATUS_NOERROR);
}
PANDAJ2534DLL_API long PTAPI PassThruClose(unsigned long DeviceID) {
@@ -140,14 +140,12 @@ PANDAJ2534DLL_API long PTAPI PassThruConnect(unsigned long DeviceID, unsigned lo
switch (ProtocolID) {
//SW seems to refer to Single Wire. https://www.nxp.com/files-static/training_pdf/20451_BUS_COMM_WBT.pdf
//SW_ protocols may be touched on here: https://www.iso.org/obp/ui/#iso:std:iso:22900:-2:ed-1:v1:en
- case J1850VPW: //These protocols are outdated and will not be supported. HDS wants them to not fail to open.
- case J1850PWM:
- case J1850VPW_PS:
- case J1850PWM_PS:
+ //case J1850VPW: // These protocols are outdated and will not be supported. HDS wants them to not fail to open.
+ //case J1850PWM: // ^-- it appears HDS no longer needs this, and TIS needs it disabled --^
+ //case J1850VPW_PS:
+ //case J1850PWM_PS:
case ISO9141: //This protocol could be implemented if 5 BAUD init support is added to the panda.
case ISO9141_PS:
- conn = std::make_shared(panda, ProtocolID, Flags, BaudRate);
- break;
case ISO14230: //Only supporting Fast init until panda adds support for 5 BAUD init.
case ISO14230_PS:
conn = std::make_shared(panda, ProtocolID, Flags, BaudRate);
@@ -263,8 +261,7 @@ PANDAJ2534DLL_API long PTAPI PassThruReadVersion(unsigned long DeviceID, char *p
} else {
j2534dll_ver = GetProductAndVersion(pandalib_filename);
}
- std::string pandalib_ver = GetProductAndVersion(_T("panda.dll"));
- std::string fullver = "(" + j2534dll_ver + "; " + pandalib_ver + ")";
+ std::string fullver = "(" + j2534dll_ver + ")";
strcpy_s(pDllVersion, 80, fullver.c_str());
strcpy_s(pApiVersion, 80, J2534_APIVER_NOVEMBER_2004);
diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj
index 6e32122b8b..fd5eac56dd 100644
--- a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj
+++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj
@@ -34,6 +34,7 @@
+
@@ -64,7 +65,7 @@
Windows
true
- kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib
+ kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib
@@ -83,7 +84,7 @@
true
true
true
- kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;$(OutDir)panda.lib
+ kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib
@@ -135,11 +136,6 @@
-
-
- {5528aefb-638d-49af-b9d4-965154e7d531}
-
-
diff --git a/panda/drivers/windows/panda_install.nsi b/panda/drivers/windows/panda_install.nsi
index 81ecc3c872..47a4423f91 100644
--- a/panda/drivers/windows/panda_install.nsi
+++ b/panda/drivers/windows/panda_install.nsi
@@ -1,5 +1,5 @@
!define J2534_Reg_Path "Software\PassThruSupport.04.04\comma.ai - panda"
-!define Install_Name "panda J2534 Drivers"
+!define Install_Name "panda J2534 driver"
;NOTE! The panda software requires a VC runtime to be installed in order to work.
;This installer must be bundled with the appropriate runtime installer, and have
@@ -21,10 +21,10 @@
Unicode true
# Set the installer display name
-Name "panda Driver"
+Name "${Install_Name}"
# set the name of the installer
-Outfile "panda install.exe"
+Outfile "${Install_Name} install.exe"
; The default installation directory
InstallDir $PROGRAMFILES\comma.ai\panda
@@ -63,18 +63,19 @@ VIProductVersion "1.0.0.0"
;--------------------------------
; Install Sections
-Section "panda driver (required)"
+Section "prerequisites"
SectionIn RO
SetOutPath "$INSTDIR"
+ File "panda.ico"
;If the visual studio version this project is compiled with changes, this section
;must be revisited. The registry key must be changed, and the VS redistributable
;binary must be updated to the VS version used.
ClearErrors
- ReadRegStr $0 HKLM ${VCRuntimeRegKey} "Version"
+ ReadRegStr $0 HKCR ${VCRuntimeRegKey} "Version"
${If} ${Errors}
DetailPrint "Installing Visual Studio C Runtime..."
File "${VCRuntimeSetupPath}\${VCRuntimeSetupFile}"
@@ -87,35 +88,22 @@ Section "panda driver (required)"
Delete "$INSTDIR\${VCRuntimeSetupFile}"
;Do the rest of the install
- SetOutPath "$INSTDIR\driver"
+ ; SetOutPath "$INSTDIR\driver"
; The inf file works for both 32 and 64 bit.
- File "Debug_x86\panda Driver Package\panda.inf"
- File "Debug_x86\panda Driver Package\panda.cat"
- ${DisableX64FSRedirection}
- nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"'
- ${EnableX64FSRedirection}
-
- SetOutPath $SYSDIR
-
- File Release_x86\panda.dll
-
- ${If} ${RunningX64}
- ${DisableX64FSRedirection}
- ;Note that the x64 VS redistributable is not installed to prevent bloat.
- ;If you are the rare person who uses the 64 bit raw panda driver, please
- ;install the correct x64 VS runtime manually.
- File Release_x64\panda.dll
- ${EnableX64FSRedirection}
- ${EndIf}
+ ; File "Debug_x86\panda Driver Package\panda.inf"
+ ; File "Debug_x86\panda Driver Package\panda.cat"
+ ; ${DisableX64FSRedirection}
+ ; nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"'
+ ; ${EnableX64FSRedirection}
; Write the installation path into the registry
- WriteRegStr HKLM "SOFTWARE\panda J2534 Drivers" "Install_Dir" "$INSTDIR"
+ WriteRegStr HKLM "SOFTWARE\${Install_Name}" "Install_Dir" "$INSTDIR"
; Write the uninstall keys for Windows
- ;WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" ""
- WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$SYSDIR\panda.dll",0'
- WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "panda J2534 Drivers"
+ WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" ""
+ WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$INSTDIR\panda.ico",0'
+ WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "${Install_Name}"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "Publisher" "comma.ai"
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "UninstallString" '"$INSTDIR\uninstall.exe"'
WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "URLInfoAbout" "https://github.com/commaai/panda/"
@@ -127,19 +115,6 @@ Section "panda driver (required)"
SectionEnd
-Section "panda devel lib/header"
-
- SetOutPath "$INSTDIR\devel"
- File panda\panda.h
-
- SetOutPath "$INSTDIR\devel\x86"
- File Release_x86\panda.lib
-
- SetOutPath "$INSTDIR\devel\x64"
- File Release_x64\panda.lib
-
-SectionEnd
-
Section "J2534 Driver"
SetOutPath $INSTDIR
@@ -165,6 +140,32 @@ Section "J2534 Driver"
SectionEnd
+Section /o "Development lib/header"
+
+ SetOutPath $SYSDIR
+
+ File Release_x86\panda.dll
+
+ ${If} ${RunningX64}
+ ${DisableX64FSRedirection}
+ ;Note that the x64 VS redistributable is not installed to prevent bloat.
+ ;If you are the rare person who uses the 64 bit raw panda driver, please
+ ;install the correct x64 VS runtime manually.
+ File Release_x64\panda.dll
+ ${EnableX64FSRedirection}
+ ${EndIf}
+
+ SetOutPath "$INSTDIR\devel"
+ File panda_shared\panda.h
+
+ SetOutPath "$INSTDIR\devel\x86"
+ File Release_x86\panda.lib
+
+ SetOutPath "$INSTDIR\devel\x64"
+ File Release_x64\panda.lib
+
+SectionEnd
+
;--------------------------------
; Uninstaller
Section "Uninstall"
@@ -176,9 +177,9 @@ Section "Uninstall"
; if Microsoft wants these inf files to be removed.
; Consider https://blog.sverrirs.com/2015/12/creating-windows-installer-and.html
; These lines just remove the inf backups.
- Delete "$INSTDIR\driver\panda.inf"
- Delete "$INSTDIR\driver\panda.cat"
- RMDir "$INSTDIR\driver"
+ ; Delete "$INSTDIR\driver\panda.inf"
+ ; Delete "$INSTDIR\driver\panda.cat"
+ ; RMDir "$INSTDIR\driver"
; Remove WinUSB driver library
Delete $SYSDIR\panda.dll
@@ -204,6 +205,7 @@ Section "Uninstall"
; Remove files and uninstaller
Delete "$INSTDIR\uninstall.exe"
Delete "$INSTDIR\pandaJ2534_0404_32.dll"
+ Delete "$INSTDIR\panda.ico"
; Remove directories used
RMDir "$INSTDIR"
diff --git a/panda/drivers/windows/panda/device.cpp b/panda/drivers/windows/panda_shared/device.cpp
similarity index 99%
rename from panda/drivers/windows/panda/device.cpp
rename to panda/drivers/windows/panda_shared/device.cpp
index a204610000..83e021b799 100644
--- a/panda/drivers/windows/panda/device.cpp
+++ b/panda/drivers/windows/panda_shared/device.cpp
@@ -1,10 +1,13 @@
#include "stdafx.h"
+
#include
#include
#include
#include
+#include
+
#include "device.h"
using namespace panda;
diff --git a/panda/drivers/windows/panda/device.h b/panda/drivers/windows/panda_shared/device.h
similarity index 97%
rename from panda/drivers/windows/panda/device.h
rename to panda/drivers/windows/panda_shared/device.h
index 3b404857cf..f11baa1c67 100644
--- a/panda/drivers/windows/panda/device.h
+++ b/panda/drivers/windows/panda_shared/device.h
@@ -4,7 +4,6 @@
//
// Define below GUIDs
//
-#include "stdafx.h"
#include
#include
diff --git a/panda/drivers/windows/panda/panda.cpp b/panda/drivers/windows/panda_shared/panda.cpp
similarity index 77%
rename from panda/drivers/windows/panda/panda.cpp
rename to panda/drivers/windows/panda_shared/panda.cpp
index 79ec08edc2..5f711b02aa 100644
--- a/panda/drivers/windows/panda/panda.cpp
+++ b/panda/drivers/windows/panda_shared/panda.cpp
@@ -1,7 +1,7 @@
// panda.cpp : Defines the exported functions for the DLL application.
//
-
#include "stdafx.h"
+
#include "device.h"
#include "panda.h"
@@ -13,13 +13,6 @@
using namespace panda;
-#pragma pack(1)
-typedef struct _PANDA_CAN_MSG_INTERNAL {
- uint32_t rir;
- uint32_t f2;
- uint8_t dat[8];
-} PANDA_CAN_MSG_INTERNAL;
-
Panda::Panda(
WINUSB_INTERFACE_HANDLE WinusbHandle,
HANDLE DeviceHandle,
@@ -28,6 +21,7 @@ Panda::Panda(
) : usbh(WinusbHandle), devh(DeviceHandle), devPath(devPath_), sn(sn_) {
printf("CREATED A PANDA %s\n", this->sn.c_str());
this->set_can_loopback(FALSE);
+ this->set_raw_io(TRUE);
this->set_alt_setting(0);
}
@@ -167,7 +161,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) {
this->set_can_loopback(TRUE);
Sleep(20); // Give time for any sent messages to appear in the RX buffer.
this->can_clear(PANDA_CAN_RX);
- for (int i = 0; i < 2; i++) {
+ // send 4 messages becaus can_recv reads 4 messages at a time
+ for (int i = 0; i < 4; i++) {
printf("Sending PAD %d\n", i);
if (this->can_send(0x7FF, FALSE, {}, 0, PANDA_CAN1) == FALSE) {
auto err = GetLastError();
@@ -177,14 +172,8 @@ bool Panda::set_alt_setting(UCHAR alt_setting) {
Sleep(10);
//this->can_clear(PANDA_CAN_RX);
- std::vector msg_recv;
- if (alt_setting == 1) {
- //Read the messages so they do not contaimnate the real message stream.
- auto err = this->can_recv_async(NULL, msg_recv, 1000);
- }
- else {
- msg_recv = this->can_recv();
- }
+ //Read the messages so they do not contaimnate the real message stream.
+ this->can_recv();
//this->set_can_loopback(FALSE);
this->set_can_loopback(loopback_backup);
@@ -203,6 +192,17 @@ UCHAR Panda::get_current_alt_setting() {
return alt_setting;
}
+bool Panda::set_raw_io(bool val) {
+ UCHAR raw_io = val;
+ if (!WinUsb_SetPipePolicy(this->usbh, 0x81, RAW_IO, sizeof(raw_io), &raw_io)) {
+ _tprintf(_T(" Error setting usb raw I/O pipe policy %d, Msg: '%s'\n"),
+ GetLastError(), GetLastErrorAsString().c_str());
+ return FALSE;
+ }
+
+ return TRUE;
+}
+
PANDA_HEALTH Panda::get_health()
{
WINUSB_SETUP_PACKET SetupPacket;
@@ -351,69 +351,85 @@ bool Panda::can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t l
return this->can_send_many(std::vector{msg});
}
-void Panda::parse_can_recv(std::vector& msg_recv, char *buff, int retcount) {
- for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
- PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i);
- PANDA_CAN_MSG in_msg;
-
- in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED);
- in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21);
- in_msg.recv_time = this->runningTime.getTimePassedUS();
- in_msg.recv_time_point = std::chrono::steady_clock::now();
- //The timestamp from the device is (in_msg_raw->f2 >> 16),
- //but this 16 bit value is a little hard to use. Using a
- //timer since the initialization of this device.
- in_msg.len = in_msg_raw->f2 & 0xF;
- memcpy(in_msg.dat, in_msg_raw->dat, 8);
-
- in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80;
- switch ((in_msg_raw->f2 >> 4) & 0x7F) {
- case PANDA_CAN1:
- in_msg.bus = PANDA_CAN1;
- break;
- case PANDA_CAN2:
- in_msg.bus = PANDA_CAN2;
- break;
- case PANDA_CAN3:
- in_msg.bus = PANDA_CAN3;
- break;
- default:
- in_msg.bus = PANDA_CAN_UNK;
- }
- msg_recv.push_back(in_msg);
+PANDA_CAN_MSG Panda::parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw) {
+ PANDA_CAN_MSG in_msg;
+
+ in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED);
+ in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21);
+ in_msg.recv_time = this->runningTime.getTimePassedUS();
+ in_msg.recv_time_point = std::chrono::steady_clock::now();
+ //The timestamp from the device is (in_msg_raw->f2 >> 16),
+ //but this 16 bit value is a little hard to use. Using a
+ //timer since the initialization of this device.
+ in_msg.len = in_msg_raw->f2 & 0xF;
+ memcpy(in_msg.dat, in_msg_raw->dat, 8);
+
+ in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80;
+ switch ((in_msg_raw->f2 >> 4) & 0x7F) {
+ case PANDA_CAN1:
+ in_msg.bus = PANDA_CAN1;
+ break;
+ case PANDA_CAN2:
+ in_msg.bus = PANDA_CAN2;
+ break;
+ case PANDA_CAN3:
+ in_msg.bus = PANDA_CAN3;
+ break;
+ default:
+ in_msg.bus = PANDA_CAN_UNK;
}
+ return in_msg;
}
-bool Panda::can_recv_async(HANDLE kill_event, std::vector& msg_buff, DWORD timeoutms) {
- int retcount;
- char buff[sizeof(PANDA_CAN_MSG_INTERNAL) * 4];
+bool Panda::can_rx_q_push(HANDLE kill_event, DWORD timeoutms) {
+ while (1) {
+ auto w_ptr = this->w_ptr;
+ auto n_ptr = w_ptr + 1;
+ if (n_ptr == CAN_RX_QUEUE_LEN) {
+ n_ptr = 0;
+ }
+
+ // Pause if there is not a slot available in the queue
+ if (n_ptr == this->r_ptr) {
+ printf("RX queue full!\n");
+ Sleep(1);
+ continue;
+ }
- // Overlapped structure required for async read.
- HANDLE m_hReadFinishedEvent = CreateEvent(NULL, TRUE, TRUE, NULL);
- OVERLAPPED m_overlappedData;
- memset(&m_overlappedData, sizeof(OVERLAPPED), 0);
- m_overlappedData.hEvent = m_hReadFinishedEvent;
+ if (this->can_rx_q[n_ptr].complete) {
+ // TODO: is ResetEvent() faster?
+ CloseHandle(this->can_rx_q[n_ptr].complete);
+ }
- HANDLE phSignals[2] = { m_hReadFinishedEvent, kill_event };
+ // Overlapped structure required for async read.
+ this->can_rx_q[n_ptr].complete = CreateEvent(NULL, TRUE, TRUE, NULL);
+ memset(&this->can_rx_q[n_ptr].overlapped, sizeof(OVERLAPPED), 0);
+ this->can_rx_q[n_ptr].overlapped.hEvent = this->can_rx_q[n_ptr].complete;
+ this->can_rx_q[n_ptr].error = 0;
- if (!WinUsb_ReadPipe(this->usbh, 0x81, (PUCHAR)buff, sizeof(buff), (PULONG)&retcount, &m_overlappedData)) {
- // An overlapped read will return true if done, or false with an
- // error of ERROR_IO_PENDING if the transfer is still in process.
- DWORD dwError = GetLastError();
- if (dwError == ERROR_IO_PENDING) {
- dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms);
+ if (!WinUsb_ReadPipe(this->usbh, 0x81, this->can_rx_q[n_ptr].data, sizeof(this->can_rx_q[n_ptr].data), &this->can_rx_q[n_ptr].count, &this->can_rx_q[n_ptr].overlapped)) {
+ // An overlapped read will return true if done, or false with an
+ // error of ERROR_IO_PENDING if the transfer is still in process.
+ this->can_rx_q[n_ptr].error = GetLastError();
+ }
+
+ // Process the pipe read call from the previous invocation of this function
+ if (this->can_rx_q[w_ptr].error == ERROR_IO_PENDING) {
+ HANDLE phSignals[2] = { this->can_rx_q[w_ptr].complete, kill_event };
+ auto dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms);
// Check if packet, timeout (nope), or break
if (dwError == WAIT_OBJECT_0) {
// Signal came from our usb object. Read the returned data.
- if (!GetOverlappedResult(this->usbh, &m_overlappedData, (PULONG)&retcount, FALSE)) {
+ if (!GetOverlappedResult(this->usbh, &this->can_rx_q[w_ptr].overlapped, &this->can_rx_q[w_ptr].count, TRUE)) {
// TODO: handle other error cases better.
dwError = GetLastError();
printf("Got overlap error %d\n", dwError);
- return TRUE;
+ continue;
}
- } else {
+ }
+ else {
WinUsb_AbortPipe(this->usbh, 0x81);
// Return FALSE to show that the optional signal
@@ -422,17 +438,40 @@ bool Panda::can_recv_async(HANDLE kill_event, std::vector& msg_bu
if (dwError == (WAIT_OBJECT_0 + 1)) {
return FALSE;
}
- return TRUE;
+ continue;
}
- } else { // ERROR_BAD_COMMAND happens when device is unplugged.
+ }
+ else if (this->can_rx_q[w_ptr].error != 0) { // ERROR_BAD_COMMAND happens when device is unplugged.
return FALSE;
}
+
+ this->w_ptr = n_ptr;
}
- parse_can_recv(msg_buff, buff, retcount);
return TRUE;
}
+void Panda::can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count) {
+ count = 0;
+
+ // No data left in queue
+ if (this->r_ptr == this->w_ptr) {
+ Sleep(1);
+ return;
+ }
+
+ auto r_ptr = this->r_ptr;
+ for (int i = 0; i < this->can_rx_q[r_ptr].count; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
+ auto in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(this->can_rx_q[r_ptr].data + i);
+ msg_out[count] = parse_can_recv(in_msg_raw);
+ ++count;
+ }
+
+ // Advance read pointer (wrap around if needed)
+ ++r_ptr;
+ this->r_ptr = (r_ptr == CAN_RX_QUEUE_LEN ? 0 : r_ptr);
+}
+
std::vector Panda::can_recv() {
std::vector msg_recv;
int retcount;
@@ -441,7 +480,11 @@ std::vector Panda::can_recv() {
if (this->bulk_read(0x81, buff, sizeof(buff), (PULONG)&retcount, 0) == FALSE)
return msg_recv;
- parse_can_recv(msg_recv, buff, retcount);
+ for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) {
+ PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i);
+ auto in_msg = parse_can_recv(in_msg_raw);
+ msg_recv.push_back(in_msg);
+ }
return msg_recv;
}
diff --git a/panda/drivers/windows/panda/panda.h b/panda/drivers/windows/panda_shared/panda.h
similarity index 87%
rename from panda/drivers/windows/panda/panda.h
rename to panda/drivers/windows/panda_shared/panda.h
index 12a4fbb318..ade8fa36a8 100644
--- a/panda/drivers/windows/panda/panda.h
+++ b/panda/drivers/windows/panda_shared/panda.h
@@ -9,7 +9,7 @@
#ifdef PANDA_EXPORTS
#define PANDA_API __declspec(dllexport)
#else
-#define PANDA_API __declspec(dllimport)
+#define PANDA_API
#endif
#include
@@ -31,6 +31,8 @@
#endif
#define LIN_MSG_MAX_LEN 10
+#define CAN_RX_QUEUE_LEN 10000
+#define CAN_RX_MSG_LEN 1000
//template class __declspec(dllexport) std::basic_string;
@@ -139,6 +141,7 @@ namespace panda {
std::string get_usb_sn();
bool set_alt_setting(UCHAR alt_setting);
UCHAR get_current_alt_setting();
+ bool Panda::set_raw_io(bool val);
PANDA_HEALTH get_health();
bool enter_bootloader();
@@ -160,9 +163,9 @@ namespace panda {
bool can_send_many(const std::vector& can_msgs);
bool can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t len, PANDA_CAN_PORT bus);
- void parse_can_recv(std::vector& msg_recv, char *buff, int retcount);
- bool can_recv_async(HANDLE kill_event, std::vector& msg_buff, DWORD timeoutms = INFINITE);
std::vector can_recv();
+ bool can_rx_q_push(HANDLE kill_event, DWORD timeoutms = INFINITE);
+ void can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count);
bool can_clear(PANDA_CAN_PORT_CLEAR bus);
std::string serial_read(PANDA_SERIAL_PORT port_number);
@@ -202,6 +205,23 @@ namespace panda {
ULONG timeout
);
+ #pragma pack(1)
+ typedef struct _PANDA_CAN_MSG_INTERNAL {
+ uint32_t rir;
+ uint32_t f2;
+ uint8_t dat[8];
+ } PANDA_CAN_MSG_INTERNAL;
+
+ typedef struct _CAN_RX_PIPE_READ {
+ unsigned char data[sizeof(PANDA_CAN_MSG_INTERNAL) * CAN_RX_MSG_LEN];
+ unsigned long count;
+ OVERLAPPED overlapped;
+ HANDLE complete;
+ DWORD error;
+ } CAN_RX_PIPE_READ;
+
+ PANDA_CAN_MSG parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw);
+
WINUSB_INTERFACE_HANDLE usbh;
HANDLE devh;
tstring devPath;
@@ -209,6 +229,9 @@ namespace panda {
bool loopback;
Timer runningTime;
+ CAN_RX_PIPE_READ can_rx_q[CAN_RX_QUEUE_LEN];
+ unsigned long w_ptr = 0;
+ unsigned long r_ptr = 0;
};
}
diff --git a/panda/drivers/windows/panda_shared/panda_shared.vcxitems b/panda/drivers/windows/panda_shared/panda_shared.vcxitems
new file mode 100644
index 0000000000..3f3b4765c0
--- /dev/null
+++ b/panda/drivers/windows/panda_shared/panda_shared.vcxitems
@@ -0,0 +1,25 @@
+
+
+
+ $(MSBuildAllProjects);$(MSBuildThisFileFullPath)
+ true
+ {0c843279-68c7-4679-ae51-9bc463d50d1c}
+
+
+
+ %(AdditionalIncludeDirectories);$(MSBuildThisFileDirectory)
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/panda/drivers/windows/panda/targetver.h b/panda/drivers/windows/panda_shared/targetver.h
similarity index 100%
rename from panda/drivers/windows/panda/targetver.h
rename to panda/drivers/windows/panda_shared/targetver.h
diff --git a/panda/examples/can_bit_transition.md b/panda/examples/can_bit_transition.md
new file mode 100644
index 0000000000..fa0a6c6bb3
--- /dev/null
+++ b/panda/examples/can_bit_transition.md
@@ -0,0 +1,25 @@
+# How to use can_bit_transition.py to reverse engineer a single bit field
+
+Let's say our goal is to find a brake pedal signal (caused by your foot pressing the brake pedal vs adaptive cruise control braking).
+
+The following process will allow you to quickly find bits that are always 0 during a period of time (when you know you were not pressing the brake with your foot) and always 1 in a different period of time (when you know you were pressing the brake with your foot).
+
+Open up a drive in cabana where you can find a place you used the brake pedal and another place where you did not use the brake pedal (and you can identify when you were on the brake pedal and when you were not). You may want to go out for a drive and put something in front of the camera after you put your foot on the brake and take it away before you take your foot off the brake so you can easily identify exactly when you had your foot on the brake based on the video in cabana. This is critical because this script needs the brake signal to always be high the entire time for one of the time frames. A 10 second time frame worked well for me.
+
+I found a drive where I knew I was not pressing the brake between timestamp 50.0 thru 65.0 and I was pressing the brake between timestamp 69.0 thru 79.0. Determine what the timestamps are in cabana by plotting any message and putting your mouse over the plot at the location you want to discover the timestamp. The tool tip on mouse hover has the format: timestamp: value
+
+Now download the log from cabana (Save Log button) and run the script passing in the timestamps
+(replace csv file name with cabana log you downloaded and time ranges with your own)
+```
+./can_bit_transition.py ./honda_crv_ex_2017_can-1520354796875.csv 50.0-65.0 69.0-79.0
+```
+
+The script will output bits that were always low in the first time range and always high in the second time range (and vice versa)
+```
+id 17c 0 -> 1 at byte 4 bitmask 1
+id 17c 0 -> 1 at byte 6 bitmask 32
+id 221 1 -> 0 at byte 0 bitmask 4
+id 1be 0 -> 1 at byte 0 bitmask 16
+```
+
+Now I go back to cabana and graph the above bits by searching for the message by id, double clicking on the appropriate bit, and then selecting "show plot". I already knew that message id 0x17c is both user brake and adaptive cruise control braking combined, so I plotted one of those signals along side 0x221 and 0x1be. By replaying a drive I could see that 0x221 was not a brake signal (when high at random times that did not correspond to braking). Next I looked at 0x1be and I found it was the brake pedal signal I was looking for (went high whenever I pressed the brake pedal and did not go high when adaptive cruise control was braking).
\ No newline at end of file
diff --git a/panda/examples/can_bit_transition.py b/panda/examples/can_bit_transition.py
new file mode 100755
index 0000000000..50d13f0a45
--- /dev/null
+++ b/panda/examples/can_bit_transition.py
@@ -0,0 +1,87 @@
+#!/usr/bin/env python
+
+import binascii
+import csv
+import sys
+
+class Message():
+ """Details about a specific message ID."""
+ def __init__(self, message_id):
+ self.message_id = message_id
+ self.ones = [0] * 8 # bit set if 1 is always seen
+ self.zeros = [0] * 8 # bit set if 0 is always seen
+
+ def printBitDiff(self, other):
+ """Prints bits that transition from always zero to always 1 and vice versa."""
+ for i in xrange(len(self.ones)):
+ zero_to_one = other.zeros[i] & self.ones[i]
+ if zero_to_one:
+ print 'id %s 0 -> 1 at byte %d bitmask %d' % (self.message_id, i, zero_to_one)
+ one_to_zero = other.ones[i] & self.zeros[i]
+ if one_to_zero:
+ print 'id %s 1 -> 0 at byte %d bitmask %d' % (self.message_id, i, one_to_zero)
+
+
+class Info():
+ """A collection of Messages."""
+
+ def __init__(self):
+ self.messages = {} # keyed by MessageID
+
+ def load(self, filename, start, end):
+ """Given a CSV file, adds information about message IDs and their values."""
+ with open(filename, 'rb') as input:
+ reader = csv.reader(input)
+ next(reader, None) # skip the CSV header
+ for row in reader:
+ if not len(row): continue
+ time = float(row[0])
+ bus = int(row[2])
+ if time < start or bus > 127:
+ continue
+ elif time > end:
+ break
+ if row[1].startswith('0x'):
+ message_id = row[1][2:] # remove leading '0x'
+ else:
+ message_id = hex(int(row[1]))[2:] # old message IDs are in decimal
+
+ if row[3].startswith('0x'):
+ data = row[3][2:] # remove leading '0x'
+ else:
+ data = row[3]
+ new_message = False
+ if message_id not in self.messages:
+ self.messages[message_id] = Message(message_id)
+ new_message = True
+ message = self.messages[message_id]
+ bytes = bytearray.fromhex(data)
+ for i in xrange(len(bytes)):
+ ones = int(bytes[i])
+ message.ones[i] = ones if new_message else message.ones[i] & ones
+ # Inverts the data and masks it to a byte to get the zeros as ones.
+ zeros = (~int(bytes[i])) & 0xff
+ message.zeros[i] = zeros if new_message else message.zeros[i] & zeros
+
+def PrintUnique(log_file, low_range, high_range):
+ # find messages with bits that are always low
+ start, end = map(float, low_range.split('-'))
+ low = Info()
+ low.load(log_file, start, end)
+ # find messages with bits that are always high
+ start, end = map(float, high_range.split('-'))
+ high = Info()
+ high.load(log_file, start, end)
+ # print messages that go from low to high
+ found = False
+ for message_id in high.messages:
+ if message_id in low.messages:
+ high.messages[message_id].printBitDiff(low.messages[message_id])
+ found = True
+ if not found: print 'No messages that transition from always low to always high found!'
+
+if __name__ == "__main__":
+ if len(sys.argv) < 4:
+ print 'Usage:\n%s log.csv - -' % sys.argv[0]
+ sys.exit(0)
+ PrintUnique(sys.argv[1], sys.argv[2], sys.argv[3])
diff --git a/panda/examples/isotp.py b/panda/examples/isotp.py
deleted file mode 100644
index fd300da751..0000000000
--- a/panda/examples/isotp.py
+++ /dev/null
@@ -1,85 +0,0 @@
-DEBUG = False
-
-def msg(x):
- if DEBUG:
- print "S:",x.encode("hex")
- if len(x) <= 7:
- ret = chr(len(x)) + x
- else:
- assert False
- return ret.ljust(8, "\x00")
-
-kmsgs = []
-def recv(panda, cnt, addr, nbus):
- global kmsgs
- ret = []
-
- while len(ret) < cnt:
- kmsgs += panda.can_recv()
- nmsgs = []
- for ids, ts, dat, bus in kmsgs:
- if ids == addr and bus == nbus and len(ret) < cnt:
- ret.append(dat)
- else:
- # leave around
- nmsgs.append((ids, ts, dat, bus))
- kmsgs = nmsgs[-256:]
- return map(str, ret)
-
-def isotp_send(panda, x, addr, bus=0, recvaddr=None):
- if recvaddr is None:
- recvaddr = addr+8
-
- if len(x) <= 7:
- panda.can_send(addr, msg(x), bus)
- else:
- ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6]
- x = x[6:]
- idx = 1
- sends = []
- while len(x) > 0:
- sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00")))
- x = x[7:]
- idx += 1
-
- # actually send
- panda.can_send(addr, ss, bus)
- rr = recv(panda, 1, recvaddr, bus)[0]
- panda.can_send_many([(addr, None, s, 0) for s in sends])
-
-def isotp_recv(panda, addr, bus=0, sendaddr=None):
- msg = recv(panda, 1, addr, bus)[0]
-
- if sendaddr is None:
- sendaddr = addr-8
-
-
- if ord(msg[0])&0xf0 == 0x10:
- # first
- tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1])
- dat = msg[2:]
-
- # 0 block size?
- CONTINUE = "\x30" + "\x00"*7
-
- panda.can_send(sendaddr, CONTINUE, bus)
-
- idx = 1
- for mm in recv(panda, (tlen-len(dat) + 7)/8, addr, bus):
- assert ord(mm[0]) == (0x20 | idx)
- dat += mm[1:]
- idx += 1
- elif ord(msg[0])&0xf0 == 0x00:
- # single
- tlen = ord(msg[0]) & 0xf
- dat = msg[1:]
- else:
- assert False
-
- dat = dat[0:tlen]
-
- if DEBUG:
- print "R:",dat.encode("hex")
-
- return dat
-
diff --git a/panda/python/__init__.py b/panda/python/__init__.py
index 011263fff9..6432f0262f 100644
--- a/panda/python/__init__.py
+++ b/panda/python/__init__.py
@@ -13,8 +13,9 @@ from esptool import ESPROM, CesantaFlasher
from flash_release import flash_release
from update import ensure_st_up_to_date
from serial import PandaSerial
+from isotp import isotp_send, isotp_recv
-__version__ = '0.0.6'
+__version__ = '0.0.7'
BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")
@@ -104,6 +105,7 @@ class Panda(object):
SAFETY_NOOUTPUT = 0
SAFETY_HONDA = 1
SAFETY_TOYOTA = 2
+ SAFETY_HONDA_BOSCH = 4
SAFETY_TOYOTA_NOLIMITS = 0x1336
SAFETY_ALLOUTPUT = 0x1337
SAFETY_ELM327 = 0xE327
@@ -181,27 +183,58 @@ class Panda(object):
except Exception:
pass
if not enter_bootloader:
- self.close()
- time.sleep(1.0)
- success = False
- # wait up to 15 seconds
- for i in range(0, 15):
+ self.reconnect()
+
+ def reconnect(self):
+ self.close()
+ time.sleep(1.0)
+ success = False
+ # wait up to 15 seconds
+ for i in range(0, 15):
+ try:
+ self.connect()
+ success = True
+ break
+ except Exception:
+ print("reconnecting is taking %d seconds..." % (i+1))
try:
- self.connect()
- success = True
- break
+ dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial))
+ dfu.recover()
except Exception:
- print("reconnecting is taking %d seconds..." % (i+1))
- try:
- dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial))
- dfu.recover()
- except Exception:
- pass
- time.sleep(1.0)
- if not success:
- raise Exception("reset failed")
+ pass
+ time.sleep(1.0)
+ if not success:
+ raise Exception("reconnect failed")
+
+ @staticmethod
+ def flash_static(handle, code):
+ # confirm flasher is present
+ fr = handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc)
+ assert fr[4:8] == "\xde\xad\xd0\x0d"
+
+ # unlock flash
+ print("flash: unlocking")
+ handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'')
- def flash(self, fn=None, code=None):
+ # erase sectors 1 and 2
+ print("flash: erasing")
+ handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'')
+ handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'')
+
+ # flash over EP2
+ STEP = 0x10
+ print("flash: flashing")
+ for i in range(0, len(code), STEP):
+ handle.bulkWrite(2, code[i:i+STEP])
+
+ # reset
+ print("flash: resetting")
+ try:
+ handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'')
+ except Exception:
+ pass
+
+ def flash(self, fn=None, code=None, reconnect=True):
if not self.bootstub:
self.reset(enter_bootstub=True)
assert(self.bootstub)
@@ -224,28 +257,12 @@ class Panda(object):
# get version
print("flash: version is "+self.get_version())
- # confirm flasher is present
- fr = self._handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc)
- assert fr[4:8] == "\xde\xad\xd0\x0d"
-
- # unlock flash
- print("flash: unlocking")
- self._handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'')
-
- # erase sectors 1 and 2
- print("flash: erasing")
- self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'')
- self._handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'')
-
- # flash over EP2
- STEP = 0x10
- print("flash: flashing")
- for i in range(0, len(code), STEP):
- self._handle.bulkWrite(2, code[i:i+STEP])
+ # do flash
+ Panda.flash_static(self._handle, code)
- # reset
- print("flash: resetting")
- self.reset()
+ # reconnect
+ if reconnect:
+ self.reconnect()
def recover(self):
self.reset(enter_bootloader=True)
@@ -315,6 +332,10 @@ class Panda(object):
def get_version(self):
return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40)
+ def is_grey(self):
+ ret = self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40)
+ return ret == "\x01"
+
def get_serial(self):
dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20)
hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4]
@@ -420,6 +441,14 @@ class Panda(object):
"""
self._handle.controlWrite(Panda.REQUEST_OUT, 0xf1, bus, 0, b'')
+ # ******************* isotp *******************
+
+ def isotp_send(self, addr, dat, bus, recvaddr=None, subaddr=None):
+ return isotp_send(self, dat, addr, bus, recvaddr, subaddr)
+
+ def isotp_recv(self, addr, bus=0, sendaddr=None, subaddr=None):
+ return isotp_recv(self, addr, bus, sendaddr, subaddr)
+
# ******************* serial *******************
def serial_read(self, port_number):
@@ -451,7 +480,11 @@ class Panda(object):
# pulse low for wakeup
def kline_wakeup(self):
+ if DEBUG:
+ print("kline wakeup...")
self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 0, 0, b'')
+ if DEBUG:
+ print("kline wakeup done")
def kline_drain(self, bus=2):
# drain buffer
@@ -460,19 +493,25 @@ class Panda(object):
ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40)
if len(ret) == 0:
break
+ elif DEBUG:
+ print("kline drain: "+str(ret).encode("hex"))
bret += ret
return bytes(bret)
def kline_ll_recv(self, cnt, bus=2):
echo = bytearray()
while len(echo) != cnt:
- echo += self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))
- return echo
+ ret = str(self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo)))
+ if DEBUG and len(ret) > 0:
+ print("kline recv: "+ret.encode("hex"))
+ echo += ret
+ return str(echo)
def kline_send(self, x, bus=2, checksum=True):
def get_checksum(dat):
result = 0
result += sum(map(ord, dat)) if isinstance(b'dat', str) else sum(dat)
+ result = -result
return struct.pack("B", result % 0x100)
self.kline_drain(bus=bus)
@@ -480,6 +519,8 @@ class Panda(object):
x += get_checksum(x)
for i in range(0, len(x), 0xf):
ts = x[i:i+0xf]
+ if DEBUG:
+ print("kline send: "+ts.encode("hex"))
self._handle.bulkWrite(2, chr(bus).encode()+ts)
echo = self.kline_ll_recv(len(ts), bus=bus)
if echo != ts:
diff --git a/panda/python/isotp.py b/panda/python/isotp.py
new file mode 100644
index 0000000000..74720b75d9
--- /dev/null
+++ b/panda/python/isotp.py
@@ -0,0 +1,135 @@
+DEBUG = False
+
+def msg(x):
+ if DEBUG:
+ print "S:",x.encode("hex")
+ if len(x) <= 7:
+ ret = chr(len(x)) + x
+ else:
+ assert False
+ return ret.ljust(8, "\x00")
+
+kmsgs = []
+def recv(panda, cnt, addr, nbus):
+ global kmsgs
+ ret = []
+
+ while len(ret) < cnt:
+ kmsgs += panda.can_recv()
+ nmsgs = []
+ for ids, ts, dat, bus in kmsgs:
+ if ids == addr and bus == nbus and len(ret) < cnt:
+ ret.append(dat)
+ else:
+ # leave around
+ nmsgs.append((ids, ts, dat, bus))
+ kmsgs = nmsgs[-256:]
+ return map(str, ret)
+
+def isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr):
+ msg = recv(panda, 1, addr, bus)[0]
+
+ # TODO: handle other subaddr also communicating
+ assert ord(msg[0]) == subaddr
+
+ if ord(msg[1])&0xf0 == 0x10:
+ # first
+ tlen = ((ord(msg[1]) & 0xf) << 8) | ord(msg[2])
+ dat = msg[3:]
+
+ # 0 block size?
+ CONTINUE = chr(subaddr) + "\x30" + "\x00"*6
+ panda.can_send(sendaddr, CONTINUE, bus)
+
+ idx = 1
+ for mm in recv(panda, (tlen-len(dat) + 5)/6, addr, bus):
+ assert ord(mm[0]) == subaddr
+ assert ord(mm[1]) == (0x20 | idx)
+ dat += mm[2:]
+ idx += 1
+ elif ord(msg[1])&0xf0 == 0x00:
+ # single
+ tlen = ord(msg[1]) & 0xf
+ dat = msg[2:]
+ else:
+ print msg.encode("hex")
+ assert False
+
+ return dat[0:tlen]
+
+# **** import below this line ****
+
+def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None):
+ if recvaddr is None:
+ recvaddr = addr+8
+
+ if len(x) <= 7 and subaddr is None:
+ panda.can_send(addr, msg(x), bus)
+ elif len(x) <= 6 and subaddr is not None:
+ panda.can_send(addr, chr(subaddr)+msg(x)[0:7], bus)
+ else:
+ if subaddr:
+ ss = chr(subaddr) + chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:5]
+ x = x[5:]
+ else:
+ ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6]
+ x = x[6:]
+ idx = 1
+ sends = []
+ while len(x) > 0:
+ if subaddr:
+ sends.append(((chr(subaddr) + chr(0x20 + (idx&0xF)) + x[0:6]).ljust(8, "\x00")))
+ x = x[6:]
+ else:
+ sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00")))
+ x = x[7:]
+ idx += 1
+
+ # actually send
+ panda.can_send(addr, ss, bus)
+ rr = recv(panda, 1, recvaddr, bus)[0]
+ if rr.find("\x30\x01") != -1:
+ for s in sends[:-1]:
+ panda.can_send(addr, s, 0)
+ rr = recv(panda, 1, recvaddr, bus)[0]
+ panda.can_send(addr, sends[-1], 0)
+ else:
+ panda.can_send_many([(addr, None, s, 0) for s in sends])
+
+def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None):
+ if sendaddr is None:
+ sendaddr = addr-8
+
+ if subaddr is not None:
+ dat = isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr)
+ else:
+ msg = recv(panda, 1, addr, bus)[0]
+
+ if ord(msg[0])&0xf0 == 0x10:
+ # first
+ tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1])
+ dat = msg[2:]
+
+ # 0 block size?
+ CONTINUE = "\x30" + "\x00"*7
+
+ panda.can_send(sendaddr, CONTINUE, bus)
+
+ idx = 1
+ for mm in recv(panda, (tlen-len(dat) + 6)/7, addr, bus):
+ assert ord(mm[0]) == (0x20 | idx)
+ dat += mm[1:]
+ idx += 1
+ elif ord(msg[0])&0xf0 == 0x00:
+ # single
+ tlen = ord(msg[0]) & 0xf
+ dat = msg[1:]
+ else:
+ assert False
+ dat = dat[0:tlen]
+
+ if DEBUG:
+ print "R:",dat.encode("hex")
+
+ return dat
+
diff --git a/panda/tests/automated/helpers.py b/panda/tests/automated/helpers.py
index daa676490d..a55f77c655 100644
--- a/panda/tests/automated/helpers.py
+++ b/panda/tests/automated/helpers.py
@@ -3,6 +3,7 @@ import sys
import time
import random
import subprocess
+import requests
from panda import Panda
from nose.tools import timed, assert_equal, assert_less, assert_greater
@@ -25,27 +26,46 @@ def connect_wifi():
assert(dongle_id.isalnum())
_connect_wifi(dongle_id, pw)
-def _connect_wifi(dongle_id, pw):
+def _connect_wifi(dongle_id, pw, insecure_okay=False):
ssid = str("panda-" + dongle_id)
print("WIFI: connecting to %s" % ssid)
- if sys.platform == "darwin":
- os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw))
- else:
- cnt = 0
- MAX_TRIES = 10
- while cnt < MAX_TRIES:
- print "WIFI: scanning %d" % cnt
- os.system("nmcli device wifi rescan")
- wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n"))
- if len(wifi_scan) != 0:
+ while 1:
+ if sys.platform == "darwin":
+ os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw))
+ else:
+ cnt = 0
+ MAX_TRIES = 10
+ while cnt < MAX_TRIES:
+ print "WIFI: scanning %d" % cnt
+ if os.system("ifconfig | grep wlp3s0") == 0:
+ os.system("sudo iwlist wlp3s0 scanning > /dev/null")
+ os.system("nmcli device wifi rescan")
+ wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n"))
+ if len(wifi_scan) != 0:
+ break
+ time.sleep(0.1)
+ # MAX_TRIES tries, ~10 seconds max
+ cnt += 1
+ assert cnt < MAX_TRIES
+ if "-pair" in wifi_scan[0]:
+ os.system("nmcli d wifi connect %s-pair" % (ssid))
+ if insecure_okay:
+ break
+ # fetch webpage
+ print "connecting to insecure network to secure"
+ r = requests.get("http://192.168.0.10/")
+ assert r.status_code==200
+
+ print "securing"
+ try:
+ r = requests.get("http://192.168.0.10/secure", timeout=0.01)
+ except requests.exceptions.Timeout:
+ pass
+ else:
+ os.system("nmcli d wifi connect %s password %s" % (ssid, pw))
break
- time.sleep(0.1)
- # MAX_TRIES tries, ~10 seconds max
- cnt += 1
- assert cnt < MAX_TRIES
- os.system("nmcli d wifi connect %s password %s" % (ssid, pw))
# TODO: confirm that it's connected to the right panda
diff --git a/panda/tests/can_printer.py b/panda/tests/can_printer.py
index a74a548109..e863889c16 100755
--- a/panda/tests/can_printer.py
+++ b/panda/tests/can_printer.py
@@ -4,6 +4,7 @@ import os
import sys
import time
from collections import defaultdict
+import binascii
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), ".."))
from panda import Panda
@@ -14,6 +15,7 @@ def sec_since_boot():
def can_printer():
p = Panda()
+ p.set_safety_mode(0x1337)
start = sec_since_boot()
lp = sec_since_boot()
@@ -28,7 +30,7 @@ def can_printer():
if sec_since_boot() - lp > 0.1:
dd = chr(27) + "[2J"
dd += "%5.2f\n" % (sec_since_boot() - start)
- for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))):
+ for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))):
dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v)
print(dd)
lp = sec_since_boot()
diff --git a/panda/tests/automated/elm_wifi.py b/panda/tests/elm_wifi.py
similarity index 100%
rename from panda/tests/automated/elm_wifi.py
rename to panda/tests/elm_wifi.py
diff --git a/panda/tests/pedal/enter_canloader.py b/panda/tests/pedal/enter_canloader.py
new file mode 100755
index 0000000000..c6f06ca354
--- /dev/null
+++ b/panda/tests/pedal/enter_canloader.py
@@ -0,0 +1,76 @@
+#!/usr/bin/env python
+import sys
+import time
+import struct
+import argparse
+import signal
+from panda import Panda
+
+class CanHandle(object):
+ def __init__(self, p):
+ self.p = p
+
+ def transact(self, dat):
+ #print "W:",dat.encode("hex")
+ self.p.isotp_send(1, dat, 0, recvaddr=2)
+
+ def _handle_timeout(signum, frame):
+ # will happen on reset
+ raise Exception("timeout")
+
+ signal.signal(signal.SIGALRM, _handle_timeout)
+ signal.alarm(1)
+ try:
+ ret = self.p.isotp_recv(2, 0, sendaddr=1)
+ finally:
+ signal.alarm(0)
+
+ #print "R:",ret.encode("hex")
+ return ret
+
+ def controlWrite(self, request_type, request, value, index, data, timeout=0):
+ # ignore data in reply, panda doesn't use it
+ return self.controlRead(request_type, request, value, index, 0, timeout)
+
+ def controlRead(self, request_type, request, value, index, length, timeout=0):
+ dat = struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length)
+ return self.transact(dat)
+
+ def bulkWrite(self, endpoint, data, timeout=0):
+ if len(data) > 0x10:
+ raise ValueError("Data must not be longer than 0x10")
+ dat = struct.pack("HH", endpoint, len(data))+data
+ return self.transact(dat)
+
+ def bulkRead(self, endpoint, length, timeout=0):
+ dat = struct.pack("HH", endpoint, 0)
+ return self.transact(dat)
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description='Flash pedal over can')
+ parser.add_argument('--recover', action='store_true')
+ parser.add_argument("fn", type=str, nargs='?', help="flash file")
+ args = parser.parse_args()
+
+ p = Panda()
+ p.set_safety_mode(0x1337)
+
+ while 1:
+ if len(p.can_recv()) == 0:
+ break
+
+ if args.recover:
+ p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x02", 0)
+ exit(0)
+ else:
+ p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0)
+
+ if args.fn:
+ time.sleep(0.1)
+ print "flashing", args.fn
+ code = open(args.fn).read()
+ Panda.flash_static(CanHandle(p), code)
+
+ print "can flash done"
+
+
diff --git a/panda/tests/read_winusb_descriptors.py b/panda/tests/read_winusb_descriptors.py
new file mode 100644
index 0000000000..e38df8d1ca
--- /dev/null
+++ b/panda/tests/read_winusb_descriptors.py
@@ -0,0 +1,29 @@
+#!/usr/bin/env python
+from panda import Panda
+from hexdump import hexdump
+
+DEBUG = False
+
+if __name__ == "__main__":
+ p = Panda()
+
+ len = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1)
+ print 'Microsoft OS String Descriptor'
+ dat = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, len[0])
+ if DEBUG: print 'LEN: {}'.format(hex(len[0]))
+ hexdump("".join(map(chr, dat)))
+
+ ms_vendor_code = dat[16]
+ if DEBUG: print 'MS_VENDOR_CODE: {}'.format(hex(len[0]))
+
+ print '\nMicrosoft Compatible ID Feature Descriptor'
+ len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, 1)
+ if DEBUG: print 'LEN: {}'.format(hex(len[0]))
+ dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, len[0])
+ hexdump("".join(map(chr, dat)))
+
+ print '\nMicrosoft Extended Properties Feature Descriptor'
+ len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1)
+ if DEBUG: print 'LEN: {}'.format(hex(len[0]))
+ dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, len[0])
+ hexdump("".join(map(chr, dat)))
diff --git a/panda/tests/standalone_test.py b/panda/tests/standalone_test.py
index 76df0235bc..ca6ea49f10 100755
--- a/panda/tests/standalone_test.py
+++ b/panda/tests/standalone_test.py
@@ -21,7 +21,7 @@ if __name__ == "__main__":
t2 = time.time()
print("100 requests took %.2f ms" % ((t2-t1)*1000))
- p.set_controls_allowed(True)
+ p.set_safety_mode(Panda.SAFETY_ALLOUTPUT)
a = 0
while True:
diff --git a/panda/tests/tucan_loopback.py b/panda/tests/tucan_loopback.py
new file mode 100755
index 0000000000..a3f3e6e2d7
--- /dev/null
+++ b/panda/tests/tucan_loopback.py
@@ -0,0 +1,125 @@
+#!/usr/bin/env python
+from __future__ import print_function
+import os
+import sys
+import time
+import random
+import argparse
+
+from hexdump import hexdump
+from itertools import permutations
+
+sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), ".."))
+from panda import Panda
+
+def get_test_string():
+ return b"test"+os.urandom(10)
+
+def run_test(sleep_duration):
+ pandas = Panda.list()
+ print(pandas)
+
+ if len(pandas) == 0:
+ print("NO PANDAS")
+ assert False
+
+ if len(pandas) == 1:
+ # if we only have one on USB, assume the other is on wifi
+ pandas.append("WIFI")
+ run_test_w_pandas(pandas, sleep_duration)
+
+def run_test_w_pandas(pandas, sleep_duration):
+ h = list(map(lambda x: Panda(x), pandas))
+ print("H", h)
+
+ for hh in h:
+ hh.set_controls_allowed(True)
+
+ # test both directions
+ for ho in permutations(range(len(h)), r=2):
+ print("***************** TESTING", ho)
+
+ panda0, panda1 = h[ho[0]], h[ho[1]]
+
+ if(panda0._serial == "WIFI"):
+ print(" *** Can not send can data over wifi panda. Skipping! ***")
+ continue
+
+ # **** test health packet ****
+ print("health", ho[0], h[ho[0]].health())
+
+ # **** test K/L line loopback ****
+ for bus in [2,3]:
+ # flush the output
+ h[ho[1]].kline_drain(bus=bus)
+
+ # send the characters
+ st = get_test_string()
+ st = b"\xaa"+chr(len(st)+3).encode()+st
+ h[ho[0]].kline_send(st, bus=bus, checksum=False)
+
+ # check for receive
+ ret = h[ho[1]].kline_drain(bus=bus)
+
+ print("ST Data:")
+ hexdump(st)
+ print("RET Data:")
+ hexdump(ret)
+ assert st == ret
+ print("K/L pass", bus, ho, "\n")
+ time.sleep(sleep_duration)
+
+ # **** test can line loopback ****
+# for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]:
+for bus, gmlan in [(0, None), (1, None)]:
+ print("\ntest can", bus)
+ # flush
+ cans_echo = panda0.can_recv()
+ cans_loop = panda1.can_recv()
+
+ if gmlan is not None:
+ panda0.set_gmlan(gmlan, bus)
+ panda1.set_gmlan(gmlan, bus)
+
+ # send the characters
+ # pick addresses high enough to not conflict with honda code
+ at = random.randint(1024, 2000)
+ st = get_test_string()[0:8]
+ panda0.can_send(at, st, bus)
+ time.sleep(0.1)
+
+ # check for receive
+ cans_echo = panda0.can_recv()
+ cans_loop = panda1.can_recv()
+
+ print("Bus", bus, "echo", cans_echo, "loop", cans_loop)
+
+ assert len(cans_echo) == 1
+ assert len(cans_loop) == 1
+
+ assert cans_echo[0][0] == at
+ assert cans_loop[0][0] == at
+
+ assert cans_echo[0][2] == st
+ assert cans_loop[0][2] == st
+
+ assert cans_echo[0][3] == 0x80 | bus
+ if cans_loop[0][3] != bus:
+ print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3]))
+ assert cans_loop[0][3] == bus
+
+ print("CAN pass", bus, ho)
+ time.sleep(sleep_duration)
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser()
+ parser.add_argument("-n", type=int, help="Number of test iterations to run")
+ parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0)
+ args = parser.parse_args()
+
+ if args.n is None:
+ while True:
+ run_test(sleep_duration=args.sleep)
+ else:
+ for i in range(args.n):
+ run_test(sleep_duration=args.sleep)
diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt
index 2779fab8e7..a005faace7 100644
--- a/requirements_openpilot.txt
+++ b/requirements_openpilot.txt
@@ -14,4 +14,5 @@ enum34==1.1.1
sympy==1.1.1
filterpy==1.0.0
smbus2==0.2.0
+pyflakes==1.5.0
-e git+https://github.com/commaai/le_python.git#egg=Logentries
diff --git a/selfdrive/assets/OpenSans-Bold.ttf b/selfdrive/assets/OpenSans-Bold.ttf
new file mode 100644
index 0000000000..7b52945603
Binary files /dev/null and b/selfdrive/assets/OpenSans-Bold.ttf differ
diff --git a/selfdrive/assets/img_chffr_wheel.png b/selfdrive/assets/img_chffr_wheel.png
new file mode 100644
index 0000000000..3f09a35a79
Binary files /dev/null and b/selfdrive/assets/img_chffr_wheel.png differ
diff --git a/selfdrive/assets/img_trafficLight_green.png b/selfdrive/assets/img_trafficLight_green.png
new file mode 100644
index 0000000000..b2e07dab03
Binary files /dev/null and b/selfdrive/assets/img_trafficLight_green.png differ
diff --git a/selfdrive/assets/img_trafficLight_none.png b/selfdrive/assets/img_trafficLight_none.png
new file mode 100644
index 0000000000..01deb5a009
Binary files /dev/null and b/selfdrive/assets/img_trafficLight_none.png differ
diff --git a/selfdrive/assets/img_trafficLight_red.png b/selfdrive/assets/img_trafficLight_red.png
new file mode 100644
index 0000000000..4c440250e4
Binary files /dev/null and b/selfdrive/assets/img_trafficLight_red.png differ
diff --git a/selfdrive/assets/img_trafficLight_yellow.png b/selfdrive/assets/img_trafficLight_yellow.png
new file mode 100644
index 0000000000..8dd5bd42c3
Binary files /dev/null and b/selfdrive/assets/img_trafficLight_yellow.png differ
diff --git a/selfdrive/assets/img_trafficSign_stop.png b/selfdrive/assets/img_trafficSign_stop.png
new file mode 100644
index 0000000000..9261c47472
Binary files /dev/null and b/selfdrive/assets/img_trafficSign_stop.png differ
diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc
index b472857300..d52c4f34fc 100644
--- a/selfdrive/boardd/boardd.cc
+++ b/selfdrive/boardd/boardd.cc
@@ -35,6 +35,8 @@
#define SAFETY_HONDA 1
#define SAFETY_TOYOTA 2
#define SAFETY_ELM327 0xE327
+#define SAFETY_GM 3
+#define SAFETY_HONDA_BOSCH 4
namespace {
@@ -95,6 +97,12 @@ void *safety_setter_thread(void *s) {
case (int)cereal::CarParams::SafetyModels::ELM327:
safety_setting = SAFETY_ELM327;
break;
+ case (int)cereal::CarParams::SafetyModels::GM:
+ safety_setting = SAFETY_GM;
+ break;
+ case (int)cereal::CarParams::SafetyModels::HONDA_BOSCH:
+ safety_setting = SAFETY_HONDA_BOSCH;
+ break;
default:
LOGE("unknown safety model: %d", safety_model);
}
@@ -517,10 +525,25 @@ void pigeon_init() {
pigeon_send("\xB5\x62\x06\x1E\x00\x00\x24\x72");
pigeon_send("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51");
pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70");
+ pigeon_send("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C");
LOGW("grey panda is ready to fly");
}
+static void pigeon_publish_raw(void *publisher, unsigned char *dat, int alen) {
+ // create message
+ capnp::MallocMessageBuilder msg;
+ cereal::Event::Builder event = msg.initRoot();
+ event.setLogMonoTime(nanos_since_boot());
+ auto ublox_raw = event.initUbloxRaw(alen);
+ memcpy(ublox_raw.begin(), dat, alen);
+
+ // send to ubloxRaw
+ auto words = capnp::messageToFlatArray(msg);
+ auto bytes = words.asBytes();
+ zmq_send(publisher, bytes.begin(), bytes.size(), 0);
+}
+
void *pigeon_thread(void *crap) {
// ubloxRaw = 8042
@@ -535,22 +558,6 @@ void *pigeon_thread(void *crap) {
if (pigeon_needs_init) {
pigeon_needs_init = false;
pigeon_init();
- } else {
- // send periodic messages
- if (cnt%3000 == 0) {
- for (unsigned char sv = 1; sv < 33; ++sv){
- const unsigned char buffer[5] = {0x0B, 0x31, 0x01, 0x00, sv};
- unsigned char CK_A = 0;
- unsigned char CK_B = 0;
- for(int i=0;i<5;i++) {
- CK_A = CK_A + buffer[i];
- CK_B = CK_B + CK_A;
- }
- const unsigned char msg[9] = {0xB5, 0x62, 0x0B, 0x31, 0x01, 0x00, sv, CK_A, CK_B};
- _pigeon_send((const char *)msg, 9);
- }
- pigeon_send("\xB5\x62\x0b\x02\x00\x00\x0d\x32");
- }
}
int alen = 0;
while (alen < 0xfc0) {
@@ -564,17 +571,7 @@ void *pigeon_thread(void *crap) {
alen += len;
}
if (alen > 0) {
- // create message
- capnp::MallocMessageBuilder msg;
- cereal::Event::Builder event = msg.initRoot();
- event.setLogMonoTime(nanos_since_boot());
- auto ublox_raw = event.initUbloxRaw(alen);
- memcpy(ublox_raw.begin(), dat, alen);
-
- // send to ubloxRaw
- auto words = capnp::messageToFlatArray(msg);
- auto bytes = words.asBytes();
- zmq_send(publisher, bytes.begin(), bytes.size(), 0);
+ pigeon_publish_raw(publisher, dat, alen);
}
// 10ms
diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py
index 0b428d04ee..243e539511 100755
--- a/selfdrive/boardd/boardd.py
+++ b/selfdrive/boardd/boardd.py
@@ -101,7 +101,7 @@ def can_init():
if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc:
handle = device.open()
handle.claimInterface(0)
- handle.controlWrite(0x40, 0xdc, SAFETY_HONDA, 0, b'')
+ handle.controlWrite(0x40, 0xdc, SAFETY_ALLOUTPUT, 0, b'')
if handle is None:
print "CAN NOT FOUND"
diff --git a/selfdrive/can/libdbc_py.py b/selfdrive/can/libdbc_py.py
index 7495c88adc..3c5d440f3b 100644
--- a/selfdrive/can/libdbc_py.py
+++ b/selfdrive/can/libdbc_py.py
@@ -1,12 +1,11 @@
import os
-import sys
import subprocess
from cffi import FFI
can_dir = os.path.dirname(os.path.abspath(__file__))
libdbc_fn = os.path.join(can_dir, "libdbc.so")
-subprocess.check_call(["make"], stdout=sys.stderr, cwd=can_dir)
+subprocess.check_call(["make"], cwd=can_dir)
ffi = FFI()
ffi.cdef("""
@@ -67,7 +66,8 @@ typedef struct {
void* can_init(int bus, const char* dbc_name,
size_t num_message_options, const MessageParseOptions* message_options,
- size_t num_signal_options, const SignalParseOptions* signal_options, bool sendcan);
+ size_t num_signal_options, const SignalParseOptions* signal_options, bool sendcan,
+ const char* tcp_addr);
void can_update(void* can, uint64_t sec, bool wait);
diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py
index 5ea6e3449e..705fe709e4 100644
--- a/selfdrive/can/packer.py
+++ b/selfdrive/can/packer.py
@@ -3,6 +3,7 @@ import numbers
from selfdrive.can.libdbc_py import libdbc, ffi
+
class CANPacker(object):
def __init__(self, dbc_name):
self.packer = libdbc.canpack_init(dbc_name)
@@ -24,6 +25,9 @@ class CANPacker(object):
# values: [(signal_name, signal_value)]
values_thing = []
+ if isinstance(values, dict):
+ values = values.items()
+
for name, value in values:
if name not in self.sig_names:
self.sig_names[name] = ffi.new("char[]", name)
@@ -42,7 +46,9 @@ class CANPacker(object):
size = self.address_to_size[addr]
else:
addr, size = self.name_to_address_and_size[addr]
- r = struct.pack(">Q", self.pack(addr, values, counter))
+
+ val = self.pack(addr, values, counter)
+ r = struct.pack(">Q", val)
return addr, r[:size]
def make_can_msg(self, addr, bus, values, counter=-1):
diff --git a/selfdrive/can/parser.cc b/selfdrive/can/parser.cc
index a32844fea4..52d7ceba7b 100644
--- a/selfdrive/can/parser.cc
+++ b/selfdrive/can/parser.cc
@@ -142,18 +142,23 @@ class CANParser {
CANParser(int abus, const std::string& dbc_name,
const std::vector &options,
const std::vector &sigoptions,
- bool sendcan)
+ bool sendcan, const std::string& tcp_addr)
: bus(abus) {
// connect to can on 8006
context = zmq_ctx_new();
subscriber = zmq_socket(context, ZMQ_SUB);
zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0);
+ std::string tcp_addr_str;
+
if (sendcan) {
- zmq_connect(subscriber, "tcp://127.0.0.1:8017");
+ tcp_addr_str = "tcp://" + tcp_addr + ":8017";
} else {
- zmq_connect(subscriber, "tcp://127.0.0.1:8006");
+ tcp_addr_str = "tcp://" + tcp_addr + ":8006";
}
+ const char *tcp_addr_char = tcp_addr_str.c_str();
+
+ zmq_connect(subscriber, tcp_addr_char);
dbc = dbc_lookup(dbc_name);
assert(dbc);
@@ -331,12 +336,12 @@ extern "C" {
void* can_init(int bus, const char* dbc_name,
size_t num_message_options, const MessageParseOptions* message_options,
size_t num_signal_options, const SignalParseOptions* signal_options,
- bool sendcan) {
+ bool sendcan, const char* tcp_addr) {
CANParser* ret = new CANParser(bus, std::string(dbc_name),
(message_options ? std::vector(message_options, message_options+num_message_options)
: std::vector{}),
(signal_options ? std::vector(signal_options, signal_options+num_signal_options)
- : std::vector{}), sendcan);
+ : std::vector{}), sendcan, std::string(tcp_addr));
return (void*)ret;
}
diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py
index 13603b7881..4806e1a1d5 100644
--- a/selfdrive/can/parser.py
+++ b/selfdrive/can/parser.py
@@ -5,11 +5,12 @@ import numbers
from selfdrive.can.libdbc_py import libdbc, ffi
class CANParser(object):
- def __init__(self, dbc_name, signals, checks=[], bus=0, sendcan=False):
+ def __init__(self, dbc_name, signals, checks=[], bus=0, sendcan=False, tcp_addr="127.0.0.1"):
self.can_valid = True
self.vl = defaultdict(dict)
self.ts = defaultdict(dict)
+ self.dbc_name = dbc_name
self.dbc = libdbc.dbc_lookup(dbc_name)
self.msg_name_to_addres = {}
self.address_to_msg_name = {}
@@ -39,10 +40,6 @@ class CANParser(object):
sig_names = dict((name, ffi.new("char[]", name)) for name, _, _ in signals)
- # Set default values by name
- for sig_name, sig_address, sig_default in signals:
- self.vl[self.address_to_msg_name[sig_address]][sig_name] = sig_default
-
signal_options_c = ffi.new("SignalParseOptions[]", [
{
'address': sig_address,
@@ -60,7 +57,7 @@ class CANParser(object):
} for msg_address, freq in message_options.iteritems()])
self.can = libdbc.can_init(bus, dbc_name, len(message_options_c), message_options_c,
- len(signal_options_c), signal_options_c, sendcan)
+ len(signal_options_c), signal_options_c, sendcan, tcp_addr)
self.p_can_valid = ffi.new("bool*")
diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py
index 8b85dbd4a7..3a17192b25 100644
--- a/selfdrive/car/__init__.py
+++ b/selfdrive/car/__init__.py
@@ -26,7 +26,9 @@ interfaces = {
HONDA.ACURA_ILX: HondaInterface,
HONDA.CRV: HondaInterface,
HONDA.ODYSSEY: HondaInterface,
- HONDA.ACURA_RDX: HondaInterface,
+ HONDA.ACURA_RDX: HondaInterface,
+ HONDA.PILOT: HondaInterface,
+
TOYOTA.PRIUS: ToyotaInterface,
TOYOTA.RAV4: ToyotaInterface,
diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py
index c1b8d7b3db..e1a492bb68 100644
--- a/selfdrive/car/honda/carcontroller.py
+++ b/selfdrive/car/honda/carcontroller.py
@@ -6,6 +6,7 @@ from common.numpy_fast import clip
from . import hondacan
from .values import AH
from common.fingerprints import HONDA as CAR
+from selfdrive.can.packer import CANPacker
def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint):
@@ -52,16 +53,17 @@ def process_hud_alert(hud_alert):
HUDData = namedtuple("HUDData",
- ["pcm_accel", "v_cruise", "X2", "car", "X4", "X5",
- "lanes", "beep", "X8", "chime", "acc_alert"])
+ ["pcm_accel", "v_cruise", "mini_car", "car", "X4",
+ "lanes", "beep", "chime", "fcw", "acc_alert", "steer_required"])
class CarController(object):
- def __init__(self, enable_camera=True):
+ def __init__(self, dbc_name, enable_camera=True):
self.braking = False
self.brake_steady = 0.
self.brake_last = 0.
self.enable_camera = enable_camera
+ self.packer = CANPacker(dbc_name)
def update(self, sendcan, enabled, CS, frame, actuators, \
pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \
@@ -85,48 +87,44 @@ class CarController(object):
self.brake_last = rate_limit(brake, self.brake_last, -2., 1./100)
# vehicle hud display, wait for one update from 10Hz 0x304 msg
- #TODO: use enum!!
if hud_show_lanes:
- hud_lanes = 0x04
+ hud_lanes = 1
else:
- hud_lanes = 0x00
+ hud_lanes = 0
# TODO: factor this out better
if enabled:
if hud_show_car:
- hud_car = 0xe0
+ hud_car = 2
else:
- hud_car = 0xd0
+ hud_car = 1
else:
- hud_car = 0xc0
+ hud_car = 0
#print chime, alert_id, hud_alert
fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert)
- hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 0x01, hud_car,
- 0xc1, 0x41, hud_lanes + steer_required,
- int(snd_beep), 0x48, (snd_chime << 5) + fcw_display, acc_alert)
+ hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 1, hud_car,
+ 0xc1, hud_lanes, int(snd_beep), snd_chime, fcw_display, acc_alert, steer_required)
if not all(isinstance(x, int) and 0 <= x < 256 for x in hud):
print "INVALID HUD", hud
- hud = HUDData(0xc6, 255, 64, 0xc0, 209, 0x41, 0x40, 0, 0x48, 0, 0)
+ hud = HUDData(0xc6, 255, 64, 0xc0, 209, 0x40, 0, 0, 0, 0)
# **** process the car messages ****
# *** compute control surfaces ***
- GAS_MAX = 1004
BRAKE_MAX = 1024/4
- if CS.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY):
+ if CS.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.PILOT):
is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e']
STEER_MAX = 0x1FFF if is_fw_modified else 0x1000
elif CS.CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX):
STEER_MAX = 0x3e8 # CR-V only uses 12-bits and requires a lower value (max value from energee)
else:
STEER_MAX = 0xF00
- GAS_OFFSET = 328
# steer torque is converted back to CAN reference (positive when steering right)
- apply_gas = int(clip(actuators.gas * GAS_MAX, 0, GAS_MAX - 1))
+ apply_gas = clip(actuators.gas, 0., 1.)
apply_brake = int(clip(self.brake_last * BRAKE_MAX, 0, BRAKE_MAX - 1))
apply_steer = int(clip(-actuators.steer * STEER_MAX, -STEER_MAX, STEER_MAX))
@@ -139,24 +137,23 @@ class CarController(object):
# Send steering command.
idx = frame % 4
- can_sends.extend(hondacan.create_steering_control(apply_steer, CS.CP.carFingerprint, idx))
+ can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, CS.CP.carFingerprint, idx))
# Send gas and brake commands.
if (frame % 2) == 0:
idx = (frame / 2) % 4
can_sends.append(
- hondacan.create_brake_command(apply_brake, pcm_override,
- pcm_cancel_cmd, hud.chime, idx))
+ hondacan.create_brake_command(self.packer, apply_brake, pcm_override,
+ pcm_cancel_cmd, hud.chime, hud.fcw, idx))
if not CS.brake_only:
# send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas.
# This prevents unexpected pedal range rescaling
- gas_amount = (apply_gas + GAS_OFFSET) * (apply_gas > 0)
- can_sends.append(hondacan.create_gas_command(gas_amount, idx))
+ can_sends.append(hondacan.create_gas_command(self.packer, apply_gas, idx))
# Send dashboard UI commands.
if (frame % 10) == 0:
idx = (frame/10) % 4
- can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.CP.carFingerprint, idx))
+ can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, idx))
# radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug)
if CS.CP.carFingerprint == CAR.ACURA_ILX:
diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py
index 374dfa3431..7bd126c112 100644
--- a/selfdrive/car/honda/carstate.py
+++ b/selfdrive/car/honda/carstate.py
@@ -8,21 +8,25 @@ import numpy as np
def parse_gear_shifter(can_gear_shifter, car_fingerprint):
- # TODO: Use values from DBC to parse this field
- if can_gear_shifter == 0x1:
- return "park"
- elif can_gear_shifter == 0x2:
- return "reverse"
+ # TODO: Use VAL from DBC to parse this field
if car_fingerprint in (CAR.ACURA_ILX, CAR.ODYSSEY):
- if can_gear_shifter == 0x3:
+ if can_gear_shifter == 0x1:
+ return "park"
+ elif can_gear_shifter == 0x2:
+ return "reverse"
+ elif can_gear_shifter == 0x3:
return "neutral"
elif can_gear_shifter == 0x4:
return "drive"
elif can_gear_shifter == 0xa:
return "sport"
elif car_fingerprint in (CAR.CIVIC, CAR.CRV, CAR.ACURA_RDX):
- if can_gear_shifter == 0x4:
+ if can_gear_shifter == 0x1:
+ return "park"
+ elif can_gear_shifter == 0x2:
+ return "reverse"
+ elif can_gear_shifter == 0x4:
return "neutral"
elif can_gear_shifter == 0x8:
return "drive"
@@ -30,6 +34,16 @@ def parse_gear_shifter(can_gear_shifter, car_fingerprint):
return "sport"
elif can_gear_shifter == 0x20:
return "low"
+ elif car_fingerprint in (CAR.PILOT):
+ # TODO: neutral?
+ if can_gear_shifter == 0x8:
+ return "reverse"
+ elif can_gear_shifter == 0x4:
+ return "park"
+ elif can_gear_shifter == 0x20:
+ return "drive"
+ elif can_gear_shifter == 0x2:
+ return "sport"
return "unknown"
@@ -122,6 +136,10 @@ def get_can_signals(CP):
("EPB_STATE", "EPB_STATUS", 0),
("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)]
checks += [("EPB_STATUS", 50)]
+ elif CP.carFingerprint == CAR.PILOT:
+ dbc_f = 'honda_pilot_touring_2017_can_generated.dbc'
+ signals += [("MAIN_ON", "SCM_BUTTONS", 0),
+ ("CAR_GAS", "GAS_PEDAL_2", 0)]
# add gas interceptor reading if we are using it
if CP.enableGas:
@@ -184,9 +202,9 @@ class CarState(object):
cp.vl["DOORS_STATUS"]['DOOR_OPEN_RL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_RR']])
self.seatbelt = not cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LAMP'] and cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LATCHED']
- # 2 = temporary 4 = temporary, hit a bump 5 (permanent) 6 = temporary 7 (permanent)
+ # 2 = temporary 3= TBD 4 = temporary, hit a bump 5 (permanent) 6 = temporary 7 (permanent)
# TODO: Use values from DBC to parse this field
- self.steer_error = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 2, 4, 6]
+ self.steer_error = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 2, 3, 4, 6]
self.steer_not_allowed = cp.vl["STEER_STATUS"]['STEER_STATUS'] != 0
self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2']
self.esp_disabled = cp.vl["VSA_STATUS"]['ESP_DISABLED']
@@ -200,7 +218,7 @@ class CarState(object):
# blend in transmission speed at low speed, since it has more low speed accuracy
self.v_weight = interp(self.v_wheel, v_weight_bp, v_weight_v)
- speed = (1. - self.v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] + self.v_weight * self.v_wheel
+ speed = (1. - self.v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] * CV.KPH_TO_MS + self.v_weight * self.v_wheel
if abs(speed - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
self.v_ego_x = np.matrix([[speed], [0.0]])
diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py
index 0f9544be1a..55d9dd8cd0 100644
--- a/selfdrive/car/honda/hondacan.py
+++ b/selfdrive/car/honda/hondacan.py
@@ -4,7 +4,6 @@ import common.numpy_fast as np
from selfdrive.config import Conversions as CV
from common.fingerprints import HONDA as CAR
-
# *** Honda specific ***
def can_cksum(mm):
s = 0
@@ -29,56 +28,88 @@ def make_can_msg(addr, dat, idx, alt):
return [addr, 0, dat, alt]
-def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx):
+def create_brake_command(packer, apply_brake, pcm_override, pcm_cancel_cmd, chime, fcw, idx):
"""Creates a CAN message for the Honda DBC BRAKE_COMMAND."""
pump_on = apply_brake > 0
brakelights = apply_brake > 0
brake_rq = apply_brake > 0
-
pcm_fault_cmd = False
- amount = struct.pack("!H", (apply_brake << 6) + pump_on)
- msg = amount + struct.pack("BBB", (pcm_override << 4) |
- (pcm_fault_cmd << 2) |
- (pcm_cancel_cmd << 1) | brake_rq, 0x80,
- brakelights << 7) + chr(chime) + "\x00"
- return make_can_msg(0x1fa, msg, idx, 0)
-
-def create_gas_command(gas_amount, idx):
+ values = {
+ "COMPUTER_BRAKE": apply_brake,
+ "COMPUTER_BRAKE_REQUEST": pump_on,
+ "CRUISE_OVERRIDE": pcm_override,
+ "CRUISE_FAULT_CMD": pcm_fault_cmd,
+ "CRUISE_CANCEL_CMD": pcm_cancel_cmd,
+ "COMPUTER_BRAKE_REQUEST_2": brake_rq,
+ "SET_ME_0X80": 0x80,
+ "BRAKE_LIGHTS": brakelights,
+ "CHIME": chime,
+ "FCW": fcw << 1, # TODO: Why are there two bits for fcw? According to dbc file the first bit should also work
+ }
+ return packer.make_can_msg("BRAKE_COMMAND", 0, values, idx)
+
+
+def create_gas_command(packer, gas_amount, idx):
"""Creates a CAN message for the Honda DBC GAS_COMMAND."""
- msg = struct.pack("!H", gas_amount)
- return make_can_msg(0x200, msg, idx, 0)
+ enable = gas_amount > 0.001
+
+ values = {"ENABLE": enable}
+
+ if enable:
+ values["GAS_COMMAND"] = gas_amount * 255.
+ values["GAS_COMMAND2"] = gas_amount * 255.
+
+ return packer.make_can_msg("GAS_COMMAND", 0, values, idx)
+
-def create_steering_control(apply_steer, car_fingerprint, idx):
+def create_steering_control(packer, apply_steer, car_fingerprint, idx):
"""Creates a CAN message for the Honda DBC STEERING_CONTROL."""
- commands = []
- if car_fingerprint in (CAR.CRV, CAR.ACURA_RDX):
- msg_0x194 = struct.pack("!h", apply_steer << 4) + ("\x80" if apply_steer != 0 else "\x00")
- commands.append(make_can_msg(0x194, msg_0x194, idx, 0))
- else:
- msg_0xe4 = struct.pack("!h", apply_steer) + ("\x80\x00" if apply_steer != 0 else "\x00\x00")
- commands.append(make_can_msg(0xe4, msg_0xe4, idx, 0))
- return commands
+ values = {
+ "STEER_TORQUE": apply_steer,
+ "STEER_TORQUE_REQUEST": apply_steer != 0,
+ }
+ return packer.make_can_msg("STEERING_CONTROL", 0, values, idx)
-def create_ui_commands(pcm_speed, hud, car_fingerprint, idx):
+def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, idx):
"""Creates an iterable of CAN messages for the UIs."""
commands = []
- pcm_speed_real = np.clip(int(round(pcm_speed / 0.002759506)), 0,
- 64000) # conversion factor from dbc file
- msg_0x30c = struct.pack("!HBBBBB", pcm_speed_real, hud.pcm_accel,
- hud.v_cruise, hud.X2, hud.car, hud.X4)
- commands.append(make_can_msg(0x30c, msg_0x30c, idx, 0))
-
- msg_0x33d = chr(hud.X5) + chr(hud.lanes) + chr(hud.beep) + chr(hud.X8)
- commands.append(make_can_msg(0x33d, msg_0x33d, idx, 0))
+
+ acc_hud_values = {
+ 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH,
+ 'PCM_GAS': hud.pcm_accel,
+ 'CRUISE_SPEED': hud.v_cruise,
+ 'ENABLE_MINI_CAR': hud.mini_car,
+ 'HUD_LEAD': hud.car,
+ 'SET_ME_X03': 0x03,
+ 'SET_ME_X03_2': 0x03,
+ 'SET_ME_X01': 0x01,
+ }
+ commands.append(packer.make_can_msg("ACC_HUD", 0, acc_hud_values, idx))
+
+ lkas_hud_values = {
+ 'SET_ME_X41': 0x41,
+ 'SET_ME_X48': 0x48,
+ 'STEERING_REQUIRED': hud.steer_required,
+ 'SOLID_LANES': hud.lanes,
+ 'BEEP': hud.beep,
+ }
+ commands.append(packer.make_can_msg('LKAS_HUD', 0, lkas_hud_values, idx))
+
if car_fingerprint in (CAR.CIVIC, CAR.ODYSSEY):
- msg_0x35e = chr(0) * 7
- commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0))
- msg_0x39f = (chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0))
- commands.append(make_can_msg(0x39f, msg_0x39f, idx, 0))
+ commands.append(packer.make_can_msg('HIGHBEAM_CONTROL', 0, {'HIGHBEAMS_ON': False}, idx))
+
+ radar_hud_values = {
+ 'ACC_ALERTS': hud.acc_alert,
+ 'LEAD_SPEED': 0x1fe, # What are these magic values
+ 'LEAD_STATE': 0x7,
+ 'LEAD_DISTANCE': 0x1e,
+ }
+ commands.append(packer.make_can_msg('RADAR_HUD', 0, radar_hud_values, idx))
return commands
+
def create_radar_commands(v_ego, car_fingerprint, idx):
"""Creates an iterable of CAN messages for the radar system."""
commands = []
@@ -104,6 +135,9 @@ def create_radar_commands(v_ego, car_fingerprint, idx):
elif car_fingerprint == CAR.ACURA_ILX:
msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00"
commands.append(make_can_msg(0x300, msg_0x300, idx, 1))
+ elif car_fingerprint == CAR.PILOT:
+ msg_0x301 = "\x00\x00\x56\x02\x58\x00\x00"
+ commands.append(make_can_msg(0x300, msg_0x300, idx, 1))
commands.append(make_can_msg(0x301, msg_0x301, idx, 1))
return commands
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index a573b3f23a..ac8f8e2cd8 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -97,7 +97,7 @@ class CarInterface(object):
# sending if read only is False
if sendcan is not None:
self.sendcan = sendcan
- self.CC = CarController(CP.enableCamera)
+ self.CC = CarController(self.cp.dbc_name, CP.enableCamera)
if self.CS.CP.carFingerprint == CAR.ACURA_ILX:
self.compute_gb = get_compute_gb_acura()
@@ -106,6 +106,10 @@ class CarInterface(object):
@staticmethod
def calc_accel_override(a_ego, a_target, v_ego, v_target):
+ # limit the pcm accel cmd if:
+ # - v_ego exceeds v_target, or
+ # - a_ego exceeds a_target and v_ego is close to v_target
+
eA = a_ego - a_target
valuesA = [1.0, 0.1]
bpA = [0.3, 1.1]
@@ -114,9 +118,17 @@ class CarInterface(object):
valuesV = [1.0, 0.1]
bpV = [0.0, 0.5]
+ valuesRangeV = [1., 0.]
+ bpRangeV = [-1., 0.]
+
+ # only limit if v_ego is close to v_target
+ speedLimiter = interp(eV, bpV, valuesV)
+ accelLimiter = max(interp(eA, bpA, valuesA), interp(eV, bpRangeV, valuesRangeV))
+
# accelOverride is more or less the max throttle allowed to pcm: usually set to a constant
# unless aTargetMax is very high and then we scale with it; this help in quicker restart
- return float(max(0.714, a_target / A_ACC_MAX)) * min(interp(eA, bpA, valuesA), interp(eV, bpV, valuesV))
+
+ return float(max(0.714, a_target / A_ACC_MAX)) * min(speedLimiter, accelLimiter)
@staticmethod
def get_params(candidate, fingerprint):
@@ -151,6 +163,7 @@ class CarInterface(object):
tireStiffnessFront_civic = 85400
tireStiffnessRear_civic = 90000
+ ret.steerKiBP, ret.steerKpBP = [[0.], [0.]]
if candidate == CAR.CIVIC:
stop_and_go = True
ret.mass = mass_civic
@@ -159,7 +172,7 @@ class CarInterface(object):
ret.steerRatio = 13.0
# Civic at comma has modified steering FW, so different tuning for the Neo in that car
is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e']
- ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24]
+ ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]]
ret.longitudinalKpBP = [0., 5., 35.]
ret.longitudinalKpV = [3.6, 2.4, 1.5]
@@ -173,7 +186,7 @@ class CarInterface(object):
ret.steerRatio = 15.3
# Acura at comma has modified steering FW, so different tuning for the Neo in that car
is_fw_modified = os.getenv("DONGLE_ID") in ['85a6c74d4ad9c310']
- ret.steerKp, ret.steerKi = [0.4, 0.12] if is_fw_modified else [0.8, 0.24]
+ ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]]
ret.longitudinalKpBP = [0., 5., 35.]
ret.longitudinalKpV = [1.2, 0.8, 0.5]
@@ -185,7 +198,7 @@ class CarInterface(object):
ret.wheelbase = 2.62
ret.centerToFront = ret.wheelbase * 0.41
ret.steerRatio = 15.3
- ret.steerKp, ret.steerKi = 0.8, 0.24
+ ret.steerKpV, ret.steerKiV = [[0.8], [0.24]]
ret.longitudinalKpBP = [0., 5., 35.]
ret.longitudinalKpV = [1.2, 0.8, 0.5]
@@ -197,19 +210,31 @@ class CarInterface(object):
ret.wheelbase = 2.68
ret.centerToFront = ret.wheelbase * 0.38
ret.steerRatio = 15.0
- ret.steerKp, ret.steerKi = 0.8, 0.24
+ ret.steerKpV, ret.steerKiV = [[0.8], [0.24]]
ret.longitudinalKpBP = [0., 5., 35.]
ret.longitudinalKpV = [1.2, 0.8, 0.5]
ret.longitudinalKiBP = [0., 35.]
- ret.longitudinalKiV = [0.18, 0.12]
+ ret.longitudinalKiV = [0.18, 0.12]
elif candidate == CAR.ODYSSEY:
stop_and_go = False
ret.mass = 4354./2.205 + std_cargo
ret.wheelbase = 3.00
ret.centerToFront = ret.wheelbase * 0.41
ret.steerRatio = 14.35
- ret.steerKp, ret.steerKi = 0.6, 0.18
+ ret.steerKpV, ret.steerKiV = [[0.6], [0.18]]
+
+ ret.longitudinalKpBP = [0., 5., 35.]
+ ret.longitudinalKpV = [1.2, 0.8, 0.5]
+ ret.longitudinalKiBP = [0., 35.]
+ ret.longitudinalKiV = [0.18, 0.12]
+ elif candidate == CAR.PILOT:
+ stop_and_go = False
+ ret.mass = 4303./2.205 + std_cargo
+ ret.wheelbase = 2.81
+ ret.centerToFront = ret.wheelbase * 0.41
+ ret.steerRatio = 16.0
+ ret.steerKpV, ret.steerKiV = [[0.38], [0.11]]
ret.longitudinalKpBP = [0., 5., 35.]
ret.longitudinalKpV = [1.2, 0.8, 0.5]
@@ -418,10 +443,13 @@ class CarInterface(object):
# it can happen that car cruise disables while comma system is enabled: need to
# keep braking if needed or if the speed is very low
- # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert
if self.CP.enableCruise and not ret.cruiseState.enabled and c.actuators.brake <= 0.:
- events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE]))
- if self.CS.CP.carFingerprint != CAR.CIVIC and ret.vEgo < 0.001:
+ # non loud alert if cruise disbales below 25mph as expected (+ a little margin)
+ if ret.vEgo < self.CP.minEnableSpeed + 2.:
+ events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE]))
+ else:
+ events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE]))
+ if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001:
events.append(create_event('manualRestart', [ET.WARNING]))
cur_time = sec_since_boot()
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index ee5c08884b..35db0c2177 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -26,7 +26,7 @@ class AH:
#[alert_idx, value]
# See dbc files for info on values"
NONE = [0, 0]
- FCW = [1, 0x8]
+ FCW = [1, 1]
STEER = [2, 1]
BRAKE_PRESSED = [3, 10]
GEAR_NOT_D = [4, 6]
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index 3fd19f9467..6aead7ba27 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -1,26 +1,36 @@
-from common.numpy_fast import clip
+from common.numpy_fast import clip, interp, int_rnd
from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car.toyota.toyotacan import make_can_msg, create_video_target,\
create_steer_command, create_ui_command, \
create_ipas_steer_command, create_accel_command, \
create_fcw_command
from selfdrive.car.toyota.values import ECU, STATIC_MSGS
+from selfdrive.can.packer import CANPacker
+# Accel limits
ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value
-ACCEL_MAX = 1500 # 1.5 m/s2
-ACCEL_MIN = -3000 # 3 m/s2
+ACCEL_MAX = 1.5 # 1.5 m/s2
+ACCEL_MIN = -3.0 # 3 m/s2
ACCEL_SCALE = max(ACCEL_MAX, -ACCEL_MIN)
+# Steer torque limits
STEER_MAX = 1500
-STEER_DELTA_UP = 10 # 1.5s time to peak torque
-STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
-STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor
+STEER_DELTA_UP = 10 # 1.5s time to peak torque
+STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
+STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor
+
+# Steer angle limits
+ANGLE_MAX_BP = [0., 5.]
+ANGLE_MAX_V = [510., 300.]
+ANGLE_DELTA_BP = [0., 5.]
+ANGLE_DELTA_V = [3., 1.]
TARGET_IDS = [0x340, 0x341, 0x342, 0x343, 0x344, 0x345,
0x363, 0x364, 0x365, 0x370, 0x371, 0x372,
0x373, 0x374, 0x375, 0x380, 0x381, 0x382,
0x383]
+
def accel_hysteresis(accel, accel_steady, enabled):
# for small accel oscillations within ACCEL_HYST_GAP, don't change the accel command
@@ -56,35 +66,65 @@ def process_hud_alert(hud_alert, audible_alert):
return steer, fcw, sound1, sound2
+def ipas_state_transition(steer_angle_enabled, enabled, ipas_state, ipas_reset_counter):
+
+ if enabled and not steer_angle_enabled:
+ #ipas_reset_counter = max(0, ipas_reset_counter - 1)
+ #if ipas_reset_counter == 0:
+ # steer_angle_enabled = True
+ #else:
+ # steer_angle_enabled = False
+ #return steer_angle_enabled, ipas_reset_counter
+ return True, 0
+
+ elif enabled and steer_angle_enabled:
+ if steer_angle_enabled and ipas_state != 3:
+ ipas_reset_counter += 1
+ else:
+ ipas_reset_counter = 0
+ if ipas_reset_counter > 10: # try every 0.1s
+ steer_angle_enabled = False
+ return steer_angle_enabled, ipas_reset_counter
+
+ else:
+ return False, 0
+
class CarController(object):
- def __init__(self, car_fingerprint, enable_camera, enable_dsu, enable_apg):
+ def __init__(self, dbc_name, car_fingerprint, enable_camera, enable_dsu, enable_apg):
self.braking = False
# redundant safety check with the board
self.controls_allowed = True
- self.last_steer = 0.
+ self.last_steer = 0
+ self.last_angle = 0
self.accel_steady = 0.
self.car_fingerprint = car_fingerprint
self.alert_active = False
self.last_standstill = False
self.standstill_req = False
+ self.angle_control = False
+
+ self.steer_angle_enabled = False
+ self.ipas_reset_counter = 0
self.fake_ecus = set()
if enable_camera: self.fake_ecus.add(ECU.CAM)
if enable_dsu: self.fake_ecus.add(ECU.DSU)
if enable_apg: self.fake_ecus.add(ECU.APGS)
+ self.packer = CANPacker(dbc_name)
+
def update(self, sendcan, enabled, CS, frame, actuators,
pcm_cancel_cmd, hud_alert, audible_alert):
# *** compute control surfaces ***
- # steer torque is converted back to CAN reference (positive when steering right)
+ # gas and brake
apply_accel = actuators.gas - actuators.brake
apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled)
- apply_accel = int(round(clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX)))
+ apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX)
- # steer torque is converted back to CAN reference (positive when steering right)
+ # steer torque
apply_steer = int(round(actuators.steer * STEER_MAX))
max_lim = min(max(CS.steer_torque_motor + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX)
@@ -98,15 +138,31 @@ class CarController(object):
else:
apply_steer = clip(apply_steer, self.last_steer - STEER_DELTA_UP, min(self.last_steer + STEER_DELTA_DOWN, STEER_DELTA_UP))
- if not enabled and CS.pcm_acc_status:
- # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated
- pcm_cancel_cmd = 1
-
# dropping torque immediately might cause eps to temp fault. On the other hand, safety_toyota
# cuts steer torque immediately anyway TODO: monitor if this is a real issue
- if not enabled or CS.steer_error:
+ # only cut torque when steer state is a known fault
+ if not enabled or CS.steer_state in [18, 50]:
apply_steer = 0
+ self.steer_angle_enabled, self.ipas_reset_counter = \
+ ipas_state_transition(self.steer_angle_enabled, enabled, CS.ipas_state, self.ipas_reset_counter)
+ #print self.steer_angle_enabled, self.ipas_reset_counter, CS.ipas_state
+
+ # steer angle
+ if self.steer_angle_enabled:
+ apply_angle = actuators.steerAngle
+ angle_lim = int_rnd(interp(CS.v_ego, ANGLE_MAX_BP, ANGLE_MAX_V))
+ apply_angle = clip(apply_angle, -angle_lim, angle_lim)
+
+ angle_rate_lim = int_rnd(interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_V))
+ apply_angle = clip(apply_angle, self.last_angle - angle_rate_lim, self.last_angle + angle_rate_lim)
+ else:
+ apply_angle = CS.angle_steers
+
+ if not enabled and CS.pcm_acc_status:
+ # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated
+ pcm_cancel_cmd = 1
+
# on entering standstill, send standstill request
if CS.standstill and not self.last_standstill:
self.standstill_req = True
@@ -115,6 +171,7 @@ class CarController(object):
self.standstill_req = False
self.last_steer = apply_steer
+ self.last_angle = apply_angle
self.last_accel = apply_accel
self.last_standstill = CS.standstill
@@ -127,17 +184,23 @@ class CarController(object):
# sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed
# on consecutive messages
if ECU.CAM in self.fake_ecus:
- can_sends.append(create_steer_command(apply_steer, frame))
+ if self.angle_control:
+ can_sends.append(create_steer_command(self.packer, 0., frame))
+ else:
+ can_sends.append(create_steer_command(self.packer, apply_steer, frame))
if ECU.APGS in self.fake_ecus:
- can_sends.append(create_ipas_steer_command(apply_steer))
+ if self.angle_control:
+ can_sends.append(create_ipas_steer_command(self.packer, apply_angle, self.steer_angle_enabled))
+ else:
+ can_sends.append(create_ipas_steer_command(self.packer, 0, 0))
# accel cmd comes from DSU, but we can spam can to cancel the system even if we are using lat only control
if (frame % 3 == 0 and ECU.DSU in self.fake_ecus) or (pcm_cancel_cmd and ECU.CAM in self.fake_ecus):
if ECU.DSU in self.fake_ecus:
- can_sends.append(create_accel_command(apply_accel, pcm_cancel_cmd, self.standstill_req))
+ can_sends.append(create_accel_command(self.packer, apply_accel, pcm_cancel_cmd, self.standstill_req))
else:
- can_sends.append(create_accel_command(0, pcm_cancel_cmd, False))
+ can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False))
if frame % 10 == 0 and ECU.CAM in self.fake_ecus:
for addr in TARGET_IDS:
@@ -157,8 +220,8 @@ class CarController(object):
send_ui = False
if (frame % 100 == 0 or send_ui) and ECU.CAM in self.fake_ecus:
- can_sends.append(create_ui_command(steer, sound1, sound2))
- can_sends.append(create_fcw_command(fcw))
+ can_sends.append(create_ui_command(self.packer, steer, sound1, sound2))
+ can_sends.append(create_fcw_command(self.packer, fcw))
#*** static msgs ***
diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py
index 24fc85239c..06df6e67a8 100644
--- a/selfdrive/car/toyota/carstate.py
+++ b/selfdrive/car/toyota/carstate.py
@@ -75,6 +75,7 @@ def get_can_parser(CP):
("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR", 0),
("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers
("LKA_STATE", "EPS_STATUS", 0),
+ ("IPAS_STATE", "EPS_STATUS", 1),
("BRAKE_LIGHTS_ACC", "ESP_CONTROL", 0),
("AUTO_HIGH_BEAM", "LIGHT_STALK", 0),
]
@@ -125,9 +126,6 @@ class CarState(object):
cp.vl["SEATS_DOORS"]['DOOR_OPEN_RL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_RR']])
self.seatbelt = not cp.vl["SEATS_DOORS"]['SEATBELT_DRIVER_UNLATCHED']
- self.steer_error = False
- self.brake_error = 0
-
can_gear = cp.vl["GEAR_PACKET"]['GEAR']
self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED']
self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL']
@@ -160,7 +158,11 @@ class CarState(object):
# we could use the override bit from dbc, but it's triggered at too high torque values
self.steer_override = abs(cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']) > 100
- self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] == 50
+ # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state
+ self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE']
+ self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] not in [2, 10]
+ self.ipas_state = cp.vl['EPS_STATUS']['IPAS_STATE']
+ self.brake_error = 0
self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']
self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS']
diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py
index 53cfbb180a..55874788cc 100755
--- a/selfdrive/car/toyota/interface.py
+++ b/selfdrive/car/toyota/interface.py
@@ -33,7 +33,7 @@ class CarInterface(object):
# sending if read only is False
if sendcan is not None:
self.sendcan = sendcan
- self.CC = CarController(CP.carFingerprint, CP.enableCamera, CP.enableDsu, CP.enableApgs)
+ self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera, CP.enableDsu, CP.enableApgs)
@staticmethod
def compute_gb(accel, speed):
@@ -72,20 +72,25 @@ class CarInterface(object):
tireStiffnessFront_civic = 85400
tireStiffnessRear_civic = 90000
+ ret.steerKiBP, ret.steerKpBP = [[0.], [0.]]
if candidate == CAR.PRIUS:
ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.70
- ret.steerRatio = 14.5 # TODO: find exact value for Prius
+ ret.steerRatio = 15.0
ret.mass = 3045./2.205 + std_cargo
- ret.steerKp, ret.steerKi = 0.6, 0.05
+ ret.steerKpV, ret.steerKiV = [[0.4], [0.01]]
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
- ret.steerRateCost = 2.
+ ret.steerRateCost = 1.5
+
+ f = 1.43353663
+ tireStiffnessFront_civic *= f
+ tireStiffnessRear_civic *= f
elif candidate in [CAR.RAV4, CAR.RAV4H]:
ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.65
ret.steerRatio = 14.5 # Rav4 2017
ret.mass = 3650./2.205 + std_cargo # mean between normal and hybrid
- ret.steerKp, ret.steerKi = 0.6, 0.05
+ ret.steerKpV, ret.steerKiV = [[0.6], [0.05]]
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
ret.steerRateCost = 1.
elif candidate == CAR.COROLLA:
@@ -93,7 +98,7 @@ class CarInterface(object):
ret.wheelbase = 2.70
ret.steerRatio = 17.8
ret.mass = 2860./2.205 + std_cargo # mean between normal and hybrid
- ret.steerKp, ret.steerKi = 0.2, 0.05
+ ret.steerKpV, ret.steerKiV = [[0.2], [0.05]]
ret.steerKf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594
ret.steerRateCost = 1.
elif candidate == CAR.LEXUS_RXH:
@@ -101,7 +106,7 @@ class CarInterface(object):
ret.wheelbase = 2.79
ret.steerRatio = 16. # official specs say 14.8, but it does not seem right
ret.mass = 4481./2.205 + std_cargo # mean between min and max
- ret.steerKp, ret.steerKi = 0.6, 0.1
+ ret.steerKpV, ret.steerKiV = [[0.6], [0.1]]
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
ret.steerRateCost = .8
@@ -145,11 +150,10 @@ class CarInterface(object):
ret.enableCamera = not check_ecu_msgs(fingerprint, candidate, ECU.CAM)
ret.enableDsu = not check_ecu_msgs(fingerprint, candidate, ECU.DSU)
- ret.enableApgs = False # not check_ecu_msgs(fingerprint, candidate, ECU.APGS)
+ ret.enableApgs = False #not check_ecu_msgs(fingerprint, candidate, ECU.APGS)
print "ECU Camera Simulated: ", ret.enableCamera
print "ECU DSU Simulated: ", ret.enableDsu
print "ECU APGS Simulated: ", ret.enableApgs
- ret.enableGas = True
ret.steerLimitAlert = False
ret.stoppingControl = False
diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py
index c4c64e45c1..4cb2c0c85c 100644
--- a/selfdrive/car/toyota/toyotacan.py
+++ b/selfdrive/car/toyota/toyotacan.py
@@ -28,62 +28,73 @@ def create_video_target(frame, addr):
return make_can_msg(addr, msg, 1, True)
-def create_ipas_steer_command(steer):
-
+def create_ipas_steer_command(packer, steer, enabled):
"""Creates a CAN message for the Toyota Steer Command."""
if steer < 0:
- move = 0x60
- steer = 0xfff + steer + 1
+ direction = 3
elif steer > 0:
- move = 0x20
+ direction = 1
else:
- move = 0x40
-
- mode = 0x30 if steer else 0x10
+ direction = 2
- steer_h = (steer & 0xF00) >> 8
- steer_l = steer & 0xff
+ mode = 3 if enabled else 1
- msg = struct.pack("!BBBBBBB", mode | steer_h, steer_l, 0x10, 0x00, move, 0x40, 0x00)
+ values = {
+ "STATE": mode,
+ "DIRECTION_CMD": direction,
+ "ANGLE": steer,
+ "SET_ME_X10": 0x10,
+ "SET_ME_X40": 0x40
+ }
+ return packer.make_can_msg("STEERING_IPAS", 0, values)
- return make_can_msg(0x266, msg, 0, True)
-def create_steer_command(steer, raw_cnt):
+def create_steer_command(packer, steer, raw_cnt):
"""Creates a CAN message for the Toyota Steer Command."""
- # from 0x80 to 0xff
- counter = ((raw_cnt & 0x3f) << 1) | 0x80
- if steer != 0:
- counter |= 1
-
- # hud
- # 00 => Regular
- # 40 => Actively Steering (with beep)
- # 80 => Actively Steering (without beep)
- hud = 0x00
- msg = struct.pack("!BhB", counter, steer, hud)
+ values = {
+ "STEER_REQUEST": abs(steer) > 0.001,
+ "STEER_TORQUE_CMD": steer,
+ "COUNTER": raw_cnt,
+ "SET_ME_1": 1,
+ }
+ return packer.make_can_msg("STEERING_LKA", 0, values)
- return make_can_msg(0x2e4, msg, 0, True)
-
-def create_accel_command(accel, pcm_cancel, standstill_req):
+def create_accel_command(packer, accel, pcm_cancel, standstill_req):
# TODO: find the exact canceling bit
- state = 0x40 if standstill_req else 0xC0
- state += pcm_cancel # this allows automatic restart from hold without driver cmd
-
- msg = struct.pack("!hBBBBB", accel, 0x63, state, 0x00, 0x00, 0x00)
-
- return make_can_msg(0x343, msg, 0, True)
-
-def create_fcw_command(fcw):
-
- msg = struct.pack("!BBBBBBBB", fcw<<4, 0x20, 0x00, 0x00, 0x10, 0x00, 0x80, 0x00)
-
- return make_can_msg(0x411, msg, 0, False)
-
-
-def create_ui_command(steer, sound1, sound2):
-
- msg = struct.pack("!BBBBBBBB", 0x54, 0x04 + steer + (sound2<<4), 0x0C, 0x00,
- sound1, 0x2C, 0x38, 0x02)
- return make_can_msg(0x412, msg, 0, False)
+ values = {
+ "ACCEL_CMD": accel,
+ "SET_ME_X63": 0x63,
+ "SET_ME_1": 1,
+ "RELEASE_STANDSTILL": not standstill_req,
+ "CANCEL_REQ": pcm_cancel,
+ }
+ return packer.make_can_msg("ACC_CONTROL", 0, values)
+
+
+def create_fcw_command(packer, fcw):
+ values = {
+ "FCW": fcw,
+ "SET_ME_X20": 0x20,
+ "SET_ME_X10": 0x10,
+ "SET_ME_X80": 0x80,
+ }
+ return packer.make_can_msg("ACC_HUD", 0, values)
+
+
+def create_ui_command(packer, steer, sound1, sound2):
+ values = {
+ "RIGHT_LINE": 1,
+ "LEFT_LINE": 1,
+ "SET_ME_X0C": 0x0c,
+ "SET_ME_X2C": 0x2c,
+ "SET_ME_X38": 0x38,
+ "SET_ME_X02": 0x02,
+ "SET_ME_X01": 1,
+ "SET_ME_X01_2": 1,
+ "REPEATED_BEEPS": sound1,
+ "TWO_BEEPS": sound2,
+ "LDA_ALERT": steer,
+ }
+ return packer.make_can_msg("LKAS_HUD", 0, values)
diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h
index 348ff45913..5cf7951e93 100644
--- a/selfdrive/common/version.h
+++ b/selfdrive/common/version.h
@@ -1 +1 @@
-#define COMMA_VERSION "0.4.2-openpilot"
+#define COMMA_VERSION "0.4.3.1-release"
diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h
index 24b882340f..2f116a4d01 100644
--- a/selfdrive/common/visionipc.h
+++ b/selfdrive/common/visionipc.h
@@ -48,7 +48,9 @@ typedef struct VisionStreamBufs {
} VisionStreamBufs;
typedef struct VIPCBufExtra {
- uint32_t frame_id; // only for yuv
+ // only for yuv
+ uint32_t frame_id;
+ uint64_t timestamp_eof;
} VIPCBufExtra;
typedef union VisionPacketData {
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 483868aa37..207e5907f8 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -104,9 +104,9 @@ def data_sample(CI, CC, thermal, calibration, health, poller, cal_status, overte
return CS, events, cal_status, overtemp, free_space
-def calc_plan(CS, events, PL, LoC, v_cruise_kph, awareness_status):
+def calc_plan(CS, events, PL, LaC, LoC, v_cruise_kph, awareness_status):
# plan runs always, independently of the state
- plan_packet = PL.update(CS, LoC, v_cruise_kph, awareness_status < -0.)
+ plan_packet = PL.update(CS, LaC, LoC, v_cruise_kph, awareness_status < -0.)
plan = plan_packet.plan
plan_ts = plan_packet.logMonoTime
@@ -211,7 +211,8 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM
def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk,
- awareness_status, PL, LaC, LoC, VM, angle_offset, rear_view_allowed, rear_view_toggle):
+ awareness_status, PL, LaC, LoC, VM, angle_offset, rear_view_allowed,
+ rear_view_toggle, passive):
# Given the state, this function returns the actuators
# reset actuators to zero
@@ -228,7 +229,7 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last,
else:
rear_view_toggle = False
- if b.type == "altButton1" and b.pressed:
+ if (b.type == "altButton1" and b.pressed) and not passive:
rear_view_toggle = not rear_view_toggle
@@ -273,8 +274,8 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last,
CP, PL.lead_1)
# *** steering PID loop ***
- actuators.steer = LaC.update(active, CS.vEgo, CS.steeringAngle,
- CS.steeringPressed, plan.dPoly, angle_offset, VM, PL)
+ actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle,
+ CS.steeringPressed, plan.dPoly, angle_offset, VM, PL)
# send a "steering required alert" if saturation count has reached the limit
if LaC.sat_flag and CP.steerLimitAlert:
@@ -400,6 +401,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_
cs_send.init('carState')
# TODO: override CS.events with all the cumulated events
cs_send.carState = copy(CS)
+ cs_send.carState.events = events
carstate.send(cs_send.to_bytes())
# broadcast carControl
@@ -407,7 +409,6 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_
cc_send.init('carControl')
cc_send.carControl = copy(CC)
carcontrol.send(cc_send.to_bytes())
- #print [i.name for i in events]
# publish mpc state at 20Hz
if hasattr(LaC, 'mpc_updated') and LaC.mpc_updated:
@@ -417,6 +418,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_
dat.liveMpc.y = list(LaC.mpc_solution[0].y)
dat.liveMpc.psi = list(LaC.mpc_solution[0].psi)
dat.liveMpc.delta = list(LaC.mpc_solution[0].delta)
+ dat.liveMpc.cost = LaC.mpc_solution[0].cost
livempc.send(dat.to_bytes())
return CC
@@ -457,6 +459,11 @@ def controlsd_thread(gctx, rate=100):
if CI is None:
raise Exception("unsupported car")
+ # if stock camera is connected, then force passive behavior
+ if not CP.enableCamera:
+ passive = True
+ sendcan = None
+
if passive:
CP.safetyModel = car.CarParams.SafetyModels.noOutput
@@ -511,7 +518,7 @@ def controlsd_thread(gctx, rate=100):
prof.checkpoint("Sample")
# define plan
- plan, plan_ts = calc_plan(CS, events, PL, LoC, v_cruise_kph, awareness_status)
+ plan, plan_ts = calc_plan(CS, events, PL, LaC, LoC, v_cruise_kph, awareness_status)
prof.checkpoint("Plan")
if not passive:
@@ -523,7 +530,7 @@ def controlsd_thread(gctx, rate=100):
# compute actuators
actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle = state_control(plan, CS, CP, state, events, v_cruise_kph,
v_cruise_kph_last, AM, rk, awareness_status, PL, LaC, LoC, VM,
- angle_offset, rear_view_allowed, rear_view_toggle)
+ angle_offset, rear_view_allowed, rear_view_toggle, passive)
prof.checkpoint("State Control")
# publish data
diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py
index 82174135e8..5e704982d6 100644
--- a/selfdrive/controls/lib/alertmanager.py
+++ b/selfdrive/controls/lib/alertmanager.py
@@ -15,14 +15,14 @@ AlertSize = log.Live100Data.AlertSize
AlertStatus = log.Live100Data.AlertStatus
class Alert(object):
- def __init__(self,
+ def __init__(self,
alert_text_1,
alert_text_2,
alert_status,
alert_size,
alert_priority,
visual_alert,
- audible_alert,
+ audible_alert,
duration_sound,
duration_hud_alert,
duration_text):
@@ -34,7 +34,7 @@ class Alert(object):
self.alert_priority = alert_priority
self.visual_alert = visual_alert if visual_alert is not None else "none"
self.audible_alert = audible_alert if audible_alert is not None else "none"
-
+
self.duration_sound = duration_sound
self.duration_hud_alert = duration_hud_alert
self.duration_text = duration_text
@@ -71,356 +71,368 @@ class AlertManager(object):
Priority.MID, None, "beepSingle", .2, 0., 0.),
"fcw": Alert(
- "Brake!",
- "Risk of Collision",
+ "Brake!",
+ "Risk of collision detected",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "fcw", "chimeRepeated", 1., 2., 2.),
"steerSaturated": Alert(
- "Take Control",
- "Turn Exceeds Limit",
- AlertStatus.userPrompt, AlertSize.full,
+ "TAKE CONTROL",
+ "Turn exceeds steering limit",
+ AlertStatus.userPrompt, AlertSize.mid,
Priority.LOW, "steerRequired", "chimeSingle", 1., 2., 3.),
"steerTempUnavailable": Alert(
- "Take Control",
- "Steer Temporarily Unavailable",
- AlertStatus.userPrompt, AlertSize.full,
+ "TAKE CONTROL",
+ "Steering temporarily unavailable",
+ AlertStatus.userPrompt, AlertSize.mid,
Priority.LOW, "steerRequired", "chimeDouble", .4, 2., 3.),
"preDriverDistracted": Alert(
- "Take Control",
- "User Distracted",
- AlertStatus.userPrompt, AlertSize.full,
- Priority.LOW, "steerRequired", "chimeDouble", .1, .1, .1),
+ "TAKE CONTROL",
+ "User appears distracted",
+ AlertStatus.userPrompt, AlertSize.mid,
+ Priority.LOW, "steerRequired", None, 0., .1, .1),
"driverDistracted": Alert(
- "Take Control to Regain Speed",
- "User Distracted",
+ "TAKE CONTROL TO REGAIN SPEED",
+ "User appears distracted",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1),
"startup": Alert(
- "Always Keep Hands on Wheel",
- "Be Ready to Take Over Any Time",
- AlertStatus.normal, AlertSize.full,
+ "Always keep hands on wheel",
+ "Be ready to take over at any time",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOWEST, None, None, 0., 0., 15.),
"ethicalDilemma": Alert(
- "Take Control Immediately",
- "Ethical Dilemma Detected",
+ "TAKE CONTROL IMMEDIATELY",
+ "Ethical Dilemma Detected",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 3.),
"steerTempUnavailableNoEntry": Alert(
- "Comma Unavailable",
- "Steer Temporary Unavailable",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Steering temporarily unavailable",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 0., 3.),
"manualRestart": Alert(
- "Take Control",
- "Resume Driving Manually",
- AlertStatus.userPrompt, AlertSize.full,
+ "TAKE CONTROL",
+ "Resume driving manually",
+ AlertStatus.userPrompt, AlertSize.mid,
Priority.LOW, None, None, 0., 0., .2),
# Non-entry only alerts
"wrongCarModeNoEntry": Alert(
- "Comma Unavailable",
- "Main Switch Off",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Main Switch Off",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 0., 3.),
"dataNeededNoEntry": Alert(
- "Comma Unavailable",
- "Data needed for calibration. Upload drive, try again",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Data needed for calibration. Upload drive, try again",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 0., 3.),
"outOfSpaceNoEntry": Alert(
- "Comma Unavailable",
- "Out of Space",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Out of storage space",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 0., 3.),
"pedalPressedNoEntry": Alert(
- "Comma Unavailable",
- "Pedal Pressed",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Pedal pressed during attempt",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, "brakePressed", "chimeDouble", .4, 2., 3.),
"speedTooLowNoEntry": Alert(
- "Comma Unavailable",
- "Speed Too Low",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Speed too low",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"brakeHoldNoEntry": Alert(
- "Comma Unavailable",
- "Brake Hold Active",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Brake hold active",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"parkBrakeNoEntry": Alert(
- "Comma Unavailable",
- "Park Brake Engaged",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Park brake engaged",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"lowSpeedLockoutNoEntry": Alert(
"Comma Unavailable",
"Cruise Fault: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
# Cancellation alerts causing soft disabling
"overheat": Alert(
- "Take Control Immediately",
- "System Overheated",
+ "TAKE CONTROL IMMEDIATELY",
+ "System Overheated",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"wrongGear": Alert(
- "Take Control Immediately",
- "Gear not D",
+ "TAKE CONTROL IMMEDIATELY",
+ "Gear not D",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"calibrationInvalid": Alert(
- "Take Control Immediately",
- "Calibration Invalid: Reposition EON and Recalibrate",
+ "TAKE CONTROL IMMEDIATELY",
+ "Calibration Invalid: Reposition EON and Recalibrate",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"calibrationInProgress": Alert(
- "Take Control Immediately",
+ "TAKE CONTROL IMMEDIATELY",
"Calibration in Progress",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"doorOpen": Alert(
- "Take Control Immediately",
- "Door Open",
+ "TAKE CONTROL IMMEDIATELY",
+ "Door Open",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"seatbeltNotLatched": Alert(
- "Take Control Immediately",
- "Seatbelt Unlatched",
+ "TAKE CONTROL IMMEDIATELY",
+ "Seatbelt Unlatched",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
"espDisabled": Alert(
- "Take Control Immediately",
- "ESP Off",
+ "TAKE CONTROL IMMEDIATELY",
+ "ESP Off",
AlertStatus.critical, AlertSize.full,
Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.),
# Cancellation alerts causing immediate disabling
"radarCommIssue": Alert(
- "Take Control Immediately",
- "Radar Error: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Radar Error: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"radarFault": Alert(
- "Take Control Immediately",
- "Radar Error: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Radar Error: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"modelCommIssue": Alert(
- "Take Control Immediately",
- "Model Error: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Model Error: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"controlsFailed": Alert(
- "Take Control Immediately",
- "Controls Failed",
+ "TAKE CONTROL IMMEDIATELY",
+ "Controls Failed",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"controlsMismatch": Alert(
- "Take Control Immediately",
- "Controls Mismatch",
+ "TAKE CONTROL IMMEDIATELY",
+ "Controls Mismatch",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"commIssue": Alert(
- "Take Control Immediately",
- "CAN Error: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "CAN Error: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"steerUnavailable": Alert(
- "Take Control Immediately",
- "Steer Fault: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Steer Fault: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"brakeUnavailable": Alert(
- "Take Control Immediately",
- "Brake Fault: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Brake Fault: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"gasUnavailable": Alert(
- "Take Control Immediately",
- "Gas Fault: Restart the Car",
+ "TAKE CONTROL IMMEDIATELY",
+ "Gas Fault: Restart the Car",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"reverseGear": Alert(
- "Take Control Immediately",
- "Reverse Gear",
+ "TAKE CONTROL IMMEDIATELY",
+ "Reverse Gear",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
"cruiseDisabled": Alert(
- "Take Control Immediately",
- "Cruise Is Off",
+ "TAKE CONTROL IMMEDIATELY",
+ "Cruise Is Off",
+ AlertStatus.critical, AlertSize.full,
+ Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
+
+ "plannerError": Alert(
+ "TAKE CONTROL IMMEDIATELY",
+ "Planner Solution Error",
AlertStatus.critical, AlertSize.full,
Priority.HIGH, "steerRequired", "chimeRepeated", 1., 3., 4.),
# not loud cancellations (user is in control)
"noTarget": Alert(
"Comma Canceled",
- "No Close Lead",
- AlertStatus.normal, AlertSize.full,
+ "No close lead car",
+ AlertStatus.normal, AlertSize.mid,
Priority.HIGH, None, "chimeDouble", .4, 2., 3.),
"speedTooLow": Alert(
"Comma Canceled",
- "Speed Too Low",
- AlertStatus.normal, AlertSize.full,
+ "Speed too low",
+ AlertStatus.normal, AlertSize.mid,
Priority.HIGH, None, "chimeDouble", .4, 2., 3.),
# Cancellation alerts causing non-entry
"overheatNoEntry": Alert(
- "Comma Unavailable",
- "System Overheated",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "System overheated",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"wrongGearNoEntry": Alert(
- "Comma Unavailable",
- "Gear not D",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Gear not D",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"calibrationInvalidNoEntry": Alert(
- "Comma Unavailable",
- "Calibration Invalid: Reposition EON and Recalibrate",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Calibration Invalid: Reposition EON and Recalibrate",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"calibrationInProgressNoEntry": Alert(
- "Comma Unavailable",
- "Calibration in Progress",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Calibration in Progress",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"doorOpenNoEntry": Alert(
- "Comma Unavailable",
- "Door Open",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Door open",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"seatbeltNotLatchedNoEntry": Alert(
- "Comma Unavailable",
- "Seatbelt Unlatched",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Seatbelt unlatched",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
-
+
"espDisabledNoEntry": Alert(
- "Comma Unavailable",
- "ESP Off",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "ESP Off",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"radarCommIssueNoEntry": Alert(
- "Comma Unavailable",
- "Radar Error: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Radar Error: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"radarFaultNoEntry": Alert(
- "Comma Unavailable",
- "Radar Error: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Radar Error: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"modelCommIssueNoEntry": Alert(
- "Comma Unavailable",
- "Model Error: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Model Error: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"controlsFailedNoEntry": Alert(
- "Comma Unavailable",
- "Controls Failed",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Controls Failed",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"commIssueNoEntry": Alert(
- "Comma Unavailable",
- "CAN Error: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "CAN Error: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"steerUnavailableNoEntry": Alert(
- "Comma Unavailable",
- "Steer Fault: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Steer Fault: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"brakeUnavailableNoEntry": Alert(
- "Comma Unavailable",
- "Brake Fault: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Brake Fault: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"gasUnavailableNoEntry": Alert(
- "Comma Unavailable",
- "Gas Error: Restart the Car",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Gas Error: Restart the Car",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"reverseGearNoEntry": Alert(
- "Comma Unavailable",
- "Reverse Gear",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Reverse Gear",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"cruiseDisabledNoEntry": Alert(
- "Comma Unavailable",
- "Cruise is Off",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "Cruise is off",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
"noTargetNoEntry": Alert(
- "Comma Unavailable",
- "No Close Lead",
- AlertStatus.normal, AlertSize.full,
+ "Comma Unavailable",
+ "No close lead car",
+ AlertStatus.normal, AlertSize.mid,
+ Priority.LOW, None, "chimeDouble", .4, 2., 3.),
+
+ "plannerErrorNoEntry": Alert(
+ "Comma Unavailable",
+ "Planner Solution Error",
+ AlertStatus.normal, AlertSize.mid,
Priority.LOW, None, "chimeDouble", .4, 2., 3.),
# permanent alerts to display on small UI upper box
"steerUnavailablePermanent": Alert(
- "STEER FAULT",
- "RESTART THE CAR",
+ "STEER FAULT: Restart the car to engage",
+ "",
AlertStatus.normal, AlertSize.small,
Priority.LOWEST, None, None, 0., 0., .2),
"brakeUnavailablePermanent": Alert(
- "BRAKE FAULT",
- "RESTART THE CAR",
+ "BRAKE FAULT: Restart the car to engage",
+ "",
AlertStatus.normal, AlertSize.small,
Priority.LOWEST, None, None, 0., 0., .2),
"lowSpeedLockoutPermanent": Alert(
- "CRUISE FAULT",
- "RESTART THE CAR",
+ "CRUISE FAULT: Restart the car to engage",
+ "",
AlertStatus.normal, AlertSize.small,
Priority.LOWEST, None, None, 0., 0., .2),
}
@@ -445,13 +457,14 @@ class AlertManager(object):
enabled=enabled)
self.activealerts.append(added_alert)
- self.activealerts.sort(key=lambda k: k.alert_priority, reverse=True)
+ # sort by priority first and then by start_time
+ self.activealerts.sort(key=lambda k: (k.alert_priority, k.start_time), reverse=True)
# TODO: cycle through alerts?
def process_alerts(self, cur_time):
# first get rid of all the expired alerts
- self.activealerts = [a for a in self.activealerts if a.start_time +
+ self.activealerts = [a for a in self.activealerts if a.start_time +
max(a.duration_sound, a.duration_hud_alert, a.duration_text) > cur_time]
ca = self.activealerts[0] if self.alertPresent() else None
diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py
index f98a0233c6..1fbd32c75a 100644
--- a/selfdrive/controls/lib/drive_helpers.py
+++ b/selfdrive/controls/lib/drive_helpers.py
@@ -2,6 +2,20 @@ from common.numpy_fast import clip
from cereal import car
+class MPC_COST_LAT:
+ PATH = 1.0
+ LANE = 3.0
+ HEADING = 1.0
+ STEER_RATE = 1.0
+
+
+class MPC_COST_LONG:
+ TTC = 5.0
+ DISTANCE = 0.1
+ ACCELERATION = 10.0
+ JERK = 20.0
+
+
class EventTypes:
ENABLE = 'enable'
PRE_ENABLE = 'preEnable'
diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py
index 74020a5920..4d5c67681e 100644
--- a/selfdrive/controls/lib/latcontrol.py
+++ b/selfdrive/controls/lib/latcontrol.py
@@ -1,7 +1,7 @@
import math
import numpy as np
-
from selfdrive.controls.lib.pid import PIController
+from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT
from selfdrive.controls.lib.lateral_mpc import libmpc_py
from common.numpy_fast import interp
from common.realtime import sec_since_boot
@@ -26,17 +26,20 @@ def get_steer_max(CP, v_ego):
class LatControl(object):
def __init__(self, VM):
- self.pid = PIController(VM.CP.steerKp, VM.CP.steerKi, k_f=VM.CP.steerKf, pos_limit=1.0)
+ self.pid = PIController((VM.CP.steerKpBP, VM.CP.steerKpV),
+ (VM.CP.steerKiBP, VM.CP.steerKiV),
+ k_f=VM.CP.steerKf, pos_limit=1.0)
self.last_cloudlog_t = 0.0
self.setup_mpc(VM.CP.steerRateCost)
def setup_mpc(self, steer_rate_cost):
self.libmpc = libmpc_py.libmpc
- self.libmpc.init(steer_rate_cost)
+ self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, steer_rate_cost)
self.mpc_solution = libmpc_py.ffi.new("log_t *")
self.cur_state = libmpc_py.ffi.new("state_t *")
self.mpc_updated = False
+ self.mpc_nans = False
self.cur_state[0].x = 0.0
self.cur_state[0].y = 0.0
self.cur_state[0].psi = 0.0
@@ -54,6 +57,7 @@ class LatControl(object):
def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offset, VM, PL):
cur_time = sec_since_boot()
self.mpc_updated = False
+ # TODO: this creates issues in replay when rewinding time: mpc won't run
if self.last_mpc_ts < PL.last_md_ts:
self.last_mpc_ts = PL.last_md_ts
self.angle_steers_des_prev = self.angle_steers_des_mpc
@@ -72,7 +76,12 @@ class LatControl(object):
l_poly, r_poly, p_poly,
PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, curvature_factor, v_ego_mpc, PL.PP.lane_width)
- delta_desired = self.mpc_solution[0].delta[1]
+ # reset to current steer angle if not active or overriding
+ if active:
+ delta_desired = self.mpc_solution[0].delta[1]
+ else:
+ delta_desired = math.radians(angle_steers - angle_offset) / VM.CP.steerRatio
+
self.cur_state[0].delta = delta_desired
self.angle_steers_des_mpc = float(math.degrees(delta_desired * VM.CP.steerRatio) + angle_offset)
@@ -80,10 +89,10 @@ class LatControl(object):
self.mpc_updated = True
# Check for infeasable MPC solution
- nans = np.any(np.isnan(list(self.mpc_solution[0].delta)))
+ self.mpc_nans = np.any(np.isnan(list(self.mpc_solution[0].delta)))
t = sec_since_boot()
- if nans:
- self.libmpc.init(VM.CP.steerRateCost)
+ if self.mpc_nans:
+ self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, VM.CP.steerRateCost)
self.cur_state[0].delta = math.radians(angle_steers) / VM.CP.steerRatio
if t > self.last_cloudlog_t + 5.0:
@@ -103,7 +112,7 @@ class LatControl(object):
self.pid.pos_limit = steers_max
self.pid.neg_limit = -steers_max
steer_feedforward = self.angle_steers_des * v_ego**2 # proportional to realigning tire momentum (~ lateral accel)
- output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override, feedforward=steer_feedforward)
+ output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override, feedforward=steer_feedforward, speed=v_ego)
self.sat_flag = self.pid.saturated
- return output_steer
+ return output_steer, float(self.angle_steers_des)
diff --git a/selfdrive/controls/lib/lateral_mpc/generator.cpp b/selfdrive/controls/lib/lateral_mpc/generator.cpp
index 53438a11f8..5d0165c091 100644
--- a/selfdrive/controls/lib/lateral_mpc/generator.cpp
+++ b/selfdrive/controls/lib/lateral_mpc/generator.cpp
@@ -4,7 +4,6 @@
#define deg2rad(d) (d/180.0*PI)
const int controlHorizon = 50;
-const double samplingTime = 0.05; // 20 Hz
using namespace std;
@@ -116,9 +115,10 @@ int main( )
ocp.minimizeLSQ(Q, h);
ocp.minimizeLSQEndTerm(QN, hN);
+ // car can't go backward to avoid "circles"
ocp.subjectTo( deg2rad(-90) <= psi <= deg2rad(90));
- ocp.subjectTo( deg2rad(-25) <= delta <= deg2rad(25));
- ocp.subjectTo( -0.1 <= t <= 0.1);
+ // more than absolute max steer angle
+ ocp.subjectTo( deg2rad(-50) <= delta <= deg2rad(50));
ocp.setNOD(18);
OCPexport mpc(ocp);
diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py
index 33bbe1898f..5970dab903 100644
--- a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py
+++ b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py
@@ -1,12 +1,11 @@
import os
-import sys
import subprocess
from cffi import FFI
mpc_dir = os.path.dirname(os.path.abspath(__file__))
libmpc_fn = os.path.join(mpc_dir, "libcommampc.so")
-subprocess.check_call(["make", "-j4"], stdout=sys.stderr, cwd=mpc_dir)
+subprocess.check_call(["make", "-j4"], cwd=mpc_dir)
ffi = FFI()
ffi.cdef("""
@@ -15,13 +14,14 @@ typedef struct {
} state_t;
typedef struct {
- double x[20];
- double y[20];
- double psi[20];
- double delta[20];
+ double x[21];
+ double y[21];
+ double psi[21];
+ double delta[21];
+ double cost;
} log_t;
-void init(double steer_rate_cost);
+void init(double pathCost, double laneCost, double headingCost, double steerRateCost);
int run_mpc(state_t * x0, log_t * solution,
double l_poly[4], double r_poly[4], double p_poly[4],
double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width);
diff --git a/selfdrive/controls/lib/lateral_mpc/mpc.c b/selfdrive/controls/lib/lateral_mpc/mpc.c
index 3c082319ee..f4cee7f2d0 100644
--- a/selfdrive/controls/lib/lateral_mpc/mpc.c
+++ b/selfdrive/controls/lib/lateral_mpc/mpc.c
@@ -22,15 +22,17 @@ typedef struct {
typedef struct {
- double x[N];
- double y[N];
- double psi[N];
- double delta[N];
+ double x[N+1];
+ double y[N+1];
+ double psi[N+1];
+ double delta[N+1];
+ double cost;
} log_t;
-void init(double steerRateCost){
+void init(double pathCost, double laneCost, double headingCost, double steerRateCost){
acado_initializeSolver();
int i;
+ const int STEP_MULTIPLIER = 3;
/* Initialize the states and controls. */
for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0;
@@ -46,18 +48,18 @@ void init(double steerRateCost){
for (i = 0; i < N; i++) {
int f = 1;
if (i > 4){
- f = 3;
+ f = STEP_MULTIPLIER;
}
- acadoVariables.W[25 * i + 0] = 1.0 * f;
- acadoVariables.W[25 * i + 6] = 1.0 * f;
- acadoVariables.W[25 * i + 12] = 1.0 * f;
- acadoVariables.W[25 * i + 18] = 1.0 * f;
+ acadoVariables.W[25 * i + 0] = pathCost * f;
+ acadoVariables.W[25 * i + 6] = laneCost * f;
+ acadoVariables.W[25 * i + 12] = laneCost * f;
+ acadoVariables.W[25 * i + 18] = headingCost * f;
acadoVariables.W[25 * i + 24] = steerRateCost * f;
}
- acadoVariables.WN[0] = 1.0;
- acadoVariables.WN[5] = 1.0;
- acadoVariables.WN[10] = 1.0;
- acadoVariables.WN[15] = 1.0;
+ acadoVariables.WN[0] = pathCost * STEP_MULTIPLIER;
+ acadoVariables.WN[5] = laneCost * STEP_MULTIPLIER;
+ acadoVariables.WN[10] = laneCost * STEP_MULTIPLIER;
+ acadoVariables.WN[15] = headingCost * STEP_MULTIPLIER;
}
int run_mpc(state_t * x0, log_t * solution,
@@ -101,18 +103,22 @@ int run_mpc(state_t * x0, log_t * solution,
acado_preparationStep();
acado_feedbackStep();
- /* printf("lat its: %d\n", acado_getNWSR()); */
-
- for (i = 0; i <= N; i++){
- solution->x[i] = acadoVariables.x[i*NX];
- solution->y[i] = acadoVariables.x[i*NX+1];
- solution->psi[i] = acadoVariables.x[i*NX+2];
- solution->delta[i] = acadoVariables.x[i*NX+3];
- }
-
- acado_shiftStates(2, 0, 0);
- acado_shiftControls( 0 );
+
+ /* printf("lat its: %d\n", acado_getNWSR()); // n iterations
+ printf("Objective: %.6f\n", acado_getObjective()); // solution cost */
+
+ for (i = 0; i <= N; i++){
+ solution->x[i] = acadoVariables.x[i*NX];
+ solution->y[i] = acadoVariables.x[i*NX+1];
+ solution->psi[i] = acadoVariables.x[i*NX+2];
+ solution->delta[i] = acadoVariables.x[i*NX+3];
+ }
+ solution->cost = acado_getObjective();
+ // Dont shift states here. Current solution is closer to next timestep than if
+ // we use the old solution as a starting point
+ //acado_shiftStates(2, 0, 0);
+ //acado_shiftControls( 0 );
return acado_getNWSR();
}
diff --git a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c
index ed897e3c02..e0b91f0554 100644
--- a/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c
+++ b/selfdrive/controls/lib/lateral_mpc/mpc_export/acado_solver.c
@@ -3948,46 +3948,46 @@ acado_macETSlu( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.g[ 21 ]) );
acado_macETSlu( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.g[ 22 ]) );
acado_macETSlu( &(acadoWorkspace.QE[ 832 ]), &(acadoWorkspace.g[ 22 ]) );
acado_macETSlu( &(acadoWorkspace.QE[ 836 ]), &(acadoWorkspace.g[ 23 ]) );
-acadoWorkspace.lb[4] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[0];
-acadoWorkspace.lb[5] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[1];
-acadoWorkspace.lb[6] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[2];
-acadoWorkspace.lb[7] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[3];
-acadoWorkspace.lb[8] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[4];
-acadoWorkspace.lb[9] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[5];
-acadoWorkspace.lb[10] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[6];
-acadoWorkspace.lb[11] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[7];
-acadoWorkspace.lb[12] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[8];
-acadoWorkspace.lb[13] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[9];
-acadoWorkspace.lb[14] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[10];
-acadoWorkspace.lb[15] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[11];
-acadoWorkspace.lb[16] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[12];
-acadoWorkspace.lb[17] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[13];
-acadoWorkspace.lb[18] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[14];
-acadoWorkspace.lb[19] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[15];
-acadoWorkspace.lb[20] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[16];
-acadoWorkspace.lb[21] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[17];
-acadoWorkspace.lb[22] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[18];
-acadoWorkspace.lb[23] = (real_t)-1.0000000000000001e-01 - acadoVariables.u[19];
-acadoWorkspace.ub[4] = (real_t)1.0000000000000001e-01 - acadoVariables.u[0];
-acadoWorkspace.ub[5] = (real_t)1.0000000000000001e-01 - acadoVariables.u[1];
-acadoWorkspace.ub[6] = (real_t)1.0000000000000001e-01 - acadoVariables.u[2];
-acadoWorkspace.ub[7] = (real_t)1.0000000000000001e-01 - acadoVariables.u[3];
-acadoWorkspace.ub[8] = (real_t)1.0000000000000001e-01 - acadoVariables.u[4];
-acadoWorkspace.ub[9] = (real_t)1.0000000000000001e-01 - acadoVariables.u[5];
-acadoWorkspace.ub[10] = (real_t)1.0000000000000001e-01 - acadoVariables.u[6];
-acadoWorkspace.ub[11] = (real_t)1.0000000000000001e-01 - acadoVariables.u[7];
-acadoWorkspace.ub[12] = (real_t)1.0000000000000001e-01 - acadoVariables.u[8];
-acadoWorkspace.ub[13] = (real_t)1.0000000000000001e-01 - acadoVariables.u[9];
-acadoWorkspace.ub[14] = (real_t)1.0000000000000001e-01 - acadoVariables.u[10];
-acadoWorkspace.ub[15] = (real_t)1.0000000000000001e-01 - acadoVariables.u[11];
-acadoWorkspace.ub[16] = (real_t)1.0000000000000001e-01 - acadoVariables.u[12];
-acadoWorkspace.ub[17] = (real_t)1.0000000000000001e-01 - acadoVariables.u[13];
-acadoWorkspace.ub[18] = (real_t)1.0000000000000001e-01 - acadoVariables.u[14];
-acadoWorkspace.ub[19] = (real_t)1.0000000000000001e-01 - acadoVariables.u[15];
-acadoWorkspace.ub[20] = (real_t)1.0000000000000001e-01 - acadoVariables.u[16];
-acadoWorkspace.ub[21] = (real_t)1.0000000000000001e-01 - acadoVariables.u[17];
-acadoWorkspace.ub[22] = (real_t)1.0000000000000001e-01 - acadoVariables.u[18];
-acadoWorkspace.ub[23] = (real_t)1.0000000000000001e-01 - acadoVariables.u[19];
+acadoWorkspace.lb[4] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[0];
+acadoWorkspace.lb[5] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[1];
+acadoWorkspace.lb[6] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[2];
+acadoWorkspace.lb[7] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[3];
+acadoWorkspace.lb[8] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[4];
+acadoWorkspace.lb[9] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[5];
+acadoWorkspace.lb[10] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[6];
+acadoWorkspace.lb[11] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[7];
+acadoWorkspace.lb[12] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[8];
+acadoWorkspace.lb[13] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[9];
+acadoWorkspace.lb[14] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[10];
+acadoWorkspace.lb[15] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[11];
+acadoWorkspace.lb[16] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[12];
+acadoWorkspace.lb[17] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[13];
+acadoWorkspace.lb[18] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[14];
+acadoWorkspace.lb[19] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[15];
+acadoWorkspace.lb[20] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[16];
+acadoWorkspace.lb[21] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[17];
+acadoWorkspace.lb[22] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[18];
+acadoWorkspace.lb[23] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[19];
+acadoWorkspace.ub[4] = (real_t)1.0000000000000000e+12 - acadoVariables.u[0];
+acadoWorkspace.ub[5] = (real_t)1.0000000000000000e+12 - acadoVariables.u[1];
+acadoWorkspace.ub[6] = (real_t)1.0000000000000000e+12 - acadoVariables.u[2];
+acadoWorkspace.ub[7] = (real_t)1.0000000000000000e+12 - acadoVariables.u[3];
+acadoWorkspace.ub[8] = (real_t)1.0000000000000000e+12 - acadoVariables.u[4];
+acadoWorkspace.ub[9] = (real_t)1.0000000000000000e+12 - acadoVariables.u[5];
+acadoWorkspace.ub[10] = (real_t)1.0000000000000000e+12 - acadoVariables.u[6];
+acadoWorkspace.ub[11] = (real_t)1.0000000000000000e+12 - acadoVariables.u[7];
+acadoWorkspace.ub[12] = (real_t)1.0000000000000000e+12 - acadoVariables.u[8];
+acadoWorkspace.ub[13] = (real_t)1.0000000000000000e+12 - acadoVariables.u[9];
+acadoWorkspace.ub[14] = (real_t)1.0000000000000000e+12 - acadoVariables.u[10];
+acadoWorkspace.ub[15] = (real_t)1.0000000000000000e+12 - acadoVariables.u[11];
+acadoWorkspace.ub[16] = (real_t)1.0000000000000000e+12 - acadoVariables.u[12];
+acadoWorkspace.ub[17] = (real_t)1.0000000000000000e+12 - acadoVariables.u[13];
+acadoWorkspace.ub[18] = (real_t)1.0000000000000000e+12 - acadoVariables.u[14];
+acadoWorkspace.ub[19] = (real_t)1.0000000000000000e+12 - acadoVariables.u[15];
+acadoWorkspace.ub[20] = (real_t)1.0000000000000000e+12 - acadoVariables.u[16];
+acadoWorkspace.ub[21] = (real_t)1.0000000000000000e+12 - acadoVariables.u[17];
+acadoWorkspace.ub[22] = (real_t)1.0000000000000000e+12 - acadoVariables.u[18];
+acadoWorkspace.ub[23] = (real_t)1.0000000000000000e+12 - acadoVariables.u[19];
for (lRun1 = 0; lRun1 < 40; ++lRun1)
{
@@ -4477,122 +4477,122 @@ tmp = acadoVariables.x[6] + acadoWorkspace.d[2];
acadoWorkspace.lbA[0] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[0] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[7] + acadoWorkspace.d[3];
-acadoWorkspace.lbA[1] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[1] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[1] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[1] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[10] + acadoWorkspace.d[6];
acadoWorkspace.lbA[2] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[2] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[11] + acadoWorkspace.d[7];
-acadoWorkspace.lbA[3] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[3] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[3] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[3] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[14] + acadoWorkspace.d[10];
acadoWorkspace.lbA[4] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[4] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[15] + acadoWorkspace.d[11];
-acadoWorkspace.lbA[5] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[5] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[5] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[5] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[18] + acadoWorkspace.d[14];
acadoWorkspace.lbA[6] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[6] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[19] + acadoWorkspace.d[15];
-acadoWorkspace.lbA[7] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[7] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[7] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[7] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[22] + acadoWorkspace.d[18];
acadoWorkspace.lbA[8] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[8] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[23] + acadoWorkspace.d[19];
-acadoWorkspace.lbA[9] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[9] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[9] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[9] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[26] + acadoWorkspace.d[22];
acadoWorkspace.lbA[10] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[10] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[27] + acadoWorkspace.d[23];
-acadoWorkspace.lbA[11] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[11] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[11] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[11] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[30] + acadoWorkspace.d[26];
acadoWorkspace.lbA[12] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[12] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[31] + acadoWorkspace.d[27];
-acadoWorkspace.lbA[13] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[13] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[13] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[13] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[34] + acadoWorkspace.d[30];
acadoWorkspace.lbA[14] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[14] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[35] + acadoWorkspace.d[31];
-acadoWorkspace.lbA[15] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[15] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[15] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[15] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[38] + acadoWorkspace.d[34];
acadoWorkspace.lbA[16] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[16] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[39] + acadoWorkspace.d[35];
-acadoWorkspace.lbA[17] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[17] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[17] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[17] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[42] + acadoWorkspace.d[38];
acadoWorkspace.lbA[18] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[18] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[43] + acadoWorkspace.d[39];
-acadoWorkspace.lbA[19] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[19] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[19] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[19] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[46] + acadoWorkspace.d[42];
acadoWorkspace.lbA[20] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[20] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[47] + acadoWorkspace.d[43];
-acadoWorkspace.lbA[21] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[21] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[21] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[21] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[50] + acadoWorkspace.d[46];
acadoWorkspace.lbA[22] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[22] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[51] + acadoWorkspace.d[47];
-acadoWorkspace.lbA[23] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[23] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[23] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[23] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[54] + acadoWorkspace.d[50];
acadoWorkspace.lbA[24] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[24] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[55] + acadoWorkspace.d[51];
-acadoWorkspace.lbA[25] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[25] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[25] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[25] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[58] + acadoWorkspace.d[54];
acadoWorkspace.lbA[26] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[26] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[59] + acadoWorkspace.d[55];
-acadoWorkspace.lbA[27] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[27] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[27] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[27] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[62] + acadoWorkspace.d[58];
acadoWorkspace.lbA[28] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[28] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[63] + acadoWorkspace.d[59];
-acadoWorkspace.lbA[29] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[29] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[29] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[29] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[66] + acadoWorkspace.d[62];
acadoWorkspace.lbA[30] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[30] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[67] + acadoWorkspace.d[63];
-acadoWorkspace.lbA[31] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[31] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[31] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[31] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[70] + acadoWorkspace.d[66];
acadoWorkspace.lbA[32] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[32] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[71] + acadoWorkspace.d[67];
-acadoWorkspace.lbA[33] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[33] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[33] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[33] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[74] + acadoWorkspace.d[70];
acadoWorkspace.lbA[34] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[34] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[75] + acadoWorkspace.d[71];
-acadoWorkspace.lbA[35] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[35] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[35] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[35] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[78] + acadoWorkspace.d[74];
acadoWorkspace.lbA[36] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[36] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[79] + acadoWorkspace.d[75];
-acadoWorkspace.lbA[37] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[37] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[37] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[37] = (real_t)8.7266462600000005e-01 - tmp;
tmp = acadoVariables.x[82] + acadoWorkspace.d[78];
acadoWorkspace.lbA[38] = (real_t)-1.5707963268000000e+00 - tmp;
acadoWorkspace.ubA[38] = (real_t)1.5707963268000000e+00 - tmp;
tmp = acadoVariables.x[83] + acadoWorkspace.d[79];
-acadoWorkspace.lbA[39] = (real_t)-4.3633231300000003e-01 - tmp;
-acadoWorkspace.ubA[39] = (real_t)4.3633231300000003e-01 - tmp;
+acadoWorkspace.lbA[39] = (real_t)-8.7266462600000005e-01 - tmp;
+acadoWorkspace.ubA[39] = (real_t)8.7266462600000005e-01 - tmp;
}
diff --git a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
index 264a2ae033..d21dc585bc 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
+++ b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
@@ -1,7 +1,6 @@
#include
const int controlHorizon = 50;
-const double samplingTime = 0.2;
using namespace std;
diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
index 8020b63c9b..b45021a97f 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
+++ b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
@@ -1,11 +1,10 @@
import os
-import sys
import subprocess
from cffi import FFI
mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__)))
-subprocess.check_call(["make", "-j4"], stdout=sys.stderr, cwd=mpc_dir)
+subprocess.check_call(["make", "-j4"], cwd=mpc_dir)
def _get_libmpc(mpc_id):
@@ -19,16 +18,17 @@ def _get_libmpc(mpc_id):
typedef struct {
- double x_ego[20];
- double v_ego[20];
- double a_ego[20];
- double j_ego[20];
- double x_l[20];
- double v_l[20];
- double a_l[20];
+ double x_ego[21];
+ double v_ego[21];
+ double a_ego[21];
+ double j_ego[21];
+ double x_l[21];
+ double v_l[21];
+ double a_l[21];
+ double cost;
} log_t;
- void init();
+ void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost);
void init_with_simulation(double v_ego, double x_l, double v_l, double a_l, double l);
int run_mpc(state_t * x0, log_t * solution,
double l);
diff --git a/selfdrive/controls/lib/longitudinal_mpc/mpc.c b/selfdrive/controls/lib/longitudinal_mpc/mpc.c
index 4e2c13c1a1..c9226d67e8 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/mpc.c
+++ b/selfdrive/controls/lib/longitudinal_mpc/mpc.c
@@ -22,18 +22,20 @@ typedef struct {
typedef struct {
- double x_ego[N];
- double v_ego[N];
- double a_ego[N];
- double j_ego[N];
- double x_l[N];
- double v_l[N];
- double a_l[N];
+ double x_ego[N+1];
+ double v_ego[N+1];
+ double a_ego[N+1];
+ double j_ego[N+1];
+ double x_l[N+1];
+ double v_l[N+1];
+ double a_l[N+1];
+ double cost;
} log_t;
-void init(){
+void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost){
acado_initializeSolver();
int i;
+ const int STEP_MULTIPLIER = 3;
/* Initialize the states and controls. */
for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0;
@@ -50,16 +52,16 @@ void init(){
for (i = 0; i < N; i++) {
int f = 1;
if (i > 4){
- f = 3;
+ f = STEP_MULTIPLIER;
}
- acadoVariables.W[16 * i + 0] = 5.0 * f; // exponential cost for danger zone
- acadoVariables.W[16 * i + 5] = 0.1 * f; // desired distance
- acadoVariables.W[16 * i + 10] = 10.0 * f; // acceleration
- acadoVariables.W[16 * i + 15] = 20.0 * f; // jerk
+ acadoVariables.W[16 * i + 0] = ttcCost * f; // exponential cost for time-to-collision (ttc)
+ acadoVariables.W[16 * i + 5] = distanceCost * f; // desired distance
+ acadoVariables.W[16 * i + 10] = accelerationCost * f; // acceleration
+ acadoVariables.W[16 * i + 15] = jerkCost * f; // jerk
}
- acadoVariables.WN[0] = 5.0; // exponential cost for danger zone
- acadoVariables.WN[4] = 0.1; // desired distance
- acadoVariables.WN[8] = 10.0; // acceleration
+ acadoVariables.WN[0] = ttcCost * STEP_MULTIPLIER; // exponential cost for danger zone
+ acadoVariables.WN[4] = distanceCost * STEP_MULTIPLIER; // desired distance
+ acadoVariables.WN[8] = accelerationCost * STEP_MULTIPLIER; // acceleration
}
@@ -129,6 +131,7 @@ int run_mpc(state_t * x0, log_t * solution, double l){
solution->j_ego[i] = acadoVariables.u[i];
}
+ solution->cost = acado_getObjective();
// Dont shift states here. Current solution is closer to next timestep than if
// we shift by 0.2 seconds.
diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py
index 40ae836b9e..b25275d668 100644
--- a/selfdrive/controls/lib/pid.py
+++ b/selfdrive/controls/lib/pid.py
@@ -1,6 +1,5 @@
import numpy as np
from common.numpy_fast import clip, interp
-import numbers
def apply_deadzone(error, deadzone):
if error > deadzone:
@@ -30,21 +29,11 @@ class PIController(object):
@property
def k_p(self):
- if isinstance(self._k_p, numbers.Number):
- kp = self._k_p
- else:
- kp = interp(self.speed, self._k_p[0], self._k_p[1])
-
- return kp
+ return interp(self.speed, self._k_p[0], self._k_p[1])
@property
def k_i(self):
- if isinstance(self._k_i, numbers.Number):
- ki = self._k_i
- else:
- ki = interp(self.speed, self._k_i[0], self._k_i[1])
-
- return ki
+ return interp(self.speed, self._k_i[0], self._k_i[1])
def _check_saturation(self, control, override, error):
saturated = (control < self.neg_limit) or (control > self.pos_limit)
diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py
index 219ba42eed..24ae0f29a0 100755
--- a/selfdrive/controls/lib/planner.py
+++ b/selfdrive/controls/lib/planner.py
@@ -12,7 +12,7 @@ import selfdrive.messaging as messaging
from selfdrive.swaglog import cloudlog
from selfdrive.config import Conversions as CV
from selfdrive.services import service_list
-from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET
+from selfdrive.controls.lib.drive_helpers import create_event, MPC_COST_LONG, EventTypes as ET
from selfdrive.controls.lib.pathplanner import PathPlanner
from selfdrive.controls.lib.longitudinal_mpc import libmpc_py
from selfdrive.controls.lib.speed_smoother import speed_smoother
@@ -34,8 +34,8 @@ _A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.]
# need fast accel at very low speed for stop and go
# make sure these accelerations are smaller than mpc limits
-_A_CRUISE_MAX_V = [1., 1., .8, .5, .3]
-_A_CRUISE_MAX_V_FOLLOWING = [1.5, 1.5, 1.2, .7, .3]
+_A_CRUISE_MAX_V = [1.1, 1.1, .8, .5, .3]
+_A_CRUISE_MAX_V_FOLLOWING = [1.6, 1.6, 1.2, .7, .3]
_A_CRUISE_MAX_BP = [0., 5., 10., 20., 40.]
# Lookup table for turns
@@ -112,7 +112,7 @@ class FCWChecker(object):
def update(self, mpc_solution, cur_time, v_ego, a_ego, x_lead, v_lead, a_lead, y_lead, vlat_lead, fcw_lead, blinkers):
mpc_solution_a = list(mpc_solution[0].a_ego)
- self.last_min_a = min(mpc_solution_a[1:])
+ self.last_min_a = min(mpc_solution_a)
self.v_lead_max = max(self.v_lead_max, v_lead)
if (fcw_lead > 0.99):
@@ -127,7 +127,7 @@ class FCWChecker(object):
self.counters['blinkers'] = self.counters['blinkers'] + 10.0 / (20 * 3.0) if not blinkers else 0
a_thr = interp(v_lead, _FCW_A_ACT_BP, _FCW_A_ACT_V)
- a_delta = min(mpc_solution_a[1:15]) - min(0.0, a_ego)
+ a_delta = min(mpc_solution_a[:15]) - min(0.0, a_ego)
fcw_allowed = all(c >= 10 for c in self.counters.values())
if (self.last_min_a < -3.0 or a_delta < a_thr) and fcw_allowed and self.last_fcw_time + 5.0 < cur_time:
@@ -164,6 +164,7 @@ class LongitudinalMpc(object):
dat.liveLongitudinalMpc.xLead = list(self.mpc_solution[0].x_l)
dat.liveLongitudinalMpc.vLead = list(self.mpc_solution[0].v_l)
dat.liveLongitudinalMpc.aLead = list(self.mpc_solution[0].a_l)
+ dat.liveLongitudinalMpc.cost = self.mpc_solution[0].cost
dat.liveLongitudinalMpc.aLeadTau = self.l
dat.liveLongitudinalMpc.qpIterations = qp_iterations
dat.liveLongitudinalMpc.mpcId = self.mpc_id
@@ -172,7 +173,8 @@ class LongitudinalMpc(object):
def setup_mpc(self):
ffi, self.libmpc = libmpc_py.get_libmpc(self.mpc_id)
- self.libmpc.init()
+ self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE,
+ MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK)
self.mpc_solution = ffi.new("log_t *")
self.cur_state = ffi.new("state_t *")
@@ -234,10 +236,10 @@ class LongitudinalMpc(object):
self.v_mpc_future = self.mpc_solution[0].v_ego[10]
# Reset if NaN or goes through lead car
- dls = np.array(list(self.mpc_solution[0].x_l)[1:]) - np.array(list(self.mpc_solution[0].x_ego)[1:])
+ dls = np.array(list(self.mpc_solution[0].x_l)) - np.array(list(self.mpc_solution[0].x_ego))
crashing = min(dls) < -50.0
nans = np.any(np.isnan(list(self.mpc_solution[0].v_ego)))
- backwards = min(list(self.mpc_solution[0].v_ego)[1:]) < -0.01
+ backwards = min(list(self.mpc_solution[0].v_ego)) < -0.01
if ((backwards or crashing) and self.prev_lead_status) or nans:
if t > self.last_cloudlog_t + 5.0:
@@ -245,7 +247,8 @@ class LongitudinalMpc(object):
cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % (
self.mpc_id, backwards, crashing, nans))
- self.libmpc.init()
+ self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE,
+ MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK)
self.cur_state[0].v_ego = CS.vEgo
self.cur_state[0].a_ego = 0.0
self.v_mpc = CS.vEgo
@@ -334,7 +337,7 @@ class Planner(object):
self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint])
# this runs whenever we get a packet that can change the plan
- def update(self, CS, LoC, v_cruise_kph, user_distracted):
+ def update(self, CS, LaC, LoC, v_cruise_kph, user_distracted):
cur_time = sec_since_boot()
v_cruise_setpoint = v_cruise_kph * CV.KPH_TO_MS
@@ -457,6 +460,8 @@ class Planner(object):
events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
if 'fault' in self.radar_errors:
events.append(create_event('radarFault', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
+ if LaC.mpc_solution[0].cost > 10000. or LaC.mpc_nans: # TODO: find a better way to detect when MPC did not converge
+ events.append(create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
# Interpolation of trajectory
dt = min(cur_time - self.acc_start_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps
diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py
index 0fa226bc95..ca41da7cb6 100644
--- a/selfdrive/controls/lib/radar_helpers.py
+++ b/selfdrive/controls/lib/radar_helpers.py
@@ -213,7 +213,7 @@ class Cluster(object):
lead.fcw = self.is_potential_fcw()
def __str__(self):
- ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f d: %4.2f" % (self.dRel, self.yRel, self.vRel, self.aRel, self.dPath)
+ ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f d: %4.2f" % (self.dRel, self.yRel, self.vRel, self.aLeadK, self.dPath)
if self.stationary:
ret += " stationary"
if self.vision:
diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py
index 4ffe15cb0e..bf7d14b6f6 100755
--- a/selfdrive/controls/radard.py
+++ b/selfdrive/controls/radard.py
@@ -260,12 +260,13 @@ def radard_thread(gctx=None):
for cnt, ids in enumerate(tracks.keys()):
if DEBUG:
- print "id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f" % \
+ print "id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f v: %1.0f" % \
(ids, tracks[ids].dRel, tracks[ids].yRel, tracks[ids].vRel,
tracks[ids].dPath, tracks[ids].vLat,
tracks[ids].vLead, tracks[ids].vLeadK,
tracks[ids].aLeadK,
- tracks[ids].stationary)
+ tracks[ids].stationary,
+ tracks[ids].measured)
dat.liveTracks[cnt].trackId = ids
dat.liveTracks[cnt].dRel = float(tracks[ids].dRel)
dat.liveTracks[cnt].yRel = float(tracks[ids].yRel)
diff --git a/selfdrive/crash.py b/selfdrive/crash.py
index 18c27ec1f5..20003ee9fa 100644
--- a/selfdrive/crash.py
+++ b/selfdrive/crash.py
@@ -1,6 +1,7 @@
"""Install exception handler for process crash."""
import os
import sys
+from selfdrive.version import version, dirty
from selfdrive.swaglog import cloudlog
@@ -16,9 +17,8 @@ if os.getenv("NOLOG") or os.getenv("NOCRASH"):
else:
from raven import Client
from raven.transport.http import HTTPTransport
-
client = Client('https://1994756b5e6f41cf939a4c65de45f4f2:cefebaf3a8aa40d182609785f7189bd7@app.getsentry.com/77924',
- install_sys_hook=False, transport=HTTPTransport)
+ install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty})
def capture_exception(*args, **kwargs):
client.captureException(*args, **kwargs)
diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py
index e1713d34f7..89dd43fa4c 100755
--- a/selfdrive/debug/dump.py
+++ b/selfdrive/debug/dump.py
@@ -4,10 +4,15 @@ import argparse
import zmq
import json
from hexdump import hexdump
+from threading import Thread
+from cereal import log
import selfdrive.messaging as messaging
from selfdrive.services import service_list
+def run_server(socketio):
+ socketio.run(app, host='0.0.0.0', port=4000)
+
if __name__ == "__main__":
context = zmq.Context()
poller = zmq.Poller()
@@ -17,33 +22,63 @@ if __name__ == "__main__":
parser.add_argument('--raw', action='store_true')
parser.add_argument('--json', action='store_true')
parser.add_argument('--dump-json', action='store_true')
+ parser.add_argument('--no-print', action='store_true')
+ parser.add_argument('--proxy', action='store_true', help='republish on localhost')
+ parser.add_argument('--map', action='store_true')
parser.add_argument('--addr', default='127.0.0.1')
parser.add_argument("socket", type=str, nargs='*', help="socket name")
args = parser.parse_args()
+ republish_socks = {}
+
for m in args.socket if len(args.socket) > 0 else service_list:
if m in service_list:
- messaging.sub_sock(context, service_list[m].port, poller, addr=args.addr)
+ port = service_list[m].port
elif m.isdigit():
- messaging.sub_sock(context, int(m), poller, addr=args.addr)
+ port = int(m)
else:
print("service not found")
exit(-1)
+ sock = messaging.sub_sock(context, port, poller, addr=args.addr)
+ if args.proxy:
+ republish_socks[sock] = messaging.pub_sock(context, port)
+
+ if args.map:
+ from flask.ext.socketio import SocketIO
+ from flask import Flask
+ app = Flask(__name__)
+ socketio = SocketIO(app, async_mode='threading')
+ server_thread = Thread(target=run_server, args=(socketio,))
+ server_thread.daemon = True
+ server_thread.start()
+ print 'server running'
while 1:
polld = poller.poll(timeout=1000)
for sock, mode in polld:
if mode != zmq.POLLIN:
continue
- if args.pipe:
- sys.stdout.write(sock.recv())
- sys.stdout.flush()
- elif args.raw:
- hexdump(sock.recv())
- elif args.json:
- print(json.loads(sock.recv()))
- elif args.dump_json:
- print json.dumps(messaging.recv_one(sock).to_dict())
- else:
- print messaging.recv_one(sock)
+ msg = sock.recv()
+ evt = log.Event.from_bytes(msg)
+ if sock in republish_socks:
+ republish_socks[sock].send(msg)
+ if args.map and evt.which() == 'liveLocation':
+ print 'send loc'
+ socketio.emit('location', {
+ 'lat': evt.liveLocation.lat,
+ 'lon': evt.liveLocation.lon,
+ 'alt': evt.liveLocation.alt,
+ })
+ if not args.no_print:
+ if args.pipe:
+ sys.stdout.write(msg)
+ sys.stdout.flush()
+ elif args.raw:
+ hexdump(msg)
+ elif args.json:
+ print(json.loads(msg))
+ elif args.dump_json:
+ print json.dumps(evt.to_dict())
+ else:
+ print evt
diff --git a/selfdrive/locationd/__init__.py b/selfdrive/locationd/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/selfdrive/locationd/ephemeris.py b/selfdrive/locationd/ephemeris.py
new file mode 100644
index 0000000000..0fbedf5250
--- /dev/null
+++ b/selfdrive/locationd/ephemeris.py
@@ -0,0 +1,140 @@
+def GET_FIELD_U(w, nb, pos):
+ return (((w) >> (pos)) & ((1 << (nb)) - 1))
+
+
+def twos_complement(v, nb):
+ sign = v >> (nb - 1)
+ value = v
+ if sign != 0:
+ value = value - (1 << nb)
+ return value
+
+
+def GET_FIELD_S(w, nb, pos):
+ v = GET_FIELD_U(w, nb, pos)
+ return twos_complement(v, nb)
+
+
+def extract_uint8(v, b):
+ return (v >> (8 * (3 - b))) & 255
+
+def extract_int8(v, b):
+ value = extract_uint8(v, b)
+ if value > 127:
+ value -= 256
+ return value
+
+class EphemerisData:
+ '''container for parsing a AID_EPH message
+ Thanks to Sylvain Munaut
+ http://cgit.osmocom.org/cgit/osmocom-lcs/tree/gps.c
+on of this parser
+
+ See IS-GPS-200F.pdf Table 20-III for the field meanings, scaling factors and
+ field widths
+ '''
+
+ def __init__(self, svId, subframes):
+ from math import pow
+ self.svId = svId
+ week_no = GET_FIELD_U(subframes[1][2+0], 10, 20)
+ # code_on_l2 = GET_FIELD_U(subframes[1][0], 2, 12)
+ # sv_ura = GET_FIELD_U(subframes[1][0], 4, 8)
+ # sv_health = GET_FIELD_U(subframes[1][0], 6, 2)
+ # l2_p_flag = GET_FIELD_U(subframes[1][1], 1, 23)
+ t_gd = GET_FIELD_S(subframes[1][2+4], 8, 6)
+ iodc = (GET_FIELD_U(subframes[1][2+0], 2, 6) << 8) | GET_FIELD_U(
+ subframes[1][2+5], 8, 22)
+
+ t_oc = GET_FIELD_U(subframes[1][2+5], 16, 6)
+ a_f2 = GET_FIELD_S(subframes[1][2+6], 8, 22)
+ a_f1 = GET_FIELD_S(subframes[1][2+6], 16, 6)
+ a_f0 = GET_FIELD_S(subframes[1][2+7], 22, 8)
+
+ c_rs = GET_FIELD_S(subframes[2][2+0], 16, 6)
+ delta_n = GET_FIELD_S(subframes[2][2+1], 16, 14)
+ m_0 = (GET_FIELD_S(subframes[2][2+1], 8, 6) << 24) | GET_FIELD_U(
+ subframes[2][2+2], 24, 6)
+ c_uc = GET_FIELD_S(subframes[2][2+3], 16, 14)
+ e = (GET_FIELD_U(subframes[2][2+3], 8, 6) << 24) | GET_FIELD_U(subframes[2][2+4], 24, 6)
+ c_us = GET_FIELD_S(subframes[2][2+5], 16, 14)
+ a_powhalf = (GET_FIELD_U(subframes[2][2+5], 8, 6) << 24) | GET_FIELD_U(
+ subframes[2][2+6], 24, 6)
+ t_oe = GET_FIELD_U(subframes[2][2+7], 16, 14)
+ # fit_flag = GET_FIELD_U(subframes[2][7], 1, 7)
+
+ c_ic = GET_FIELD_S(subframes[3][2+0], 16, 14)
+ omega_0 = (GET_FIELD_S(subframes[3][2+0], 8, 6) << 24) | GET_FIELD_U(
+ subframes[3][2+1], 24, 6)
+ c_is = GET_FIELD_S(subframes[3][2+2], 16, 14)
+ i_0 = (GET_FIELD_S(subframes[3][2+2], 8, 6) << 24) | GET_FIELD_U(
+ subframes[3][2+3], 24, 6)
+ c_rc = GET_FIELD_S(subframes[3][2+4], 16, 14)
+ w = (GET_FIELD_S(subframes[3][2+4], 8, 6) << 24) | GET_FIELD_U(subframes[3][5], 24, 6)
+ omega_dot = GET_FIELD_S(subframes[3][2+6], 24, 6)
+ idot = GET_FIELD_S(subframes[3][2+7], 14, 8)
+
+ self._rsvd1 = GET_FIELD_U(subframes[1][2+1], 23, 6)
+ self._rsvd2 = GET_FIELD_U(subframes[1][2+2], 24, 6)
+ self._rsvd3 = GET_FIELD_U(subframes[1][2+3], 24, 6)
+ self._rsvd4 = GET_FIELD_U(subframes[1][2+4], 16, 14)
+ self.aodo = GET_FIELD_U(subframes[2][2+7], 5, 8)
+
+ # Definition of Pi used in the GPS coordinate system
+ gpsPi = 3.1415926535898
+
+ # now form variables in radians, meters and seconds etc
+ self.Tgd = t_gd * pow(2, -31)
+ self.A = pow(a_powhalf * pow(2, -19), 2.0)
+ self.cic = c_ic * pow(2, -29)
+ self.cis = c_is * pow(2, -29)
+ self.crc = c_rc * pow(2, -5)
+ self.crs = c_rs * pow(2, -5)
+ self.cuc = c_uc * pow(2, -29)
+ self.cus = c_us * pow(2, -29)
+ self.deltaN = delta_n * pow(2, -43) * gpsPi
+ self.ecc = e * pow(2, -33)
+ self.i0 = i_0 * pow(2, -31) * gpsPi
+ self.idot = idot * pow(2, -43) * gpsPi
+ self.M0 = m_0 * pow(2, -31) * gpsPi
+ self.omega = w * pow(2, -31) * gpsPi
+ self.omega_dot = omega_dot * pow(2, -43) * gpsPi
+ self.omega0 = omega_0 * pow(2, -31) * gpsPi
+ self.toe = t_oe * pow(2, 4)
+
+ # clock correction information
+ self.toc = t_oc * pow(2, 4)
+ self.gpsWeek = week_no
+ self.af0 = a_f0 * pow(2, -31)
+ self.af1 = a_f1 * pow(2, -43)
+ self.af2 = a_f2 * pow(2, -55)
+
+ iode1 = GET_FIELD_U(subframes[2][2+0], 8, 22)
+ iode2 = GET_FIELD_U(subframes[3][2+7], 8, 22)
+ self.valid = (iode1 == iode2) and (iode1 == (iodc & 0xff))
+ self.iode = iode1
+
+ if GET_FIELD_U(subframes[4][2+0], 2, 28) != 1:
+ raise RuntimeError("subframe 4 not of type 1")
+ if GET_FIELD_U(subframes[5][2+0], 2, 28) != 1:
+ raise RuntimeError("subframe 5 not of type 1")
+ print 'page :', GET_FIELD_U(subframes[4][2+0], 6, 22)
+ if GET_FIELD_U(subframes[4][2+0], 6, 22) == 56:
+ a0 = GET_FIELD_S(subframes[4][2], 8, 14) * pow(2, -30)
+ a1 = GET_FIELD_S(subframes[4][2], 8, 6) * pow(2, -27)
+ a2 = GET_FIELD_S(subframes[4][3], 8, 22) * pow(2, -24)
+ a3 = GET_FIELD_S(subframes[4][3], 8, 14) * pow(2, -24)
+ b0 = GET_FIELD_S(subframes[4][3], 8, 6) * pow(2, 11)
+ b1 = GET_FIELD_S(subframes[4][4], 8, 22) * pow(2, 14)
+ b2 = GET_FIELD_S(subframes[4][4], 8, 14) * pow(2, 16)
+ b3 = GET_FIELD_S(subframes[4][4], 8, 6) * pow(2, 16)
+
+ self.ionoAlpha = [a0, a1, a2, a3]
+ self.ionoBeta = [b0, b1, b2, b3]
+ self.ionoCoeffsValid = True
+ else:
+ self.ionoAlpha = []
+ self.ionoBeta = []
+ self.ionoCoeffsValid = False
+
+
diff --git a/selfdrive/locationd/locationd_dummy.py b/selfdrive/locationd/locationd_dummy.py
new file mode 100755
index 0000000000..2c44932f1e
--- /dev/null
+++ b/selfdrive/locationd/locationd_dummy.py
@@ -0,0 +1,73 @@
+#!/usr/bin/env python
+import zmq
+from copy import copy
+from selfdrive import messaging
+from selfdrive.services import service_list
+from cereal import log
+
+from common.transformations.coordinates import geodetic2ecef
+
+def main(gctx=None):
+ context = zmq.Context()
+ poller = zmq.Poller()
+ gps_sock = messaging.sub_sock(context, service_list['gpsLocation'].port, poller)
+ gps_ext_sock = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, poller)
+ app_sock = messaging.sub_sock(context, service_list['applanixLocation'].port, poller)
+ loc_sock = messaging.pub_sock(context, service_list['liveLocation'].port)
+
+ last_ext, last_gps, last_app = -1, -1, -1
+ # 5 sec
+ max_gap = 5*1e9
+ preferred_type = None
+
+ while 1:
+ for sock, event in poller.poll(500):
+ if sock is app_sock:
+ msg = messaging.recv_one(sock)
+ last_app = msg.logMonoTime
+ this_type = 'app'
+ if sock is gps_sock:
+ msg = messaging.recv_one(sock)
+ gps_pkt = msg.gpsLocation
+ last_gps = msg.logMonoTime
+ this_type = 'gps'
+ if sock is gps_ext_sock:
+ msg = messaging.recv_one(sock)
+ gps_pkt = msg.gpsLocationExternal
+ last_ext = msg.logMonoTime
+ this_type = 'ext'
+
+ last = max(last_gps, last_ext, last_app)
+
+ if last_app > last - max_gap:
+ new_preferred_type = 'app'
+ elif last_ext > last - max_gap:
+ new_preferred_type = 'ext'
+ else:
+ new_preferred_type = 'gps'
+
+ if preferred_type != new_preferred_type:
+ print "switching from %s to %s" % (preferred_type, new_preferred_type)
+ preferred_type = new_preferred_type
+
+ if this_type == preferred_type:
+ new_msg = messaging.new_message()
+ if this_type == 'app':
+ # straight proxy the applanix
+ new_msg.init('liveLocation')
+ new_msg.liveLocation = copy(msg.applanixLocation)
+ else:
+ new_msg.logMonoTime = msg.logMonoTime
+ new_msg.init('liveLocation')
+ pkt = new_msg.liveLocation
+ pkt.lat = gps_pkt.latitude
+ pkt.lon = gps_pkt.longitude
+ pkt.alt = gps_pkt.altitude
+ pkt.speed = gps_pkt.speed
+ pkt.heading = gps_pkt.bearing
+ pkt.positionECEF = [float(x) for x in geodetic2ecef([pkt.lat, pkt.lon, pkt.alt])]
+ pkt.source = log.LiveLocationData.SensorSource.dummy
+ loc_sock.send(new_msg.to_bytes())
+
+if __name__ == '__main__':
+ main()
diff --git a/selfdrive/locationd/ublox.py b/selfdrive/locationd/ublox.py
new file mode 100644
index 0000000000..228dfc8433
--- /dev/null
+++ b/selfdrive/locationd/ublox.py
@@ -0,0 +1,995 @@
+#!/usr/bin/env python
+'''
+UBlox binary protocol handling
+
+Copyright Andrew Tridgell, October 2012
+Released under GNU GPL version 3 or later
+
+WARNING: This code has originally intended for
+ublox version 7, it has been adapted to work
+for ublox version 8, not all functions may work.
+'''
+
+import struct
+import time, os
+
+# protocol constants
+PREAMBLE1 = 0xb5
+PREAMBLE2 = 0x62
+
+# message classes
+CLASS_NAV = 0x01
+CLASS_RXM = 0x02
+CLASS_INF = 0x04
+CLASS_ACK = 0x05
+CLASS_CFG = 0x06
+CLASS_MON = 0x0A
+CLASS_AID = 0x0B
+CLASS_TIM = 0x0D
+CLASS_ESF = 0x10
+
+# ACK messages
+MSG_ACK_NACK = 0x00
+MSG_ACK_ACK = 0x01
+
+# NAV messages
+MSG_NAV_POSECEF = 0x1
+MSG_NAV_POSLLH = 0x2
+MSG_NAV_STATUS = 0x3
+MSG_NAV_DOP = 0x4
+MSG_NAV_SOL = 0x6
+MSG_NAV_PVT = 0x7
+MSG_NAV_POSUTM = 0x8
+MSG_NAV_VELNED = 0x12
+MSG_NAV_VELECEF = 0x11
+MSG_NAV_TIMEGPS = 0x20
+MSG_NAV_TIMEUTC = 0x21
+MSG_NAV_CLOCK = 0x22
+MSG_NAV_SVINFO = 0x30
+MSG_NAV_AOPSTATUS = 0x60
+MSG_NAV_DGPS = 0x31
+MSG_NAV_DOP = 0x04
+MSG_NAV_EKFSTATUS = 0x40
+MSG_NAV_SBAS = 0x32
+MSG_NAV_SOL = 0x06
+
+# RXM messages
+MSG_RXM_RAW = 0x15
+MSG_RXM_SFRB = 0x11
+MSG_RXM_SFRBX = 0x13
+MSG_RXM_SVSI = 0x20
+MSG_RXM_EPH = 0x31
+MSG_RXM_ALM = 0x30
+MSG_RXM_PMREQ = 0x41
+
+# AID messages
+MSG_AID_ALM = 0x30
+MSG_AID_EPH = 0x31
+MSG_AID_ALPSRV = 0x32
+MSG_AID_AOP = 0x33
+MSG_AID_DATA = 0x10
+MSG_AID_ALP = 0x50
+MSG_AID_DATA = 0x10
+MSG_AID_HUI = 0x02
+MSG_AID_INI = 0x01
+MSG_AID_REQ = 0x00
+
+# CFG messages
+MSG_CFG_PRT = 0x00
+MSG_CFG_ANT = 0x13
+MSG_CFG_DAT = 0x06
+MSG_CFG_EKF = 0x12
+MSG_CFG_ESFGWT = 0x29
+MSG_CFG_CFG = 0x09
+MSG_CFG_USB = 0x1b
+MSG_CFG_RATE = 0x08
+MSG_CFG_SET_RATE = 0x01
+MSG_CFG_NAV5 = 0x24
+MSG_CFG_FXN = 0x0E
+MSG_CFG_INF = 0x02
+MSG_CFG_ITFM = 0x39
+MSG_CFG_MSG = 0x01
+MSG_CFG_NAVX5 = 0x23
+MSG_CFG_NMEA = 0x17
+MSG_CFG_NVS = 0x22
+MSG_CFG_PM2 = 0x3B
+MSG_CFG_PM = 0x32
+MSG_CFG_RINV = 0x34
+MSG_CFG_RST = 0x04
+MSG_CFG_RXM = 0x11
+MSG_CFG_SBAS = 0x16
+MSG_CFG_TMODE2 = 0x3D
+MSG_CFG_TMODE = 0x1D
+MSG_CFG_TPS = 0x31
+MSG_CFG_TP = 0x07
+MSG_CFG_GNSS = 0x3E
+MSG_CFG_ODO = 0x1E
+
+# ESF messages
+MSG_ESF_MEAS = 0x02
+MSG_ESF_STATUS = 0x10
+
+# INF messages
+MSG_INF_DEBUG = 0x04
+MSG_INF_ERROR = 0x00
+MSG_INF_NOTICE = 0x02
+MSG_INF_TEST = 0x03
+MSG_INF_WARNING = 0x01
+
+# MON messages
+MSG_MON_SCHD = 0x01
+MSG_MON_HW = 0x09
+MSG_MON_HW2 = 0x0B
+MSG_MON_IO = 0x02
+MSG_MON_MSGPP = 0x06
+MSG_MON_RXBUF = 0x07
+MSG_MON_RXR = 0x21
+MSG_MON_TXBUF = 0x08
+MSG_MON_VER = 0x04
+
+# TIM messages
+MSG_TIM_TP = 0x01
+MSG_TIM_TM2 = 0x03
+MSG_TIM_SVIN = 0x04
+MSG_TIM_VRFY = 0x06
+
+# port IDs
+PORT_DDC = 0
+PORT_SERIAL1 = 1
+PORT_SERIAL2 = 2
+PORT_USB = 3
+PORT_SPI = 4
+
+# dynamic models
+DYNAMIC_MODEL_PORTABLE = 0
+DYNAMIC_MODEL_STATIONARY = 2
+DYNAMIC_MODEL_PEDESTRIAN = 3
+DYNAMIC_MODEL_AUTOMOTIVE = 4
+DYNAMIC_MODEL_SEA = 5
+DYNAMIC_MODEL_AIRBORNE1G = 6
+DYNAMIC_MODEL_AIRBORNE2G = 7
+DYNAMIC_MODEL_AIRBORNE4G = 8
+
+#reset items
+RESET_HOT = 0
+RESET_WARM = 1
+RESET_COLD = 0xFFFF
+
+RESET_HW = 0
+RESET_SW = 1
+RESET_SW_GPS = 2
+RESET_HW_GRACEFUL = 4
+RESET_GPS_STOP = 8
+RESET_GPS_START = 9
+
+
+class UBloxError(Exception):
+ '''Ublox error class'''
+
+ def __init__(self, msg):
+ Exception.__init__(self, msg)
+ self.message = msg
+
+
+class UBloxAttrDict(dict):
+ '''allow dictionary members as attributes'''
+
+ def __init__(self):
+ dict.__init__(self)
+
+ def __getattr__(self, name):
+ try:
+ return self.__getitem__(name)
+ except KeyError:
+ raise AttributeError(name)
+
+ def __setattr__(self, name, value):
+ if self.__dict__.has_key(name):
+ # allow set on normal attributes
+ dict.__setattr__(self, name, value)
+ else:
+ self.__setitem__(name, value)
+
+
+def ArrayParse(field):
+ '''parse an array descriptor'''
+ arridx = field.find('[')
+ if arridx == -1:
+ return (field, -1)
+ alen = int(field[arridx + 1:-1])
+ fieldname = field[:arridx]
+ return (fieldname, alen)
+
+
+class UBloxDescriptor:
+ '''class used to describe the layout of a UBlox message'''
+
+ def __init__(self,
+ name,
+ msg_format,
+ fields=[],
+ count_field=None,
+ format2=None,
+ fields2=None):
+ self.name = name
+ self.msg_format = msg_format
+ self.fields = fields
+ self.count_field = count_field
+ self.format2 = format2
+ self.fields2 = fields2
+
+ def unpack(self, msg):
+ '''unpack a UBloxMessage, creating the .fields and ._recs attributes in msg'''
+ msg._fields = {}
+
+ # unpack main message blocks. A comm
+ formats = self.msg_format.split(',')
+ buf = msg._buf[6:-2]
+ count = 0
+ msg._recs = []
+ fields = self.fields[:]
+
+ for fmt in formats:
+ size1 = struct.calcsize(fmt)
+ if size1 > len(buf):
+ raise UBloxError("%s INVALID_SIZE1=%u" % (self.name, len(buf)))
+ f1 = list(struct.unpack(fmt, buf[:size1]))
+ i = 0
+ while i < len(f1):
+ field = fields.pop(0)
+ (fieldname, alen) = ArrayParse(field)
+ if alen == -1:
+ msg._fields[fieldname] = f1[i]
+ if self.count_field == fieldname:
+ count = int(f1[i])
+ i += 1
+ else:
+ msg._fields[fieldname] = [0] * alen
+ for a in range(alen):
+ msg._fields[fieldname][a] = f1[i]
+ i += 1
+ buf = buf[size1:]
+ if len(buf) == 0:
+ break
+
+ if self.count_field == '_remaining':
+ count = len(buf) / struct.calcsize(self.format2)
+
+ if count == 0:
+ msg._unpacked = True
+ if len(buf) != 0:
+ raise UBloxError("EXTRA_BYTES=%u" % len(buf))
+ return
+
+ size2 = struct.calcsize(self.format2)
+ for c in range(count):
+ r = UBloxAttrDict()
+ if size2 > len(buf):
+ raise UBloxError("INVALID_SIZE=%u, " % len(buf))
+ f2 = list(struct.unpack(self.format2, buf[:size2]))
+ for i in range(len(self.fields2)):
+ r[self.fields2[i]] = f2[i]
+ buf = buf[size2:]
+ msg._recs.append(r)
+ if len(buf) != 0:
+ raise UBloxError("EXTRA_BYTES=%u" % len(buf))
+ msg._unpacked = True
+
+ def pack(self, msg, msg_class=None, msg_id=None):
+ '''pack a UBloxMessage from the .fields and ._recs attributes in msg'''
+ f1 = []
+ if msg_class is None:
+ msg_class = msg.msg_class()
+ if msg_id is None:
+ msg_id = msg.msg_id()
+ msg._buf = ''
+
+ fields = self.fields[:]
+ for f in fields:
+ (fieldname, alen) = ArrayParse(f)
+ if not fieldname in msg._fields:
+ break
+ if alen == -1:
+ f1.append(msg._fields[fieldname])
+ else:
+ for a in range(alen):
+ f1.append(msg._fields[fieldname][a])
+ try:
+ # try full length message
+ fmt = self.msg_format.replace(',', '')
+ msg._buf = struct.pack(fmt, *tuple(f1))
+ except Exception:
+ # try without optional part
+ fmt = self.msg_format.split(',')[0]
+ msg._buf = struct.pack(fmt, *tuple(f1))
+
+ length = len(msg._buf)
+ if msg._recs:
+ length += len(msg._recs) * struct.calcsize(self.format2)
+ header = struct.pack('= level:
+ print(msg)
+
+ def unpack(self):
+ '''unpack a message'''
+ if not self.valid():
+ raise UBloxError('INVALID MESSAGE')
+ type = self.msg_type()
+ if not type in msg_types:
+ raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf)))
+ msg_types[type].unpack(self)
+ return self._fields, self._recs
+
+ def pack(self):
+ '''pack a message'''
+ if not self.valid():
+ raise UBloxError('INVALID MESSAGE')
+ type = self.msg_type()
+ if not type in msg_types:
+ raise UBloxError('Unknown message %s' % str(type))
+ msg_types[type].pack(self)
+
+ def name(self):
+ '''return the short string name for a message'''
+ if not self.valid():
+ raise UBloxError('INVALID MESSAGE')
+ type = self.msg_type()
+ if not type in msg_types:
+ raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf)))
+ return msg_types[type].name
+
+ def msg_class(self):
+ '''return the message class'''
+ return ord(self._buf[2])
+
+ def msg_id(self):
+ '''return the message id within the class'''
+ return ord(self._buf[3])
+
+ def msg_type(self):
+ '''return the message type tuple (class, id)'''
+ return (self.msg_class(), self.msg_id())
+
+ def msg_length(self):
+ '''return the payload length'''
+ (payload_length, ) = struct.unpack(' 0 and ord(self._buf[0]) != PREAMBLE1:
+ return False
+ if len(self._buf) > 1 and ord(self._buf[1]) != PREAMBLE2:
+ self.debug(1, "bad pre2")
+ return False
+ if self.needed_bytes() == 0 and not self.valid():
+ if len(self._buf) > 8:
+ self.debug(1, "bad checksum len=%u needed=%u" % (len(self._buf),
+ self.needed_bytes()))
+ else:
+ self.debug(1, "bad len len=%u needed=%u" % (len(self._buf), self.needed_bytes()))
+ return False
+ return True
+
+ def add(self, bytes):
+ '''add some bytes to a message'''
+ self._buf += bytes
+ while not self.valid_so_far() and len(self._buf) > 0:
+ '''handle corrupted streams'''
+ self._buf = self._buf[1:]
+ if self.needed_bytes() < 0:
+ self._buf = ""
+
+ def checksum(self, data=None):
+ '''return a checksum tuple for a message'''
+ if data is None:
+ data = self._buf[2:-2]
+ #cs = 0
+ ck_a = 0
+ ck_b = 0
+ for i in data:
+ ck_a = (ck_a + ord(i)) & 0xFF
+ ck_b = (ck_b + ck_a) & 0xFF
+ return (ck_a, ck_b)
+
+ def valid_checksum(self):
+ '''check if the checksum is OK'''
+ (ck_a, ck_b) = self.checksum()
+ #d = self._buf[2:-2]
+ (ck_a2, ck_b2) = struct.unpack('= 8 and self.needed_bytes() == 0 and self.valid_checksum()
+
+
+class UBlox:
+ '''main UBlox control class.
+
+ port can be a file (for reading only) or a serial device
+ '''
+
+ def __init__(self, port, baudrate=115200, timeout=0, panda=False, grey=False):
+
+ self.serial_device = port
+ self.baudrate = baudrate
+ self.use_sendrecv = False
+ self.read_only = False
+ self.debug_level = 0
+
+ if panda:
+ from panda import Panda, PandaSerial
+
+ self.panda = Panda()
+
+ # resetting U-Blox module
+ self.panda.set_esp_power(0)
+ time.sleep(0.1)
+ self.panda.set_esp_power(1)
+ time.sleep(0.5)
+
+ # can't set above 9600 now...
+ self.baudrate = 9600
+ self.dev = PandaSerial(self.panda, 1, self.baudrate)
+
+ self.baudrate = 460800
+ print "upping baud:",self.baudrate
+ self.send_nmea("$PUBX,41,1,0007,0003,%u,0" % self.baudrate)
+ time.sleep(0.1)
+
+ self.dev = PandaSerial(self.panda, 1, self.baudrate)
+ elif grey:
+ import zmq
+ from selfdrive.services import service_list
+ import selfdrive.messaging as messaging
+
+ class BoarddSerial(object):
+ def __init__(self):
+ context = zmq.Context()
+ self.ubloxRaw = messaging.sub_sock(context, service_list['ubloxRaw'].port)
+ self.buf = ""
+
+ def read(self, n):
+ for msg in messaging.drain_sock(self.ubloxRaw, len(self.buf) < n):
+ self.buf += msg.ubloxRaw
+ ret = self.buf[:n]
+ self.buf = self.buf[n:]
+ return ret
+
+
+ def write(self, dat):
+ pass
+
+ self.dev = BoarddSerial()
+ else:
+ if self.serial_device.startswith("tcp:"):
+ import socket
+ a = self.serial_device.split(':')
+ destination_addr = (a[1], int(a[2]))
+ self.dev = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
+ self.dev.connect(destination_addr)
+ self.dev.setblocking(1)
+ self.dev.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
+ self.use_sendrecv = True
+ elif os.path.isfile(self.serial_device):
+ self.read_only = True
+ self.dev = open(self.serial_device, mode='rb')
+ else:
+ import serial
+ self.dev = serial.Serial(
+ self.serial_device,
+ baudrate=self.baudrate,
+ dsrdtr=False,
+ rtscts=False,
+ xonxoff=False,
+ timeout=timeout)
+
+ self.logfile = None
+ self.log = None
+ self.preferred_dynamic_model = None
+ self.preferred_usePPP = None
+ self.preferred_dgps_timeout = None
+
+ def close(self):
+ '''close the device'''
+ self.dev.close()
+ self.dev = None
+
+ def set_debug(self, debug_level):
+ '''set debug level'''
+ self.debug_level = debug_level
+
+ def debug(self, level, msg):
+ '''write a debug message'''
+ if self.debug_level >= level:
+ print(msg)
+
+ def set_logfile(self, logfile, append=False):
+ '''setup logging to a file'''
+ if self.log is not None:
+ self.log.close()
+ self.log = None
+ self.logfile = logfile
+ if self.logfile is not None:
+ if append:
+ mode = 'ab'
+ else:
+ mode = 'wb'
+ self.log = open(self.logfile, mode=mode)
+
+ def set_preferred_dynamic_model(self, model):
+ '''set the preferred dynamic model for receiver'''
+ self.preferred_dynamic_model = model
+ if model is not None:
+ self.configure_poll(CLASS_CFG, MSG_CFG_NAV5)
+
+ def set_preferred_dgps_timeout(self, timeout):
+ '''set the preferred DGPS timeout for receiver'''
+ self.preferred_dgps_timeout = timeout
+ if timeout is not None:
+ self.configure_poll(CLASS_CFG, MSG_CFG_NAV5)
+
+ def set_preferred_usePPP(self, usePPP):
+ '''set the preferred usePPP setting for the receiver'''
+ if usePPP is None:
+ self.preferred_usePPP = None
+ return
+ self.preferred_usePPP = int(usePPP)
+ self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5)
+
+ def nmea_checksum(self, msg):
+ d = msg[1:]
+ cs = 0
+ for i in d:
+ cs ^= ord(i)
+ return cs
+
+ def write(self, buf):
+ '''write some bytes'''
+ if not self.read_only:
+ if self.use_sendrecv:
+ return self.dev.send(buf)
+ return self.dev.write(buf)
+
+ def read(self, n):
+ '''read some bytes'''
+ if self.use_sendrecv:
+ import socket
+ try:
+ return self.dev.recv(n)
+ except socket.error:
+ return ''
+ return self.dev.read(n)
+
+ def send_nmea(self, msg):
+ if not self.read_only:
+ s = msg + "*%02X" % self.nmea_checksum(msg) + "\r\n"
+ self.write(s)
+
+ def set_binary(self):
+ '''put a UBlox into binary mode using a NMEA string'''
+ if not self.read_only:
+ print("try set binary at %u" % self.baudrate)
+ self.send_nmea("$PUBX,41,0,0007,0001,%u,0" % self.baudrate)
+ self.send_nmea("$PUBX,41,1,0007,0001,%u,0" % self.baudrate)
+ self.send_nmea("$PUBX,41,2,0007,0001,%u,0" % self.baudrate)
+ self.send_nmea("$PUBX,41,3,0007,0001,%u,0" % self.baudrate)
+ self.send_nmea("$PUBX,41,4,0007,0001,%u,0" % self.baudrate)
+ self.send_nmea("$PUBX,41,5,0007,0001,%u,0" % self.baudrate)
+
+ def disable_nmea(self):
+ ''' stop sending all types of nmea messages '''
+ self.send_nmea("$PUBX,40,GSV,1,1,1,1,1,0")
+ self.send_nmea("$PUBX,40,GGA,0,0,0,0,0,0")
+ self.send_nmea("$PUBX,40,GSA,0,0,0,0,0,0")
+ self.send_nmea("$PUBX,40,VTG,0,0,0,0,0,0")
+ self.send_nmea("$PUBX,40,TXT,0,0,0,0,0,0")
+ self.send_nmea("$PUBX,40,RMC,0,0,0,0,0,0")
+
+ def seek_percent(self, pct):
+ '''seek to the given percentage of a file'''
+ self.dev.seek(0, 2)
+ filesize = self.dev.tell()
+ self.dev.seek(pct * 0.01 * filesize)
+
+ def special_handling(self, msg):
+ '''handle automatic configuration changes'''
+ if msg.name() == 'CFG_NAV5':
+ msg.unpack()
+ sendit = False
+ pollit = False
+ if self.preferred_dynamic_model is not None and msg.dynModel != self.preferred_dynamic_model:
+ msg.dynModel = self.preferred_dynamic_model
+ sendit = True
+ pollit = True
+ if self.preferred_dgps_timeout is not None and msg.dgpsTimeOut != self.preferred_dgps_timeout:
+ msg.dgpsTimeOut = self.preferred_dgps_timeout
+ self.debug(2, "Setting dgpsTimeOut=%u" % msg.dgpsTimeOut)
+ sendit = True
+ # we don't re-poll for this one, as some receivers refuse to set it
+ if sendit:
+ msg.pack()
+ self.send(msg)
+ if pollit:
+ self.configure_poll(CLASS_CFG, MSG_CFG_NAV5)
+ if msg.name() == 'CFG_NAVX5' and self.preferred_usePPP is not None:
+ msg.unpack()
+ if msg.usePPP != self.preferred_usePPP:
+ msg.usePPP = self.preferred_usePPP
+ msg.mask = 1 << 13
+ msg.pack()
+ self.send(msg)
+ self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5)
+
+ def receive_message(self, ignore_eof=False):
+ '''blocking receive of one ublox message'''
+ msg = UBloxMessage()
+ while True:
+ n = msg.needed_bytes()
+ b = self.read(n)
+ if not b:
+ if ignore_eof:
+ time.sleep(0.01)
+ continue
+ if len(msg._buf) > 0:
+ self.debug(1, "dropping %d bytes" % len(msg._buf))
+ return None
+ msg.add(b)
+ if self.log is not None:
+ self.log.write(b)
+ self.log.flush()
+ if msg.valid():
+ self.special_handling(msg)
+ return msg
+
+ def receive_message_noerror(self, ignore_eof=False):
+ '''blocking receive of one ublox message, ignoring errors'''
+ try:
+ return self.receive_message(ignore_eof=ignore_eof)
+ except UBloxError as e:
+ print(e)
+ return None
+ except OSError as e:
+ # Occasionally we get hit with 'resource temporarily unavailable'
+ # messages here on the serial device, catch them too.
+ print(e)
+ return None
+
+ def send(self, msg):
+ '''send a preformatted ublox message'''
+ if not msg.valid():
+ self.debug(1, "invalid send")
+ return
+ if not self.read_only:
+ self.write(msg._buf)
+
+ def send_message(self, msg_class, msg_id, payload):
+ '''send a ublox message with class, id and payload'''
+ msg = UBloxMessage()
+ msg._buf = struct.pack(' /sys/module/dwc3_msm/parameters/otg_switch")
+ from smbus2 import SMBus
bus = SMBus(7, force=True)
bus.write_byte_data(0x21, 0x10, 0xf) # mask all interrupts
bus.write_byte_data(0x21, 0x03, 0x1) # set drive current and global interrupt disable
@@ -300,6 +298,7 @@ def set_eon_fan(val):
if not EON:
return
+ from smbus2 import SMBus
if last_eon_fan_val is None or last_eon_fan_val != val:
bus = SMBus(7, force=True)
bus.write_byte_data(0x21, 0x04, 0x2)
@@ -391,7 +390,6 @@ def manager_thread():
params = Params()
- passive = params.get("Passive") == "1"
passive_starter = LocationStarter()
started_ts = None
@@ -400,6 +398,7 @@ def manager_thread():
fan_speed = 0
ignition_seen = False
battery_was_high = False
+ panda_seen = False
health_sock.RCVTIMEO = 1500
@@ -455,14 +454,22 @@ def manager_thread():
ignition = td is not None and td.health.started
ignition_seen = ignition_seen or ignition
+ # add voltage check for ignition
+ if not ignition_seen and td is not None and td.health.voltage > 13500:
+ ignition = True
+
do_uninstall = params.get("DoUninstall") == "1"
accepted_terms = params.get("HasAcceptedTerms") == "1"
should_start = ignition
- # start on gps in passive mode
- if passive and not ignition_seen:
- should_start = should_start or passive_starter.update(started_ts, location)
+ # have we seen a panda?
+ panda_seen = panda_seen or td is not None
+
+ # start on gps movement if we haven't seen ignition and are in passive mode
+ should_start = should_start or (not (ignition_seen and td) # seen ignition and panda is connected
+ and params.get("Passive") == "1"
+ and passive_starter.update(started_ts, location))
# with 2% left, we killall, otherwise the phone will take a long time to boot
should_start = should_start and avail > 0.02
@@ -509,6 +516,7 @@ def manager_thread():
running=running.keys(),
count=count,
health=(td.to_dict() if td else None),
+ location=(location.to_dict() if location else None),
thermal=msg.to_dict())
if do_uninstall:
@@ -641,7 +649,12 @@ def main():
if params.get("IsUploadVideoOverCellularEnabled") is None:
params.put("IsUploadVideoOverCellularEnabled", "1")
- params.put("Passive", "1" if os.getenv("PASSIVE") else "0")
+ # is this chffrplus?
+ if os.getenv("PASSIVE") is not None:
+ params.put("Passive", str(int(os.getenv("PASSIVE"))))
+
+ if params.get("Passive") is None:
+ raise Exception("Passive must be set to continue")
# put something on screen while we set things up
if os.getenv("PREPAREONLY") is not None:
diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd
index c4fd915875..24b0995d8b 100755
Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ
diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord
index 75fd6cc6e1..61168b0237 100755
Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ
diff --git a/selfdrive/service_list.yaml b/selfdrive/service_list.yaml
index 0d726314ba..897df4425b 100644
--- a/selfdrive/service_list.yaml
+++ b/selfdrive/service_list.yaml
@@ -55,13 +55,22 @@ gpsPlannerPoints: [8043, true]
gpsPlannerPlan: [8044, true]
applanixRaw: [8046, true]
orbLocation: [8047, true]
-trafficSigns: [8048, true]
+trafficEvents: [8048, true]
liveLocationTiming: [8049, true]
orbslamCorrection: [8050, true]
liveLocationCorrected: [8051, true]
+orbObservation: [8052, true]
+applanixLocation: [8053, true]
+liveLocationKalman: [8054, true]
+uiNavigationEvent: [8055, true]
+orbOdometry: [8057, true]
+orbFeatures: [8058, true]
+orbKeyFrame: [8059, true]
+uiLayoutState: [8060, true]
testModel: [8040, false]
testLiveLocation: [8045, false]
+testJoystick: [8056, false]
# manager -- base process to manage starting and stopping of all others
diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py
index 1c97cea4b8..ca20ce9acf 100755
--- a/selfdrive/test/plant/plant.py
+++ b/selfdrive/test/plant/plant.py
@@ -170,7 +170,7 @@ class Plant(object):
fcw = True
if self.cp.vl[0x1fa]['COMPUTER_BRAKE_REQUEST']:
- brake = self.cp.vl[0x1fa]['COMPUTER_BRAKE']
+ brake = self.cp.vl[0x1fa]['COMPUTER_BRAKE'] * 0.003906248
else:
brake = 0.0
diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py
index 430b31d881..bac43a0a19 100644
--- a/selfdrive/tombstoned.py
+++ b/selfdrive/tombstoned.py
@@ -7,7 +7,7 @@ import datetime
from raven import Client
from raven.transport.http import HTTPTransport
-from selfdrive.version import version
+from selfdrive.version import version, dirty
from selfdrive.swaglog import cloudlog
def get_tombstones():
@@ -69,7 +69,7 @@ def main(gctx):
initial_tombstones = set(get_tombstones())
client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615',
- install_sys_hook=False, transport=HTTPTransport)
+ install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty})
while True:
now_tombstones = set(get_tombstones())
diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c
index 99d351dbf9..c234511ebb 100644
--- a/selfdrive/ui/ui.c
+++ b/selfdrive/ui/ui.c
@@ -44,13 +44,28 @@
#define STATUS_ALERT 4
#define STATUS_MAX 5
-#define UI_BUF_COUNT 4
+#define ALERTSIZE_NONE 0
+#define ALERTSIZE_SMALL 1
+#define ALERTSIZE_MID 2
+#define ALERTSIZE_FULL 3
+#define UI_BUF_COUNT 4
-const int box_x = 330;
-const int box_y = 30;
-const int box_width = 1560;
-const int box_height = 1020;
+const int vwp_w = 1920;
+const int vwp_h = 1080;
+const int nav_w = 0;
+const int nav_ww= 0;
+const int sbr_w = 300;
+const int bdr_s = 30;
+const int box_x = sbr_w+bdr_s;
+const int box_y = bdr_s;
+const int box_w = vwp_w-sbr_w-(bdr_s*2);
+const int box_h = vwp_h-(bdr_s*2);
+const int viz_x = box_x+nav_w;
+const int viz_y = box_y;
+const int viz_w = box_w-nav_w;
+const int viz_h = box_h;
+const int viz_header_h = 420;
const uint8_t bg_colors[][4] = {
[STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff},
@@ -61,11 +76,18 @@ const uint8_t bg_colors[][4] = {
};
const uint8_t alert_colors[][4] = {
- [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0x80},
- [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0x80},
- [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0x80},
- [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0x80},
- [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0x80},
+ [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xf1},
+ [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xf1},
+ [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xf1},
+ [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xf1},
+ [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xf1},
+};
+
+const int alert_sizes[] = {
+ [ALERTSIZE_NONE] = 0,
+ [ALERTSIZE_SMALL] = 241,
+ [ALERTSIZE_MID] = 390,
+ [ALERTSIZE_FULL] = vwp_h,
};
typedef struct UIScene {
@@ -91,6 +113,15 @@ typedef struct UIScene {
float curvature;
int engaged;
+ bool uilayout_sidebarcollapsed;
+ bool uilayout_mapenabled;
+ // responsive sizes for sidebar
+ int ui_viz_rx;
+ int ui_viz_rw;
+ // responsize offset for frame + projections
+ int ui_frame_offset;
+ int ui_world_offset;
+
int lead_status;
float lead_d_rel, lead_y_rel, lead_v_rel;
@@ -110,7 +141,6 @@ typedef struct UIScene {
int cal_status;
int cal_perc;
-
// Used to show gps planner status
bool gps_planner_active;
@@ -130,6 +160,8 @@ typedef struct UIState {
int font_courbd;
int font_sans_regular;
int font_sans_semibold;
+ int font_sans_bold;
+ int img_wheel;
zsock_t *thermal_sock;
void *thermal_sock_raw;
@@ -146,6 +178,9 @@ typedef struct UIState {
zsock_t *plus_sock;
void *plus_sock_raw;
+ zsock_t *uilayout_sock;
+ void *uilayout_sock_raw;
+
int plus_state;
// vision state
@@ -185,6 +220,7 @@ typedef struct UIState {
int status;
bool is_metric;
bool passive;
+ int alert_size;
float light_sensor;
} UIState;
@@ -273,7 +309,7 @@ static const mat4 device_transform = {{
// frame from 4/3 to box size with a 2x zoon
static const mat4 frame_transform = {{
- 2*(4./3.)/((float)box_width/box_height), 0.0, 0.0, 0.0,
+ 2*(4./3.)/((float)box_w/viz_h), 0.0, 0.0, 0.0,
0.0, 2.0, 0.0, 0.0,
0.0, 0.0, 1.0, 0.0,
0.0, 0.0, 0.0, 1.0,
@@ -299,6 +335,10 @@ static void ui_init(UIState *s) {
assert(s->live100_sock);
s->live100_sock_raw = zsock_resolve(s->live100_sock);
+ s->uilayout_sock = zsock_new_sub(">tcp://127.0.0.1:8060", "");
+ assert(s->uilayout_sock);
+ s->uilayout_sock_raw = zsock_resolve(s->uilayout_sock);
+
s->livecalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", "");
assert(s->livecalibration_sock);
s->livecalibration_sock_raw = zsock_resolve(s->livecalibration_sock);
@@ -334,6 +374,11 @@ static void ui_init(UIState *s) {
assert(s->font_sans_regular >= 0);
s->font_sans_semibold = nvgCreateFont(s->vg, "sans-semibold", "../assets/OpenSans-SemiBold.ttf");
assert(s->font_sans_semibold >= 0);
+ s->font_sans_bold = nvgCreateFont(s->vg, "sans-bold", "../assets/OpenSans-Bold.ttf");
+ assert(s->font_sans_bold >= 0);
+
+ assert(s->img_wheel >= 0);
+ s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1);
// init gl
s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader);
@@ -627,7 +672,7 @@ static void draw_x_y(UIState *s, const float *x_coords, const float *y_coords, s
}
static void draw_path(UIState *s, const float *points, float off,
- NVGcolor color) {
+ NVGcolor color, int width) {
const UIScene *scene = &s->scene;
nvgSave(s->vg);
@@ -643,7 +688,7 @@ static void draw_path(UIState *s, const float *points, float off,
nvgBeginPath(s->vg);
nvgStrokeColor(s->vg, color);
- nvgStrokeWidth(s->vg, 5);
+ nvgStrokeWidth(s->vg, width);
bool started = false;
for (int i=0; i<50; i++) {
@@ -673,22 +718,21 @@ static void draw_path(UIState *s, const float *points, float off,
}
static void draw_model_path(UIState *s, const PathData path, NVGcolor color) {
+ draw_path(s, path.points, 0.0, color, 4*path.prob);
float var = min(path.std, 0.7);
- draw_path(s, path.points, 0.0, color);
color.a /= 4;
- draw_path(s, path.points, -var, color);
- draw_path(s, path.points, var, color);
+ draw_path(s, path.points, -var, color, 2);
+ draw_path(s, path.points, var, color, 2);
}
static void draw_steering(UIState *s, float curvature) {
-
float points[50];
for (int i = 0; i < 50; i++) {
float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999)) / 2.);
points[i] = y_actual;
}
- draw_path(s, points, 0.0, nvgRGBA(0, 0, 255, 128));
+ draw_path(s, points, 0.0, nvgRGBA(0, 0, 255, 128), 5);
}
static void draw_frame(UIState *s) {
@@ -709,10 +753,10 @@ static void draw_frame(UIState *s) {
} else {
out_mat = matmul(device_transform, frame_transform);
- x1 = 0.0;
- x2 = 1.0;
- y1 = 0.0;
- y2 = 1.0;
+ x1 = 1.0;
+ x2 = 0.0;
+ y1 = 1.0;
+ y2 = 0.0;
}
const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3};
@@ -779,270 +823,541 @@ static void ui_draw_rounded_rect(
nvgStroke(c);
}
-// Draw all world space objects.
-static void ui_draw_world(UIState *s) {
+static void fill_lane(UIState *s, const float *l_points, const float *r_points, float off,
+ NVGcolor color) {
const UIScene *scene = &s->scene;
- if (!scene->world_objects_visible) {
- return;
+
+ nvgSave(s->vg);
+
+ // path coords are worked out in rgb-box space
+ nvgTranslate(s->vg, 240.0f, 0.0);
+
+ // zoom in 2x
+ nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2);
+ nvgScale(s->vg, 2.0, 2.0);
+
+ nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height);
+
+ nvgBeginPath(s->vg);
+ bool started = false;
+
+ int gradient_start_x = 0;
+ int gradient_start_y = 0;
+ int gradient_end_x = 0;
+ int gradient_end_y = 0;
+
+ // left side of lane
+ for (int i=0; i<50; i++) {
+ float px = (float)i;
+ float py = l_points[i] + off;
+
+ vec4 p_car_space = (vec4){{px, py, 0., 1.}};
+ vec3 p_full_frame = car_space_to_full_frame(s, p_car_space);
+
+ float x = p_full_frame.v[0];
+ float y = p_full_frame.v[1];
+ if (x < 0 || y < 0.) {
+ continue;
+ }
+
+ if (!started) {
+ nvgMoveTo(s->vg, x, y);
+ gradient_start_x = x;
+ gradient_start_y = y;
+ started = true;
+ } else {
+ nvgLineTo(s->vg, x, y);
+ }
}
- //draw_steering(s, scene->curvature);
+ // right side of lane
+ for (int i=50; i>0; i--) {
+ float px = (float)i;
+ float py = r_points[i] + off;
+
+ vec4 p_car_space = (vec4){{px, py, 0., 1.}};
+ vec3 p_full_frame = car_space_to_full_frame(s, p_car_space);
+ float x = p_full_frame.v[0];
+ float y = p_full_frame.v[1];
+ if (x < 0 || y < 0.) {
+ continue;
+ }
+
+ if (!started) {
+ nvgMoveTo(s->vg, x, y);
+ started = true;
+ } else {
+ nvgLineTo(s->vg, x, y);
+ gradient_end_y = y;
+ gradient_end_x = x;
+ }
+ }
+
+ NVGpaint bg = nvgLinearGradient(s->vg, gradient_start_x, gradient_start_y, gradient_end_x, gradient_end_y,
+ nvgRGBAf(0.6, 0.6, 0.6, 1.0*scene->model.left_lane.prob), nvgRGBAf(0.6, 0.6, 0.6, 1.0*scene->model.right_lane.prob));
+
+ nvgFillPaint(s->vg, bg);
+ nvgFill(s->vg);
+
+ nvgRestore(s->vg);
+}
+
+static void ui_draw_vision_lanes(UIState *s) {
+ const UIScene *scene = &s->scene;
if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) {
- int left_lane_color = (int)(255 * scene->model.left_lane.prob);
- int right_lane_color = (int)(255 * scene->model.right_lane.prob);
+ // draw left lane edge
draw_model_path(
s, scene->model.left_lane,
- nvgRGBA(left_lane_color, left_lane_color, left_lane_color, 128));
+ nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob));
+
+ // draw right lane edge
draw_model_path(
s, scene->model.right_lane,
- nvgRGBA(right_lane_color, right_lane_color, right_lane_color, 128));
+ nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob));
- // draw paths
- draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(0xc0, 0xc0, 0xc0, 255));
+ // draw projected path line
+ draw_path(s, scene->model.path.points, 0.0f, nvgRGBA(0xc0, 0xc0, 0xc0, 255), 5);
// draw MPC only if engaged
if (scene->engaged) {
- draw_x_y(s, &scene->mpc_x[1], &scene->mpc_y[1], 19, nvgRGBA(255, 0, 0, 255));
+ draw_x_y(s, &scene->mpc_x[0], &scene->mpc_y[0], 20, nvgRGBA(255, 0, 0, 255));
}
}
}
-static void ui_draw_vision(UIState *s) {
+static void ui_draw_vision_topbar(UIState *s) {
const UIScene *scene = &s->scene;
- glClearColor(0.0, 0.0, 0.0, 0.0);
- glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
+ const int bar_x = box_x;
+ const int bar_y = box_y;
+ const int bar_width = box_w;
+ const int bar_height = 250 - box_y;
- // hack for eon ui
- glEnable(GL_SCISSOR_TEST);
- glScissor(box_x, s->fb_h-(box_y+box_height), box_width, box_height);
- glViewport(box_x, s->fb_h-(box_y+box_height), box_width, box_height);
- draw_frame(s);
- glViewport(0, 0, s->fb_w, s->fb_h);
- glDisable(GL_SCISSOR_TEST);
+ assert(s->status < ARRAYSIZE(bg_colors));
+ const uint8_t *color = bg_colors[s->status];
- // nvg drawings
- glEnable(GL_BLEND);
- glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
- // glEnable(GL_CULL_FACE);
+ nvgBeginPath(s->vg);
+ nvgRect(s->vg, bar_x, bar_y, bar_width, bar_height);
+ nvgFillColor(s->vg, nvgRGBA(color[0], color[1], color[2], color[3]));
+ nvgFill(s->vg);
- glClear(GL_STENCIL_BUFFER_BIT);
+ const int message_y = box_y;
+ const int message_height = bar_height;
+ const int message_width = 800;
+ const int message_x = box_x + box_w / 2 - message_width / 2;
- nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f);
+ // message background
+ nvgBeginPath(s->vg);
+ NVGpaint bg = nvgLinearGradient(s->vg, message_x, message_y, message_x, message_y+message_height,
+ nvgRGBAf(0.0, 0.0, 0.0, 0.0), nvgRGBAf(0.0, 0.0, 0.0, 0.1));
+ nvgFillPaint(s->vg, bg);
+ nvgRect(s->vg, message_x, message_y, message_width, message_height);
+ nvgFill(s->vg);
- nvgSave(s->vg);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
- // hack for eon ui
- const int inner_height = box_width*9/16;
- nvgScissor(s->vg, box_x, box_y, box_width, box_height);
- nvgTranslate(s->vg, box_x, box_y + (box_height-inner_height)/2.0);
- nvgScale(s->vg, (float)box_width / s->fb_w, (float)inner_height / s->fb_h);
+ if (s->passive) {
+ if (s->scene.started_ts > 0) {
+ // draw drive time when passive
- if (!scene->frontview) {
- // ui_draw_transformed_box(s, 0xFF00FF00);
- ui_draw_world(s);
+ uint64_t dt = nanos_since_boot() - s->scene.started_ts;
- if (scene->lead_status) {
- draw_cross(s, scene->lead_d_rel + 2.7, scene->lead_y_rel, 30,
- nvgRGBA(255, 0, 0, 128));
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 40*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+
+ char time_str[64];
+ if (dt > 60*60*1000000000ULL) {
+ // hours
+ snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d:%02d",
+ (int)(dt/(60*60*1000000000ULL)),
+ (int)((dt%(60*60*1000000000ULL))/(60*1000000000ULL)),
+ (int)(dt%(60*1000000000ULL)/1000000000ULL));
+ } else {
+ snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d",
+ (int)(dt/(60*1000000000ULL)),
+ (int)(dt%(60*1000000000ULL)/1000000000ULL));
+ }
+ nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, time_str, NULL);
}
+ } else {
+ // status text
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 48*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ if (s->scene.alert_size == cereal_Live100Data_AlertSize_small) {
+ nvgFontSize(s->vg, 40*2.5);
+ nvgText(s->vg, message_x+message_width/2, 115, s->scene.alert_text1, NULL);
+ nvgFontSize(s->vg, 26*2.5);
+ nvgText(s->vg, message_x+message_width/2, 185, s->scene.alert_text2, NULL);
+ } else if (s->status == STATUS_DISENGAGED) {
+ nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "DISENGAGED", NULL);
+ } else if (s->status == STATUS_ENGAGED) {
+ nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "ENGAGED", NULL);
+ }
+ }
- const float label_size = 65.0f;
+ // set speed
+ const int left_x = bar_x;
+ const int left_y = bar_y;
+ const int left_width = (bar_width - message_width) / 2;
+ const int left_height = bar_height;
- nvgFontFace(s->vg, "courbd");
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 40*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- if (scene->awareness_status > 0) {
- nvgBeginPath(s->vg);
- int bar_height = scene->awareness_status * 700;
- nvgRect(s->vg, 100, 300 + (700 - bar_height), 50, bar_height);
- nvgFillColor(s->vg, nvgRGBA(255 * (1 - scene->awareness_status),
- 255 * scene->awareness_status, 0, 128));
- nvgFill(s->vg);
+ if (scene->v_cruise != 255 && scene->v_cruise != 0) {
+ char speed_str[16];
+ if (s->is_metric) {
+ snprintf(speed_str, sizeof(speed_str), "%3d kph",
+ (int)(scene->v_cruise + 0.5));
+ } else {
+ /* Convert KPH to MPH. Using an approximated mph to kph
+ conversion factor of 1.60642 because this is what the Honda
+ hud seems to be using */
+ snprintf(speed_str, sizeof(speed_str), "%3d mph",
+ (int)(scene->v_cruise * 0.6225 + 0.5));
}
+ nvgText(s->vg, left_x+left_width/2, 115, speed_str, NULL);
+ } else {
+ nvgText(s->vg, left_x+left_width/2, 115, "N/A", NULL);
+ }
- // Draw calibration progress (if needed)
- if (scene->cal_status == CALIBRATION_UNCALIBRATED) {
- int rec_width = 1120;
- int x_pos = 500;
- nvgBeginPath(s->vg);
- nvgStrokeWidth(s->vg, 14);
- nvgRoundedRect(s->vg, (1920-rec_width)/2, 920, rec_width, 225, 20);
- nvgStroke(s->vg);
- nvgFillColor(s->vg, nvgRGBA(0,0,0,180));
- nvgFill(s->vg);
+ nvgFontFace(s->vg, "sans-regular");
+ nvgFontSize(s->vg, 26*2.5);
+ nvgText(s->vg, left_x+left_width/2, 185, "SET SPEED", NULL);
- nvgFontSize(s->vg, 40*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE);
- nvgFontFace(s->vg, "sans-semibold");
- nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 220));
- char calib_status_str[64];
- snprintf(calib_status_str, sizeof(calib_status_str), "Calibration in Progress: %d%%", scene->cal_perc);
+ // lead car
+ const int right_y = bar_y;
+ const int right_width = (bar_width - message_width) / 2;
+ const int right_x = bar_x+bar_width-right_width;
+ const int right_height = bar_height;
- nvgText(s->vg, x_pos, 1010, calib_status_str, NULL);
- if (s->is_metric) {
- nvgText(s->vg, x_pos + 120, 1110, "Drive above 72 km/h", NULL);
- } else {
- nvgText(s->vg, x_pos + 120, 1110, "Drive above 45 mph", NULL);
- }
- } else if (scene->gps_planner_active) {
- int rec_width = 1120;
- int x_pos = 500;
- nvgBeginPath(s->vg);
- nvgStrokeWidth(s->vg, 14);
- nvgRoundedRect(s->vg, (1920-rec_width)/2, 920, rec_width, 225, 20);
- nvgStroke(s->vg);
- nvgFillColor(s->vg, nvgRGBA(0,0,0,180));
- nvgFill(s->vg);
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 40*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- nvgFontSize(s->vg, 40*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE);
- nvgFontFace(s->vg, "sans-semibold");
- nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 220));
- nvgText(s->vg, x_pos, 1010, "GPS planner active", NULL);
+ if (scene->lead_status) {
+ char radar_str[16];
+ // lead car is always in meters
+ if (s->is_metric || true) {
+ snprintf(radar_str, sizeof(radar_str), "%d m", (int)scene->lead_d_rel);
+ } else {
+ snprintf(radar_str, sizeof(radar_str), "%d ft", (int)(scene->lead_d_rel * 3.28084));
}
+ nvgText(s->vg, right_x+right_width/2, 115, radar_str, NULL);
+ } else {
+ nvgText(s->vg, right_x+right_width/2, 115, "N/A", NULL);
}
- nvgRestore(s->vg);
+ nvgFontFace(s->vg, "sans-regular");
+ nvgFontSize(s->vg, 26*2.5);
+ nvgText(s->vg, right_x+right_width/2, 185, "LEAD CAR", NULL);
+}
+static void ui_draw_calibration_status(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
- if (!ui_alert_active(s) && !scene->frontview) {
- // draw top bar
+ int viz_calib_w = 1120;
+ int viz_calib_x = (ui_viz_rx + ((ui_viz_rw/2) - (viz_calib_w/2)));
+ int viz_calib_y = 760;
+ int viz_calib_h = 250;
+ int viz_calibtext_x = (ui_viz_rx + (ui_viz_rw/2));
- const int bar_x = box_x;
- const int bar_y = box_y;
- const int bar_width = box_width;
- const int bar_height = 250 - box_y;
+ nvgBeginPath(s->vg);
+ nvgStrokeWidth(s->vg, 10);
+ nvgRoundedRect(s->vg, viz_calib_x, viz_calib_y, viz_calib_w, viz_calib_h, 20);
+ nvgStroke(s->vg);
+ nvgFillColor(s->vg, nvgRGBA(0,0,0,180));
+ nvgFill(s->vg);
- assert(s->status < ARRAYSIZE(bg_colors));
- const uint8_t *color = bg_colors[s->status];
+ nvgFontSize(s->vg, 40*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 220));
+ char calib_status_str[64];
+ snprintf(calib_status_str, sizeof(calib_status_str), "Calibration in Progress: %d%%", scene->cal_perc);
- nvgBeginPath(s->vg);
- nvgRect(s->vg, bar_x, bar_y, bar_width, bar_height);
- nvgFillColor(s->vg, nvgRGBA(color[0], color[1], color[2], color[3]));
- nvgFill(s->vg);
+ nvgText(s->vg, viz_calibtext_x, viz_calib_y+100, calib_status_str, NULL);
+ if (s->is_metric) {
+ nvgText(s->vg, viz_calibtext_x, viz_calib_y+200, "Drive above 72 km/h", NULL);
+ } else {
+ nvgText(s->vg, viz_calibtext_x, viz_calib_y+200, "Drive above 45 mph", NULL);
+ }
+}
- const int message_y = box_y;
- const int message_height = bar_height;
- const int message_width = 800;
- const int message_x = box_x + box_width / 2 - message_width / 2;
+static void ui_draw_gpsplanner_status(UIState *s) {
+ const UIScene *scene = &s->scene;
- // message background
- nvgBeginPath(s->vg);
- NVGpaint bg = nvgLinearGradient(s->vg, message_x, message_y, message_x, message_y+message_height,
- nvgRGBAf(0.0, 0.0, 0.0, 0.0), nvgRGBAf(0.0, 0.0, 0.0, 0.1));
- nvgFillPaint(s->vg, bg);
- nvgRect(s->vg, message_x, message_y, message_width, message_height);
- nvgFill(s->vg);
+ int rec_width = 1120;
+ int x_pos = 500;
+ nvgBeginPath(s->vg);
+ nvgStrokeWidth(s->vg, 14);
+ nvgRoundedRect(s->vg, (1920-rec_width)/2, 920, rec_width, 225, 20);
+ nvgStroke(s->vg);
+ nvgFillColor(s->vg, nvgRGBA(0,0,0,180));
+ nvgFill(s->vg);
- nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ nvgFontSize(s->vg, 40*2.5);
+ nvgTextAlign(s->vg, NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE);
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 220));
+ nvgText(s->vg, x_pos, 1010, "GPS planner active", NULL);
+}
+
+
+// Draw all world space objects.
+static void ui_draw_world(UIState *s) {
+ const UIScene *scene = &s->scene;
+ if (!scene->world_objects_visible) {
+ return;
+ }
- if (s->passive) {
- if (s->scene.started_ts > 0) {
- // draw drive time when passive
+ //draw_steering(s, scene->curvature);
+ ui_draw_vision_lanes(s);
- uint64_t dt = nanos_since_boot() - s->scene.started_ts;
+}
- nvgFontFace(s->vg, "sans-semibold");
- nvgFontSize(s->vg, 40*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+static void ui_draw_vision_maxspeed(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
+ float maxspeed = s->scene.v_cruise;
- char time_str[64];
- if (dt > 60*60*1000000000ULL) {
- // hours
- snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d:%02d",
- (int)(dt/(60*60*1000000000ULL)),
- (int)((dt%(60*60*1000000000ULL))/(60*1000000000ULL)),
- (int)(dt%(60*1000000000ULL)/1000000000ULL));
- } else {
- snprintf(time_str, sizeof(time_str), "Drive time: %d:%02d",
- (int)(dt/(60*1000000000ULL)),
- (int)(dt%(60*1000000000ULL)/1000000000ULL));
- }
- nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, time_str, NULL);
- }
+ const int viz_maxspeed_x = (ui_viz_rx + (bdr_s*2));
+ const int viz_maxspeed_y = (viz_y + (bdr_s*1.5));
+ const int viz_maxspeed_w = 180;
+ const int viz_maxspeed_h = 202;
+ char maxspeed_str[32];
+ bool is_cruise_set = (maxspeed != 0 && maxspeed != 255);
+
+ nvgBeginPath(s->vg);
+ nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 20);
+ nvgStrokeColor(s->vg, nvgRGBA(255,255,255,80));
+ nvgStrokeWidth(s->vg, 6);
+ nvgStroke(s->vg);
+
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ nvgFontFace(s->vg, "sans-regular");
+ nvgFontSize(s->vg, 26*2.5);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200));
+ nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 148, "MAX", NULL);
+
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 52*2.5);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ if (is_cruise_set) {
+ if (s->is_metric) {
+ snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(maxspeed + 0.5));
} else {
- // status text
- nvgFontFace(s->vg, "sans-semibold");
- nvgFontSize(s->vg, 48*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- if (s->scene.alert_size == cereal_Live100Data_AlertSize_small) {
- nvgFontSize(s->vg, 40*2.5);
- nvgText(s->vg, message_x+message_width/2, 115, s->scene.alert_text1, NULL);
- nvgFontSize(s->vg, 26*2.5);
- nvgText(s->vg, message_x+message_width/2, 185, s->scene.alert_text2, NULL);
- } else if (s->status == STATUS_DISENGAGED) {
- nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "DISENGAGED", NULL);
- } else if (s->status == STATUS_ENGAGED) {
- nvgText(s->vg, message_x+message_width/2, message_y+message_height/2+15, "ENGAGED", NULL);
- }
+ snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(maxspeed * 0.6225 + 0.5));
}
+ nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 242, maxspeed_str, NULL);
+ } else {
+ nvgFontSize(s->vg, 42*2.5);
+ nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 242, "N/A", NULL);
+ }
+}
- // set speed
- const int left_x = bar_x;
- const int left_y = bar_y;
- const int left_width = (bar_width - message_width) / 2;
- const int left_height = bar_height;
+static void ui_draw_vision_speed(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
+ float speed = s->scene.v_ego;
- nvgFontFace(s->vg, "sans-semibold");
- nvgFontSize(s->vg, 40*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ const int viz_speed_w = 280;
+ const int viz_speed_x = ui_viz_rx+((ui_viz_rw/2)-(viz_speed_w/2));
+ char speed_str[32];
- if (scene->v_cruise != 255 && scene->v_cruise != 0) {
- char speed_str[16];
- if (s->is_metric) {
- snprintf(speed_str, sizeof(speed_str), "%3d kph",
- (int)(scene->v_cruise + 0.5));
- } else {
- /* Convert KPH to MPH. Using an approximated mph to kph
- conversion factor of 1.609 because this is what the Honda
- hud seems to be using */
- snprintf(speed_str, sizeof(speed_str), "%3d mph",
- (int)(scene->v_cruise * 0.621504 + 0.5));
- }
- nvgText(s->vg, left_x+left_width/2, 115, speed_str, NULL);
- } else {
- nvgText(s->vg, left_x+left_width/2, 115, "N/A", NULL);
+ nvgBeginPath(s->vg);
+ nvgRect(s->vg, viz_speed_x, viz_y, viz_speed_w, viz_header_h);
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+
+ if (s->is_metric) {
+ snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 3.6 + 0.5));
+ } else {
+ snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 2.2374144 + 0.5));
+ }
+ nvgFontFace(s->vg, "sans-bold");
+ nvgFontSize(s->vg, 96*2.5);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ nvgText(s->vg, viz_speed_x+viz_speed_w/2, 240, speed_str, NULL);
+
+ nvgFontFace(s->vg, "sans-regular");
+ nvgFontSize(s->vg, 36*2.5);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200));
+
+ if (s->is_metric) {
+ nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "kph", NULL);
+ } else {
+ nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "mph", NULL);
+ }
+}
+
+static void ui_draw_vision_wheel(UIState *s) {
+ const UIScene *scene = &s->scene;
+ const int ui_viz_rx = scene->ui_viz_rx;
+ const int ui_viz_rw = scene->ui_viz_rw;
+ const int viz_event_w = 220;
+ const int viz_event_x = ((ui_viz_rx + ui_viz_rw) - (viz_event_w + (bdr_s*2)));
+ const int viz_event_y = (viz_y + (bdr_s*1.5));
+ const int viz_event_h = (viz_header_h - (bdr_s*1.5));
+ // draw steering wheel
+ const int viz_wheel_size = 96;
+ const int viz_wheel_x = viz_event_x + (viz_event_w-viz_wheel_size);
+ const int viz_wheel_y = viz_event_y + (viz_wheel_size/2);
+ const int img_wheel_size = viz_wheel_size*1.5;
+ const int img_wheel_x = viz_wheel_x-(img_wheel_size/2);
+ const int img_wheel_y = viz_wheel_y-25;
+ float img_wheel_alpha = 0.5f;
+ bool is_engaged = (s->status == STATUS_ENGAGED);
+ bool is_warning = (s->status == STATUS_WARNING);
+ if (is_engaged || is_warning) {
+ nvgBeginPath(s->vg);
+ nvgCircle(s->vg, viz_wheel_x, (viz_wheel_y + (bdr_s*1.5)), viz_wheel_size);
+ if (is_engaged) {
+ nvgFillColor(s->vg, nvgRGBA(23, 134, 68, 255));
+ } else if (is_warning) {
+ nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 255));
}
+ nvgFill(s->vg);
+ img_wheel_alpha = 1.0f;
+ }
+ nvgBeginPath(s->vg);
+ NVGpaint imgPaint = nvgImagePattern(s->vg, img_wheel_x, img_wheel_y,
+ img_wheel_size, img_wheel_size, 0, s->img_wheel, img_wheel_alpha);
+ nvgRect(s->vg, img_wheel_x, img_wheel_y, img_wheel_size, img_wheel_size);
+ nvgFillPaint(s->vg, imgPaint);
+ nvgFill(s->vg);
+}
- nvgFontFace(s->vg, "sans-regular");
- nvgFontSize(s->vg, 26*2.5);
- nvgText(s->vg, left_x+left_width/2, 185, "SET SPEED", NULL);
+static void ui_draw_vision_header(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
+
+ nvgBeginPath(s->vg);
+ NVGpaint gradient = nvgLinearGradient(s->vg, ui_viz_rx,
+ (viz_y+(viz_header_h-(viz_header_h/2.5))),
+ ui_viz_rx, viz_y+viz_header_h,
+ nvgRGBAf(0,0,0,0.45), nvgRGBAf(0,0,0,0));
+ nvgFillPaint(s->vg, gradient);
+ nvgRect(s->vg, ui_viz_rx, viz_y, ui_viz_rw, viz_header_h);
+ nvgFill(s->vg);
- // lead car
- const int right_y = bar_y;
- const int right_width = (bar_width - message_width) / 2;
- const int right_x = bar_x+bar_width-right_width;
- const int right_height = bar_height;
+ ui_draw_vision_maxspeed(s);
+ ui_draw_vision_speed(s);
+ ui_draw_vision_wheel(s);
+}
+
+static void ui_draw_vision_alert(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
+ bool hasSidebar = !s->scene.uilayout_sidebarcollapsed;
+ bool mapEnabled = s->scene.uilayout_mapenabled;
+ bool longAlert1 = strlen(scene->alert_text1) > 15;
+
+ const uint8_t *color = alert_colors[s->status];
+ const int alr_s = alert_sizes[s->alert_size];
+ const int alr_x = ui_viz_rx-(mapEnabled?(hasSidebar?nav_w:(nav_ww+(bdr_s*2))):0)-bdr_s;
+ const int alr_w = ui_viz_rw+(mapEnabled?(hasSidebar?nav_w:(nav_ww+(bdr_s*2))):0)+(bdr_s*2);
+ const int alr_h = alr_s+(s->alert_size==ALERTSIZE_NONE?0:bdr_s);
+ const int alr_y = vwp_h-alr_h;
+
+ nvgBeginPath(s->vg);
+ nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h);
+ nvgFillColor(s->vg, nvgRGBA(color[0],color[1],color[2],color[3]));
+ nvgFill(s->vg);
+
+ nvgBeginPath(s->vg);
+ NVGpaint gradient = nvgLinearGradient(s->vg, alr_x, alr_y, alr_x, alr_y+alr_h,
+ nvgRGBAf(0.0,0.0,0.0,0.05), nvgRGBAf(0.0,0.0,0.0,0.35));
+ nvgFillPaint(s->vg, gradient);
+ nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h);
+ nvgFill(s->vg);
+
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ if (s->alert_size == ALERTSIZE_SMALL) {
nvgFontFace(s->vg, "sans-semibold");
nvgFontSize(s->vg, 40*2.5);
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+15, scene->alert_text1, NULL);
+ } else if (s->alert_size == ALERTSIZE_MID) {
+ nvgFontFace(s->vg, "sans-bold");
+ nvgFontSize(s->vg, 48*2.5);
+ nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2-45, scene->alert_text1, NULL);
+ nvgFontFace(s->vg, "sans-regular");
+ nvgFontSize(s->vg, 36*2.5);
+ nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+75, scene->alert_text2, NULL);
+ } else if (s->alert_size == ALERTSIZE_FULL) {
+ nvgFontSize(s->vg, (longAlert1?72:96)*2.5);
+ nvgFontFace(s->vg, "sans-bold");
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE);
+ nvgTextBox(s->vg, alr_x, alr_y+(longAlert1?360:420), alr_w-60, scene->alert_text1, NULL);
+ nvgFontSize(s->vg, 48*2.5);
+ nvgFontFace(s->vg, "sans-regular");
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BOTTOM);
+ nvgTextBox(s->vg, alr_x, alr_h-(longAlert1?300:360), alr_w-60, scene->alert_text2, NULL);
+ }
+}
+
+static void ui_draw_vision(UIState *s) {
+ const UIScene *scene = &s->scene;
+ int ui_viz_rx = scene->ui_viz_rx;
+ int ui_viz_rw = scene->ui_viz_rw;
+
+ glClearColor(0.0, 0.0, 0.0, 0.0);
+ glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
+
+ // scissor for EON UI
+ glEnable(GL_SCISSOR_TEST);
+ glScissor(ui_viz_rx, s->fb_h-(viz_y+viz_h), ui_viz_rw, viz_h);
+ glViewport(ui_viz_rx, s->fb_h-(viz_y+viz_h), ui_viz_rw, viz_h);
+ draw_frame(s);
+ glViewport(0, 0, s->fb_w, s->fb_h);
+ glDisable(GL_SCISSOR_TEST);
+
+ glEnable(GL_BLEND);
+ glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
+ glClear(GL_STENCIL_BUFFER_BIT);
+
+ nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f);
+ nvgSave(s->vg);
+
+ // hack for eon
+ const int inner_height = ui_viz_rw*9/16;
+ nvgScissor(s->vg, ui_viz_rx, viz_y, ui_viz_rw, viz_h);
+ nvgTranslate(s->vg, ui_viz_rx, viz_y + (viz_h-inner_height)/2.0);
+ nvgScale(s->vg, (float)ui_viz_rw / s->fb_w, (float)inner_height / s->fb_h);
+
+ if (!scene->frontview) {
+ ui_draw_world(s);
if (scene->lead_status) {
- char radar_str[16];
- // lead car is always in meters
- if (s->is_metric || true) {
- snprintf(radar_str, sizeof(radar_str), "%d m", (int)scene->lead_d_rel);
- } else {
- snprintf(radar_str, sizeof(radar_str), "%d ft", (int)(scene->lead_d_rel * 3.28084));
- }
- nvgText(s->vg, right_x+right_width/2, 115, radar_str, NULL);
- } else {
- nvgText(s->vg, right_x+right_width/2, 115, "N/A", NULL);
+ draw_cross(s, scene->lead_d_rel + 2.7, scene->lead_y_rel, 30,
+ nvgRGBA(255, 0, 0, 128));
}
+ }
- nvgFontFace(s->vg, "sans-regular");
- nvgFontSize(s->vg, 26*2.5);
- nvgText(s->vg, right_x+right_width/2, 185, "LEAD CAR", NULL);
+ nvgRestore(s->vg);
+
+ ui_draw_vision_header(s);
+ if (scene->cal_status == CALIBRATION_UNCALIBRATED) {
+ ui_draw_calibration_status(s);
}
+ ui_draw_vision_alert(s);
nvgEndFrame(s->vg);
-
glDisable(GL_BLEND);
- // glDisable(GL_CULL_FACE);
}
+
static void ui_draw_alerts(UIState *s) {
const UIScene *scene = &s->scene;
@@ -1057,7 +1372,7 @@ static void ui_draw_alerts(UIState *s) {
}
nvgBeginPath(s->vg);
- nvgRect(s->vg, box_x, box_y, box_width, box_height);
+ nvgRect(s->vg, box_x, box_y, box_w, box_h);
nvgFillColor(s->vg, nvgRGBA(color[0], color[1], color[2], color[3]));
nvgFill(s->vg);
@@ -1070,7 +1385,7 @@ static void ui_draw_alerts(UIState *s) {
}
nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE);
- nvgTextBox(s->vg, box_x + 50, box_y + 287, box_width - 50, alert_text1_upper, NULL);
+ nvgTextBox(s->vg, box_x + 50, box_y + 287, box_w - 50, alert_text1_upper, NULL);
if (strlen(scene->alert_text2) > 0) {
@@ -1079,7 +1394,7 @@ static void ui_draw_alerts(UIState *s) {
nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
nvgFontSize(s->vg, 44.0*2.5);
nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BOTTOM);
- nvgTextBox(s->vg, box_x + 50, box_y + box_height - 250, box_width - 50, scene->alert_text2, NULL);
+ nvgTextBox(s->vg, box_x + 50, box_y + box_h - 250, box_w - 50, scene->alert_text2, NULL);
}
}
@@ -1138,10 +1453,10 @@ static void ui_draw(UIState *s) {
nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f);
- if (s->vision_connected) {
+ if (s->vision_connected && !s->scene.uilayout_sidebarcollapsed) {
ui_draw_aside(s);
}
- ui_draw_alerts(s);
+ // ui_draw_alerts(s);
nvgEndFrame(s->vg);
glDisable(GL_BLEND);
@@ -1235,12 +1550,18 @@ static void ui_update(UIState *s) {
assert(glGetError() == GL_NO_ERROR);
+ // Default UI Measurements (Assumes sidebar visible)
+ s->scene.ui_viz_rx = box_x;
+ s->scene.ui_viz_rw = box_w;
+ s->scene.ui_frame_offset = -(sbr_w - 4*bdr_s);
+ s->scene.ui_world_offset = -(sbr_w - 6*bdr_s);
+
s->vision_connect_firstrun = false;
}
// poll for events
while (true) {
- zmq_pollitem_t polls[8] = {{0}};
+ zmq_pollitem_t polls[9] = {{0}};
polls[0].socket = s->live100_sock_raw;
polls[0].events = ZMQ_POLLIN;
polls[1].socket = s->livecalibration_sock_raw;
@@ -1253,15 +1574,16 @@ static void ui_update(UIState *s) {
polls[4].events = ZMQ_POLLIN;
polls[5].socket = s->thermal_sock_raw;
polls[5].events = ZMQ_POLLIN;
-
- polls[6].socket = s->plus_sock_raw;
+ polls[6].socket = s->uilayout_sock_raw;
polls[6].events = ZMQ_POLLIN;
+ polls[7].socket = s->plus_sock_raw;
+ polls[7].events = ZMQ_POLLIN;
- int num_polls = 7;
+ int num_polls = 8;
if (s->vision_connected) {
assert(s->ipc_fd >= 0);
- polls[7].fd = s->ipc_fd;
- polls[7].events = ZMQ_POLLIN;
+ polls[8].fd = s->ipc_fd;
+ polls[8].events = ZMQ_POLLIN;
num_polls++;
}
@@ -1275,12 +1597,12 @@ static void ui_update(UIState *s) {
}
if (polls[0].revents || polls[1].revents || polls[2].revents ||
- polls[3].revents || polls[4].revents) {
+ polls[3].revents || polls[4].revents || polls[6].revents || polls[7].revents) {
// awake on any (old) activity
set_awake(s, true);
}
- if (s->vision_connected && polls[7].revents) {
+ if (s->vision_connected && polls[8].revents) {
// vision ipc event
VisionPacket rp;
err = vipc_recv(s->ipc_fd, &rp);
@@ -1329,7 +1651,7 @@ static void ui_update(UIState *s) {
} else {
assert(false);
}
- } else if (polls[6].revents) {
+ } else if (polls[7].revents) {
// plus socket
zmq_msg_t msg;
@@ -1347,7 +1669,7 @@ static void ui_update(UIState *s) {
} else {
// zmq messages
void* which = NULL;
- for (int i=0; i<6; i++) {
+ for (int i=0; iscene.alert_ts = eventd.logMonoTime;
s->scene.alert_size = datad.alertSize;
+ if (datad.alertSize == cereal_Live100Data_AlertSize_none) {
+ s->alert_size = ALERTSIZE_NONE;
+ } else if (datad.alertSize == cereal_Live100Data_AlertSize_small) {
+ s->alert_size = ALERTSIZE_SMALL;
+ } else if (datad.alertSize == cereal_Live100Data_AlertSize_mid) {
+ s->alert_size = ALERTSIZE_MID;
+ } else if (datad.alertSize == cereal_Live100Data_AlertSize_full) {
+ s->alert_size = ALERTSIZE_FULL;
+ }
if (datad.alertStatus == cereal_Live100Data_AlertStatus_userPrompt) {
update_status(s, STATUS_WARNING);
@@ -1474,17 +1805,68 @@ static void ui_update(UIState *s) {
}
s->scene.started_ts = datad.startedTs;
+ } else if (eventd.which == cereal_Event_uiLayoutState) {
+ struct cereal_UiLayoutState datad;
+ cereal_read_UiLayoutState(&datad, eventd.uiLayoutState);
+ s->scene.uilayout_sidebarcollapsed = datad.sidebarCollapsed;
+ s->scene.uilayout_mapenabled = datad.mapEnabled;
+
+ bool hasSidebar = !s->scene.uilayout_sidebarcollapsed;
+ bool mapEnabled = s->scene.uilayout_mapenabled;
+ if (mapEnabled) {
+ s->scene.ui_viz_rx = hasSidebar ? viz_x : (viz_x-(bdr_s*2));
+ s->scene.ui_viz_rw = hasSidebar ? viz_w : (viz_w+(bdr_s*2));
+ } else {
+ s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x-sbr_w+bdr_s*2);
+ s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w+sbr_w-(bdr_s*2));
+ s->scene.ui_frame_offset = hasSidebar ? -(sbr_w - 4*bdr_s) : -(bdr_s*2);
+ s->scene.ui_world_offset = hasSidebar ? -(sbr_w - 6*bdr_s) : -(bdr_s*2);
+ }
}
-
capn_free(&ctx);
-
zmq_msg_close(&msg);
-
}
}
}
+static int vision_subscribe(int fd, VisionPacket *rp, int type) {
+ int err;
+ LOGW("vision_subscribe type:%d", type);
+
+ VisionPacket p1 = {
+ .type = VIPC_STREAM_SUBSCRIBE,
+ .d = { .stream_sub = { .type = type, .tbuffer = true, }, },
+ };
+ err = vipc_send(fd, &p1);
+ if (err < 0) {
+ close(fd);
+ return 0;
+ }
+
+ do {
+ err = vipc_recv(fd, rp);
+ if (err <= 0) {
+ close(fd);
+ return 0;
+ }
+
+ // release what we aren't ready for yet
+ if (rp->type == VIPC_STREAM_ACQUIRE) {
+ VisionPacket rep = {
+ .type = VIPC_STREAM_RELEASE,
+ .d = { .stream_rel = {
+ .type = rp->d.stream_acq.type,
+ .idx = rp->d.stream_acq.idx,
+ }},
+ };
+ vipc_send(fd, &rep);
+ }
+ } while (rp->type != VIPC_STREAM_BUFS || rp->d.stream_bufs.type != type);
+
+ return 1;
+}
+
static void* vision_connect_thread(void *args) {
int err;
@@ -1499,43 +1881,9 @@ static void* vision_connect_thread(void *args) {
int fd = vipc_connect();
if (fd < 0) continue;
-
-
- VisionPacket p1 = {
- .type = VIPC_STREAM_SUBSCRIBE,
- .d = { .stream_sub = { .type = VISION_STREAM_UI_BACK, .tbuffer = true, }, },
- };
- err = vipc_send(fd, &p1);
- if (err < 0) {
- close(fd);
- continue;
- }
- VisionPacket p2 = {
- .type = VIPC_STREAM_SUBSCRIBE,
- .d = { .stream_sub = { .type = VISION_STREAM_UI_FRONT, .tbuffer = true, }, },
- };
- err = vipc_send(fd, &p2);
- if (err < 0) {
- close(fd);
- continue;
- }
-
- // printf("init recv\n");
- VisionPacket back_rp;
- err = vipc_recv(fd, &back_rp);
- if (err <= 0) {
- close(fd);
- continue;
- }
- assert(back_rp.type == VIPC_STREAM_BUFS);
- VisionPacket front_rp;
- err = vipc_recv(fd, &front_rp);
- if (err <= 0) {
- close(fd);
- continue;
- }
- assert(front_rp.type == VIPC_STREAM_BUFS);
-
+ VisionPacket back_rp, front_rp;
+ if (!vision_subscribe(fd, &back_rp, VISION_STREAM_UI_BACK)) continue;
+ if (!vision_subscribe(fd, &front_rp, VISION_STREAM_UI_FRONT)) continue;
pthread_mutex_lock(&s->lock);
assert(!s->vision_connected);
@@ -1676,6 +2024,7 @@ int main() {
if (EON) {
// light sensor is only exposed on EONs
+
float clipped_light_sensor = (s->light_sensor*LIGHT_SENSOR_M) + LIGHT_SENSOR_B;
if (clipped_light_sensor > 255) clipped_light_sensor = 255;
smooth_light_sensor = clipped_light_sensor * 0.01 + smooth_light_sensor * 0.99;
diff --git a/selfdrive/updated.py b/selfdrive/updated.py
index 516fa31ba9..67a592996a 100644
--- a/selfdrive/updated.py
+++ b/selfdrive/updated.py
@@ -8,6 +8,7 @@ import subprocess
from common.basedir import BASEDIR
from selfdrive.swaglog import cloudlog
+from selfdrive.version import dirty
def main(gctx=None):
while True:
@@ -17,7 +18,13 @@ def main(gctx=None):
time.sleep(60)
continue
- r = subprocess.call(["nice", "-n", "19", "git", "fetch", "--depth=1"])
+ # If there are modifications we want to full history
+ # otherwise only store head to save space
+ if dirty:
+ r = subprocess.call(["nice", "-n", "19", "git", "fetch", "--unshallow"])
+ else:
+ r = subprocess.call(["nice", "-n", "19", "git", "fetch", "--depth=1"])
+
cloudlog.info("git fetch: %r", r)
if r:
time.sleep(60)
diff --git a/selfdrive/version.py b/selfdrive/version.py
index b5d667f39a..e1f9e27fa8 100644
--- a/selfdrive/version.py
+++ b/selfdrive/version.py
@@ -1,3 +1,18 @@
import os
+import subprocess
with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf:
version = _versionf.read().split('"')[1]
+
+try:
+ origin = subprocess.check_output(["git", "config", "--get", "remote.origin.url"])
+ if "-private" in origin:
+ upstream = "origin/master"
+ else:
+ if 'chffrplus' in origin:
+ upstream = "origin/release"
+ else:
+ upstream = "origin/release2"
+
+ dirty = subprocess.call(["git", "diff-index", "--quiet", upstream, "--"]) != 0
+except subprocess.CalledProcessError:
+ dirty = True
diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README
index ae92bd4b3f..d237562739 100644
--- a/selfdrive/visiond/README
+++ b/selfdrive/visiond/README
@@ -1,3 +1,3 @@
-visiond runs the openpilot vision pipeline. Everything running between the camera hardware and model outputs lives here.
+visiond runs the openpilot/chffrplus vision pipeline. Everything running between the camera hardware and model outputs lives here.
Contact us if you'd like features added or support for your platform.
diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond
index 2a8b8e1ef0..0854b8a262 100755
Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ