diff --git a/README.md b/README.md
index 367ba9cd418a92..9032d54b09ecb4 100644
--- a/README.md
+++ b/README.md
@@ -15,9 +15,9 @@ Table of Contents
* [Supported Cars](#supported-cars)
* [Community Maintained Cars](#community-maintained-cars)
* [In Progress Cars](#in-progress-cars)
-* [How can I add support for my car?](#how-can-i-add-support-for-my-car-)
+* [How can I add support for my car?](#how-can-i-add-support-for-my-car)
* [Directory structure](#directory-structure)
-* [User Data / chffr Account / Crash Reporting](#user-data-chffr-account-crash-reporting)
+* [User Data / chffr Account / Crash Reporting](#user-data--chffr-account--crash-reporting)
* [Testing on PC](#testing-on-pc)
* [Contributing](#contributing)
* [Licensing](#licensing)
@@ -35,7 +35,7 @@ Also, we have a several thousand people community on [slack](https://slack.comma
- |
+ |
|
|
|
@@ -51,53 +51,56 @@ Also, we have a several thousand people community on [slack](https://slack.comma
Hardware
------
-Right now openpilot supports the [EON Dashcam DevKit](https://comma.ai/shop/products/eon-dashcam-devkit). We'd like to support other platforms as well.
+At the moment openpilot supports the [EON Dashcam DevKit](https://comma.ai/shop/products/eon-dashcam-devkit). A [panda](https://shop.comma.ai/products/panda-obd-ii-dongle) and a [giraffe](https://comma.ai/shop/products/giraffe/) are recommended tools to interface the EON with the car. We'd like to support other platforms as well.
Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` during NEOS setup.
Supported Cars
------
-| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | Giraffe |
-| ---------------------| ------------------------| ---------------------| --------| ---------------| -----------------| ---------------|-------------------|
-| Acura | ILX 2016-17 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | Nidec |
-| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | Nidec |
-| Chevrolet3| Malibu 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
-| Chevrolet3| Volt 2017-18 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
-| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | Bosch |
-| Honda | Civic 2016-18 | Honda Sensing | Yes | Yes | 0mph | 12mph | Nidec |
-| Honda | Civic 2017-18 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
-| Honda | CR-V 2015-16 | Touring | Yes | Yes | 25mph1| 12mph | Nidec |
-| Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
-| Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 0mph | Inverted Nidec |
-| Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec |
-| Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | Inverted Nidec |
-| Honda | Ridgeline 2017-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec |
-| Hyundai | Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | Custom6|
-| Hyundai | Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | Custom6|
-| Hyundai | Genesis 2018 | All | Yes | Stock | 19mph | 34mph | Custom6|
-| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom6|
-| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6|
-| Lexus | RX Hybrid 2016-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | Toyota |
-| Toyota | C-HR 2017-184| All | Yes | Stock | 0mph | 0mph | Toyota |
-| Toyota | Corolla 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota |
-| Toyota | Highlander 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Highlander Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Prius 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Prius Prime 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
-| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | Toyota |
-| Toyota | Rav4 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota |
-| Toyota | Rav4 Hybrid 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | Giraffe |
+| ---------------------| -------------------------| ---------------------| --------| ---------------| -----------------| ---------------|-------------------|
+| Acura | ILX 2016-17 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | Nidec |
+| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | Nidec |
+| Chevrolet3| Malibu 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
+| Chevrolet3| Volt 2017-18 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
+| Cadillac3 | ATS 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
+| GMC3 | Acadia Denali 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
+| Holden3 | Astra 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | Custom7|
+| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | Bosch |
+| Honda | Civic Sedan/Coupe 2016-18| Honda Sensing | Yes | Yes | 0mph | 12mph | Nidec |
+| Honda | Civic Hatchback 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
+| Honda | CR-V 2015-16 | Touring | Yes | Yes | 25mph1| 12mph | Nidec |
+| Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch |
+| Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 0mph | Inverted Nidec |
+| Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec |
+| Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | Inverted Nidec |
+| Honda | Ridgeline 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec |
+| Hyundai | Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | Custom6|
+| Hyundai | Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | Custom6|
+| Hyundai | Genesis 2018 | All | Yes | Stock | 19mph | 34mph | Custom6|
+| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom6|
+| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6|
+| Lexus | RX Hybrid 2016-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | Toyota |
+| Toyota | C-HR 2017-184 | All | Yes | Stock | 0mph | 0mph | Toyota |
+| Toyota | Corolla 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota |
+| Toyota | Highlander 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Highlander Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Prius 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Prius Prime 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | Toyota |
+| Toyota | Rav4 2017-18 | All | Yes | Yes2| 20mph | 0mph | Toyota |
+| Toyota | Rav4 Hybrid 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
1[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)***
2When disconnecting the Driver Support Unit (DSU), otherwise longitudinal control is stock ACC. For DSU locations, see [Toyota Wiki page](https://community.comma.ai/wiki/index.php/Toyota)
3[GM installation guide](https://zoneos.com/volt/).
4It needs an extra 120Ohm resistor ([pic1](https://i.imgur.com/CmdKtTP.jpg), [pic2](https://i.imgur.com/s2etUo6.jpg)) on bus 3 and giraffe switches set to 01X1 (11X1 for stock LKAS), where X depends on if you have the [comma power](https://comma.ai/shop/products/power/).
528mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
-6Open sourced [Hyundai Giraffe](https://github.com/commaai/neo/tree/master/giraffe/hyundai) is designed ofor the 2019 Sante Fe; pinout may differ for other Hyundais.
-7Community built Giraffe, find more information here, [GM Giraffe](https://zoneos.com/shop/)
+6Open sourced [Hyundai Giraffe](https://github.com/commaai/neo/tree/master/giraffe/hyundai) is designed ofor the 2019 Sante Fe; pinout may differ for other Hyundais.
+7Community built Giraffe, find more information here, [GM Giraffe](https://zoneos.com/shop/).
Community Maintained Cars
------
diff --git a/RELEASES.md b/RELEASES.md
index 3720b53506940c..216feb83cfcf61 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,3 +1,13 @@
+Version 0.5.7 (2018-12-06)
+========================
+ * Speed limit from OpenStreetMap added to UI
+ * Highlight speed limit when speed exceeds road speed limit plus a delta
+ * Option to limit openpilot max speed to road speed limit plus a delta
+ * Cadillac ATS support thanks to vntarasov!
+ * GMC Acadia support thanks to CryptoKylan!
+ * Decrease GPU power consumption
+ * NEOSv8 autoupdate
+
Version 0.5.6 (2018-11-16)
========================
* Refresh settings layout and add feature descriptions
@@ -7,6 +17,7 @@ Version 0.5.6 (2018-11-16)
* More tuning to Honda positive accelerations
* Reduce brake pump use on Hondas
* Chevrolet Malibu support thanks to tylergets!
+ * Holden Astra support thanks to AlexHill!
Version 0.5.5 (2018-10-20)
========================
diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk
index a9e5738a40cd3c..84ebf24ae42ecd 100644
Binary files a/apk/ai.comma.plus.offroad.apk and b/apk/ai.comma.plus.offroad.apk differ
diff --git a/cereal/Makefile b/cereal/Makefile
index b86fa68f585816..dc6b7f9d51fa03 100644
--- a/cereal/Makefile
+++ b/cereal/Makefile
@@ -6,13 +6,16 @@ GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++
JS := gen/js/car.capnp.js gen/js/log.capnp.js
UNAME_M ?= $(shell uname -m)
-
# only generate C++ for docker tests
ifneq ($(OPTEST),1)
GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/include/c++.capnp.h gen/c/include/java.capnp.h
ifeq ($(UNAME_M),x86_64)
- GENS += gen/java/Car.java gen/java/Log.java
+ ifneq (, $(shell which capnpc-java))
+ GENS += gen/java/Car.java gen/java/Log.java
+ else
+ $(warning capnpc-java not found, skipping java build)
+ endif
endif
endif
diff --git a/cereal/car.capnp b/cereal/car.capnp
index 2f25aa0d1ac02e..bf982f8aba0da6 100644
--- a/cereal/car.capnp
+++ b/cereal/car.capnp
@@ -355,6 +355,7 @@ struct CarParams {
radarOffCan @47 :Bool; # True when radar objects aren't visible on CAN
steerActuatorDelay @48 :Float32; # Steering wheel actuator delay in seconds
+ openpilotLongitudinalControl @50 :Bool; # is openpilot doing the longitudinal control?
enum SteerControlType {
torque @0;
diff --git a/cereal/log.capnp b/cereal/log.capnp
index 389b550ad421ae..e643728e0031ec 100644
--- a/cereal/log.capnp
+++ b/cereal/log.capnp
@@ -276,7 +276,8 @@ struct ThermalData {
startedTs @13 :UInt64;
thermalStatus @14 :ThermalStatus;
- chargerDisabled @17 :Bool;
+ chargingError @17 :Bool;
+ chargingDisabled @18 :Bool;
enum ThermalStatus {
green @0; # all processes run
@@ -344,6 +345,7 @@ struct LiveCalibrationData {
warpMatrix @0 :List(Float32);
# camera_frame_from_model_frame
warpMatrix2 @5 :List(Float32);
+ warpMatrixBig @6 :List(Float32);
calStatus @1 :Int8;
calCycle @2 :Int32;
calPerc @3 :Int8;
@@ -562,6 +564,10 @@ struct Plan {
gpsPlannerActive @19 :Bool;
+ # maps
+ vCurvature @21 :Float32;
+ decelForTurn @22 :Bool;
+
struct GpsTrajectory {
x @0 :List(Float32);
y @1 :List(Float32);
@@ -1567,8 +1573,17 @@ struct LiveParametersData {
}
struct LiveMapData {
- valid @0 :Bool;
+ speedLimitValid @0 :Bool;
speedLimit @1 :Float32;
+ curvatureValid @2 :Bool;
+ curvature @3 :Float32;
+ wayId @4 :UInt64;
+ roadX @5 :List(Float32);
+ roadY @6 :List(Float32);
+ lastGps @7: GpsLocationData;
+ roadCurvatureX @8 :List(Float32);
+ roadCurvature @9 :List(Float32);
+ distToTurn @10 :Float32;
}
diff --git a/common/params.py b/common/params.py
index 3981a341f4e28c..cc137d5a7b15c4 100755
--- a/common/params.py
+++ b/common/params.py
@@ -63,6 +63,7 @@ class UnknownKeyName(Exception):
"IsUploadVideoOverCellularEnabled": TxType.PERSISTENT,
"IsDriverMonitoringEnabled": TxType.PERSISTENT,
"IsGeofenceEnabled": TxType.PERSISTENT,
+ "SpeedLimitOffset": TxType.PERSISTENT,
# written: visiond
# read: visiond, controlsd
"CalibrationParams": TxType.PERSISTENT,
@@ -74,6 +75,8 @@ class UnknownKeyName(Exception):
"DoUninstall": TxType.CLEAR_ON_MANAGER_START,
"ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START,
"IsUpdateAvailable": TxType.PERSISTENT,
+ "LongitudinalControl": TxType.PERSISTENT,
+ "LimitSetSpeed": TxType.PERSISTENT,
"RecordFront": TxType.PERSISTENT,
}
diff --git a/common/transformations/model.py b/common/transformations/model.py
index 107c3d542c2036..424bd6158e43c1 100644
--- a/common/transformations/model.py
+++ b/common/transformations/model.py
@@ -83,7 +83,7 @@ def get_model_height_transform(camera_frame_from_road_frame, height):
# camera_frame_from_model_frame aka 'warp matrix'
# was: calibration.h/CalibrationTransform
-def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height):
+def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height=model_height):
vp = vp_from_ke(camera_frame_from_road_frame)
model_camera_from_model_frame = np.array([
diff --git a/installer/updater/updater b/installer/updater/updater
index a5defb4108b556..0b8602b3550175 100755
Binary files a/installer/updater/updater and b/installer/updater/updater differ
diff --git a/opendbc/generator/honda/honda_insight_ex_2019_can.dbc b/opendbc/generator/honda/honda_insight_ex_2019_can.dbc
new file mode 100644
index 00000000000000..ff988cf9dae796
--- /dev/null
+++ b/opendbc/generator/honda/honda_insight_ex_2019_can.dbc
@@ -0,0 +1,44 @@
+CM_ "IMPORT _bosch_2018.dbc"
+
+BO_ 419 GEARBOX: 8 PCM
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" 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_ BRAKE_ERROR_1 : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_ERROR_2 : 12|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_ 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_ HUD_LEAD : 40|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_TO_64 : 31|8@0+ (1,0) [0|255] "" XXX
+ SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ ZEROS_BOH3 : 47|7@0+ (1,0) [0|127] "" XXX
+ SG_ ZEROS_BOH4 : 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_ 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_ 419 GEAR 10 "R" 1 "D" 0 "P";
+ VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" ;
+
+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/toyota/_comma.dbc b/opendbc/generator/toyota/_comma.dbc
index 4e4c82d80e7c71..64d5ebc8d03764 100644
--- a/opendbc/generator/toyota/_comma.dbc
+++ b/opendbc/generator/toyota/_comma.dbc
@@ -11,14 +11,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/generator/toyota/_toyota_2017.dbc b/opendbc/generator/toyota/_toyota_2017.dbc
index 294b948ddef737..7fb249cac04af3 100644
--- a/opendbc/generator/toyota/_toyota_2017.dbc
+++ b/opendbc/generator/toyota/_toyota_2017.dbc
@@ -248,9 +248,9 @@ VAL_ 1553 UNITS 1 "km" 2 "miles";
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left";
VAL_ 1161 TSGN1 1 "speed sign" 0 "none";
VAL_ 1161 TSGN2 1 "speed sign" 0 "none";
-VAL_ 1161 SPLSGN2 15 "conditional" 0 "none";
+VAL_ 1161 SPLSGN2 15 "conditional blank" 5 "rain" 0 "none";
VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry";
-VAL_ 1162 SPLSGN3 15 "conditional" 0 "none";
+VAL_ 1162 SPLSGN3 15 "conditional blank" 5 "rain" 0 "none";
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
diff --git a/opendbc/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain.dbc
index 27f181dc0fa681..1342c49f75f81d 100644
--- a/opendbc/gm_global_a_powertrain.dbc
+++ b/opendbc/gm_global_a_powertrain.dbc
@@ -180,6 +180,7 @@ BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM
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
+ SG_ FCWAlert : 41|2@0+ (1,0) [0|3] "" XXX
BO_ 1001 ECMVehicleSpeed: 8 K20_ECM
SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO
diff --git a/opendbc/honda_insight_ex_2019_can_generated.dbc b/opendbc/honda_insight_ex_2019_can_generated.dbc
new file mode 100644
index 00000000000000..00050aa8d4332a
--- /dev/null
+++ b/opendbc/honda_insight_ex_2019_can_generated.dbc
@@ -0,0 +1,311 @@
+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_ 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.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_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" 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_ 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_ 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_ 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_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX
+ 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_ 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_ 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_insight_ex_2019_can.dbc starts here"
+
+
+BO_ 419 GEARBOX: 8 PCM
+ SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
+ SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" 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_ BRAKE_ERROR_1 : 13|1@0+ (1,0) [0|1] "" EON
+ SG_ BRAKE_ERROR_2 : 12|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_ 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_ HUD_LEAD : 40|1@0+ (1,0) [0|1] "" XXX
+ SG_ SET_TO_64 : 31|8@0+ (1,0) [0|255] "" XXX
+ SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX
+ SG_ ZEROS_BOH3 : 47|7@0+ (1,0) [0|127] "" XXX
+ SG_ ZEROS_BOH4 : 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_ 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_ 419 GEAR 10 "R" 1 "D" 0 "P";
+ VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" ;
+
+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/hyundai_santa_fe_2019_ccan.dbc b/opendbc/hyundai_kia_generic.dbc
similarity index 100%
rename from opendbc/hyundai_santa_fe_2019_ccan.dbc
rename to opendbc/hyundai_kia_generic.dbc
diff --git a/opendbc/kia_sorento_2018.dbc b/opendbc/kia_sorento_2018.dbc
deleted file mode 100644
index 919da4cc2dd90c..00000000000000
--- a/opendbc/kia_sorento_2018.dbc
+++ /dev/null
@@ -1,1391 +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_: IAP ODS _4WD BCM HUD DATC MDPS AAF_Tester AEMC SMK _4WD EPB CUBIS MTS TMU EVP CGW TPMS LPI DI_BOX SPAS ACU Dummy AFLS CLU EMS AVM LDWS_LKAS SCC IBOX LCA PGS AHLS SAS AAF ECS ESC PSB TCU ABS REA FATC FPCM SNV LVR XXX
-
-
-BO_ 1532 ODS13: 5 ODS
- SG_ CR_Ods_ID : 0|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_Chksum_H : 8|8@1+ (1,0) [0|255] "" Dummy
- SG_ CR_Ods_Chksum_L : 16|8@1+ (1,0) [0|255] "" Dummy
- SG_ CR_Ods_RomID_H : 24|8@1+ (1,0) [0|255] "" Dummy
- SG_ CR_Ods_RomID_L : 32|8@1+ (1,0) [0|255] "" Dummy
-
-BO_ 1531 ODS12: 8 ODS
- SG_ CR_Ods_SerNum0 : 0|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum1 : 8|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum2 : 16|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum3 : 24|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum4 : 32|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum5 : 40|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum6 : 48|8@1+ (1,0) [0|255] "" ACU
- SG_ CR_Ods_SerNum7 : 56|8@1+ (1,0) [0|255] "" ACU
-
-BO_ 1530 ODS11: 8 ODS
- SG_ CF_Ods_PrcCmd : 1|1@1+ (1,0) [0|1] "" Dummy
- SG_ CF_Ods_BtsFail : 3|1@1+ (1,0) [0|1] "" Dummy
- SG_ CF_Ods_AcuRcvSN : 4|1@1+ (1,0) [0|1] "" ACU
- SG_ CF_Ods_EolCal : 5|1@1+ (1,0) [0|1] "" ACU
- SG_ CF_Ods_PsFail : 6|1@1+ (1,0) [0|1] "" ACU
- SG_ CF_Ods_EcuFail : 7|1@1+ (1,0) [0|1] "" ACU
- SG_ CF_Ods_WgtStat : 8|1@1+ (1,0) [0|1] "" ACU
- SG_ CF_Ods_OccStat : 16|1@1+ (1,0) [0|1] "" ACU
- SG_ CR_Wcs_ErrStat : 32|8@1+ (1,0) [0|63] "" ACU
- SG_ CR_Wcs_ClassStat : 40|8@1+ (1,0) [0|4] "" ACU,BCM
-
-BO_ 1017 ECS12: 4 ECS
- SG_ Height_FL : 0|8@1+ (1,-128) [-128|127] "mm" AFLS
- SG_ Height_FR : 8|8@1+ (1,-128) [-128|127] "mm" AFLS
- SG_ Height_RL : 16|8@1+ (1,-128) [-128|127] "mm" AFLS
- SG_ Height_RR : 24|8@1+ (1,-128) [-128|127] "mm" AFLS
-
-BO_ 1268 SPAS12: 8 SPAS
- SG_ CF_Spas_HMI_Stat : 0|8@1+ (1,0) [0|255] "" CLU
- SG_ CF_Spas_Disp : 8|2@1+ (1,0) [0|3] "" CLU,EMS
- SG_ CF_Spas_FIL_Ind : 10|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FIR_Ind : 13|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FOL_Ind : 16|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FOR_Ind : 19|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_VolDown : 22|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_RIL_Ind : 24|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_RIR_Ind : 27|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FLS_Alarm : 30|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_ROL_Ind : 32|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_ROR_Ind : 35|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FCS_Alarm : 38|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_FI_Ind : 40|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_RI_Ind : 43|3@1+ (1,0) [0|7] "" AVM,CLU
- SG_ CF_Spas_FRS_Alarm : 46|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_FR_Alarm : 48|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_Spas_RR_Alarm : 50|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_Spas_BEEP_Alarm : 52|4@1+ (1,0) [0|15] "" BCM,CLU
- SG_ CF_Spas_StatAlarm : 56|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Spas_RLS_Alarm : 57|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_RCS_Alarm : 59|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_RRS_Alarm : 61|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1265 CLU11: 4 CLU
- SG_ CF_Clu_CruiseSwState : 0|3@1+ (1,0) [0|7] "" EMS,LDWS_LKAS,SCC
- SG_ CF_Clu_CruiseSwMain : 3|1@1+ (1,0) [0|1] "" EMS,LDWS_LKAS,SCC
- SG_ CF_Clu_SldMainSW : 4|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Clu_ParityBit1 : 5|1@1+ (1,0) [0|1] "pulse count" EMS
- SG_ CF_Clu_VanzDecimal : 6|2@1+ (0.125,0) [0|0.375] "" EMS
- SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0) [0|255.5] "km/h or MPH" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC
- SG_ CF_Clu_SPEED_UNIT : 17|1@1+ (1,0) [0|1] "" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC
- SG_ CF_Clu_DetentOut : 18|1@1+ (1,0) [0|1] "" AVM,BCM,LCA,PGS,SPAS
- SG_ CF_Clu_RheostatLevel : 19|5@1+ (1,0) [0|31] "" AVM,BCM,LCA,PGS,SPAS
- SG_ CF_Clu_CluInfo : 24|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_AmpInfo : 25|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_AliveCnt1 : 28|4@1+ (1,0) [0|15] "" AHLS,EMS,EPB,LDWS_LKAS,MDPS,SCC
-
-BO_ 1492 TMU_GW_PE_01: 8 CLU
- SG_ TMU_IVRActivity : 0|2@1+ (1,0) [0|3] "" DATC
- SG_ TMU_PhoneActivity : 2|2@1+ (1,0) [0|3] "" DATC
-
-BO_ 1491 HU_DATC_PE_00: 8 CLU
- SG_ HU_VRActivity : 0|2@1+ (1,0) [0|3] "" DATC
- SG_ HU_PhoneActivity : 2|2@1+ (1,0) [0|3] "" DATC
- SG_ BlowerNoiseControl : 4|2@1+ (1,0) [0|3] "" DATC
-
-BO_ 1490 HU_DATC_E_02: 8 CLU
- SG_ HU_DATC_RearOnOffSet : 6|2@1+ (1,0) [0|3] "" DATC
- SG_ HU_DATC_ADSOnOffSet : 8|2@1+ (1,0) [0|3] "" DATC
-
-BO_ 1479 EMS21: 8 EMS
- SG_ SCR_LEVEL_WARN_LAMP : 0|1@1+ (1,0) [0|1] "" CLU
- SG_ SCR_LEVEL_WARN : 1|3@1+ (1,0) [0|4] "" CLU
- SG_ SCR_SYS_ERROR_WARN : 4|3@1+ (1,0) [0|7] "" CLU
- SG_ SCR_SYSTEM_WARN_LAMP : 7|1@1+ (1,0) [0|1] "" CLU
- SG_ SCR_INDUCEMENT_EXIT_COND : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ SCR_UREA_LEVEL : 16|8@1+ (0.5,0) [0|100] "%" CLU
- SG_ SCR_NO_REMAINING_RESTARTS : 24|8@1+ (1,0) [0|255] "" CLU
- SG_ SCR_REMAINING_DISTANCE : 32|16@1+ (1,0) [0|25000] "km" CLU
-
-BO_ 1472 GW_Warning_PE: 8 BCM
- SG_ Audio_VolumeDown : 38|2@1+ (1,0) [0|3] "" CLU
- SG_ Pas_Spkr_Flh_Alarm : 48|2@1+ (1,0) [0|3] "" CLU
- SG_ Pas_Spkr_Fcnt_Alarm : 50|2@1+ (1,0) [0|3] "" CLU
- SG_ Pas_Spkr_Frh_Alarm : 52|2@1+ (1,0) [0|3] "" CLU
- SG_ Pas_Spkr_Rlh_Alarm : 56|2@1+ (1,0) [0|3] "" CLU,PGS
- SG_ Pas_Spkr_Rcnt_Alarm : 58|2@1+ (1,0) [0|3] "" CLU
- SG_ Pas_Spkr_Rrh_Alarm : 60|2@1+ (1,0) [0|3] "" CLU,PGS
-
-BO_ 1984 CAL_SAS11: 2 ESC
- SG_ CCW : 0|4@1+ (1,0) [0|15] "" SAS
- SG_ SAS_CID : 4|11@1+ (1,0) [0|2047] "" SAS
-
-BO_ 1456 CLU12: 4 CLU
- SG_ CF_Clu_Odometer : 0|24@1+ (0.1,0) [0|1677721.4] "km" _4WD,AAF,BCM,CUBIS,EMS,EPB,IBOX,LDWS_LKAS,SCC,TPMS
-
-BO_ 688 SAS11: 5 MDPS
- SG_ SAS_Angle : 0|16@1- (0.1,0) [-3276.8|3276.7] "Deg" _4WD,ACU,AFLS,AVM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU,_4WD,ACU,AFLS,AVM,BCM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU
- SG_ SAS_Speed : 16|8@1- (4,0) [0|1016] "" AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU,AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU
- SG_ SAS_Stat : 24|8@1+ (1,0) [0|255] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU
- SG_ MsgCount : 32|4@1+ (1,0) [0|15] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS
- SG_ CheckSum : 36|4@1+ (1,0) [0|15] "" ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS
-
-BO_ 1441 ACU12: 8 ACU
- SG_ CR_Acu_SN : 0|64@1+ (1,0) [0|0] "" ODS
-
-BO_ 1440 ACU11: 8 ACU
- SG_ CF_Ods_SNRcv : 1|1@1+ (1,0) [0|1] "" ODS
- SG_ CF_Ods_IDRcv : 2|1@1+ (1,0) [0|1] "" ODS
- SG_ CF_Ods_RZReq : 4|1@1+ (1,0) [0|1] "" ODS
- SG_ CF_Abg_DepInhEnt : 6|1@1+ (1,0) [0|1] "" ODS
- SG_ CF_Abg_DepEnt : 7|1@1+ (1,0) [0|1] "" ODS
- SG_ CF_PasBkl_FltStat : 28|1@1+ (1,0) [0|1] "" ODS,PSB
- SG_ CF_DriBkl_FltStat : 29|1@1+ (1,0) [0|1] "" ODS,PSB
- SG_ CF_PasBkl_Stat : 30|1@1+ (1,0) [0|1] "" IBOX,ODS,PSB,TMU
- SG_ CF_DriBkl_Stat : 31|1@1+ (1,0) [0|1] "" ODS,PSB
- SG_ CF_SWL_Ind : 32|2@1+ (1,0) [0|3] "" CUBIS,IBOX
- SG_ CF_Acu_FltStat : 34|2@1+ (1,0) [0|3] "" CUBIS,IBOX
- SG_ CF_Acu_ExtOfSab : 36|2@1+ (1,0) [0|3] "" BCM,CLU,CUBIS,IBOX
- SG_ CF_Acu_Dtc : 40|16@1+ (1,0) [0|65535] "" CUBIS,IBOX
- SG_ CF_Acu_NumOfFlt : 56|8@1+ (1,0) [0|255] "" CUBIS,IBOX
-
-BO_ 1437 AHLS11: 8 AHLS
- SG_ CF_Ahls_WarnLamp : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Ahls_WarnMsg : 2|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1434 PSB11: 2 PSB
- SG_ PSB_LH_FAIL : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ PSB_LH_TGL : 2|1@1+ (1,0) [0|1] "" CLU
- SG_ PSB_LH_ACT : 3|4@1+ (1,0) [0|4] "" Dummy
- SG_ PSB_RH_FAIL : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ PSB_RH_TGL : 10|1@1+ (1,0) [0|1] "" CLU
- SG_ PSB_RH_ACT : 11|4@1+ (1,0) [0|4] "" Dummy
-
-BO_ 916 TCS13: 8 ESC
- SG_ aBasis : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC
- SG_ BrakeLight : 11|1@1+ (1,0) [0|1] "" CLU,EMS,SCC
- SG_ DCEnable : 12|1@1+ (1,0) [0|1] "" EMS,SCC
- SG_ AliveCounterTCS : 13|3@1+ (1,0) [0|7] "" EMS,SCC
- SG_ ACCReqLim : 22|2@1+ (1,0) [0|3] "" EMS,SCC
- SG_ TQI_ACC : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS
- SG_ ACCEL_REF_ACC : 32|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC
- SG_ ACCEnable : 43|2@1+ (1,0) [0|3] "" EMS,SCC
- SG_ DriverOverride : 45|2@1+ (1,0) [0|3] "" EMS,SCC
- SG_ StandStill : 47|1@1+ (1,0) [0|1] "" EMS,SCC
- SG_ CheckSum_TCS3 : 48|4@1+ (1,0) [0|15] "" EMS,SCC
- SG_ ACC_EQUIP : 52|1@1+ (1,0) [0|1] "" EMS,SCC
- SG_ PBRAKE_ACT : 53|1@1+ (1,0) [0|1] "" EMS,SCC
- SG_ ACC_REQ : 54|1@1+ (1,0) [0|1] "" EMS
- SG_ DriverBraking : 55|1@1+ (1,0) [0|1] "" EMS,SCC
- SG_ CF_VSM_Coded : 56|1@1+ (1,0) [0|1] "" SCC
- SG_ CF_VSM_Avail : 57|2@1+ (1,0) [0|3] "" CLU,SCC
- SG_ CF_VSM_Handshake : 59|1@1+ (1,0) [0|1] "" SCC
- SG_ CF_DriBkeStat : 60|1@1+ (1,0) [0|1] "" SCC
- SG_ CF_VSM_ConfSwi : 61|2@1+ (1,0) [0|3] "" SCC
- SG_ AEB_EQUIP : 63|1@1+ (1,0) [0|1] "" SCC
-
-BO_ 1427 TPMS11: 6 BCM
- SG_ TPMS_W_LAMP : 0|2@1+ (1,0) [0|3] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX
- SG_ TREAD_W_LAMP : 2|2@1+ (1,0) [0|3] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX
- SG_ POS_FL_W_LAMP : 4|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX
- SG_ POS_FR_W_LAMP : 5|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX
- SG_ POS_RL_W_LAMP : 6|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX
- SG_ POS_RR_W_LAMP : 7|1@1+ (1,0) [0|1] "" CLU,CUBIS,HUD,IBOX
- SG_ STATUS_TPMS : 8|3@1+ (1,0) [0|0] "" CLU
- SG_ UNIT : 11|2@1+ (1,0) [0|3] "" CLU
- SG_ PRESSURE_FL : 16|8@1+ (1,0) [0|255] "" CLU
- SG_ PRESSURE_FR : 24|8@1+ (1,0) [0|255] "" CLU
- SG_ PRESSURE_RL : 32|8@1+ (1,0) [0|255] "" CLU
- SG_ PRESSURE_RR : 40|8@1+ (1,0) [0|255] "" CLU
-
-BO_ 915 TCS12: 4 ESC
- SG_ SA_COUNT : 0|16@1+ (2,-32768) [-32768|98302] "" _4WD,ACU,MDPS
- SG_ SA_Z_COUNT : 16|15@1+ (2,-32768) [-32768|32766] "" _4WD,ACU,MDPS
- SG_ SA_Z_FLAG : 31|1@1+ (1,0) [0|1] "" _4WD,ACU,MDPS
-
-BO_ 1170 EMS19: 8 EMS
- SG_ CF_Ems_BrkReq : 0|1@1+ (1,0) [0|1] "" ESC,IBOX,TCU
- SG_ CF_Ems_DnShftReq : 1|4@1+ (1,0) [0|14] "" IBOX,TCU
- SG_ CF_Ems_RepModChk : 5|2@1+ (1,0) [0|3] "" IBOX
- SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1,0) [0|1] "" AAF,IBOX
- SG_ CF_Ems_DecelReq : 8|12@1+ (0.001,-4.094) [-4.094|0] "m/s^2" ESC,IBOX,TCU
- SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0) [0|4094] "hPa" CLU,IBOX
- SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40) [0|254] "deg" CLU,IBOX
- SG_ DPF_LAMP_STAT : 40|2@1+ (1,0) [0|3] "" CLU,IBOX
- SG_ BAT_LAMP_STAT : 42|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41) [-41|85.5] "deg" AAF,IBOX
- SG_ CF_Ems_OPSFail : 56|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1,0) [0|3] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU
- SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1,0) [0|15] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU
-
-BO_ 1425 AFLS11: 2 AFLS
- SG_ AFLS_STAT : 1|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Afls_TrfChgStat : 3|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Afls_LedHLStat : 4|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 912 SPAS11: 7 SPAS
- SG_ CF_Spas_Stat : 0|4@1+ (1,0) [0|15] "" ESC,MDPS
- SG_ CF_Spas_TestMode : 4|2@1+ (1,0) [0|3] "" MDPS
- SG_ CR_Spas_StrAngCmd : 8|16@1- (0.1,0) [-3276.8|3276.7] "" MDPS
- SG_ CF_Spas_BeepAlarm : 24|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Spas_Mode_Seq : 28|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Spas_AliveCnt : 32|8@1+ (1,0) [0|255] "" MDPS
- SG_ CF_Spas_Chksum : 40|8@1+ (1,0) [0|255] "" MDPS
- SG_ CF_Spas_PasVol : 48|3@1+ (1,0) [0|7] "" CGW,CLU
-
-BO_ 1168 EPB11: 7 EPB
- SG_ EPB_I_LAMP : 0|4@1+ (1,0) [0|15] "" BCM,CLU,CUBIS,ESC,IBOX
- SG_ EPB_F_LAMP : 4|2@1+ (1,0) [0|3] "" CLU,CUBIS,ESC,IBOX
- SG_ EPB_ALARM : 6|2@1+ (1,0) [0|3] "" CLU,ESC
- SG_ EPB_CLU : 8|8@1+ (1,0) [0|255] "" CLU,ESC
- SG_ EPB_SWITCH : 16|2@1+ (1,0) [0|3] "" ESC,SCC
- SG_ EPB_RBL : 18|1@1+ (1,0) [0|1] "" EMS,ESC
- SG_ EPB_STATUS : 19|3@1+ (1,0) [0|7] "" CLU,EMS,ESC,SCC,TCU
- SG_ EPB_FRC_ERR : 22|2@1+ (1,0) [0|3] "" EMS,ESC,SCC,TCU
- SG_ EPB_DBF_STAT : 24|1@1+ (1,0) [0|1] "" ESC
- SG_ ESP_ACK : 25|1@1+ (1,0) [0|1] "" ESC
- SG_ EPB_DBF_REQ : 26|1@1+ (1,0) [0|1] "" ESC
- SG_ EPB_FAIL : 29|3@1+ (1,0) [0|7] "" ESC,SCC
- SG_ EPB_FORCE : 32|12@1+ (1,-1000) [-1000|3000] "" ESC
- SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0) [0|2.54] "g" ESC
-
-BO_ 399 EMS_H12: 8 EMS
- SG_ R_TqAcnApvC : 0|8@1+ (0.2,0) [0|51] "Nm" DATC,IBOX
- SG_ R_PAcnC : 8|8@1+ (125,0) [0|31875] "hPa" DATC,IBOX
- SG_ TQI_B : 16|8@1+ (0.390625,0) [0|99.609375] "%" ABS,ESC,IBOX
- SG_ SLD_VS : 24|8@1+ (1,0) [0|255] "km/h" CLU,IBOX
- SG_ CF_CdaStat : 32|3@1+ (1,0) [0|7] "" AEMC,IBOX,TCU
- SG_ CF_Ems_IsgStat : 35|3@1+ (1,0) [0|7] "" ABS,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,MDPS,SMK,TCU
- SG_ CF_Ems_OilChg : 38|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ R_NEngIdlTgC : 40|8@1+ (10,0) [0|2550] "rpm" DATC,IBOX,TCU
- SG_ CF_Ems_UpTarGr : 48|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_DownTarGr : 49|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_DesCurGr : 50|4@1+ (1,0) [0|15] "" CLU,IBOX
- SG_ CF_Ems_SldAct : 54|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_SldPosAct : 55|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_HPresStat : 56|1@1+ (1,0) [0|1] "" IBOX,TCU
- SG_ CF_Ems_IsgBuz : 57|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_FCopen : 59|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Ems_ActEcoAct : 60|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU
- SG_ CF_Ems_EngRunNorm : 61|1@1+ (1,0) [0|1] "" ABS,ESC,IBOX,TCU
- SG_ CF_Ems_IsgStat2 : 62|2@1+ (2,0) [0|3] "" CLU,IBOX,TCU
-
-BO_ 1419 LCA11: 8 LCA
- SG_ CF_Lca_Stat : 0|4@1+ (1,0) [0|15] "" BCM,CLU
- SG_ CF_Rcta_Stat : 4|4@1+ (1,0) [0|15] "" BCM,CLU
- SG_ CF_Lca_IndLeft : 8|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_Rcw_Stat : 10|4@1+ (1,0) [0|15] "" BCM,CLU
- SG_ CF_RCW_Warning : 14|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_Lca_IndRight : 16|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_Lca_SndWan_Stat : 18|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_FR_SndWan : 20|1@1+ (1,0) [0|1] "" BCM,CLU
- SG_ CF_FL_SndWan : 21|1@1+ (1,0) [0|1] "" BCM,CLU
- SG_ CF_RR_SndWan : 22|1@1+ (1,0) [0|1] "" BCM,CLU
- SG_ CF_RL_SndWan : 23|1@1+ (1,0) [0|1] "" BCM,CLU
- SG_ CF_Lca_IndBriLeft : 24|8@1+ (1,0) [0|255] "" BCM,CLU
- SG_ CF_Lca_IndBriRight : 32|8@1+ (1,0) [0|255] "" BCM,CLU
- SG_ CF_RCTA_IndBriLeft : 40|8@1+ (1,0) [0|255] "" BCM,CLU
- SG_ CF_RCTA_IndBriRight : 48|8@1+ (1,0) [0|255] "" BCM,CLU
- SG_ CF_RCTA_IndLeft : 56|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_RCTA_IndRight : 58|2@1+ (1,0) [0|3] "" BCM,CLU
- SG_ CF_SndWarnForClu : 60|1@1+ (1,0) [0|1] "" CLU
-
-BO_ 906 ABS11: 8 ABS
- SG_ ABS_DEF : 0|1@1+ (1,0) [0|1] "" _4WD,ACU,EMS,SPAS,TCU
- SG_ EBD_DEF : 1|1@1+ (1,0) [0|1] "" _4WD,EMS,SPAS,TCU
- SG_ ABS_ACT : 2|1@1+ (1,0) [0|1] "" _4WD,ACU,EPB,SPAS,TCU
- SG_ ABS_W_LAMP : 3|1@1+ (1,0) [0|1] "" _4WD,CLU,CUBIS,MTS,TMU
- SG_ EBD_W_LAMP : 4|1@1+ (1,0) [0|1] "" _4WD,CLU
- SG_ ABS_DIAG : 5|1@1+ (1,0) [0|1] "" _4WD,CLU
- SG_ ESS_STAT : 6|2@1+ (1,0) [0|3] "" _4WD,BCM,CLU,EMS
-
-BO_ 903 WHL_PUL11: 6 ABS
- SG_ WHL_PUL_FL : 0|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS
- SG_ WHL_PUL_FR : 8|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS
- SG_ WHL_PUL_RL : 16|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS
- SG_ WHL_PUL_RR : 24|8@1+ (0.5,0) [0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS
- SG_ WHL_DIR_FL : 32|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS
- SG_ WHL_DIR_FR : 34|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS
- SG_ WHL_DIR_RL : 36|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS
- SG_ WHL_DIR_RR : 38|2@1+ (1,0) [0|3] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS
- SG_ WHL_PUL_Chksum : 40|8@1+ (1,0) [0|255] "" EPB,SPAS,TPMS,EPB,LCA,LDWS_LKAS,SPAS,TPMS
-
-BO_ 1415 TMU11: 8 IBOX
- SG_ CF_Tmu_VehSld : 0|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Tmu_VehImmo : 1|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Tmu_ReqRepCnd : 2|2@1+ (1,0) [0|3] "" EMS
- SG_ CF_Tmu_AirconCtr : 4|1@1+ (1,0) [0|1] "" DATC
- SG_ CF_Tmu_TempMd : 5|1@1+ (1,0) [0|1] "" DATC
- SG_ CF_Tmu_TempSet : 6|16@1+ (1,0) [0|20] "" DATC
- SG_ CF_Tmu_DefrostCtr : 22|1@1+ (1,0) [0|1] "" DATC,FATC
- SG_ CF_Tmu_AliveCnt1 : 56|4@1+ (1,0) [0|15] "" EMS
-
-BO_ 902 WHL_SPD11: 8 ABS
- SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS
- SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,ACU,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS
- SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,BCM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,BCM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS
- SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0) [0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS
- SG_ WHL_SPD_AliveCounter_LSB : 14|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
- SG_ WHL_SPD_AliveCounter_MSB : 30|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
- SG_ WHL_SPD_Checksum_LSB : 46|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
- SG_ WHL_SPD_Checksum_MSB : 62|2@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
-
-BO_ 1414 EVP11: 3 EVP
- SG_ CF_Evp_Stat : 0|1@1+ (1,0) [0|1] "" CLU
-
-BO_ 1412 AAF11: 8 AAF
- SG_ CF_Aaf_ActFlapStatus : 0|2@1+ (1,0) [0|3] "" AAF_Tester
- SG_ CF_Aaf_ModeStatus : 2|3@1+ (1,0) [0|7] "" AAF_Tester
- SG_ CF_Aaf_WrnLamp : 5|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Aaf_ErrStatus : 6|10@1+ (1,0) [0|1023] "" AAF_Tester,EMS
- SG_ CF_Aaf_OpenRqSysAct : 16|8@1+ (1,0) [0|255] "" AAF_Tester
- SG_ CF_Aaf_PStatus : 24|8@1+ (1,0) [0|100] "%" AAF_Tester
- SG_ CF_Aaf_OpenRqSysSol : 32|8@1+ (1,0) [0|255] "" AAF_Tester
- SG_ CF_Aaf_SolFlapStatus : 40|2@1+ (1,0) [0|3] "" AAF_Tester
- SG_ CF_Aaf_MilOnReq : 42|1@1+ (1,0) [0|1] "" EMS
-
-BO_ 900 EMS17: 8 EMS
- SG_ CF_Ems_PkpCurMSV : 0|8@1+ (1,0) [0|255] "" DI_BOX
- SG_ CF_Ems_HolCurMSV : 8|8@1+ (1,0) [0|255] "" DI_BOX
- SG_ CF_Ems_InjVBnkAct : 16|8@1+ (1,0) [0|255] "" DI_BOX
- SG_ CF_Ems_InjVActSet : 24|8@1+ (1,0) [0|255] "" DI_BOX
- SG_ CF_Ems_DiagFulHDEV : 32|1@1+ (1,0) [0|1] "" DI_BOX
- SG_ CF_Ems_SwiOffIC1 : 33|1@1+ (1,0) [0|1] "" DI_BOX
- SG_ CF_Ems_SwiOffIC2 : 34|1@1+ (1,0) [0|1] "" DI_BOX
- SG_ CF_Ems_DiagReqHDEV : 38|1@1+ (1,0) [0|1] "" DI_BOX
- SG_ CR_Ems_DutyCycMSV : 40|8@1+ (0.3921568627,0) [0|100] "%" DI_BOX
- SG_ CR_Ems_BatVolRly : 48|8@1+ (0.1,0) [0|25.5] "V" DI_BOX
-
-BO_ 387 REA11: 8 REA
- SG_ CF_EndBst_PwmDuH : 0|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_PwmDuL : 1|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_PwmFqOutRng : 2|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_HbriOverCur : 3|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_HbriOverTemp : 4|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_PosSnsKOR : 6|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_PosSnsOSOR : 7|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_EepFlt : 8|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_RomFlt : 9|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_RamFlt : 10|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_CanFlt : 11|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_AgH : 12|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_AgL : 13|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_EndBst_ORVol : 14|1@1+ (1,0) [0|1] "" EMS
- SG_ CR_EndBst_ActPos : 16|16@1+ (0.117,0) [1.989|118.053] "" EMS
- SG_ CR_EndBst_DemPos : 32|16@1+ (0.117,0) [0|119.691] "" EMS
- SG_ CR_EndBst_HbriPwr : 48|16@1+ (0.045,0) [0|99.99] "%" EMS
-
-BO_ 1411 CUBIS11: 8 CUBIS
- SG_ CF_Cubis_HUDisp : 0|4@1+ (1,0) [0|15] "" CLU
-
-BO_ 899 FATC11: 8 DATC
- SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0) [0|50.8] "Nm" EMS,IBOX
- SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1,0) [0|1] "" AAF,EMS,IBOX
- SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Fatc_EcvFlt : 10|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Fatc_BlwrOn : 11|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_FATC_Iden : 12|2@1+ (1,0) [0|3] "" EMS,IBOX
- SG_ CF_Fatc_BlwrMax : 14|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX
- SG_ CF_Fatc_EngStartReq : 15|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Fatc_CtrInf : 17|3@1+ (1,0) [0|7] "" EMS,IBOX
- SG_ CF_Fatc_MsgCnt : 20|4@1+ (1,0) [0|15] "" EMS,IBOX
- SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40) [-40|60] "deg" BCM,CLU,EMS,IBOX,SPAS,TCU,TPMS
- SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40) [-40|60] "deg" AAF,AHLS,CLU,EMS,IBOX,SPAS,TCU
- SG_ CF_Fatc_Compload : 40|3@1+ (1,0) [0|7] "" EMS,IBOX
- SG_ CF_Fatc_ActiveEco : 43|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Fatc_AutoActivation : 44|1@1+ (1,0) [0|1] "" IBOX
- SG_ CF_Fatc_DefSw : 45|1@1+ (1,0) [0|1] "" BCM,IBOX
- SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Fatc_ChkSum : 56|8@1+ (1,0) [0|255] "" EMS,IBOX,SPAS
-
-BO_ 129 EMS_DCT12: 8 EMS
- SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5,0) [0|315] "Min" TCU
- SG_ BRAKE_ACT : 6|2@1+ (1,0) [0|3] "" TCU
- SG_ CF_Ems_EngOperStat : 8|8@1+ (1,0) [0|255] "" TCU
- SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "deg" TCU
- SG_ CF_Ems_Alive2 : 56|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Ems_ChkSum2 : 60|4@1+ (1,0) [0|15] "" TCU
-
-BO_ 897 MDPS11: 8 MDPS
- SG_ CF_Mdps_WLmp : 0|2@1+ (1,0) [0|3] "" CLU,CUBIS,EMS,IBOX,SPAS
- SG_ CF_Mdps_Flex : 2|3@1+ (1,0) [0|3] "" CLU,LDWS_LKAS
- SG_ CF_Mdps_FlexDisp : 5|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Mdps_Stat : 7|4@1+ (1,0) [0|15] "" SPAS
- SG_ CR_Mdps_DrvTq : 11|12@1+ (0.01,-20.48) [-20.48|20.46] "" SPAS
- SG_ CF_Mdps_ALTRequest : 23|1@1+ (1,0) [0|1] "" EMS
- SG_ CR_Mdps_StrAng : 24|16@1- (0.1,0) [-3276.8|3276.7] "Deg" SPAS
- SG_ CF_Mdps_AliveCnt : 40|8@1+ (1,0) [0|255] "" LDWS_LKAS,SPAS
- SG_ CF_Mdps_Chksum : 48|8@1+ (1,0) [0|255] "" LDWS_LKAS,SPAS
- SG_ CF_Mdps_SPAS_FUNC : 57|1@1+ (1,0) [0|1] "flag" SPAS
- SG_ CF_Mdps_LKAS_FUNC : 58|1@1+ (1,0) [0|1] "flag" LDWS_LKAS
- SG_ CF_Mdps_CurrMode : 59|2@1+ (1,0) [0|3] "" LDWS_LKAS
- SG_ CF_Mdps_Type : 61|2@1+ (1,0) [0|2] "" LDWS_LKAS,SPAS
-
-BO_ 896 DI_BOX13: 8 DI_BOX
- SG_ CF_DiBox_HPreInjVConfStat : 0|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_HPreInjVStat1 : 8|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_HPreInjVStat2 : 16|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_HPreInjVPkp : 24|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_HPreInjVBpt : 32|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_ErrRegFrtMSV : 40|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_ErrRegSedMSV : 48|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_SPIErrSedMSV : 56|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_SPIErrFrtMSV : 57|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_IDErrSedMSV : 58|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_IDErrFrtMSV : 59|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_IniStatMSV : 60|1@1+ (1,0) [0|1] "" EMS
-
-BO_ 128 EMS_DCT11: 8 EMS
- SG_ PV_AV_CAN : 0|8@1+ (0.3906,0) [0|99.603] "%" TCU
- SG_ TQ_STND : 8|6@1+ (10,0) [0|630] "Nm" TCU
- SG_ F_N_ENG : 14|1@1+ (1,0) [0|1] "" TCU
- SG_ F_SUB_TQI : 15|1@1+ (1,0) [0|1] "" TCU
- SG_ N : 16|16@1+ (0.25,0) [0|16383.75] "rpm" TCU
- SG_ TQI_ACOR : 32|8@1+ (0.390625,0) [0|99.6094] "%" IBOX,TCU
- SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" TCU
- SG_ TQI : 48|8@1+ (0.390625,0) [0|99.609375] "%" TCU
- SG_ CF_Ems_Alive : 56|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Ems_ChkSum : 60|4@1+ (1,0) [0|15] "" TCU
-
-BO_ 1407 HU_MON_PE_01: 8 CLU
- SG_ HU_Type : 0|8@1+ (1,0) [0|255] "" AVM,PGS
-
-BO_ 127 CGW5: 8 BCM
- SG_ C_StopLampLhOpenSts : 0|1@1+ (1,0) [0|1] "" CLU
- SG_ C_StopLampRhOpenSts : 1|1@1+ (1,0) [0|1] "" CLU
- SG_ C_HMSLOpenSts : 2|1@1+ (1,0) [0|1] "" CLU
- SG_ C_HLampLowLhOpenSts : 3|1@1+ (1,0) [0|1] "" CLU
- SG_ C_HLampLowRhOpenSts : 4|1@1+ (1,0) [0|1] "" CLU
- SG_ C_HLampHighLhOpenSts : 5|1@1+ (1,0) [0|1] "" CLU
- SG_ C_HLampHighRhOpenSts : 6|1@1+ (1,0) [0|1] "" CLU
- SG_ C_DRLLampLhOpenSts : 7|1@1+ (1,0) [0|1] "" CLU
- SG_ C_DRLLampRhOpenSts : 8|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearFOGLhOpenSts : 9|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearFOGRhOpenSts : 10|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontFOGLhOpenSts : 11|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontFOGRhOpenSts : 12|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearEXTTailLhOpenSts : 13|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearEXTTailRhOpenSts : 14|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontEXTTailLhOpenSts : 15|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontEXTTailRhOpenSts : 16|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearTSIGLhOpenSts : 17|1@1+ (1,0) [0|1] "" CLU
- SG_ C_RearTSIGRhOpenSts : 18|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontTSIGLhOpenSts : 19|1@1+ (1,0) [0|1] "" CLU
- SG_ C_FrontTSIGRhOpenSts : 20|1@1+ (1,0) [0|1] "" CLU
- SG_ C_SBendingLhOpenSts : 21|1@1+ (1,0) [0|1] "" CLU
- SG_ C_SBendingRhOpenSts : 22|1@1+ (1,0) [0|1] "" CLU
- SG_ C_LicensePlateLhOpenSts : 23|1@1+ (1,0) [0|1] "" CLU
- SG_ C_LicensePlateRhOpenSts : 24|1@1+ (1,0) [0|1] "" CLU
-
-BO_ 1151 ESP11: 6 ESC
- SG_ AVH_STAT : 0|2@1+ (1,0) [0|3] "" EMS,EPB,TCU
- SG_ LDM_STAT : 2|1@1+ (1,0) [0|1] "" EPB,TCU
- SG_ REQ_EPB_ACT : 3|2@1+ (1,0) [0|3] "" EPB,TCU
- SG_ REQ_EPB_STAT : 5|1@1+ (1,0) [0|1] "" EPB
- SG_ ECD_ACT : 6|1@1+ (1,0) [0|1] "" EPB
- SG_ _4WD_LIM_REQ : 7|1@1+ (1,0) [0|1] "" _4WD,EMS
- SG_ ROL_CNT_ESP : 8|8@1+ (1,0) [0|255] "" EPB,TCU
- SG_ _4WD_TQC_LIM : 16|16@1+ (1,0) [0|65535] "Nm" _4WD,EMS
- SG_ _4WD_CLU_LIM : 32|8@1+ (0.390625,0) [0|99.609375] "%" _4WD,EMS
- SG_ _4WD_OPEN : 40|2@1+ (1,0) [0|3] "" _4WD,EMS
- SG_ _4WD_LIM_MODE : 42|1@1+ (1,0) [0|1] "" _4WD
-
-BO_ 1397 HU_AVM_E_00: 8 CLU
- SG_ HU_AVM_Cal_Cmd : 0|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_Cal_Method : 4|2@1+ (1,0) [0|3] "" AVM,PGS
- SG_ HU_AVM_Save_Controlpoint : 6|2@1+ (1,0) [0|3] "" AVM,PGS
- SG_ HU_AVM_PT_X : 8|12@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_RearViewPointOpt : 20|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_PT_Y : 24|12@1+ (1,0) [0|4095] "" AVM,PGS
- SG_ HU_AVM_FrontViewPointOpt : 36|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_SelectedMenu : 40|5@1+ (1,0) [0|31] "" AVM,PGS
- SG_ HU_AVM_CameraOff : 45|2@1+ (1,0) [0|3] "" AVM,PGS
- SG_ HU_AVM_Option : 48|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_CrossLineMove_Cmd : 52|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_RearView_Option : 56|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_FrontView_Option : 60|4@1+ (1,0) [0|15] "" AVM,PGS
-
-BO_ 1395 HU_AVM_E_01: 8 CLU
- SG_ HU_PGSSelectedMenu : 0|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_PGSOption : 8|5@1+ (1,0) [0|31] "" AVM,PGS
- SG_ HU_AVM_ParkingAssistMenu : 56|4@1+ (1,0) [0|15] "" AVM,PGS
- SG_ HU_AVM_ParkingAssistSB : 60|4@1+ (1,0) [0|15] "" AVM,PGS
-
-BO_ 1393 OPI11: 5 OPI
- SG_ CR_Opi_Spd_Rpm : 0|8@1+ (20,0) [0|3500] "rpm" TCU
- SG_ CF_Opi_Over_Temp : 8|1@1+ (1,0) [0|1] "" TCU
- SG_ CF_Opi_Over_Cur : 9|1@1+ (1,0) [0|1] "" EMS,TCU
- SG_ CF_Opi_Over_Vol : 10|1@1+ (1,0) [0|1] "" TCU
- SG_ CF_Opi_Hall_Fail : 11|1@1+ (1,0) [0|1] "" EMS,TCU
- SG_ CF_Opi_Flt : 12|1@1+ (1,0) [0|1] "" EMS,TCU
- SG_ CF_Opi_Motor_Dir : 15|1@1+ (1,0) [0|1] "" TCU
- SG_ CF_Opi_Romver : 16|8@1+ (1,0) [0|255] "" TCU
- SG_ CF_Opi_PWM_Rate : 24|12@1+ (1,0) [0|100] "%" TCU
-
-BO_ 625 LPI11: 8 LPI
- SG_ FUP_LPG_MMV : 0|8@1+ (128,0) [0|32640] "hPa" EMS
- SG_ LV_FUEL_TYPE_BOX : 8|1@1+ (1,0) [0|1] "" EMS
- SG_ LV_BFS_IN_PROGRESS : 9|1@1+ (1,0) [0|1] "" EMS
- SG_ LV_GAS_OK : 10|1@1+ (1,0) [0|1] "" EMS
- SG_ LV_FUP_ENA_THD : 11|1@1+ (1,0) [0|1] "" BCM,CLU,EMS,SMK
- SG_ LPI_OBD : 12|4@1+ (1,0) [0|15] "" EMS
- SG_ ERR_GAS : 16|8@1+ (1,0) [0|255] "" EMS
- SG_ FAC_TI_GAS_COR : 24|16@1+ (0.0000305,0) [0|1.9988175] "" EMS
- SG_ FTL_AFU : 40|8@1+ (0.392,0) [0|99.96] "%" EMS
- SG_ BFS_CYL : 48|8@1+ (1,0) [0|6] "Cyl Nr." EMS
- SG_ LV_PRE_CDN_LEAK : 56|1@1+ (1,0) [0|1] "" EMS
- SG_ LV_CONF_INJECTION_DELAY : 57|1@1+ (1,0) [0|1] "" EMS
- SG_ LV_LPG_SW_DRIVER_REQ : 58|1@1+ (1,0) [0|1] "" EMS
-
-BO_ 356 VSM11: 4 ESC
- SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" MDPS
- SG_ CF_Esc_Act : 12|1@1+ (1,0) [0|1] "" LDWS_LKAS,MDPS
- SG_ CF_Esc_CtrMode : 13|3@1+ (1,0) [0|7] "" MDPS
- SG_ CF_Esc_Def : 16|1@1+ (1,0) [0|1] "" MDPS
- SG_ CF_Esc_AliveCnt : 17|4@1+ (1,0) [0|15] "" LDWS_LKAS,MDPS
- SG_ CF_Esc_Chksum : 24|8@1+ (1,0) [0|255] "" LDWS_LKAS,MDPS
-
-BO_ 1379 PGS_HU_PE_01: 8 PGS
- SG_ PGS_State : 0|4@1+ (1,0) [0|15] "" CLU
- SG_ PGS_ParkGuideState : 8|5@1+ (1,0) [0|31] "" CLU
- SG_ PGS_Option : 16|5@1+ (1,0) [0|31] "" CLU
- SG_ PGS_Version : 32|16@1+ (1,0) [0|65535] "" CLU
-
-BO_ 354 TCU_DCT13: 3 TCU
- SG_ Clutch_Driving_Tq : 0|10@1+ (1,-512) [0|0] "Nm" ESC
- SG_ Cluster_Engine_RPM : 10|13@1+ (0.9766,0) [0|0] "" CLU
- SG_ Cluster_Engine_RPM_Flag : 23|1@1+ (1,0) [0|0] "" CLU
-
-BO_ 1378 HUD11: 4 HUD
- SG_ CF_Hud_HeightStaus : 0|5@1+ (1,0) [0|31] "" CLU
- SG_ CF_Hud_PBackStatus : 6|2@1+ (1,0) [0|0] "" BCM,CLU
- SG_ CF_Hud_Brightness : 8|5@1+ (1,0) [0|31] "" CLU
-
-BO_ 608 EMS16: 8 EMS
- SG_ GLOW_STAT : 24|1@1+ (1,0) [0|1] "" BCM,CLU,IBOX,SMK
- SG_ CRUISE_LAMP_M : 25|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU
- SG_ CRUISE_LAMP_S : 26|1@1+ (1,0) [0|1] "" CLU,IBOX,TCU
- SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1,0) [0|1] "" IBOX,TCU
- SG_ SOAK_TIME_ERROR : 31|1@1+ (1,0) [0|1] "" DATC,EPB,IBOX,TCU
- SG_ TQI_MAX : 40|8@1+ (0.390625,0) [0|99.609375] "%" ESC,IBOX,TCU
- SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60] "" IBOX,TCU
- SG_ Checksum : 56|4@1+ (1,0) [0|15] "" ECS,IBOX,LDWS_LKAS,MDPS,SCC
- SG_ AliveCounter : 60|2@1+ (1,0) [0|3] "" IBOX,LDWS_LKAS,MDPS,SCC
- SG_ CF_Ems_AclAct : 62|2@1+ (1,0) [0|3] "" IBOX,SCC
- SG_ TQI : 8|8@1+ (1.7,0) [0|440] "%" ESC,IBOX,TCU
- SG_ TQI_MIN : 0|8@1+ (1.7,0) [0|99.609375] "nm" ESC,IBOX,TCU
- SG_ TQI_TARGET : 16|8@1+ (1.7,0) [0|440] "nm" EPB,ESC,IBOX,TCU
- SG_ ENG_STAT : 28|3@1+ (1,0) [0|7] "" ABS,AHLS,AVM,BCM,CLU,EPB,ESC,EVP,FPCM,IBOX,LCA,LDWS_LKAS,MDPS,SCC,SMK,TCU
- SG_ SOAK_TIME : 32|8@1+ (1,0) [0|255] "Min" _4WD,DATC,EPB,IBOX,TCU
-
-BO_ 1371 AVM_HU_PE_00: 8 AVM
- SG_ AVM_View : 0|5@1+ (1,0) [0|31] "" CLU
- SG_ AVM_ParkingAssist_BtnSts : 5|3@1+ (1,0) [0|7] "" CLU
- SG_ AVM_Display_Message : 8|8@1+ (1,0) [0|255] "" CLU
- SG_ AVM_Popup_Msg : 16|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_Ready : 20|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_ParkingAssist_Step : 24|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_FrontBtn_Type : 28|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_Option : 32|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_HU_FrontViewPointOpt : 36|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_HU_RearView_Option : 40|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_HU_FrontView_Option : 44|4@1+ (1,0) [0|15] "" CLU
- SG_ AVM_Version : 48|16@1+ (1,0) [0|65535] "" CLU
-
-BO_ 1370 HU_AVM_PE_00: 8 CLU
- SG_ HU_AVM_Status : 0|2@1+ (1,0) [0|3] "" AVM,PGS
-
-BO_ 1369 CGW4: 8 BCM
- SG_ CF_Gway_MemoryP1Cmd : 0|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_MemoryP2Cmd : 1|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_PBackP1Cmd : 2|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_PBackP2Cmd : 3|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_StrgWhlHeatedState : 4|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_PBackStopCmd : 5|1@1+ (1,0) [0|1] "" CLU,HUD
- SG_ CF_Gway_StaticBendLhAct : 6|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_StaticBendRhAct : 7|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_DrvWdwStat : 8|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_RLWdwState : 9|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_RRWdwState : 10|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_AstWdwStat : 11|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_MemoryEnable : 12|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_PBACKStopCmd : 13|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_PBACKStop : 14|1@1+ (1,0) [0|1] "" CLU,HUD
- SG_ CF_Gway_IMSBuzzer : 15|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_DrvSeatBeltInd : 36|2@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_AstSeatBeltInd : 38|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_RCSeatBeltInd : 40|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_RLSeatBeltInd : 42|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_RRSeatBeltInd : 44|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_RrWiperHighSw : 46|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_RrWiperLowSw : 47|1@1+ (1,0) [0|1] "" CLU
-
-BO_ 1367 EngFrzFrm12: 8 EMS
- SG_ PID_06h : 0|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU
- SG_ PID_07h : 8|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU
- SG_ PID_08h : 16|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU
- SG_ PID_09h : 24|8@1+ (0.78125,-100) [-100|99.22] "%" AAF,IBOX,TCU
- SG_ PID_0Bh : 32|8@1+ (1,0) [0|255] "kPa" AAF,IBOX,TCU
- SG_ PID_23h : 40|16@1+ (10,0) [0|655350] "kPa" AAF,IBOX,TCU
-
-BO_ 1366 EngFrzFrm11: 8 EMS
- SG_ PID_04h : 0|8@1+ (0.3921568627,0) [0|100] "%" AAF,TCU
- SG_ PID_05h : 8|8@1+ (1,-40) [-40|215] "deg" AAF,TCU
- SG_ PID_0Ch : 16|16@1+ (0.25,0) [0|16383.75] "rpm" AAF,TCU
- SG_ PID_0Dh : 32|8@1+ (1,0) [0|255] "km/h" AAF,TCU
- SG_ PID_11h : 40|8@1+ (0.3921568627,0) [0|100] "%" AAF,TCU
- SG_ PID_03h : 48|16@1+ (1,0) [0|65535] "" AAF,TCU
-
-BO_ 1365 FPCM11: 8 FPCM
- SG_ CR_Fpcm_LPActPre : 0|8@1+ (3.137254902,0) [0|800] "kPa" EMS
- SG_ CF_Fpcm_LPPumpOverCur : 8|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_PreSnrHi : 9|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_PreSnrDisc : 10|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_PreSnrShort : 11|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_LPPumpDiscShort : 12|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_LP_System_Error : 13|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_PreSnrSigErr : 14|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Fpcm_LPCtrCirFlt : 15|1@1+ (1,0) [0|1] "" EMS
-
-BO_ 852 LVR11: 7 LVR
- SG_ CF_Lvr_GearInf : 0|4@1+ (1,0) [0|15] "" CLU,TCU
- SG_ CF_Lvr_PRelStat : 4|1@1+ (1,0) [0|1] "" BCM,CLU,SMK,TCU
- SG_ CF_Lvr_BkeAct : 5|1@1+ (1,0) [0|1] "" TCU
- SG_ CF_Lvr_NFnStat : 6|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Lvr_PosInf : 8|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Lvr_PosCpl : 12|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Lvr_UlkButStat : 18|2@1+ (1,0) [0|3] "" TCU
- SG_ CF_Lvr_PNStat : 20|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Lvr_ShtLkStat : 24|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Lvr_ShfErrInf : 28|20@1+ (1,0) [0|8191] "" CLU,TCU
- SG_ CF_Lvr_AC : 48|4@1+ (1,0) [0|15] "" TCU
- SG_ CF_Lvr_CS : 52|4@1+ (1,0) [0|15] "" TCU
-
-BO_ 1363 CGW2: 8 BCM
- SG_ CF_Gway_GwayDiagState : 0|1@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_DDMDiagState : 1|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_SCMDiagState : 2|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_PSMDiagState : 3|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_SJBDiagState : 4|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_IPMDiagState : 5|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_LDMFail : 6|2@1+ (1,0) [0|3] "" CLU,LDWS_LKAS,LDWS_LKAS
- SG_ CF_Gway_CLUSwGuiCtrl : 10|3@1+ (1,0) [0|63] "" CLU,Dummy
- SG_ CF_Gway_CLUSwGroup : 13|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_CLUSwMode : 14|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_CLUSwEnter : 15|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_AutoLightValue : 16|1@1+ (1,0) [0|1] "" LCA,LCA
- SG_ CF_Gway_BrakeFluidSw : 17|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_DrvSeatBeltInd : 18|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_AvTail : 20|1@1+ (1,0) [0|3] "" CLU,SNV,SNV
- SG_ CF_Gway_RearFogAct : 21|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_ExtTailAct : 22|1@1+ (1,0) [0|1] "" AVM,CLU,LCA,PGS,SPAS,AVM,LCA,PGS,SPAS
- SG_ CF_Gway_RRDrSw : 23|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_RLDrSw : 24|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_IntTailAct : 25|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_CountryCfg : 26|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,Dummy
- SG_ CF_Gway_WiperParkPosition : 32|1@1+ (1,0) [0|1] "" AFLS,EMS,LDWS_LKAS,AFLS,EMS,LDWS_LKAS
- SG_ CF_Gway_HLLowLHFail : 33|1@1+ (1,0) [0|1] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV
- SG_ CF_Gway_HLLowRHFail : 34|1@1+ (1,0) [0|1] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV
- SG_ CF_Gway_ESCLFailWarn : 35|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_ESCLNotLockedWarn : 36|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_ESCLNotUnlockWarn : 37|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_IDoutWarn : 38|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_ImmoLp : 40|1@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_BCMRKEID : 41|3@1+ (1,0) [0|7] "" CLU,Dummy
- SG_ CF_Gway_VehicleNotPWarn : 44|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_DeactivationWarn : 45|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_KeyBATDischargeWarn : 46|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_SSBWarn : 47|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_SMKFobID : 48|3@1+ (1,0) [0|7] "" CLU,Dummy
- SG_ CF_Gway_SMKRKECmd : 51|3@1+ (1,0) [0|7] "" CLU,Dummy
- SG_ CF_Gway_AutoLightOption : 54|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_SJBDeliveryMode : 55|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_KeyoutLp : 56|1@1+ (1,0) [0|1] "" CLU,Dummy
- SG_ CF_Gway_SMKDispWarn : 57|4@1+ (1,0) [0|15] "" CLU,Dummy
- SG_ CF_Gway_WngBuz : 61|3@1+ (1,0) [0|7] "" CLU,Dummy
-
-BO_ 339 TCS11: 8 ESC
- SG_ TCS_REQ : 0|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,TCU
- SG_ MSR_C_REQ : 1|1@1+ (1,0) [0|1] "" EMS,EPB,SCC,TCU
- SG_ TCS_PAS : 2|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,SCC,SPAS,TCU
- SG_ TCS_GSC : 3|1@1+ (1,0) [0|1] "" _4WD,EMS,TCU
- SG_ CF_Esc_LimoInfo : 4|2@1+ (1,0) [0|3] "" _4WD,SCC
- SG_ ABS_DIAG : 6|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB
- SG_ ABS_DEF : 7|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,SCC,SPAS,TCU
- SG_ TCS_DEF : 8|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SCC,SPAS,TCU
- SG_ TCS_CTL : 9|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SCC,SPAS,TCU
- SG_ ABS_ACT : 10|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU
- SG_ EBD_DEF : 11|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,SPAS,TCU
- SG_ ESP_PAS : 12|1@1+ (1,0) [0|1] "" _4WD,ACU,CLU,EMS,EPB,LDWS_LKAS,SCC,TCU
- SG_ ESP_DEF : 13|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,TCU
- SG_ ESP_CTL : 14|1@1+ (1,0) [0|1] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU
- SG_ TCS_MFRN : 15|1@1+ (1,0) [0|1] "" EMS,EPB,TCU
- SG_ DBC_CTL : 16|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB
- SG_ DBC_PAS : 17|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB
- SG_ DBC_DEF : 18|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB
- SG_ HAC_CTL : 19|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU
- SG_ HAC_PAS : 20|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU
- SG_ HAC_DEF : 21|1@1+ (1,0) [0|1] "" _4WD,CLU,EMS,EPB,TCU
- SG_ ESS_STAT : 22|2@1+ (1,0) [0|3] "" _4WD,BCM,CLU,EMS,EPB
- SG_ TQI_TCS : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU
- SG_ TQI_MSR : 32|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU
- SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0) [0|99.609375] "%" EMS,EPB,TCU
- SG_ CF_Esc_BrkCtl : 48|1@1+ (1,0) [0|1] "" EMS
- SG_ BLA_CTL : 49|2@1+ (1,0) [0|3] "" BCM,CGW,CLU
- SG_ AliveCounter_TCS1 : 52|4@1+ (1,0) [0|14] "" EMS,EPB,LDWS_LKAS
- SG_ CheckSum_TCS1 : 56|8@1+ (1,0) [0|255] "" EMS,EPB,LDWS_LKAS
-
-BO_ 1362 SNV11: 4 SNV
- SG_ CF_SNV_DisplayControl : 0|2@1+ (1,0) [0|3] "" CLU,HUD
- SG_ CF_Snv_BeepWarning : 2|2@1+ (1,0) [0|3] "" CLU,HUD
- SG_ CF_Snv_WarningMessage : 4|3@1+ (1,0) [0|7] "" CLU,HUD
- SG_ CF_Snv_DetectionEnable : 7|1@1+ (1,0) [0|1] "" BCM,CLU,HUD
- SG_ CF_Snv_PedestrianDetect : 8|2@1+ (1,0) [0|3] "" BCM,CLU,HUD
- SG_ CF_Snv_IRLampControl : 10|2@1+ (1,0) [0|3] "" BCM,CLU,HUD
-
-BO_ 593 MDPS12: 8 MDPS
- SG_ CR_Mdps_StrColTq : 0|11@1+ (0.0078125,-8) [-8|7.9921875] "Nm" LDWS_LKAS
- SG_ CF_Mdps_Def : 11|1@1+ (1,0) [0|1] "" ESC
- SG_ CF_Mdps_ToiUnavail : 12|1@1+ (1,0) [0|1] "" LDWS_LKAS
- SG_ CF_Mdps_ToiActive : 13|1@1+ (1,0) [0|1] "" LDWS_LKAS
- SG_ CF_Mdps_ToiFlt : 14|1@1+ (1,0) [0|1] "" LDWS_LKAS
- SG_ CF_Mdps_FailStat : 15|1@1+ (1,0) [0|1] "" LDWS_LKAS
- SG_ CF_Mdps_MsgCount2 : 16|8@1+ (1,0) [0|255] "" ESC,LDWS_LKAS
- SG_ CF_Mdps_Chksum2 : 24|8@1+ (1,0) [0|255] "" ESC,LDWS_LKAS
- SG_ CF_Mdps_SErr : 37|1@1+ (1,0) [0|1] "" ESC
- SG_ CR_Mdps_StrTq : 40|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" ESC
- SG_ CR_Mdps_OutTq : 52|12@1+ (0.1,-204.8) [-204.8|204.7] "" ESC,LDWS_LKAS
-
-BO_ 1360 IAP11: 3 IAP
- SG_ CF_Iap_EcoPmodSwi : 0|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Iap_EcoPmodAct : 1|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Iap_ReqWarn : 2|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1356 TCU_DCT14: 8 TCU
- SG_ Vehicle_Stop_Time : 0|5@1+ (1,0) [0|0] "" CLU
- SG_ HILL_HOLD_WARNING : 5|1@1+ (1,0) [0|0] "" CLU
-
-BO_ 1353 BAT11: 8 EMS
- SG_ BAT_SNSR_I : 0|16@1+ (0.01,-327) [-327|328] "A" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SOC : 16|8@1+ (1,0) [0|100] "%" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SNSR_V : 24|14@1+ (0.001,6) [6|18] "V" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SNSR_Temp : 38|9@1- (0.5,-40) [-40|125] "deg" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SNSR_State : 47|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SOH : 48|7@1+ (1,0) [0|100] "%" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SNSR_Invalid : 55|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SOF : 56|7@1+ (0.1,0) [0|12] "V" CGW,CUBIS,IBOX,TMU
- SG_ BAT_SNSR_Error : 63|1@1+ (1,0) [0|1] "" CGW,CUBIS,IBOX,TMU
-
-BO_ 1351 EMS15: 8 EMS
- SG_ ECGPOvrd : 0|1@1+ (1,0) [0|1] "" ESC,IBOX,SCC
- SG_ QECACC : 1|1@1+ (1,0) [0|1] "" ESC,IBOX
- SG_ ECFail : 2|1@1+ (1,0) [0|1] "" ESC,IBOX
- SG_ SwitchOffCondExt : 3|1@1+ (1,0) [0|1] "" ESC,IBOX
- SG_ BLECFail : 4|1@1+ (1,0) [0|1] "" ESC,IBOX
- SG_ CF_Ems_IsaAct : 5|1@1+ (1,0) [0|1] "" CLU
- SG_ FA_PV_CAN : 8|8@1+ (0.3906,0) [0|99.2] "%" IBOX,LDWS_LKAS,TCU
- SG_ IntAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "deg" _4WD,ECS,EPB,IBOX,TCU
- SG_ STATE_DC_OBD : 24|7@1+ (1,0) [0|127] "" IBOX,TCU
- SG_ INH_DC_OBD : 31|1@1+ (1,0) [0|1] "" IBOX,TCU
- SG_ CTR_IG_CYC_OBD : 32|16@1+ (1,0) [0|65535] "" ACU,IBOX,TCU
- SG_ CTR_CDN_OBD : 48|16@1+ (1,0) [0|65535] "" IBOX,TCU
-
-BO_ 1350 DI_BOX12: 8 DI_BOX
- SG_ CF_DiBox_FrtInjVDiagReg0 : 0|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_FrtInjVDiagReg1 : 8|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_FrtInjVDiagReg2 : 16|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_SedInjVDiagReg0 : 24|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_SedInjVDiagReg1 : 32|8@1+ (1,0) [0|255] "" EMS
- SG_ CF_DiBox_SedInjVDiagReg2 : 40|8@1+ (1,0) [0|255] "" EMS
- SG_ CR_DiBox_BatVol : 48|8@1+ (0.1,0) [0|25.5] "V" EMS
- SG_ CF_DiBox_SedInjVChg : 56|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_FrtInjVChg : 57|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_SedInjVErrSPI : 58|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_DiBox_FrtInjVErrSPI : 59|1@1+ (1,0) [0|1] "" EMS
-
-BO_ 1349 EMS14: 8 EMS
- SG_ IMMO_LAMP_STAT : 0|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ L_MIL : 1|1@1+ (1,0) [0|1] "" CLU,CUBIS,IBOX
- SG_ IM_STAT : 2|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ AMP_CAN : 3|5@1+ (10.731613,458.98) [458.98|791.660003] "mmHg" CLU,IBOX,TCU,TPMS
- SG_ BAT_Alt_FR_Duty : 8|8@1+ (0.4,0) [0|100] "%" CGW,CUBIS,IBOX,TMU
- SG_ VB : 24|8@1+ (0.1015625,0) [0|25.8984375] "V" CLU,CUBIS,DATC,EPB,FPCM,IBOX
- SG_ EMS_VS : 32|12@1+ (0.0625,0) [0|255.875] "km/h" CLU
- SG_ TEMP_FUEL : 56|8@1+ (0.75,-48) [-48|143.25] "deg" FPCM
-
-BO_ 68 DATC11: 8 DATC
- SG_ CF_Datc_Type : 0|8@1+ (1,0) [0|255] "" CLU
- SG_ CF_Datc_VerMaj : 8|8@1+ (1,0) [0|255] "" CLU
- SG_ CF_Datc_VerMin : 16|8@1+ (1,0) [0|255] "" CLU
- SG_ CR_Datc_OutTempC : 24|8@1+ (0.5,-41) [-41|86.5] "deg" CLU,FPCM
- SG_ CR_Datc_OutTempF : 32|8@1+ (1,-42) [-42|213] "deg" CLU
- SG_ CF_Datc_IncarTemp : 40|8@1+ (0.5,-40) [-40|60] "deg" BCM,CLU
-
-BO_ 67 DATC13: 8 DATC
- SG_ CF_Datc_TempDispUnit : 0|2@1+ (1,0) [0|3] "" CLU,IBOX
- SG_ CF_Datc_ModDisp : 2|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Datc_IonClean : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_ChgReqDisp : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_IntakeDisp : 10|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_AutoDisp : 12|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_FrDefLed : 14|2@1+ (1,0) [0|3] "" CLU,IBOX
- SG_ CF_Datc_AutoDefogBlink : 16|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_ClmScanDisp : 18|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_AqsDisp : 20|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_AcDisp : 22|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_OpSts : 25|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Mtc_MaxAcDisp : 28|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_DualDisp : 30|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_PwrInf : 32|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Datc_RearManual : 38|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_RearAutoDisp : 40|2@1+ (1,0) [0|1] "" CLU
- SG_ CF_Datc_RearOffDisp : 42|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_RearClimateScnDisp : 44|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_RearChgReqDisp : 46|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_RearModDisp : 48|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Datc_RearBlwDisp : 52|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Datc_PSModDisp : 56|4@1+ (1,0) [0|15] "" CLU
- SG_ CF_Datc_FrontBlwDisp : 60|4@1+ (1,0) [0|15] "" CLU,IBOX
-
-BO_ 66 DATC12: 8 DATC
- SG_ CR_Datc_DrTempDispC : 0|8@1+ (0.5,14) [15|32] "deg" CLU,IBOX
- SG_ CR_Datc_DrTempDispF : 8|8@1+ (1,56) [58|90] "��" CLU,IBOX
- SG_ CR_Datc_PsTempDispC : 16|8@1+ (0.5,14) [15|32] "deg" CLU,IBOX
- SG_ CR_Datc_PsTempDispF : 24|8@1+ (1,56) [58|90] "��" CLU,IBOX
- SG_ CR_Datc_RearDrTempDispC : 40|8@1+ (0.5,14) [15|32] "deg" CLU
- SG_ CR_Datc_RearDrTempDispF : 48|8@1+ (1,58) [58|90] "��" CLU
- SG_ CF_Datc_CO2_Warning : 56|8@1+ (1,0) [0|3] "" CLU
-
-BO_ 1345 CGW1: 8 BCM
- SG_ CF_Gway_IGNSw : 0|3@1+ (1,0) [0|7] "" AVM,CLU,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC
- SG_ CF_Gway_RKECmd : 3|3@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX
- SG_ CF_Gway_DrvKeyLockSw : 6|1@1+ (1,0) [0|1] "" ECS,EMS,IBOX,ECS,EMS,IBOX
- SG_ CF_Gway_DrvKeyUnlockSw : 7|1@1+ (1,0) [0|1] "" ECS,EMS,IBOX,ECS,EMS,IBOX
- SG_ CF_Gway_DrvDrSw : 8|2@1+ (1,0) [0|3] "" CLU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU
- SG_ CF_Gway_DrvSeatBeltSw : 10|2@1+ (1,0) [0|3] "" EMS,EPB,ESC,IBOX,PSB,TCU,EMS,EPB,ESC,IBOX,PSB,TCU
- SG_ CF_Gway_TrunkTgSw : 12|2@1+ (1,0) [0|3] "" CLU,ECS,EMS,EPB,ESC,IBOX,ECS,EMS,EPB,ESC,IBOX
- SG_ CF_Gway_AstSeatBeltSw : 14|2@1+ (1,0) [0|3] "" IBOX,PSB,IBOX,PSB
- SG_ CF_Gway_SMKOption : 16|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,EMS,IBOX,SMK
- SG_ CF_Gway_HoodSw : 17|2@1+ (1,0) [0|3] "" CLU,EMS,EPB,ESC,IBOX,EMS,EPB,ESC,IBOX
- SG_ CF_Gway_TurnSigLh : 19|2@1+ (1,0) [0|3] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC
- SG_ CF_Gway_WiperIntT : 21|3@1+ (1,0) [0|7] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_WiperIntSw : 24|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_WiperLowSw : 25|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_WiperHighSw : 26|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_WiperAutoSw : 27|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_RainSnsState : 28|3@1+ (1,0) [0|7] "" AFLS,EMS,IBOX,LDWS_LKAS,AFLS,EMS,ESC,IBOX,LDWS_LKAS
- SG_ CF_Gway_HeadLampLow : 31|1@1+ (1,0) [0|1] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,SNV,AFLS,EMS,IBOX,LDWS_LKAS,SNV
- SG_ CF_Gway_HeadLampHigh : 32|1@1+ (1,0) [0|1] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,AFLS,EMS,IBOX,LDWS_LKAS
- SG_ CF_Gway_HazardSw : 33|2@1+ (1,0) [0|3] "" ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS,ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS
- SG_ CF_Gway_AstDrSw : 35|1@1+ (1,0) [0|1] "" CLU,IBOX,IBOX
- SG_ CF_Gway_DefoggerRly : 36|1@1+ (1,0) [0|1] "" EMS,IBOX,EMS,IBOX
- SG_ CF_Gway_ALightStat : 37|1@1+ (1,0) [0|1] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS
- SG_ CF_Gway_LightSwState : 38|2@1+ (1,0) [0|3] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS
- SG_ CF_Gway_Frt_Fog_Act : 40|1@1+ (1,0) [0|1] "" AFLS,CLU,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS
- SG_ CF_Gway_TSigRHSw : 41|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS
- SG_ CF_Gway_TSigLHSw : 42|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS
- SG_ CF_Gway_DriveTypeOption : 43|1@1+ (1,0) [0|1] "" CLU,IBOX,LDWS_LKAS,IBOX,LDWS_LKAS
- SG_ CF_Gway_StarterRlyState : 44|1@1+ (1,0) [0|1] "" EMS,IBOX,EMS,IBOX,SMK
- SG_ CF_Gway_PassiveAccessLock : 45|2@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK
- SG_ CF_Gway_WiperMistSw : 47|1@1+ (1,0) [0|1] "" CLU,EMS,IBOX,LDWS_LKAS
- SG_ CF_Gway_PassiveAccessUnlock : 48|2@1+ (1,0) [0|7] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK
- SG_ CF_Gway_RrSunRoofOpenState : 50|1@1+ (1,0) [0|1] "" CLU,DATC,IBOX
- SG_ CF_Gway_PassingSW : 51|1@1+ (1,0) [0|1] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS
- SG_ CF_Gway_HBAControlMode : 52|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS
- SG_ CF_Gway_HLpHighSw : 53|1@1+ (1,0) [0|1] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS
- SG_ CF_Gway_InhibitRMT : 54|2@1+ (1,0) [0|3] "" EMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,MDPS,PGS,SCC,SPAS,TPMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,PGS,SCC,SPAS,TPMS
- SG_ CF_Gway_RainSnsOption : 56|1@1+ (1,0) [0|1] "" CLU
- SG_ C_SunRoofOpenState : 57|1@1+ (1,0) [0|1] "" CLU,DATC,IBOX,DATC,IBOX
- SG_ CF_Gway_Ign1 : 58|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_Ign2 : 59|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Gway_ParkBrakeSw : 60|2@1+ (1,0) [0|3] "" CLU,ESC,IBOX,SCC,ESC,IBOX,SCC
- SG_ CF_Gway_TurnSigRh : 62|2@1+ (1,0) [0|3] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC
-
-BO_ 64 DATC14: 8 DATC
- SG_ CF_Datc_AqsLevelOut : 0|4@1+ (1,0) [0|3] "" CLU
- SG_ CF_Datc_DiagMode : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ CR_Datc_SelfDiagCode : 8|8@1+ (1,-1) [0|254] "" CLU
- SG_ DATC_SyncDisp : 16|4@1+ (1,0) [0|3] "" CLU
- SG_ DATC_OffDisp : 20|2@1+ (1,0) [0|3] "" CLU
- SG_ DATC_SmartVentDisp : 22|2@1+ (1,0) [0|3] "" CLU
- SG_ DATC_SmartVentOnOffStatus : 24|2@1+ (1,0) [0|3] "" CLU
- SG_ DATC_AutoDefogSysOff_Disp : 26|2@1+ (1,0) [0|3] "" CLU
- SG_ DATC_ADSDisp : 28|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 832 LKAS11: 8 LDWS_LKAS
- SG_ Byte0 : 0|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte1 : 8|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte2 : 16|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte3 : 24|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte4 : 32|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte5 : 40|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte6 : 48|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte7 : 56|8@1+ (1,0) [0|3] "" XXX
-
-
-
-BO_ 1342 LKAS12: 6 LDWS_LKAS
- SG_ Byte0 : 0|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte1 : 8|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte2 : 16|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte3 : 24|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte4 : 32|8@1+ (1,0) [0|3] "" XXX
- SG_ Byte5 : 40|8@1+ (1,0) [0|3] "" XXX
-
-BO_ 1338 TMU_GW_E_01: 8 CLU
- SG_ CF_Gway_TeleReqDrLock : 0|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Gway_TeleReqDrUnlock : 2|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Gway_TeleReqHazard : 4|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Gway_TeleReqHorn : 6|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Gway_TeleReqEngineOperate : 8|2@1+ (1,0) [0|3] "" BCM
-
-BO_ 1078 PAS11: 4 BCM
- SG_ CF_Gway_PASDisplayFLH : 0|3@1+ (1,0) [0|7] "" AVM,CLU,AVM
- SG_ CF_Gway_PASDisplayFRH : 3|3@1+ (1,0) [0|7] "" AVM,CLU,AVM
- SG_ CF_Gway_PASRsound : 6|2@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_PASDisplayFCTR : 8|3@1+ (1,0) [0|7] "" AVM,CLU,AVM
- SG_ CF_Gway_PASDisplayRCTR : 11|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM
- SG_ CF_Gway_PASFsound : 14|2@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_PASDisplayRLH : 16|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM
- SG_ CF_Gway_PASDisplayRRH : 19|3@1+ (1,0) [0|7] "" AVM,CLU,PGS,AVM
- SG_ CF_Gway_PASCheckSound : 22|2@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_PASSystemOn : 24|2@1+ (1,0) [0|3] "" CLU,Dummy
- SG_ CF_Gway_PASOption : 26|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_PASDistance : 28|1@1+ (1,0) [0|1] "" CLU
-
-BO_ 48 EMS18: 6 EMS
- SG_ CF_Ems_DC1NumPerMSV : 0|8@1+ (1,0) [0|255] "" DI_BOX
- SG_ CF_Ems_DC2NumPerMSV : 8|16@1+ (1,0) [0|65535] "" DI_BOX
- SG_ CR_Ems_DutyCyc1MSV : 24|8@1+ (0.1953,0) [0|49.8] "%" DI_BOX
- SG_ CR_Ems_DutyCyc2MSV : 32|8@1+ (0.13725,0) [0|35] "%" DI_BOX
- SG_ CR_Ems_DutyCyc3MSV : 40|8@1+ (0.392,0) [0|100] "%" DI_BOX
-
-BO_ 1322 CLU15: 8 CLU
- SG_ CF_Clu_VehicleSpeed : 0|8@1+ (1,0) [0|255] "" BCM
- SG_ CF_Clu_InhibitP : 9|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_InhibitR : 10|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_InhibitN : 11|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_InhibitD : 12|1@1+ (1,0) [0|1] "" BCM
- SG_ CF_Clu_HudInfoSet : 13|7@1+ (1,0) [0|127] "" HUD
- SG_ CF_Clu_HudFontColorSet : 20|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_HudBrightUpSW : 22|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_HudBrightDnSW : 24|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_HudHeightUpSW : 26|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_HudHeightDnSW : 28|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_HudSet : 30|1@1+ (1,0) [0|1] "" HUD
- SG_ CF_Clu_HudFontSizeSet : 31|2@1+ (1,0) [0|3] "" HUD
- SG_ CF_Clu_LanguageInfo : 33|5@1+ (1,0) [0|31] "" BCM,PGS
- SG_ CF_Clu_ClusterSound : 38|1@1- (1,0) [0|0] "" BCM,CGW,FATC
-
-BO_ 1066 _4WD13: 6 _4WD
- SG_ _4WD_CURRENT : 0|8@1+ (0.390625,0) [-50|50] "A" TCU
- SG_ _4WD_POSITION : 8|16@1+ (0.015625,0) [-180|180] "Deg" TCU
- SG_ _4WD_CLU_THERM_STR : 24|8@1+ (1,0) [0|100] "%" TCU
- SG_ _4WD_STATUS : 32|8@1+ (1,0) [0|15] "" ESC,TCU
-
-BO_ 1065 _4WD12: 8 _4WD
- SG_ Ster_Pos : 0|16@1+ (1,-600) [-600|600] "Deg" ESC
- SG_ FRSS : 16|8@1+ (1,0) [0|254] "km/h" ESC
- SG_ FLSS : 24|8@1+ (1,0) [0|254] "km/h" ESC
- SG_ RRSS : 32|8@1+ (1,0) [0|254] "km/h" ESC
- SG_ RLSS : 40|8@1+ (1,0) [0|254] "km/h" ESC
- SG_ CLU_PRES : 48|16@1+ (0.0625,-50) [-50|50] "Bar" ESC
-
-BO_ 809 EMS12: 8 EMS
- SG_ TEMP_ENG : 8|8@1+ (0.75,-48) [-48|143.25] "deg" _4WD,BCM,CLU,DATC,EPB,ESC,IBOX,SMK,TCU
- SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0) [0|1.99155] "" IBOX,TCU
- SG_ VB_OFF_ACT : 24|1@1+ (1,0) [0|1] "" IBOX,TCU
- SG_ ACK_ES : 25|1@1+ (1,0) [0|1] "" _4WD,ACU,IBOX
- SG_ CONF_MIL_FMY : 26|3@1+ (1,0) [0|7] "" ESC,IBOX,TCU
- SG_ OD_OFF_REQ : 29|1@1+ (1,0) [0|1] "" IBOX,TCU
- SG_ ACC_ACT : 30|1@1+ (1,0) [0|1] "" _4WD,ABS,CLU,ESC,IAP,IBOX,SCC,TCU
- SG_ CLU_ACK : 31|1@1+ (1,0) [0|1] "" _4WD,EPB,ESC,IBOX
- SG_ BRAKE_ACT : 32|2@1+ (1,0) [0|3] "" _4WD,ABS,ACU,AFLS,CLU,DATC,ECS,EPB,ESC,IBOX,LDWS_LKAS,TCU
- SG_ ENG_CHR : 34|4@1+ (1,0) [0|15] "" _4WD,ABS,ACU,CLU,DATC,EPB,ESC,FATC,IBOX,SCC,SMK,TCU
- SG_ GP_CTL : 38|2@1+ (1,0) [0|3] "" IBOX
- SG_ TPS : 40|8@1+ (0.4694836,-15.0234742) [-15.0234742|104.6948357] "%" _4WD,ABS,ACU,CLU,DATC,ECS,EPB,ESC,IBOX,TCU
- SG_ PV_AV_CAN : 48|8@1+ (0.3906,0) [0|99.603] "%" _4WD,AAF,ABS,ACU,AFLS,CLU,DATC,EPB,ESC,IAP,IBOX,LDWS_LKAS,SCC,TCU
- SG_ ENG_VOL : 56|8@1+ (0.1,0) [0|25.5] "liter" _4WD,ABS,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,SCC,SMK
-
-BO_ 1064 _4WD11: 8 _4WD
- SG_ _4WD_TYPE : 0|2@1+ (1,0) [0|3] "" ACU,ESC,TPMS
- SG_ _4WD_SUPPORT : 2|2@1+ (1,0) [0|3] "" ABS,ESC,TPMS
- SG_ _4WD_ERR : 8|8@1+ (1,0) [0|255] "" CLU,ESC
- SG_ CLU_DUTY : 16|8@1+ (1,0) [0|64] "%" ABS,ESC
- SG_ R_TIRE : 24|8@1+ (1,200) [200|455] "mm" ABS,ESC,TPMS
- SG_ _4WD_SW : 32|8@1+ (1,0) [0|9.9] "" ESC
- SG_ _2H_ACT : 40|1@1+ (1,0) [0|1] "" ABS,ESC
- SG_ _4H_ACT : 41|1@1+ (1,0) [0|1] "" ABS,CLU,ESC,TPMS
- SG_ LOW_ACT : 42|1@1+ (1,0) [0|1] "" ABS,ESC,TCU,TPMS
- SG_ AUTO_ACT : 43|1@1+ (1,0) [0|1] "" ABS,ESC,TPMS
- SG_ LOCK_ACT : 44|1@1+ (1,0) [0|1] "" ABS,CLU,ESC,TPMS
- SG_ _4WD_TQC_CUR : 48|16@1+ (1,0) [0|65535] "Nm" ABS,ESC
-
-BO_ 1319 HU_GW_E_01: 8 CLU
- SG_ C_ADrLNValueSet : 0|3@1+ (1,0) [0|7] "" BCM
- SG_ C_ADrUNValueSet : 4|3@1+ (1,0) [0|7] "" BCM
- SG_ C_TwUnNValueSet : 8|2@1+ (1,0) [0|3] "" BCM
- SG_ C_ABuzzerNValueSet : 10|2@1+ (1,0) [0|3] "" BCM
- SG_ C_ArmWKeyNValueSet : 12|2@1+ (1,0) [0|3] "" BCM
- SG_ C_PSMNValueSet : 14|2@1+ (1,0) [0|3] "" BCM
- SG_ C_SCMNValueSet : 16|2@1+ (1,0) [0|3] "" BCM
- SG_ C_HLEscortNValueSet : 18|2@1+ (1,0) [0|3] "" BCM
- SG_ C_WELNValueSet : 20|2@1+ (1,0) [0|3] "" BCM
- SG_ C_TriTurnLNValueSet : 22|2@1+ (1,0) [0|3] "" BCM
- SG_ C_SNVWarnNValueSet : 24|2@1+ (1,0) [0|3] "" BCM
- SG_ C_LkasWarnNValueSet : 26|2@1+ (1,0) [0|3] "" BCM
-
-BO_ 1318 HU_GW_E_00: 8 CLU
- SG_ C_ADrLURValueReq : 0|2@1+ (1,0) [0|3] "" BCM
- SG_ C_TwUnRValueReq : 2|2@1+ (1,0) [0|3] "" BCM
- SG_ C_AlarmRValueReq : 4|2@1+ (1,0) [0|3] "" BCM
- SG_ C_IMSRValueReq : 6|2@1+ (1,0) [0|3] "" BCM
- SG_ C_HLEscortRValueReq : 8|2@1+ (1,0) [0|3] "" BCM
- SG_ C_WELRValueReq : 10|2@1+ (1,0) [0|3] "" BCM
- SG_ C_TriTurnLRValueReq : 12|2@1+ (1,0) [0|3] "" BCM
- SG_ C_SNVWarnRValueReq : 14|2@1+ (1,0) [0|3] "" BCM
- SG_ C_LkasWarnRValueReq : 16|2@1+ (1,0) [0|3] "" BCM
-
-BO_ 1317 GW_HU_E_01: 8 BCM
- SG_ C_ADrLRValue : 0|3@1+ (1,0) [0|7] "" CLU
- SG_ C_ADrURValue : 4|3@1+ (1,0) [0|7] "" CLU
- SG_ C_TwUnRValue : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ C_ABuzzerRValue : 10|2@1+ (1,0) [0|3] "" CLU
- SG_ C_ArmWKeyRValue : 12|2@1+ (1,0) [0|3] "" CLU
- SG_ C_PSMRValue : 14|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SCMRValue : 16|2@1+ (1,0) [0|3] "" CLU
- SG_ C_HLEscortRValue : 18|2@1+ (1,0) [0|3] "" CLU
- SG_ C_WELRValue : 20|2@1+ (1,0) [0|3] "" CLU
- SG_ C_TriTurnLRValue : 22|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1316 GW_HU_E_00: 8 BCM
- SG_ C_ADrLUNValueConf : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ C_TwUnNValueConf : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ C_AlarmNValueConf : 4|2@1+ (1,0) [0|3] "" CLU
- SG_ C_PSMNValueConf : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SCMNValueConf : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ C_HLEscortNValueConf : 10|2@1+ (1,0) [0|3] "" CLU
- SG_ C_WELNValueConf : 12|2@1+ (1,0) [0|3] "" CLU
- SG_ C_TriTurnLNValueConf : 14|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1315 GW_SWRC_PE: 8 BCM
- SG_ C_ModeSW : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ C_MuteSW : 4|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SeekDnSW : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SeekUpSW : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ C_BTPhoneCallSW : 10|2@1+ (1,0) [0|3] "" CLU
- SG_ C_BTPhoneHangUpSW : 12|2@1+ (1,0) [0|3] "" CLU
- SG_ C_DISCDownSW : 14|2@1+ (1,0) [0|3] "" CLU
- SG_ C_DISCUpSW : 16|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SdsSW : 18|2@1+ (1,0) [0|3] "" CLU
- SG_ C_MTSSW : 20|2@1+ (1,0) [0|3] "" CLU
- SG_ C_VolDnSW : 22|2@1+ (1,0) [0|3] "" CLU
- SG_ C_VolUpSW : 24|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1314 GW_IPM_PE_1: 8 BCM
- SG_ C_AV_Tail : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ C_ParkingBrakeSW : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ C_RKECMD : 4|4@1+ (1,0) [0|15] "" CLU
- SG_ C_BAState : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ C_IGNSW : 12|3@1+ (1,0) [0|7] "" CLU
- SG_ C_CountryCfg : 16|3@1+ (1,0) [0|7] "" CLU
- SG_ C_TailLampActivity : 26|2@1+ (1,0) [0|3] "" CLU
- SG_ RearSW_RSELockOnOff : 28|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SMKTeleCrankingState : 32|2@1+ (1,0) [0|3] "" CLU
- SG_ C_SMKTeleCrankingFailRes : 34|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1057 SCC12: 8 SCC
- SG_ CF_VSM_Prefill : 0|1@1+ (1,0) [0|1] "" ESC
- SG_ CF_VSM_DecCmdAct : 1|1@1+ (1,0) [0|1] "" ESC
- SG_ CF_VSM_HBACmd : 2|2@1+ (1,0) [0|3] "" ESC
- SG_ CF_VSM_Warn : 4|2@1+ (1,0) [0|3] "" CLU,ESC,IAP
- SG_ CF_VSM_Stat : 6|2@1+ (1,0) [0|3] "" CLU,ESC,PSB
- SG_ CF_VSM_BeltCmd : 8|3@1+ (1,0) [0|7] "" ESC,PSB
- SG_ ACCFailInfo : 11|2@1+ (1,0) [0|3] "" CLU,CUBIS,ESC,IBOX
- SG_ ACCMode : 13|2@1+ (1,0) [0|3] "" CLU,ESC,IBOX,TCU
- SG_ StopReq : 15|1@1+ (1,0) [0|1] "" EPB,ESC
- SG_ CR_VSM_DecCmd : 16|8@1+ (0.01,0) [0|2.55] "g" ESC
- SG_ aReqMax : 24|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU
- SG_ TakeOverReq : 35|1@1+ (1,0) [0|1] "" CLU,ESC,TCU
- SG_ PreFill : 36|1@1+ (1,0) [0|1] "" ESC,TCU
- SG_ aReqMin : 37|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU
- SG_ CF_VSM_ConfMode : 48|2@1+ (1,0) [0|3] "" CLU,ESC
- SG_ AEB_Failinfo : 50|2@1+ (1,0) [0|3] "" CLU,ESC
- SG_ AEB_Status : 52|2@1+ (1,0) [0|3] "" CLU,ESC
- SG_ AEB_CmdAct : 54|1@1+ (1,0) [0|1] "" ESC
- SG_ AEB_StopReq : 55|1@1+ (1,0) [0|1] "" CLU,ESC
- SG_ CR_VSM_Alive : 56|4@1+ (1,0) [0|15] "" ESC,PSB
- SG_ CR_VSM_ChkSum : 60|4@1+ (1,0) [0|15] "" ESC,PSB
-
-BO_ 1313 GW_DDM_PE: 8 BCM
- SG_ C_DRVDoorStatus : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ C_ASTDoorStatus : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ C_RLDoorStatus : 4|2@1+ (1,0) [0|3] "" CLU
- SG_ C_RRDoorStatus : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ C_TrunkStatus : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ C_OSMirrorStatus : 10|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1056 SCC11: 8 SCC
- SG_ MainMode_ACC : 0|1@1+ (1,0) [0|1] "" CLU,EMS,ESC
- SG_ SCCInfoDisplay : 1|3@1+ (1,0) [0|7] "" CLU,ESC
- SG_ AliveCounterACC : 4|4@1+ (1,0) [0|15] "" CLU,EMS,ESC,TCU
- SG_ VSetDis : 8|8@1+ (1,0) [0|255] "km/h or MPH" CLU,ESC,TCU
- SG_ ObjValid : 16|1@1+ (1,0) [0|1] "" CLU,ESC,TCU
- SG_ DriverAlertDisplay : 17|2@1+ (1,0) [0|3] "" CLU,ESC
- SG_ TauGapSet : 19|3@1+ (1,0) [0|7] "" CLU,ESC,TCU
- SG_ ACC_ObjStatus : 22|2@1+ (1,0) [0|3] "" ABS,ESC
- SG_ ACC_ObjLatPos : 24|9@1+ (0.1,-20) [-20|31.1] "m" ABS,ESC
- SG_ ACC_ObjDist : 33|11@1+ (0.1,0) [0|204.7] "m" ABS,ESC
- SG_ ACC_ObjRelSpd : 44|12@1+ (0.1,-170) [-170|239.5] "m/s" ABS,ESC
- SG_ Navi_SCC_Curve_Status : 56|2@1+ (1,0) [0|3] "" CLU
- SG_ Navi_SCC_Curve_Act : 58|2@1+ (1,0) [0|3] "" CLU
- SG_ Navi_SCC_Camera_Act : 60|2@1+ (1,0) [0|3] "" CLU
- SG_ Navi_SCC_Camera_Status : 62|2@1+ (1,0) [0|3] "" CLU
-
-BO_ 1312 CGW3: 8 BCM
- SG_ CR_Photosensor_LH : 0|8@1+ (78.125,0) [0|20000] "" DATC,DATC
- SG_ CR_Photosensor_RH : 10|8@1+ (78.125,0) [0|20000] "" DATC,DATC
- SG_ CF_Hoodsw_memory : 22|2@1+ (1,0) [0|3] "" EMS,EMS
- SG_ C_MirOutTempSns : 24|8@1+ (0.5,-40.5) [-40|60] "deg" AAF,CLU,DATC,EMS,SPAS,AAF,DATC,EMS,SPAS
-
-BO_ 544 ESP12: 8 ESC
- SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,TCU
- SG_ LAT_ACCEL_STAT : 11|1@1+ (1,0) [0|1] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU
- SG_ LAT_ACCEL_DIAG : 12|1@1+ (1,0) [0|1] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU
- SG_ LONG_ACCEL : 13|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PSB,SCC,SPAS,TCU
- SG_ LONG_ACCEL_STAT : 24|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU
- SG_ LONG_ACCEL_DIAG : 25|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU
- SG_ CYL_PRES : 26|12@1+ (0.1,0) [0|409.5] "Bar" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU
- SG_ CYL_PRES_STAT : 38|1@1+ (1,0) [0|1] "" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU
- SG_ CYL_PRESS_DIAG : 39|1@1+ (1,0) [0|1] "" _4WD,ECS,EMS,EPB,IBOX,PSB,SCC,TCU
- SG_ YAW_RATE : 40|13@1+ (0.01,-40.95) [-40.95|40.96] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU
- SG_ YAW_RATE_STAT : 53|1@1+ (1,0) [0|1] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU
- SG_ YAW_RATE_DIAG : 54|1@1+ (1,0) [0|1] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU
- SG_ ESP12_AliveCounter : 56|4@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
- SG_ ESP12_Checksum : 60|4@1+ (1,0) [0|15] "" _4WD,EMS,LPI,TCU,TMU
-
-BO_ 1307 CLU16: 8 CLU
- SG_ CF_Clu_TirePressUnitNValueSet : 0|3@1+ (1,0) [0|7] "" TPMS
- SG_ CF_Clu_SlifNValueSet : 3|2@1+ (1,0) [0|3] "" LDWS_LKAS
- SG_ CF_Clu_RearWiperNValueSet : 12|2@1+ (1,0) [0|3] "" BCM
-
-BO_ 790 EMS11: 8 EMS
- SG_ SWI_IGK : 0|1@1+ (1,0) [0|1] "" _4WD,ABS,ACU,AHLS,CUBIS,DI_BOX,ECS,EPB,ESC,IBOX,LDWS_LKAS,MDPS,REA,SAS,SCC,TCU
- SG_ F_N_ENG : 1|1@1+ (1,0) [0|1] "" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,IBOX,MDPS,SCC,TCU
- SG_ ACK_TCS : 2|1@1+ (1,0) [0|1] "" ESC,IBOX
- SG_ PUC_STAT : 3|1@1+ (1,0) [0|1] "" _4WD,CLU,DATC,IBOX,TCU
- SG_ TQ_COR_STAT : 4|2@1+ (1,0) [0|3] "" _4WD,ESC,IBOX,TCU
- SG_ RLY_AC : 6|1@1+ (1,0) [0|1] "" DATC,IBOX,TCU
- SG_ F_SUB_TQI : 7|1@1+ (1,0) [0|1] "" _4WD,ECS,EPB,ESC,IBOX,TCU
- SG_ TQI_ACOR : 8|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU
- SG_ N : 16|16@1+ (0.25,0) [0|16383.75] "rpm" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,FPCM,IBOX,MDPS,SCC,TCU
- SG_ TQI : 32|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,ECS,EPB,ESC,IBOX,TCU
- SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU
- SG_ VS : 48|8@1+ (1,0) [0|254] "km/h" _4WD,AAF,ACU,AHLS,BCM,CLU,DATC,ECS,EPB,IBOX,LCA,LDWS_LKAS,LVR,MDPS,ODS,SCC,SMK,SPAS,TCU,TPMS
- SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0) [0|2] "" _4WD,IBOX,TCU
-
-BO_ 1301 CLU14: 8 CLU
- SG_ CF_Clu_ADrUNValueSet : 0|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_ADrLNValueSet : 3|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_EscortHLNValueSet : 6|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_DoorLSNValueSet : 8|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_PSMNValueSet : 11|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_TTUnlockNValueSet : 14|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_PTGMNValueSet : 16|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_SCMNValueSet : 18|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_WlightNValueSet : 20|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_TempUnitNValueSet : 22|2@1+ (1,0) [0|3] "" BCM,DATC
- SG_ CF_Clu_MoodLpNValueSet : 24|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_TrfChgSet : 27|2@1+ (1,0) [0|3] "" AFLS
- SG_ CF_Clu_OTTurnNValueSet : 29|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_LcaNValueSet : 32|2@1+ (1,0) [0|3] "" LCA
- SG_ CF_Clu_RctaNValueSet : 34|2@1+ (1,0) [0|3] "" LCA
- SG_ CF_Clu_RcwNValueSet : 36|2@1+ (1,0) [0|3] "" LCA
- SG_ CF_Clu_EscOffNValueSet : 38|3@1+ (1,0) [0|7] "" ESC
- SG_ CF_Clu_SccNaviCrvNValueSet : 41|2@1+ (1,0) [0|3] "" SCC
- SG_ CF_Clu_SccNaviCamNValueSet : 43|2@1+ (1,0) [0|3] "" SCC
- SG_ CF_Clu_SccAebNValueSet : 45|2@1+ (1,0) [0|3] "" SCC
- SG_ CF_Clu_LkasModeNValueSet : 47|2@1+ (1,0) [0|3] "" LDWS_LKAS
- SG_ CF_Clu_FcwNValueSet : 51|2@1+ (1,0) [0|3] "" LDWS_LKAS
- SG_ CF_Clu_PasSpkrLvNValueSet : 53|3@1+ (1,0) [0|7] "" BCM
- SG_ CF_Clu_SccDrvModeNValueSet : 56|3@1+ (1,0) [0|7] "" SCC
- SG_ CF_Clu_HAnBNValueSet : 59|2@1+ (1,0) [0|3] "" BCM
- SG_ CF_Clu_HfreeTrunkTgNValueSet : 61|3@1+ (1,0) [0|7] "" BCM
-
-BO_ 275 TCU13: 8 TCU
- SG_ N_TGT_LUP : 0|8@1+ (10,500) [500|3040] "rpm" EMS,IBOX
- SG_ SLOPE_TCU : 8|6@1+ (0.5,-16) [-16|15.5] "%" CLU,CUBIS,EMS,IBOX
- SG_ CF_Tcu_InhCda : 14|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_IsgInhib : 15|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1,0) [0|3] "" EMS,IBOX
- SG_ CF_Tcu_NCStat : 18|2@1+ (1,0) [0|3] "" EMS,IBOX
- SG_ CF_Tcu_TarGr : 20|4@1+ (1,0) [0|15] "" _4WD,CLU,DATC,EMS,EPB,ESC,IBOX,SCC
- SG_ CF_Tcu_ShfPatt : 24|4@1+ (1,0) [0|15] "" CLU,CUBIS,EMS,IBOX
- SG_ CF_Tcu_InhVis : 28|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_PRelReq : 29|1@1+ (1,0) [0|1] "" IBOX,LVR
- SG_ CF_Tcu_ITPhase : 30|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10,0) [0|2540] "Nm/s" EMS,IBOX
- SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20,0) [0|3500] "rpm" EMS,IBOX
- SG_ CF_Tcu_SptRdy : 48|1@1+ (1,0) [0|1] "" CLU,IBOX
- SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ CF_Tcu_Alive3 : 58|2@1+ (1,0) [0|3] "" EMS,IBOX
- SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1,0) [0|15] "" EMS,IBOX
-
-BO_ 274 TCU12: 8 TCU
- SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" EMS,IBOX
- SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" _4WD,EMS,ESC,IBOX,SCC,TPMS
- SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX,SCC
- SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX,SCC
- SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" BCM,CLU,DATC,EMS,IBOX,LCA,LVR,PGS,SMK,SNV
- SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" EMS,IBOX
- SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" EMS,IBOX
- SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" EMS,IBOX
- SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.9921875] "km/h" CLU,EMS,IBOX,LCA
-
-BO_ 273 TCU11: 8 TCU
- SG_ TQI_TCU_INC : 0|8@1+ (0.390625,0) [0|99.609375] "%" EMS,ESC,IBOX
- SG_ G_SEL_DISP : 8|4@1+ (1,0) [0|15] "" _4WD,AFLS,AVM,BCM,CGW,CLU,CUBIS,ECS,EMS,EPB,ESC,IAP,IBOX,LCA,LDWS_LKAS,LVR,MDPS,PGS,SCC,SMK,SNV,SPAS,TPMS
- SG_ F_TCU : 12|2@1+ (1,0) [0|3] "" EMS,ESC,IBOX
- SG_ TCU_TYPE : 14|2@1+ (1,0) [0|3] "" _4WD,EMS,ESC,IBOX
- SG_ TCU_OBD : 16|3@1+ (1,0) [0|7] "" EMS,ESC,IBOX
- SG_ SWI_GS : 19|1@1+ (1,0) [0|1] "" _4WD,EMS,EPB,ESC,IBOX,SCC
- SG_ GEAR_TYPE : 20|4@1+ (1,0) [0|15] "" _4WD,CLU,EMS,ESC,IBOX,SCC
- SG_ TQI_TCU : 24|8@1+ (0.390625,0) [0|99.609375] "%" EMS,ESC,IBOX
- SG_ TEMP_AT : 32|8@1+ (1,-40) [-40|214] "deg" AAF,CLU,CUBIS,EMS,ESC,IBOX
- SG_ N_TC : 40|16@1+ (0.25,0) [0|16383.5] "rpm" _4WD,EMS,EPB,ESC,IBOX
- SG_ SWI_CC : 56|2@1+ (1,0) [0|3] "" _4WD,CLU,EMS,ESC,IBOX
- SG_ CF_Tcu_Alive1 : 58|2@1+ (1,0) [0|3] "" EMS,IBOX
- SG_ CF_Tcu_ChkSum1 : 60|4@1+ (1,0) [0|15] "" EMS,IBOX
-
-BO_ 16 ACU13: 8 ACU
- SG_ CF_Acu_CshAct : 0|1@1+ (1,0) [0|1] "" CUBIS,IBOX,ODS
-
-BO_ 1040 CGW_USM1: 8 BCM
- SG_ CF_Gway_ATTurnRValue : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_PTGMRValue : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_EscortHLRValue : 4|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_TTUnlockRValue : 6|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_ADrLRValue : 8|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_ADrURValue : 11|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_SCMRValue : 14|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_WlightRValue : 16|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_PSMRValue : 18|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_OTTurnRValue : 21|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_DrLockSoundRValue : 24|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_HAnBRValue : 27|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_MoodLpRValue : 30|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_HfreeTrunkRValue : 32|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_AutoLightRValue : 35|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_Gway_RearWiperRValue : 38|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_Gway_PasSpkrLvRValue : 40|3@1+ (1,0) [0|7] "" CLU
-
-BO_ 1292 CLU13: 8 CLU
- SG_ CF_Clu_LowfuelWarn : 0|2@1+ (1,0) [0|3] "" BCM,FPCM,IBOX
- SG_ CF_Clu_RefDetMod : 2|1@1+ (1,0) [0|1] "" IBOX
- SG_ CF_Clu_AvgFCU : 3|2@1+ (1,0) [0|3] "" IBOX
- SG_ CF_Clu_AvsmCur : 5|1@1+ (1,0) [0|1] "" ESC,SCC
- SG_ CF_Clu_AvgFCI : 6|10@1+ (0.1,0) [0|102.2] "" IBOX
- SG_ CF_Clu_DrivingModeSwi : 16|2@1+ (1,0) [0|3] "" DATC,ECS,EMS,ESC,IAP,MDPS,TCU
- SG_ CF_Clu_FuelDispLvl : 18|5@1+ (1,0) [0|31] "" CGW,IBOX
- SG_ CF_Clu_FlexSteerSW : 23|1@1+ (1,0) [0|1] "" MDPS
- SG_ CF_Clu_DTE : 24|10@1+ (1,0) [0|1023] "" DATC
- SG_ CF_Clu_TripUnit : 34|2@1+ (1,0) [0|3] "" DATC
- SG_ CF_Clu_SWL_Stat : 36|3@1+ (1,0) [0|7] "" ACU,EMS
- SG_ CF_Clu_ActiveEcoSW : 39|1@1+ (1,0) [0|1] "" DATC,EMS,TCU
- SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1,0) [0|7] "" CUBIS,EMS,IAP,IBOX
- SG_ CF_Clu_IsaMainSW : 43|1@1+ (1,0) [0|1] "" EMS
- SG_ CF_Clu_LdwsLkasSW : 56|1@1+ (1,0) [0|1] "" LDWS_LKAS
- SG_ CF_Clu_AltLStatus : 59|1@1+ (1,0) [0|1] "" BCM,DATC,EMS
- SG_ CF_Clu_AliveCnt2 : 60|4@1+ (1,0) [0|15] "" EMS,LDWS_LKAS
-
-BO_ 1290 SCC13: 8 SCC
- SG_ SCCDrvModeRValue : 0|3@1+ (1,0) [0|7] "" CLU
- SG_ SCC_Equip : 3|1@1+ (1,0) [0|1] "" ESC
- SG_ AebDrvSetStatus : 4|3@1+ (1,0) [0|7] "" CLU,ESC
-
-BO_ 1287 TCS15: 4 ESC
- SG_ ABS_W_LAMP : 0|1@1+ (1,0) [0|1] "" _4WD,CLU,CUBIS,IBOX
- SG_ TCS_OFF_LAMP : 1|2@1+ (1,0) [0|1] "" _4WD,ACU,CLU
- SG_ TCS_LAMP : 3|2@1+ (1,0) [0|3] "" _4WD,ACU,CLU,CUBIS,IBOX,SCC
- SG_ DBC_W_LAMP : 5|1@1+ (1,0) [0|1] "" _4WD,CLU
- SG_ DBC_F_LAMP : 6|2@1+ (1,0) [0|3] "" _4WD,CLU
- SG_ ESC_Off_Step : 8|2@1+ (1,0) [0|3] "" CLU
- SG_ AVH_CLU : 16|8@1+ (1,0) [0|255] "" CLU,EPB
- SG_ AVH_I_LAMP : 24|2@1+ (1,0) [0|3] "" EPB
- SG_ EBD_W_LAMP : 26|1@1+ (1,0) [0|1] "" _4WD,CLU
- SG_ AVH_ALARM : 27|2@1+ (1,0) [0|3] "" CLU
- SG_ AVH_LAMP : 29|3@1+ (1,0) [0|7] "" CLU,EPB,SPAS
-
-BO_ 1282 TCU14: 4 TCU
- SG_ CF_TCU_WarnMsg : 0|3@1+ (1,0) [0|7] "" CLU
- SG_ CF_TCU_WarnImg : 3|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_TCU_WarnSnd : 4|1@1+ (1,0) [0|1] "" CLU
- SG_ CF_Tcu_GSel_BlinkReq : 5|1@1+ (1,0) [0|1] "" CLU,LVR
- SG_ CF_Tcu_StRelStat : 12|1@1+ (1,0) [0|1] "" CLU,EMS,ESC
- SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1,0) [0|7] "" CLU,EMS,ESC
- SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1,0) [0|3] "" CLU,EMS,ESC
-
-BO_ 1281 ECS11: 3 ECS
- SG_ ECS_W_LAMP : 0|1@1+ (1,0) [0|1] "" CLU,CUBIS,IBOX
- SG_ SYS_NA : 1|1@1+ (1,0) [0|1] "" CLU
- SG_ ECS_DEF : 2|1@1+ (1,0) [0|1] "" CLU
- SG_ ECS_DIAG : 3|1@1+ (1,0) [0|1] "" CLU
- SG_ L_CHG_NA : 4|1@1+ (1,0) [0|1] "" CLU
- SG_ Leveling_Off : 5|1@1+ (1,0) [0|1] "" CLU
- SG_ LC_overheat : 6|1@1+ (1,0) [0|1] "" CLU
- SG_ Lifting : 8|1@1+ (1,0) [0|1] "" CLU
- SG_ Lowering : 9|1@1+ (1,0) [0|1] "" CLU
- SG_ Damping_Mode : 10|2@1+ (1,0) [0|3] "" CLU
- SG_ REQ_Damping : 12|2@1+ (1,0) [0|3] "" CLU
- SG_ REQ_Height : 14|2@1+ (1,0) [0|3] "" CLU
- SG_ REQ_level : 16|4@1+ (1,0) [0|15] "" CLU
- SG_ ACT_Height : 20|4@1+ (1,0) [0|15] "" CLU
-
-BO_ 1024 CLU_CFG11: 2 CLU
- SG_ Vehicle_Type : 0|16@1+ (1,0) [0|65536] "" _4WD
-
-BO_ 1280 ACU14: 1 ACU
- SG_ CF_SWL_Ind : 0|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_TTL_Ind : 2|2@1+ (1,0) [0|3] "" CLU
- SG_ CF_SBR_Ind : 4|2@1+ (1,0) [0|3] "" BCM,CLU
-
-BO_ 512 EMS20: 6 EMS
- SG_ FCO : 0|16@1+ (0.128,0) [0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX
- SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0) [0|800] "kPa" FPCM,IBOX
- SG_ Split_Stat : 32|1@1+ (1,0) [0|1] "" FPCM
-
-BO_ 872 AT01: 8 XXX
- SG_ Gear : 32|4@1+ (1,0) [0|15] "" XXX
diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
index 94ca42f816d344..c9ca14e06ae198 100644
--- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
+++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc
index c44f2e4b1cab3a..8991abd5772720 100644
--- a/opendbc/toyota_avalon_2017_pt_generated.dbc
+++ b/opendbc/toyota_avalon_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
index 4a3c48f96cfb81..ae2245514ced32 100644
--- a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
+++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_chr_2018_pt_generated.dbc b/opendbc/toyota_chr_2018_pt_generated.dbc
index f9da41c3c2d4a1..e33e2830e70e19 100644
--- a/opendbc/toyota_chr_2018_pt_generated.dbc
+++ b/opendbc/toyota_chr_2018_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc
index 5c9fdb457ae721..e289cacb203efb 100644
--- a/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc
+++ b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc
index 0331f23c6c1416..0da9fdfe2f0b28 100644
--- a/opendbc/toyota_corolla_2017_pt_generated.dbc
+++ b/opendbc/toyota_corolla_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc
index 10220a752ddeb0..5a237de1205b29 100644
--- a/opendbc/toyota_highlander_2017_pt_generated.dbc
+++ b/opendbc/toyota_highlander_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
index f69d6629cf3146..09741f7a29f6f7 100644
--- a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
+++ b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc
index 73de10d50a6285..835197f84ea5b6 100644
--- a/opendbc/toyota_prius_2017_pt_generated.dbc
+++ b/opendbc/toyota_prius_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc
index a63c5351f63fb6..d0a74da2aeeafe 100644
--- a/opendbc/toyota_rav4_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
index 2d3825d03ddfc9..6cb8d412c84cf8 100644
--- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
@@ -15,14 +15,14 @@ BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
BO_ 512 GAS_COMMAND: 6 EON
- SG_ GAS_COMMAND : 7|16@0+ (0.0244140625,0) [0|1] "" INTERCEPTOR
- SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
+ SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
- SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
- SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
+ SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" EON
diff --git a/panda/VERSION b/panda/VERSION
index 301779b03ec401..02e8c95da5fd8a 100644
--- a/panda/VERSION
+++ b/panda/VERSION
@@ -1 +1 @@
-v1.1.7
\ No newline at end of file
+v1.1.8
\ No newline at end of file
diff --git a/panda/board/main.c b/panda/board/main.c
index 8bb6a0cee09681..b1033bb732e2df 100644
--- a/panda/board/main.c
+++ b/panda/board/main.c
@@ -589,6 +589,8 @@ int main() {
uint64_t marker = 0;
#define CURRENT_THRESHOLD 0xF00
#define CLICKS 8
+ // Enough clicks to ensure that enumeration happened. Should be longer than bootup time of the device connected to EON
+ #define CLICKS_BOOTUP 30
#endif
for (cnt=0;;cnt++) {
@@ -615,8 +617,8 @@ int main() {
}
break;
case USB_POWER_CDP:
- // been CLICKS clicks since we switched to CDP
- if ((cnt-marker) >= CLICKS) {
+ // been CLICKS_BOOTUP clicks since we switched to CDP
+ if ((cnt-marker) >= CLICKS_BOOTUP ) {
// measure current draw, if positive and no enumeration, switch to DCP
if (!is_enumerated && current < CURRENT_THRESHOLD) {
puts("USBP: no enumeration with current draw, switching to DCP mode\n");
diff --git a/panda/board/pedal.toyota/.gitignore b/panda/board/pedal.toyota/.gitignore
new file mode 100644
index 00000000000000..94053f2925089b
--- /dev/null
+++ b/panda/board/pedal.toyota/.gitignore
@@ -0,0 +1 @@
+obj/*
diff --git a/panda/board/pedal.toyota/Makefile b/panda/board/pedal.toyota/Makefile
new file mode 100644
index 00000000000000..9917e381503b03
--- /dev/null
+++ b/panda/board/pedal.toyota/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.toyota/README b/panda/board/pedal.toyota/README
new file mode 100644
index 00000000000000..2e439174f1fea0
--- /dev/null
+++ b/panda/board/pedal.toyota/README
@@ -0,0 +1,31 @@
+MOVE ALL FILES TO board/pedal TO FLASH
+
+
+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.toyota/main.c b/panda/board/pedal.toyota/main.c
new file mode 100644
index 00000000000000..6e28275f67555b
--- /dev/null
+++ b/panda/board/pedal.toyota/main.c
@@ -0,0 +1,291 @@
+//#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
+
+// ***************************** toyota can checksum ****************************
+
+int can_cksum(uint8_t *dat, uint8_t len, uint16_t addr)
+{
+ uint8_t checksum = 0;
+ checksum =((addr & 0xFF00) >> 8) + (addr & 0x00FF) + len + 1;
+ //uint16_t temp_msg = msg;
+
+ for (int ii = 0; ii < len; ii++)
+ {
+ checksum += (dat[ii]);
+ //temp_msg = temp_msg >> 8;
+ }
+ //return ((msg & ~0xFF) & (checksum & 0xFF));
+ return checksum;
+}
+
+// ***************************** 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;
+
+#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 = 0;
+ if (can_cksum(dat, 5, CAN_GAS_INPUT) == dat2[1]) {
+ if (index == 0) {
+ #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;
+ }
+
+ } 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 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);
+ 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;
+ } 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/phonelibs/openblas/libopenblas.so b/phonelibs/openblas/libopenblas.so
new file mode 120000
index 00000000000000..7a792bc9071885
--- /dev/null
+++ b/phonelibs/openblas/libopenblas.so
@@ -0,0 +1 @@
+libopenblas_armv8p-r0.2.19.so
\ No newline at end of file
diff --git a/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so b/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so
new file mode 100755
index 00000000000000..ace58c8a13122f
Binary files /dev/null and b/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so differ
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/PKG-INFO b/pyextra/overpy-0.4-py2.7.egg-info/PKG-INFO
deleted file mode 100644
index 96d494a147e90f..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/PKG-INFO
+++ /dev/null
@@ -1,123 +0,0 @@
-Metadata-Version: 1.1
-Name: overpy
-Version: 0.4
-Summary: Python Wrapper to access the OpenStreepMap Overpass API
-Home-page: https://github.com/DinoTools/python-overpy
-Author: PhiBo (DinoTools)
-Author-email: UNKNOWN
-License: MIT
-Description: Python Overpass Wrapper
- =======================
-
- A Python Wrapper to access the Overpass API.
-
- Have a look at the `documentation`_ to find additional information.
-
- .. image:: https://pypip.in/version/overpy/badge.svg
- :target: https://pypi.python.org/pypi/overpy/
- :alt: Latest Version
-
- .. image:: https://pypip.in/license/overpy/badge.svg
- :target: https://pypi.python.org/pypi/overpy/
- :alt: License
-
- .. image:: https://travis-ci.org/DinoTools/python-overpy.svg?branch=master
- :target: https://travis-ci.org/DinoTools/python-overpy
-
- .. image:: https://coveralls.io/repos/DinoTools/python-overpy/badge.png?branch=master
- :target: https://coveralls.io/r/DinoTools/python-overpy?branch=master
-
- Features
- --------
-
- * Query Overpass API
- * Parse JSON and XML response data
- * Additional helper functions
-
- Install
- -------
-
- **Requirements:**
-
- Supported Python versions:
-
- * Python 2.7
- * Python >= 3.2
- * PyPy and PyPy3
-
- **Install:**
-
- .. code-block:: console
-
- $ pip install overpy
-
- Examples
- --------
-
- Additional examples can be found in the `documentation`_ and in the *examples* directory.
-
- .. code-block:: python
-
- import overpy
-
- api = overpy.Overpass()
-
- # fetch all ways and nodes
- result = api.query("""
- way(50.746,7.154,50.748,7.157) ["highway"];
- (._;>;);
- out body;
- """)
-
- for way in result.ways:
- print("Name: %s" % way.tags.get("name", "n/a"))
- print(" Highway: %s" % way.tags.get("highway", "n/a"))
- print(" Nodes:")
- for node in way.nodes:
- print(" Lat: %f, Lon: %f" % (node.lat, node.lon))
-
-
- Helper
- ~~~~~~
-
- Helper methods are available to provide easy access to often used requests.
-
- .. code-block:: python
-
- import overpy.helper
-
- # 3600062594 is the OSM id of Chemnitz and is the bounding box for the request
- street = overpy.helper.get_street(
- "Straße der Nationen",
- "3600062594"
- )
-
- # this finds an intersection between Straße der Nationen and Carolastraße in Chemnitz
- intersection = overpy.helper.get_intersection(
- "Straße der Nationen",
- "Carolastraße",
- "3600062594"
- )
-
-
- License
- -------
-
- Published under the MIT (see LICENSE for more information)
-
- .. _`documentation`: http://python-overpy.readthedocs.org/
-
-Keywords: OverPy Overpass OSM OpenStreetMap
-Platform: UNKNOWN
-Classifier: Development Status :: 4 - Beta
-Classifier: License :: OSI Approved :: MIT License
-Classifier: Operating System :: OS Independent
-Classifier: Programming Language :: Python
-Classifier: Programming Language :: Python :: 2.7
-Classifier: Programming Language :: Python :: 3
-Classifier: Programming Language :: Python :: 3.2
-Classifier: Programming Language :: Python :: 3.3
-Classifier: Programming Language :: Python :: 3.4
-Classifier: Programming Language :: Python :: 3.5
-Classifier: Programming Language :: Python :: Implementation :: CPython
-Classifier: Programming Language :: Python :: Implementation :: PyPy
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/SOURCES.txt b/pyextra/overpy-0.4-py2.7.egg-info/SOURCES.txt
deleted file mode 100644
index 66bf17f7c4d393..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/SOURCES.txt
+++ /dev/null
@@ -1,61 +0,0 @@
-CHANGELOG.rst
-LICENSE
-MANIFEST.in
-README.rst
-setup.cfg
-setup.py
-docs/make.bat
-docs/source/api.rst
-docs/source/changelog.rst
-docs/source/conf.py
-docs/source/contributing.rst
-docs/source/example.rst
-docs/source/index.rst
-docs/source/introduction.rst
-examples/get_areas.py
-examples/get_nodes.py
-examples/get_ways.py
-overpy/__about__.py
-overpy/__init__.py
-overpy/exception.py
-overpy/helper.py
-overpy.egg-info/PKG-INFO
-overpy.egg-info/SOURCES.txt
-overpy.egg-info/dependency_links.txt
-overpy.egg-info/not-zip-safe
-overpy.egg-info/top_level.txt
-tests/__init__.py
-tests/base_class.py
-tests/test_exception.py
-tests/test_json.py
-tests/test_request.py
-tests/test_result.py
-tests/test_result_way.py
-tests/test_xml.py
-tests/json/area-01.json
-tests/json/node-01.json
-tests/json/relation-01.json
-tests/json/relation-02.json
-tests/json/relation-03.json
-tests/json/relation-04.json
-tests/json/result-expand-01.json
-tests/json/result-expand-02.json
-tests/json/result-way-01.json
-tests/json/result-way-02.json
-tests/json/result-way-03.json
-tests/json/way-01.json
-tests/json/way-02.json
-tests/json/way-03.json
-tests/json/way-04.json
-tests/response/bad-request-encoding.html
-tests/response/bad-request.html
-tests/xml/area-01.xml
-tests/xml/node-01.xml
-tests/xml/relation-01.xml
-tests/xml/relation-02.xml
-tests/xml/relation-03.xml
-tests/xml/relation-04.xml
-tests/xml/way-01.xml
-tests/xml/way-02.xml
-tests/xml/way-03.xml
-tests/xml/way-04.xml
\ No newline at end of file
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/dependency_links.txt b/pyextra/overpy-0.4-py2.7.egg-info/dependency_links.txt
deleted file mode 100644
index 8b137891791fe9..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/dependency_links.txt
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/installed-files.txt b/pyextra/overpy-0.4-py2.7.egg-info/installed-files.txt
deleted file mode 100644
index 0cd05ada1f7c8d..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/installed-files.txt
+++ /dev/null
@@ -1,56 +0,0 @@
-../overpy/__about__.py
-../overpy/__about__.pyc
-../overpy/__init__.py
-../overpy/__init__.pyc
-../overpy/exception.py
-../overpy/exception.pyc
-../overpy/helper.py
-../overpy/helper.pyc
-../tests/__init__.py
-../tests/__init__.pyc
-../tests/base_class.py
-../tests/base_class.pyc
-../tests/json/area-01.json
-../tests/json/node-01.json
-../tests/json/relation-01.json
-../tests/json/relation-02.json
-../tests/json/relation-03.json
-../tests/json/relation-04.json
-../tests/json/result-expand-01.json
-../tests/json/result-expand-02.json
-../tests/json/result-way-01.json
-../tests/json/result-way-02.json
-../tests/json/result-way-03.json
-../tests/json/way-01.json
-../tests/json/way-02.json
-../tests/json/way-03.json
-../tests/json/way-04.json
-../tests/response/bad-request-encoding.html
-../tests/response/bad-request.html
-../tests/test_exception.py
-../tests/test_exception.pyc
-../tests/test_json.py
-../tests/test_json.pyc
-../tests/test_request.py
-../tests/test_request.pyc
-../tests/test_result.py
-../tests/test_result.pyc
-../tests/test_result_way.py
-../tests/test_result_way.pyc
-../tests/test_xml.py
-../tests/test_xml.pyc
-../tests/xml/area-01.xml
-../tests/xml/node-01.xml
-../tests/xml/relation-01.xml
-../tests/xml/relation-02.xml
-../tests/xml/relation-03.xml
-../tests/xml/relation-04.xml
-../tests/xml/way-01.xml
-../tests/xml/way-02.xml
-../tests/xml/way-03.xml
-../tests/xml/way-04.xml
-PKG-INFO
-SOURCES.txt
-dependency_links.txt
-not-zip-safe
-top_level.txt
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/not-zip-safe b/pyextra/overpy-0.4-py2.7.egg-info/not-zip-safe
deleted file mode 100644
index 8b137891791fe9..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/not-zip-safe
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/pyextra/overpy-0.4-py2.7.egg-info/top_level.txt b/pyextra/overpy-0.4-py2.7.egg-info/top_level.txt
deleted file mode 100644
index 4611d9bb608014..00000000000000
--- a/pyextra/overpy-0.4-py2.7.egg-info/top_level.txt
+++ /dev/null
@@ -1,2 +0,0 @@
-overpy
-tests
diff --git a/pyextra/overpy/__init__.py b/pyextra/overpy/__init__.py
index 8e038bda96bd02..2836080ab7d017 100644
--- a/pyextra/overpy/__init__.py
+++ b/pyextra/overpy/__init__.py
@@ -5,6 +5,8 @@
import json
import re
import sys
+import time
+import requests
from overpy import exception
from overpy.__about__ import (
@@ -18,12 +20,15 @@
XML_PARSER_DOM = 1
XML_PARSER_SAX = 2
-if PY2:
- from urllib2 import urlopen
- from urllib2 import HTTPError
-elif PY3:
- from urllib.request import urlopen
- from urllib.error import HTTPError
+# Try to convert some common attributes
+# http://wiki.openstreetmap.org/wiki/Elements#Common_attributes
+GLOBAL_ATTRIBUTE_MODIFIERS = {
+ "changeset": int,
+ "timestamp": lambda ts: datetime.strptime(ts, "%Y-%m-%dT%H:%M:%SZ"),
+ "uid": int,
+ "version": int,
+ "visible": lambda v: v.lower() == "true"
+}
def is_valid_type(element, cls):
@@ -41,11 +46,16 @@ def is_valid_type(element, cls):
class Overpass(object):
"""
Class to access the Overpass API
+
+ :cvar default_max_retry_count: Global max number of retries (Default: 0)
+ :cvar default_retry_timeout: Global time to wait between tries (Default: 1.0s)
"""
+ default_max_retry_count = 0
default_read_chunk_size = 4096
+ default_retry_timeout = 1.0
default_url = "http://overpass-api.de/api/interpreter"
- def __init__(self, read_chunk_size=None, url=None, xml_parser=XML_PARSER_SAX):
+ def __init__(self, read_chunk_size=None, url=None, xml_parser=XML_PARSER_SAX, max_retry_count=None, retry_timeout=None, timeout=5.0, headers=None):
"""
:param read_chunk_size: Max size of each chunk read from the server response
:type read_chunk_size: Integer
@@ -53,6 +63,14 @@ def __init__(self, read_chunk_size=None, url=None, xml_parser=XML_PARSER_SAX):
:type url: str
:param xml_parser: The xml parser to use
:type xml_parser: Integer
+ :param max_retry_count: Max number of retries (Default: default_max_retry_count)
+ :type max_retry_count: Integer
+ :param retry_timeout: Time to wait between tries (Default: default_retry_timeout)
+ :type retry_timeout: float
+ :param timeout: HTTP request timeout
+ :type timeout: float
+ :param headers: HTTP request headers
+ :type headers: dict
"""
self.url = self.default_url
if url is not None:
@@ -63,7 +81,34 @@ def __init__(self, read_chunk_size=None, url=None, xml_parser=XML_PARSER_SAX):
if read_chunk_size is None:
read_chunk_size = self.default_read_chunk_size
self.read_chunk_size = read_chunk_size
+
+ if max_retry_count is None:
+ max_retry_count = self.default_max_retry_count
+ self.max_retry_count = max_retry_count
+
+ if retry_timeout is None:
+ retry_timeout = self.default_retry_timeout
+ self.retry_timeout = retry_timeout
+
self.xml_parser = xml_parser
+ self.timeout = timeout
+ self.headers = headers
+
+ def _handle_remark_msg(self, msg):
+ """
+ Try to parse the message provided with the remark tag or element.
+
+ :param str msg: The message
+ :raises overpy.exception.OverpassRuntimeError: If message starts with 'runtime error:'
+ :raises overpy.exception.OverpassRuntimeRemark: If message starts with 'runtime remark:'
+ :raises overpy.exception.OverpassUnknownError: If we are unable to identify the error
+ """
+ msg = msg.strip()
+ if msg.startswith("runtime error:"):
+ raise exception.OverpassRuntimeError(msg=msg)
+ elif msg.startswith("runtime remark:"):
+ raise exception.OverpassRuntimeRemark(msg=msg)
+ raise exception.OverpassUnknownError(msg=msg)
def query(self, query):
"""
@@ -76,56 +121,79 @@ def query(self, query):
if not isinstance(query, bytes):
query = query.encode("utf-8")
- try:
- f = urlopen(self.url, query)
- except HTTPError as e:
- f = e
-
- response = f.read(self.read_chunk_size)
- while True:
- data = f.read(self.read_chunk_size)
- if len(data) == 0:
- break
- response = response + data
- f.close()
-
- if f.code == 200:
- if PY2:
- http_info = f.info()
- content_type = http_info.getheader("content-type")
- else:
- content_type = f.getheader("Content-Type")
-
- if content_type == "application/json":
- return self.parse_json(response)
+ retry_num = 0
+ retry_exceptions = []
+ do_retry = True if self.max_retry_count > 0 else False
+ while retry_num <= self.max_retry_count:
+ if retry_num > 0:
+ time.sleep(self.retry_timeout)
+ retry_num += 1
- if content_type == "application/osm3s+xml":
- return self.parse_xml(response)
+ try:
+ if self.headers is not None:
+ r = requests.post(self.url, query, timeout=self.timeout, headers=self.headers)
+ else:
+ r = requests.post(self.url, query, timeout=self.timeout)
+ response = r.content
+ except (requests.exceptions.BaseHTTPError, requests.exceptions.RequestException) as e:
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
- raise exception.OverpassUnknownContentType(content_type)
+ if r.status_code == 200:
+ content_type = r.headers["Content-Type"]
- if f.code == 400:
- msgs = []
- for msg in self._regex_extract_error_msg.finditer(response):
- tmp = self._regex_remove_tag.sub(b"", msg.group("msg"))
- try:
- tmp = tmp.decode("utf-8")
- except UnicodeDecodeError:
- tmp = repr(tmp)
- msgs.append(tmp)
+ if content_type == "application/json":
+ return self.parse_json(response)
- raise exception.OverpassBadRequest(
- query,
- msgs=msgs
- )
+ if content_type == "application/osm3s+xml":
+ return self.parse_xml(response)
- if f.code == 429:
- raise exception.OverpassTooManyRequests
+ e = exception.OverpassUnknownContentType(content_type)
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
+ elif r.status_code == 400:
+ msgs = []
+ for msg in self._regex_extract_error_msg.finditer(response):
+ tmp = self._regex_remove_tag.sub(b"", msg.group("msg"))
+ try:
+ tmp = tmp.decode("utf-8")
+ except UnicodeDecodeError:
+ tmp = repr(tmp)
+ msgs.append(tmp)
+
+ e = exception.OverpassBadRequest(
+ query,
+ msgs=msgs
+ )
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
+ elif r.status_code == 429:
+ e = exception.OverpassTooManyRequests
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
+ elif r.status_code == 504:
+ e = exception.OverpassGatewayTimeout
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
- if f.code == 504:
- raise exception.OverpassGatewayTimeout
+ # No valid response code
+ e = exception.OverpassUnknownHTTPStatusCode(r.status_code)
+ if not do_retry:
+ raise e
+ retry_exceptions.append(e)
+ continue
- raise exception.OverpassUnknownHTTPStatusCode(f.code)
+ raise exception.MaxRetriesReached(retry_count=retry_num, exceptions=retry_exceptions)
def parse_json(self, data, encoding="utf-8"):
"""
@@ -139,8 +207,11 @@ def parse_json(self, data, encoding="utf-8"):
:rtype: overpy.Result
"""
if isinstance(data, bytes):
- data = data.decode(encoding)
+ data = data.decode(encoding)
+
data = json.loads(data, parse_float=Decimal)
+ if "remark" in data:
+ self._handle_remark_msg(msg=data.get("remark"))
return Result.from_json(data, api=self)
def parse_xml(self, data, encoding="utf-8", parser=None):
@@ -155,13 +226,16 @@ def parse_xml(self, data, encoding="utf-8", parser=None):
"""
if parser is None:
parser = self.xml_parser
-
if isinstance(data, bytes):
data = data.decode(encoding)
if PY2 and not isinstance(data, str):
# Python 2.x: Convert unicode strings
data = data.encode(encoding)
+ m = re.compile("(?P[^<>]*)").search(data)
+ if m:
+ self._handle_remark_msg(m.group("msg"))
+
return Result.from_xml(data, api=self, parser=parser)
@@ -279,23 +353,39 @@ def from_json(cls, data, api=None):
return result
@classmethod
- def from_xml(cls, data, api=None, parser=XML_PARSER_SAX):
+ def from_xml(cls, data, api=None, parser=None):
"""
- Create a new instance and load data from xml object.
+ Create a new instance and load data from xml data or object.
+
+ .. note::
+ If parser is set to None, the functions tries to find the best parse.
+ By default the SAX parser is chosen if a string is provided as data.
+ The parser is set to DOM if an xml.etree.ElementTree.Element is provided as data value.
:param data: Root element
- :type data: xml.etree.ElementTree.Element
- :param api:
+ :type data: str | xml.etree.ElementTree.Element
+ :param api: The instance to query additional information if required.
:type api: Overpass
- :param parser: Specify the parser to use(DOM or SAX)
- :type parser: Integer
+ :param parser: Specify the parser to use(DOM or SAX)(Default: None = autodetect, defaults to SAX)
+ :type parser: Integer | None
:return: New instance of Result object
:rtype: Result
"""
+ if parser is None:
+ if isinstance(data, str):
+ parser = XML_PARSER_SAX
+ else:
+ parser = XML_PARSER_DOM
+
result = cls(api=api)
if parser == XML_PARSER_DOM:
import xml.etree.ElementTree as ET
- root = ET.fromstring(data)
+ if isinstance(data, str):
+ root = ET.fromstring(data)
+ elif isinstance(data, ET.Element):
+ root = data
+ else:
+ raise exception.OverPyException("Unable to detect data type.")
for elem_cls in [Node, Way, Relation, Area]:
for child in root:
@@ -522,17 +612,10 @@ def __init__(self, attributes=None, result=None, tags=None):
"""
self._result = result
- # Try to convert some common attributes
- # http://wiki.openstreetmap.org/wiki/Elements#Common_attributes
- self._attribute_modifiers = {
- "changeset": int,
- "timestamp": lambda ts: datetime.strptime(ts, "%Y-%m-%dT%H:%M:%SZ"),
- "uid": int,
- "version": int,
- "visible": lambda v: v.lower() == "true"
- }
self.attributes = attributes
- for n, m in self._attribute_modifiers.items():
+ # ToDo: Add option to modify attribute modifiers
+ attribute_modifiers = dict(GLOBAL_ATTRIBUTE_MODIFIERS.items())
+ for n, m in attribute_modifiers.items():
if n in self.attributes:
self.attributes[n] = m(self.attributes[n])
self.id = None
diff --git a/pyextra/overpy/exception.py b/pyextra/overpy/exception.py
index 7179d246a59015..3d8416a1257ef1 100644
--- a/pyextra/overpy/exception.py
+++ b/pyextra/overpy/exception.py
@@ -37,6 +37,18 @@ def __str__(self):
)
+class MaxRetriesReached(OverPyException):
+ """
+ Raised if max retries reached and the Overpass server didn't respond with a result.
+ """
+ def __init__(self, retry_count, exceptions):
+ self.exceptions = exceptions
+ self.retry_count = retry_count
+
+ def __str__(self):
+ return "Unable get any result from the Overpass API server after %d retries." % self.retry_count
+
+
class OverpassBadRequest(OverPyException):
"""
Raised if the Overpass API service returns a syntax error.
@@ -62,6 +74,29 @@ def __str__(self):
return "\n".join(tmp_msgs)
+class OverpassError(OverPyException):
+ """
+ Base exception to report errors if the response returns a remark tag or element.
+
+ .. note::
+ If you are not sure which of the subexceptions you should use, use this one and try to parse the message.
+
+ For more information have a look at https://github.com/DinoTools/python-overpy/issues/62
+
+ :param str msg: The message from the remark tag or element
+ """
+ def __init__(self, msg=None):
+ #: The message from the remark tag or element
+ self.msg = msg
+
+ def __str__(self):
+ if self.msg is None:
+ return "No error message provided"
+ if not isinstance(self.msg, str):
+ return str(self.msg)
+ return self.msg
+
+
class OverpassGatewayTimeout(OverPyException):
"""
Raised if load of the Overpass API service is too high and it can't handle the request.
@@ -70,6 +105,22 @@ def __init__(self):
OverPyException.__init__(self, "Server load too high")
+class OverpassRuntimeError(OverpassError):
+ """
+ Raised if the server returns a remark-tag(xml) or remark element(json) with a message starting with
+ 'runtime error:'.
+ """
+ pass
+
+
+class OverpassRuntimeRemark(OverpassError):
+ """
+ Raised if the server returns a remark-tag(xml) or remark element(json) with a message starting with
+ 'runtime remark:'.
+ """
+ pass
+
+
class OverpassTooManyRequests(OverPyException):
"""
Raised if the Overpass API service returns a 429 status code.
@@ -94,6 +145,13 @@ def __str__(self):
return "Unknown content type: %s" % self.content_type
+class OverpassUnknownError(OverpassError):
+ """
+ Raised if the server returns a remark-tag(xml) or remark element(json) and we are unable to find any reason.
+ """
+ pass
+
+
class OverpassUnknownHTTPStatusCode(OverPyException):
"""
Raised if the returned HTTP status code isn't handled by OverPy.
diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt
index deb37d08655808..b623e2a25e2e11 100644
--- a/requirements_openpilot.txt
+++ b/requirements_openpilot.txt
@@ -5,7 +5,7 @@ libusb1==1.5.0
pycapnp==0.6.3
pyzmq==15.4.0
raven==5.23.0
-requests==2.10.0
+requests==2.20.0
setproctitle==1.1.10
simplejson==3.8.2
pyyaml==3.12
@@ -16,4 +16,5 @@ filterpy==1.2.4
smbus2==0.2.0
pyflakes==1.6.0
-e git+https://github.com/commaai/le_python.git@5eef8f5be5929d33973e1b10e686fa0cdcd6792f#egg=Logentries
+-e git+https://github.com/commaai/python-overpy.git@f86529af402d4642e1faeb146671c40284007323#egg=overpy
Flask==1.0.2
diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py
index d897a815f2cb03..1e7b233ddda491 100755
--- a/selfdrive/boardd/boardd.py
+++ b/selfdrive/boardd/boardd.py
@@ -71,9 +71,10 @@ def __parse_can_buffer(dat):
def can_send_many(arr):
snds = []
for addr, _, dat, alt in arr:
- snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat
- snd = snd.ljust(0x10, '\x00')
- snds.append(snd)
+ if addr < 0x800: # only support 11 bit addr
+ snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat
+ snd = snd.ljust(0x10, '\x00')
+ snds.append(snd)
while 1:
try:
handle.bulkWrite(3, ''.join(snds))
diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py
index 1f0e36e0dc23ef..633ce4b8ae0458 100755
--- a/selfdrive/car/ford/interface.py
+++ b/selfdrive/car/ford/interface.py
@@ -119,6 +119,7 @@ def get_params(candidate, fingerprint):
ret.brakeMaxV = [1., 0.8]
ret.enableCamera = not any(x for x in [970, 973, 984] if x in fingerprint)
+ ret.openpilotLongitudinalControl = False
cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera)
ret.steerLimitAlert = False
diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py
index 14b165dc6aea61..fd90ffd4dcf0ca 100644
--- a/selfdrive/car/gm/carcontroller.py
+++ b/selfdrive/car/gm/carcontroller.py
@@ -10,7 +10,7 @@
class CarControllerParams():
def __init__(self, car_fingerprint):
- if car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
self.STEER_MAX = 300
self.STEER_STEP = 2 # how often we update the steer cmd
self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s)
@@ -104,7 +104,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, \
self.apply_steer_last = apply_steer
idx = (frame / P.STEER_STEP) % 4
- if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
can_sends.append(gmcan.create_steering_control(self.packer_pt,
canbus.powertrain, apply_steer, idx, lkas_enabled))
if self.car_fingerprint == CAR.CADILLAC_CT6:
@@ -113,7 +113,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, \
### GAS/BRAKE ###
- if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
# no output if not enabled, but keep sending keepalive messages
# treat pedals as one
final_pedal = actuators.gas - actuators.brake
diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py
index 6d5b3a9d505f6c..24c73a3079b23a 100644
--- a/selfdrive/car/gm/carstate.py
+++ b/selfdrive/car/gm/carstate.py
@@ -31,15 +31,18 @@ def get_powertrain_can_parser(CP, canbus):
("LKATorqueDeliveredStatus", "PSCMStatus", 0),
]
- if CP.carFingerprint in (CAR.VOLT, CAR.MALIBU):
+ if CP.carFingerprint == CAR.VOLT:
signals += [
("RegenPaddle", "EBCMRegenPaddle", 0),
+ ]
+ if CP.carFingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
+ signals += [
("TractionControlOn", "ESPStatus", 0),
("EPBClosed", "EPBStatus", 0),
("CruiseMainOn", "ECMEngineStatus", 0),
("CruiseState", "AcceleratorPedal2", 0),
]
- elif CP.carFingerprint == CAR.CADILLAC_CT6:
+ if CP.carFingerprint == CAR.CADILLAC_CT6:
signals += [
("ACCCmdActive", "ASCMActiveCruiseControlStatus", 0)
]
@@ -48,6 +51,7 @@ def get_powertrain_can_parser(CP, canbus):
class CarState(object):
def __init__(self, CP, canbus):
+ self.CP = CP
# initialize can parser
self.car_fingerprint = CP.carFingerprint
@@ -117,14 +121,17 @@ def update(self, pt_cp):
self.left_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 1
self.right_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 2
- if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
self.park_brake = pt_cp.vl["EPBStatus"]['EPBClosed']
self.main_on = pt_cp.vl["ECMEngineStatus"]['CruiseMainOn']
self.acc_active = False
self.esp_disabled = pt_cp.vl["ESPStatus"]['TractionControlOn'] != 1
- self.regen_pressed = bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle'])
self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]['CruiseState']
- else:
+ if self.car_fingerprint == CAR.VOLT:
+ self.regen_pressed = bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle'])
+ else:
+ self.regen_pressed = False
+ if self.car_fingerprint == CAR.CADILLAC_CT6:
self.park_brake = False
self.main_on = False
self.acc_active = pt_cp.vl["ASCMActiveCruiseControlStatus"]['ACCCmdActive']
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index e1f9fc51736174..9ec1b9e5d0e12c 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -12,15 +12,6 @@
except ImportError:
CarController = None
-# Car chimes, beeps, blinker sounds etc
-class CM:
- TOCK = 0x81
- TICK = 0x82
- LOW_BEEP = 0x84
- HIGH_BEEP = 0x85
- LOW_CHIME = 0x86
- HIGH_CHIME = 0x87
-
class CanBus(object):
def __init__(self):
self.powertrain = 0
@@ -71,13 +62,14 @@ def get_params(candidate, fingerprint):
# Have to go passive if ASCM is online (ACC-enabled cars),
# or camera is on powertrain bus (LKA cars without ACC).
ret.enableCamera = not any(x for x in STOCK_CONTROL_MSGS[candidate] if x in fingerprint)
+ ret.openpilotLongitudinalControl = ret.enableCamera
std_cargo = 136
if candidate == CAR.VOLT:
# supports stop and go, but initial engage must be above 18mph (which include conservatism)
ret.minEnableSpeed = 18 * CV.MPH_TO_MS
- # kg of standard extra cargo to count for drive, gas, etc...
+ # kg of standard extra cargo to count for driver, gas, etc...
ret.mass = 1607 + std_cargo
ret.safetyModel = car.CarParams.SafetyModels.gm
ret.wheelbase = 2.69
@@ -95,10 +87,39 @@ def get_params(candidate, fingerprint):
ret.steerRatioRear = 0.
ret.centerToFront = ret.wheelbase * 0.4 # wild guess
+ elif candidate == CAR.HOLDEN_ASTRA:
+ # kg of standard extra cargo to count for driver, gas, etc...
+ ret.mass = 1363 + std_cargo
+ ret.wheelbase = 2.662
+ # Remaining parameters copied from Volt for now
+ ret.centerToFront = ret.wheelbase * 0.4
+ ret.minEnableSpeed = 18 * CV.MPH_TO_MS
+ ret.safetyModel = car.CarParams.SafetyModels.gm
+ ret.steerRatio = 15.7
+ ret.steerRatioRear = 0.
+
+ elif candidate == CAR.ACADIA:
+ ret.minEnableSpeed = -1 # engage speed is decided by pcm
+ ret.mass = 4353. * CV.LB_TO_KG + std_cargo
+ ret.safetyModel = car.CarParams.SafetyModels.gm
+ ret.wheelbase = 2.86
+ ret.steerRatio = 14.4 #end to end is 13.46
+ ret.steerRatioRear = 0.
+ ret.centerToFront = ret.wheelbase * 0.4
+
+ elif candidate == CAR.CADILLAC_ATS:
+ ret.minEnableSpeed = 18 * CV.MPH_TO_MS
+ ret.mass = 1601 + std_cargo
+ ret.safetyModel = car.CarParams.SafetyModels.gm
+ ret.wheelbase = 2.78
+ ret.steerRatio = 15.3
+ ret.steerRatioRear = 0.
+ ret.centerToFront = ret.wheelbase * 0.49
+
elif candidate == CAR.CADILLAC_CT6:
# engage speed is decided by pcm
ret.minEnableSpeed = -1
- # kg of standard extra cargo to count for drive, gas, etc...
+ # kg of standard extra cargo to count for driver, gas, etc...
ret.mass = 4016. * CV.LB_TO_KG + std_cargo
ret.safetyModel = car.CarParams.SafetyModels.cadillac
ret.wheelbase = 3.11
@@ -264,8 +285,7 @@ def update(self, c):
if ret.seatbeltUnlatched:
events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
- if self.CS.car_fingerprint in (CAR.VOLT, CAR.MALIBU):
-
+ if self.CS.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
if self.CS.brake_error:
events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT]))
if not self.CS.gear_shifter_valid:
diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py
index 8e564b1b924152..6af0d3f8fae843 100755
--- a/selfdrive/car/gm/radar_interface.py
+++ b/selfdrive/car/gm/radar_interface.py
@@ -22,7 +22,7 @@
def create_radard_can_parser(canbus, car_fingerprint):
dbc_f = DBC[car_fingerprint]['radar']
- if car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
# C1A-ARS3-A by Continental
radar_targets = range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)
signals = zip(['FLRRNumValidTargets',
diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py
index b4f8d90601418a..17260fe27b3897 100644
--- a/selfdrive/car/gm/values.py
+++ b/selfdrive/car/gm/values.py
@@ -4,9 +4,12 @@
AudibleAlert = car.CarControl.HUDControl.AudibleAlert
class CAR:
+ HOLDEN_ASTRA = "HOLDEN ASTRA RS-V BK 2017"
VOLT = "CHEVROLET VOLT PREMIER 2017"
+ CADILLAC_ATS = "CADILLAC ATS Premium Performance 2018"
CADILLAC_CT6 = "CADILLAC CT6 SUPERCRUISE 2018"
MALIBU = "CHEVROLET MALIBU PREMIER 2017"
+ ACADIA = "GMC ACADIA DENALI 2018"
class CruiseButtons:
UNPRESS = 1
@@ -36,7 +39,7 @@ class CM:
def is_eps_status_ok(eps_status, car_fingerprint):
valid_eps_status = []
- if car_fingerprint in (CAR.VOLT, CAR.MALIBU):
+ if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS):
valid_eps_status += [0, 1]
elif car_fingerprint == CAR.CADILLAC_CT6:
valid_eps_status += [0, 1, 4, 5, 6]
@@ -55,6 +58,10 @@ def parse_gear_shifter(can_gear):
return car.CarState.GearShifter.unknown
FINGERPRINTS = {
+ # Astra BK MY17, ASCM unplugged
+ CAR.HOLDEN_ASTRA: [{
+ 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7,
+ }],
CAR.VOLT: [
# Volt Premier w/ ACC 2017
{
@@ -64,6 +71,11 @@ def parse_gear_shifter(can_gear):
{
170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8
}],
+ CAR.CADILLAC_ATS: [
+ # Cadillac ATS Coupe Premium Performance 3.6L RWD w/ ACC 2018
+ {
+ 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8
+ }],
CAR.CADILLAC_CT6: [{
190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 336: 1, 338: 6, 340: 6, 352: 5, 354: 5, 356: 8, 368: 3, 372: 5, 381: 8, 386: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 458: 5, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 800: 6, 801: 8, 804: 3, 810: 8, 832: 8, 833: 8, 834: 8, 835: 6, 836: 5, 837: 8, 838: 8, 839: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 884: 8, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 1, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1934: 7, 2016: 8, 2024: 8
}],
@@ -72,18 +84,29 @@ def parse_gear_shifter(can_gear):
{
190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8,
}],
+ CAR.ACADIA: [
+ # Acadia Denali w/ /ACC 2018
+ {
+ 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8
+ }],
}
STEER_THRESHOLD = 1.0
STOCK_CONTROL_MSGS = {
+ CAR.HOLDEN_ASTRA: [384, 715],
CAR.VOLT: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd"
CAR.MALIBU: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd"
- CAR.CADILLAC_CT6: [], # Cadillac does not require ASCMs to be disconnected
+ CAR.ACADIA: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd"
+ CAR.CADILLAC_ATS: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd"
+ CAR.CADILLAC_CT6: [], # CT6 does not require ASCMs to be disconnected
}
DBC = {
+ CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
CAR.MALIBU: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
+ CAR.ACADIA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
+ CAR.CADILLAC_ATS: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
CAR.CADILLAC_CT6: dbc_dict('cadillac_ct6_powertrain', 'cadillac_ct6_object', chassis_dbc='cadillac_ct6_chassis'),
}
diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py
index f46343c18fc7d6..99d4a2214300c2 100644
--- a/selfdrive/car/honda/carstate.py
+++ b/selfdrive/car/honda/carstate.py
@@ -40,8 +40,6 @@ def get_can_signals(CP):
("LEFT_BLINKER", "SCM_FEEDBACK", 0),
("RIGHT_BLINKER", "SCM_FEEDBACK", 0),
("GEAR", "GEARBOX", 0),
- ("BRAKE_ERROR_1", "STANDSTILL", 1),
- ("BRAKE_ERROR_2", "STANDSTILL", 1),
("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1),
("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0),
("BRAKE_PRESSED", "POWERTRAIN_DATA", 0),
@@ -63,7 +61,6 @@ def get_can_signals(CP):
("STEERING_SENSORS", 100),
("SCM_FEEDBACK", 10),
("GEARBOX", 100),
- ("STANDSTILL", 50),
("SEATBELT_STATUS", 10),
("CRUISE", 10),
("POWERTRAIN_DATA", 100),
@@ -84,9 +81,12 @@ def get_can_signals(CP):
checks += [("GAS_PEDAL_2", 100)]
else:
# Nidec signals.
- signals += [("CRUISE_SPEED_PCM", "CRUISE", 0),
+ signals += [("BRAKE_ERROR_1", "STANDSTILL", 1),
+ ("BRAKE_ERROR_2", "STANDSTILL", 1),
+ ("CRUISE_SPEED_PCM", "CRUISE", 0),
("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0)]
- checks += [("CRUISE_PARAMS", 50)]
+ checks += [("CRUISE_PARAMS", 50),
+ ("STANDSTILL", 50)]
if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH):
signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)]
@@ -205,7 +205,10 @@ def update(self, cp, cp_cam):
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.steer_warning = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 3] # 3 is low speed lockout, not worth a warning
- self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2']
+ if self.CP.radarOffCan:
+ self.brake_error = 0
+ else:
+ 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']
# calc best v_ego estimate, by averaging two opposite corners
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index 3ab57b899e9344..e6c4ed4de1ef93 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -151,10 +151,13 @@ def get_params(candidate, fingerprint):
ret.safetyModel = car.CarParams.SafetyModels.hondaBosch
ret.enableCamera = True
ret.radarOffCan = True
+ ret.openpilotLongitudinalControl = False
else:
ret.safetyModel = car.CarParams.SafetyModels.honda
ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint)
ret.enableGasInterceptor = 0x201 in fingerprint
+ ret.openpilotLongitudinalControl = ret.enableCamera
+
cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera)
cloudlog.warn("ECU Gas Interceptor: %r", ret.enableGasInterceptor)
@@ -485,8 +488,8 @@ def update(self, c):
ret.buttonEvents = buttonEvents
# events
- # TODO: I don't like the way capnp does enums
- # These strings aren't checked at compile time
+ # TODO: event names aren't checked at compile time.
+ # Maybe there is a way to use capnp enums directly
events = []
if not self.CS.can_valid:
self.can_invalid_count += 1
@@ -494,12 +497,15 @@ def update(self, c):
events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
else:
self.can_invalid_count = 0
+
if not self.CS.cam_can_valid and self.CP.enableCamera:
self.cam_can_invalid_count += 1
- if self.cam_can_invalid_count >= 5 and self.CS.CP.carFingerprint not in HONDA_BOSCH:
+ # wait 1.0s before throwing the alert to avoid it popping when you turn off the car
+ if self.cam_can_invalid_count >= 100 and self.CS.CP.carFingerprint not in HONDA_BOSCH:
events.append(create_event('invalidGiraffeHonda', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT]))
else:
self.cam_can_invalid_count = 0
+
if self.CS.steer_error:
events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT]))
elif self.CS.steer_warning:
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index 17492eaf08ad96..5cf3ae24176086 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -113,11 +113,19 @@ class CAR:
57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 339: 7, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 837: 5, 856: 7, 871: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1618: 5, 1668: 5
}],
CAR.PILOT_2019: [{
- 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5
+ 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5
+ },
+ # 2019 Pilot EX-L
+ {
+ 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5
}],
# Ridgeline w/ Added Comma Pedal Support (512L & 513L)
CAR.RIDGELINE: [{
57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 471: 3, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1613: 5, 1616: 5, 1618: 5, 1668: 5, 2015: 3
+ },
+ # 2019 Ridgeline
+ {
+ 57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422:8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 424: 5, 1613: 5, 1616: 5, 1618: 5, 1623: 5, 1668: 5
}]
}
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index 96174ef09643e8..c525c0185e939b 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -163,6 +163,7 @@ def get_params(candidate, fingerprint):
ret.longPidDeadzoneV = [0.]
ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint)
+ ret.openpilotLongitudinalControl = False
ret.steerLimitAlert = False
ret.stoppingControl = False
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index ad5191195b92b1..8de0252410b16b 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -11,11 +11,11 @@ def get_hud_alerts(visual_alert, audible_alert):
return 0
class CAR:
- SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019"
ELANTRA = "HYUNDAI ELANTRA LIMITED ULTIMATE 2017"
GENESIS = "HYUNDAI GENESIS 2018"
- KIA_SORENTO = "KIA SORENTO GT LINE 2018" # Top Trim Kia Sorento for Australian Market, AWD Diesel 8sp Auto
+ KIA_SORENTO = "KIA SORENTO GT LINE 2018"
KIA_STINGER = "KIA STINGER GT2 2018"
+ SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019"
class Buttons:
NONE = 0
@@ -24,9 +24,6 @@ class Buttons:
CANCEL = 4
FINGERPRINTS = {
- CAR.SANTA_FE: [{
- 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8
- }],
CAR.ELANTRA: [{
66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
}],
@@ -39,9 +36,12 @@ class Buttons:
CAR.KIA_STINGER: [{
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8
}],
+ CAR.SANTA_FE: [{
+ 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8
+ }],
}
-CAMERA_MSGS = [832, 1156, 1191, 1342] # msgs sent by the camera
+CAMERA_MSGS = [832, 1156, 1191, 1342]
CHECKSUM = {
"crc8": [CAR.SANTA_FE],
@@ -50,9 +50,9 @@ class Buttons:
}
DBC = {
- CAR.SANTA_FE: dbc_dict('hyundai_santa_fe_2019_ccan', None),
- CAR.ELANTRA: dbc_dict('hyundai_santa_fe_2019_ccan', None),
- CAR.GENESIS: dbc_dict('hyundai_santa_fe_2019_ccan', None),
- CAR.KIA_SORENTO: dbc_dict('hyundai_santa_fe_2019_ccan', None),
- CAR.KIA_STINGER: dbc_dict('hyundai_santa_fe_2019_ccan', None),
+ CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None),
+ CAR.GENESIS: dbc_dict('hyundai_kia_generic', None),
+ CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None),
+ CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None),
+ CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None),
}
diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py
index 5edbcbbd113f78..b7d60a4257bfee 100755
--- a/selfdrive/car/mock/interface.py
+++ b/selfdrive/car/mock/interface.py
@@ -47,6 +47,7 @@ def get_params(candidate, fingerprint):
ret.carFingerprint = candidate
ret.safetyModel = car.CarParams.SafetyModels.noOutput
+ ret.openpilotLongitudinalControl = False
# FIXME: hardcoding honda civic 2016 touring params so they can be used to
# scale unknown params for other cars
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index b0c6bf5209f63b..987d66c4923ab9 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -4,7 +4,7 @@
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
+ create_fcw_command, create_gas_command
from selfdrive.car.toyota.values import ECU, STATIC_MSGS
from selfdrive.can.packer import CANPacker
@@ -127,7 +127,16 @@ def update(self, sendcan, enabled, CS, frame, actuators,
# *** compute control surfaces ***
# gas and brake
- apply_accel = actuators.gas - actuators.brake
+
+ apply_gas = clip(actuators.gas, 0., 1.)
+
+ if CS.CP.enableGasInterceptor:
+ # send only send brake values if interceptor is detected. otherwise, send the regular value
+ # +0.06 offset to reduce ABS pump usage when OP is engaged
+ apply_accel = 0.06 - actuators.brake
+ else:
+ apply_accel = actuators.gas - actuators.brake
+
apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled)
apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX)
@@ -221,6 +230,11 @@ def update(self, sendcan, enabled, CS, frame, actuators,
else:
can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False))
+ if CS.CP.enableGasInterceptor:
+ # 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
+ can_sends.append(create_gas_command(self.packer, apply_gas))
+
if frame % 10 == 0 and ECU.CAM in self.fake_ecus and not forwarding_camera:
for addr in TARGET_IDS:
can_sends.append(create_video_target(frame/10, addr))
diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py
index 71d33b0ab7c2a2..bb3b3f05217795 100644
--- a/selfdrive/car/toyota/carstate.py
+++ b/selfdrive/car/toyota/carstate.py
@@ -62,6 +62,11 @@ def get_can_parser(CP):
if CP.carFingerprint == CAR.PRIUS:
signals += [("STATE", "AUTOPARK_STATUS", 0)]
+
+ # add gas interceptor reading if we are using it
+ if CP.enableGasInterceptor:
+ signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0))
+ checks.append(("GAS_SENSOR", 50))
return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
@@ -112,7 +117,10 @@ def update(self, cp, cp_cam):
self.seatbelt = not cp.vl["SEATS_DOORS"]['SEATBELT_DRIVER_UNLATCHED']
self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED']
- self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL']
+ if self.CP.enableGasInterceptor:
+ self.pedal_gas = cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS']
+ else:
+ self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL']
self.car_gas = self.pedal_gas
self.esp_disabled = cp.vl["ESP_CONTROL"]['TC_DISABLED']
diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py
index 57e90339cc6ae7..abc1d8225ea502 100755
--- a/selfdrive/car/toyota/interface.py
+++ b/selfdrive/car/toyota/interface.py
@@ -61,7 +61,7 @@ def get_params(candidate, fingerprint):
ret.safetyModel = car.CarParams.SafetyModels.toyota
# pedal
- ret.enableCruise = True
+ ret.enableCruise = not ret.enableGasInterceptor
# FIXME: hardcoding honda civic 2016 touring params so they can be used to
# scale unknown params for other cars
@@ -77,6 +77,7 @@ def get_params(candidate, fingerprint):
ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay
if candidate == CAR.PRIUS:
+ stop_and_go = True
ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.70
ret.steerRatio = 15.00 # unknown end-to-end spec
@@ -88,6 +89,7 @@ def get_params(candidate, fingerprint):
ret.steerActuatorDelay = 0.25
elif candidate in [CAR.RAV4, CAR.RAV4H]:
+ stop_and_go = True if (candidate in CAR.RAV4H) else False
ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.65
ret.steerRatio = 16.30 # 14.5 is spec end-to-end
@@ -97,6 +99,7 @@ def get_params(candidate, fingerprint):
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
elif candidate == CAR.COROLLA:
+ stop_and_go = False
ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.70
ret.steerRatio = 17.8
@@ -106,6 +109,7 @@ def get_params(candidate, fingerprint):
ret.steerKf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594
elif candidate == CAR.LEXUS_RXH:
+ stop_and_go = True
ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file
ret.wheelbase = 2.79
ret.steerRatio = 16. # 14.8 is spec end-to-end
@@ -115,6 +119,7 @@ def get_params(candidate, fingerprint):
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
elif candidate in [CAR.CHR, CAR.CHRH]:
+ stop_and_go = True
ret.safetyParam = 100
ret.wheelbase = 2.63906
ret.steerRatio = 13.6
@@ -124,6 +129,7 @@ def get_params(candidate, fingerprint):
ret.steerKf = 0.00006
elif candidate in [CAR.CAMRY, CAR.CAMRYH]:
+ stop_and_go = True
ret.safetyParam = 100
ret.wheelbase = 2.82448
ret.steerRatio = 13.7
@@ -133,6 +139,7 @@ def get_params(candidate, fingerprint):
ret.steerKf = 0.00006
elif candidate in [CAR.HIGHLANDER, CAR.HIGHLANDERH]:
+ stop_and_go = True
ret.safetyParam = 100
ret.wheelbase = 2.78
ret.steerRatio = 16.0
@@ -147,14 +154,13 @@ def get_params(candidate, fingerprint):
ret.longPidDeadzoneBP = [0., 9.]
ret.longPidDeadzoneV = [0., .15]
+ #detect the Pedal address
+ ret.enableGasInterceptor = 0x201 in fingerprint
+
+
# min speed to enable ACC. if car can do stop and go, then set enabling speed
# to a negative value, so it won't matter.
- # hybrid models can't do stop and go even though the stock ACC can't
- if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.CHR,
- CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.HIGHLANDERH, CAR.HIGHLANDER]:
- ret.minEnableSpeed = -1.
- elif candidate in [CAR.RAV4, CAR.COROLLA]: # TODO: hack ICE to do stop and go
- ret.minEnableSpeed = 19. * CV.MPH_TO_MS
+ ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else 19. * CV.MPH_TO_MS
centerToRear = ret.wheelbase - ret.centerToFront
# TODO: get actual value, for now starting with reasonable value for
@@ -178,26 +184,33 @@ def get_params(candidate, fingerprint):
# steer, gas, brake limitations VS speed
ret.steerMaxBP = [16. * CV.KPH_TO_MS, 45. * CV.KPH_TO_MS] # breakpoints at 1 and 40 kph
ret.steerMaxV = [1., 1.] # 2/3rd torque allowed above 45 kph
- ret.gasMaxBP = [0.]
- ret.gasMaxV = [0.5]
ret.brakeMaxBP = [5., 20.]
ret.brakeMaxV = [1., 0.8]
ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM)
ret.enableDsu = not check_ecu_msgs(fingerprint, ECU.DSU)
ret.enableApgs = False #not check_ecu_msgs(fingerprint, ECU.APGS)
+ ret.openpilotLongitudinalControl = ret.enableCamera and ret.enableDsu
cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera)
cloudlog.warn("ECU DSU Simulated: %r", ret.enableDsu)
cloudlog.warn("ECU APGS Simulated: %r", ret.enableApgs)
+ cloudlog.warn("ECU Gas Interceptor: %r", ret.enableGasInterceptor)
ret.steerLimitAlert = False
- ret.stoppingControl = False
- ret.startAccel = 0.0
-
ret.longitudinalKpBP = [0., 5., 35.]
- ret.longitudinalKpV = [3.6, 2.4, 1.5]
ret.longitudinalKiBP = [0., 35.]
- ret.longitudinalKiV = [0.54, 0.36]
+ ret.stoppingControl = False
+
+ if ret.enableGasInterceptor:
+ ret.gasMaxBP = [0., 9., 35]
+ ret.gasMaxV = [0.2, 0.5, 0.7]
+ ret.longitudinalKpV = [1.2, 0.8, 0.5]
+ ret.longitudinalKiV = [0.18, 0.12]
+ else:
+ ret.gasMaxBP = [0.]
+ ret.gasMaxV = [0.5]
+ ret.longitudinalKpV = [3.6, 2.4, 1.5]
+ ret.longitudinalKiV = [0.54, 0.36]
return ret
@@ -233,7 +246,11 @@ def update(self, c):
# gas pedal
ret.gas = self.CS.car_gas
- ret.gasPressed = self.CS.pedal_gas > 0
+ if self.CP.enableGasInterceptor:
+ # use interceptor values to disengage on pedal press
+ ret.gasPressed = self.CS.pedal_gas > 15
+ else:
+ ret.gasPressed = self.CS.pedal_gas > 0
# brake pedal
ret.brake = self.CS.user_brake
@@ -252,9 +269,11 @@ def update(self, c):
ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS
ret.cruiseState.available = bool(self.CS.main_on)
ret.cruiseState.speedOffset = 0.
- if self.CP.carFingerprint in [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER]:
+
+ if self.CP.carFingerprint in [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER] or self.CP.enableGasInterceptor:
# ignore standstill in hybrid vehicles, since pcm allows to restart without
# receiving any special command
+ # also if interceptor is detected
ret.cruiseState.standstill = False
else:
ret.cruiseState.standstill = self.CS.pcm_acc_status == 7
diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py
index 6587f32f66c06a..2c05bdf22d1873 100644
--- a/selfdrive/car/toyota/toyotacan.py
+++ b/selfdrive/car/toyota/toyotacan.py
@@ -75,6 +75,18 @@ def create_accel_command(packer, accel, pcm_cancel, standstill_req):
}
return packer.make_can_msg("ACC_CONTROL", 0, values)
+def create_gas_command(packer, gas_amount):
+ """Creates a CAN message for the Pedal DBC GAS_COMMAND."""
+ 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)
+
def create_fcw_command(packer, fcw):
values = {
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index d4929e7bc2c98b..e03c4a3a8c459d 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -48,8 +48,8 @@ class ECU:
(0x2E7, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, '\xa8\x9c\x31\x9c\x00\x00\x00\x02'),
(0x33E, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, '\x0f\xff\x26\x40\x00\x1f\x00'),
(0x344, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'),
- (0x365, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'),
- (0x365, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'),
+ (0x365, ECU.DSU, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'),
+ (0x365, ECU.DSU, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'),
(0x366, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x4d\x82\x40\x02\x00'),
(0x366, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'),
(0x470, ECU.DSU, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, '\x00\x00\x02\x7a'),
@@ -79,7 +79,7 @@ def check_ecu_msgs(fingerprint, ecu):
FINGERPRINTS = {
CAR.RAV4: [{
- 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, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 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: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 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, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 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: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 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, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
CAR.RAV4H: [{
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 296: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 550: 8, 552: 4, 560: 7, 562: 4, 581: 5, 608: 8, 610: 5, 643: 7, 705: 8, 713: 8, 725: 2, 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: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 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, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
@@ -89,28 +89,33 @@ def check_ecu_msgs(fingerprint, ecu):
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 800: 8, 830: 7, 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: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1207: 8, 1227: 8, 1235: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 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, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8
}],
CAR.PRIUS: [{
- 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
},
# Prius Prime
{
- 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 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, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 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, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
},
# Taiwanese Prius Prime
{
- 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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 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, 974: 8, 975: 5, 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, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 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, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 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, 974: 8, 975: 5, 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, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 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, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
+ #Corolla w/ added Pedal Support (512L and 513L)
CAR.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
+ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 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
},
- # Corolla LE 2017
+ # Corolla LE 2017 w/ added Pedal Support (512L and 513L)
{
- 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, 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, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8
+ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 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, 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, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8
}],
CAR.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
+ },
+ # RX450HL
+ {
+ 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, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 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, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 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, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
CAR.CHR: [{
- 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8
+ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8
}],
CAR.CHRH: [{
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: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 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: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h
index 617c8189cba23d..422faa02b65add 100644
--- a/selfdrive/common/version.h
+++ b/selfdrive/common/version.h
@@ -1 +1 @@
-#define COMMA_VERSION "0.5.6-release"
+#define COMMA_VERSION "0.5.7-release"
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index f4fa0d8140f491..0a96c233516499 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -2,13 +2,11 @@
import gc
import zmq
import json
-
from cereal import car, log
from common.numpy_fast import clip
from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper
from common.profiler import Profiler
from common.params import Params
-
import selfdrive.messaging as messaging
from selfdrive.config import Conversions as CV
from selfdrive.services import service_list
@@ -25,17 +23,12 @@
from selfdrive.controls.lib.alertmanager import AlertManager
from selfdrive.controls.lib.vehicle_model import VehicleModel
from selfdrive.controls.lib.driver_monitor import DriverStatus
+from selfdrive.locationd.calibration_helpers import Calibration, Filter
ThermalStatus = log.ThermalData.ThermalStatus
State = log.Live100Data.ControlState
-class Calibration:
- UNCALIBRATED = 0
- CALIBRATED = 1
- INVALID = 2
-
-
def isActive(state):
"""Check if the actuators are enabled"""
return state in [State.enabled, State.softDisabling]
@@ -126,14 +119,14 @@ def data_sample(CI, CC, thermal, calibration, health, driver_monitor, gps_locati
return CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter
-def calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence):
+def calc_plan(CS, CP, VM, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence):
"""Calculate a longitudinal plan using MPC"""
# Slow down when based on driver monitoring or geofence
force_decel = driver_status.awareness < 0. or (geofence is not None and not geofence.in_geofence)
# Update planner
- plan_packet = PL.update(CS, LaC, LoC, v_cruise_kph, force_decel)
+ plan_packet = PL.update(CS, CP, VM, LaC, LoC, v_cruise_kph, force_decel)
plan = plan_packet.plan
plan_ts = plan_packet.logMonoTime
events += list(plan.events)
@@ -293,7 +286,10 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last,
extra_text_1, extra_text_2 = "", ""
if e == "calibrationIncomplete":
extra_text_1 = str(cal_perc) + "%"
- extra_text_2 = "35 kph" if is_metric else "15 mph"
+ if is_metric:
+ extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_KPH))) + " kph"
+ else:
+ extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_MPH))) + " mph"
AM.add(str(e) + "Permanent", enabled, extra_text_1=extra_text_1, extra_text_2=extra_text_2)
AM.process_alerts(sec_since_boot())
@@ -463,6 +459,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
# Write CarParams for radard and boardd safety mode
params.put("CarParams", CP.to_bytes())
+ params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0")
state = State.disabled
soft_disable_timer = 0
@@ -498,7 +495,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
prof.checkpoint("Sample")
# Define longitudinal plan (MPC)
- plan, plan_ts = calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence)
+ plan, plan_ts = calc_plan(CS, CP, VM, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence)
prof.checkpoint("Plan")
if not passive:
@@ -514,7 +511,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
# Publish data
CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol,
- live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive)
+ live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive)
prof.checkpoint("Sent")
rk.keep_time() # Run at 100Hz
diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
index 658ee1b85bbcfb..36b6f8b7e0b8d3 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
+++ b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py
@@ -1,11 +1,19 @@
import os
+import platform
import subprocess
from cffi import FFI
mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__)))
-subprocess.check_call(["make", "-j4"], cwd=mpc_dir)
+if platform.machine() == "x86_64":
+ try:
+ FFI().dlopen(os.path.join(mpc_dir, "libmpc1.so"))
+ except OSError:
+ # libmpc1.so is likely built for aarch64. cleaning...
+ subprocess.check_call(["make", "clean"], cwd=mpc_dir)
+
+subprocess.check_call(["make", "-j4"], cwd=mpc_dir)
def _get_libmpc(mpc_id):
libmpc_fn = os.path.join(mpc_dir, "libmpc%d.so" % mpc_id)
@@ -36,9 +44,7 @@ def _get_libmpc(mpc_id):
return (ffi, ffi.dlopen(libmpc_fn))
-
mpcs = [_get_libmpc(1), _get_libmpc(2)]
-
def get_libmpc(mpc_id):
return mpcs[mpc_id - 1]
diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py
index 89ca649504b277..b986740113904d 100755
--- a/selfdrive/controls/lib/planner.py
+++ b/selfdrive/controls/lib/planner.py
@@ -6,6 +6,7 @@
from copy import copy
from cereal import log
from collections import defaultdict
+from common.params import Params
from common.realtime import sec_since_boot
from common.numpy_fast import interp
import selfdrive.messaging as messaging
@@ -19,6 +20,10 @@
from selfdrive.controls.lib.longcontrol import LongCtrlState, MIN_CAN_SPEED
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU
+# Max lateral acceleration, used to caclulate how much to slow down in turns
+A_Y_MAX = 2.0 # m/s^2
+NO_CURVATURE_SPEED = 200. * CV.MPH_TO_MS
+
_DT = 0.01 # 100Hz
_DT_MPC = 0.2 # 5Hz
MAX_SPEED_ERROR = 2.0
@@ -249,8 +254,10 @@ def __init__(self, CP, fcw_enabled):
context = zmq.Context()
self.CP = CP
self.poller = zmq.Poller()
+
self.live20 = messaging.sub_sock(context, service_list['live20'].port, conflate=True, poller=self.poller)
self.model = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=self.poller)
+ self.live_map_data = messaging.sub_sock(context, service_list['liveMapData'].port, conflate=True, poller=self.poller)
if os.environ.get('GPS_PLANNER_ACTIVE', False):
self.gps_planner_plan = messaging.sub_sock(context, service_list['gpsPlannerPlan'].port, conflate=True, poller=self.poller, addr=GPS_PLANNER_ADDR)
@@ -293,8 +300,12 @@ def __init__(self, CP, fcw_enabled):
self.last_gps_planner_plan = None
self.gps_planner_active = False
+ self.last_live_map_data = None
self.perception_state = log.Live20Data.new_message()
+ self.params = Params()
+ self.v_speedlimit = NO_CURVATURE_SPEED
+
def choose_solution(self, v_cruise_setpoint, enabled):
if enabled:
solutions = {'cruise': self.v_cruise}
@@ -327,7 +338,7 @@ def choose_solution(self, v_cruise_setpoint, enabled):
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, LaC, LoC, v_cruise_kph, force_slow_decel):
+ def update(self, CS, CP, VM, LaC, LoC, v_cruise_kph, force_slow_decel):
cur_time = sec_since_boot()
v_cruise_setpoint = v_cruise_kph * CV.KPH_TO_MS
@@ -342,6 +353,8 @@ def update(self, CS, LaC, LoC, v_cruise_kph, force_slow_decel):
l20 = messaging.recv_one(socket)
elif socket is self.gps_planner_plan:
gps_planner_plan = messaging.recv_one(socket)
+ elif socket is self.live_map_data:
+ self.last_live_map_data = messaging.recv_one(socket).liveMapData
if gps_planner_plan is not None:
self.last_gps_planner_plan = gps_planner_plan
@@ -381,9 +394,23 @@ def update(self, CS, LaC, LoC, v_cruise_kph, force_slow_decel):
enabled = (LoC.long_control_state == LongCtrlState.pid) or (LoC.long_control_state == LongCtrlState.stopping)
following = self.lead_1.status and self.lead_1.dRel < 45.0 and self.lead_1.vLeadK > CS.vEgo and self.lead_1.aLeadK > 0.0
+
+ if self.last_live_map_data:
+ self.v_speedlimit = NO_CURVATURE_SPEED
+
+ # Speed limit
+ if self.last_live_map_data.speedLimitValid:
+ speed_limit = self.last_live_map_data.speedLimit
+ set_speed_limit_active = self.params.get("LimitSetSpeed") == "1" and self.params.get("SpeedLimitOffset") is not None
+
+ if set_speed_limit_active:
+ offset = float(self.params.get("SpeedLimitOffset"))
+ self.v_speedlimit = speed_limit + offset
+
+ v_cruise_setpoint = min([v_cruise_setpoint, self.v_speedlimit])
+
# Calculate speed for normal cruise control
if enabled:
-
accel_limits = map(float, calc_cruise_accel_limits(CS.vEgo, following))
# TODO: make a separate lookup for jerk tuning
jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])]
@@ -449,9 +476,9 @@ def update(self, CS, LaC, LoC, v_cruise_kph, force_slow_decel):
if self.model_dead:
events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
if self.radar_dead or 'commIssue' in self.radar_errors:
- events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
+ events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
if 'fault' in self.radar_errors:
- events.append(create_event('radarFault', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
+ events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_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]))
diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py
new file mode 100644
index 00000000000000..f2909007594924
--- /dev/null
+++ b/selfdrive/locationd/calibration_helpers.py
@@ -0,0 +1,11 @@
+import math
+
+class Filter:
+ MIN_SPEED = 7 # m/s (~15.5mph)
+ MAX_YAW_RATE = math.radians(3) # per second
+
+class Calibration:
+ UNCALIBRATED = 0
+ CALIBRATED = 1
+ INVALID = 2
+
diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py
index 695e698cee970c..6c395efed20dc8 100755
--- a/selfdrive/locationd/calibrationd.py
+++ b/selfdrive/locationd/calibrationd.py
@@ -3,22 +3,20 @@
import zmq
import cv2
import copy
-import math
import json
import numpy as np
import selfdrive.messaging as messaging
+from selfdrive.locationd.calibration_helpers import Calibration, Filter
from selfdrive.swaglog import cloudlog
from selfdrive.services import service_list
from common.params import Params
from common.ffi_wrapper import ffi_wrap
import common.transformations.orientation as orient
-from common.transformations.model import model_height, get_camera_frame_from_model_frame
+from common.transformations.model import model_height, get_camera_frame_from_model_frame, get_camera_frame_from_bigmodel_frame
from common.transformations.camera import view_frame_from_device_frame, get_view_frame_from_road_frame, \
eon_intrinsics, get_calib_from_vp, normalize, denormalize, H, W
-MIN_SPEED_FILTER = 7 # m/s (~15.5mph)
-MAX_YAW_RATE_FILTER = math.radians(3) # per second
FRAMES_NEEDED = 120 # allow to update VP every so many frames
VP_CYCLES_NEEDED = 2
CALIBRATION_CYCLES_NEEDED = FRAMES_NEEDED * VP_CYCLES_NEEDED
@@ -42,12 +40,6 @@
ffi, lib = ffi_wrap('get_vp', c_code, c_header)
-class Calibration:
- UNCALIBRATED = 0
- CALIBRATED = 1
- INVALID = 2
-
-
def increment_grid_c(grid, lines, n):
lib.increment_grid(ffi.cast("double *", grid.ctypes.data),
ffi.cast("double *", lines.ctypes.data),
@@ -131,8 +123,8 @@ def rescale_grid(self):
def update(self, uvs, yaw_rate, speed):
if len(uvs) < 10 or \
- abs(yaw_rate) > MAX_YAW_RATE_FILTER or \
- speed < MIN_SPEED_FILTER:
+ abs(yaw_rate) > Filter.MAX_YAW_RATE or \
+ speed < Filter.MIN_SPEED:
return
rot_speeds = np.array([0.,0.,-yaw_rate])
uvs[:,1,:] = denormalize(correct_pts(normalize(uvs[:,1,:]), rot_speeds, self.dt))
@@ -216,13 +208,15 @@ def send_data(self, livecalibration):
calib = get_calib_from_vp(self.vp)
extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height)
ke = eon_intrinsics.dot(extrinsic_matrix)
- warp_matrix = get_camera_frame_from_model_frame(ke, model_height)
+ warp_matrix = get_camera_frame_from_model_frame(ke)
+ warp_matrix_big = get_camera_frame_from_bigmodel_frame(ke)
cal_send = messaging.new_message()
cal_send.init('liveCalibration')
cal_send.liveCalibration.calStatus = self.cal_status
cal_send.liveCalibration.calPerc = min(self.frame_counter * 100 / CALIBRATION_CYCLES_NEEDED, 100)
cal_send.liveCalibration.warpMatrix2 = map(float, warp_matrix.flatten())
+ cal_send.liveCalibration.warpMatrixBig = map(float, warp_matrix_big.flatten())
cal_send.liveCalibration.extrinsicMatrix = map(float, extrinsic_matrix.flatten())
livecalibration.send(cal_send.to_bytes())
diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd
index 881b9e84fea041..ce1e7ecd2f6fa5 100755
Binary files a/selfdrive/loggerd/loggerd and b/selfdrive/loggerd/loggerd differ
diff --git a/selfdrive/manager.py b/selfdrive/manager.py
index 6b64a4af77f224..704728872d4df4 100755
--- a/selfdrive/manager.py
+++ b/selfdrive/manager.py
@@ -41,9 +41,9 @@ def unblock_stdout():
os._exit(os.wait()[1])
if __name__ == "__main__":
- if os.path.isfile("/init.qcom.rc") \
- and (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 6):
-
+ neos_update_required = os.path.isfile("/init.qcom.rc") \
+ and (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 8)
+ if neos_update_required:
# update continue.sh before updating NEOS
if os.path.isfile(os.path.join(BASEDIR, "scripts", "continue.sh")):
from shutil import copyfile
@@ -54,6 +54,9 @@ def unblock_stdout():
subprocess.check_call(["git", "clean", "-xdf"], cwd=BASEDIR)
os.system(os.path.join(BASEDIR, "installer", "updater", "updater"))
raise Exception("NEOS outdated")
+ elif os.path.isdir("/data/neoupdate"):
+ from shutil import rmtree
+ rmtree("/data/neoupdate")
unblock_stdout()
@@ -88,6 +91,7 @@ def unblock_stdout():
"controlsd": "selfdrive.controls.controlsd",
"radard": "selfdrive.controls.radard",
"ubloxd": "selfdrive.locationd.ubloxd",
+ "mapd": "selfdrive.mapd.mapd",
"loggerd": ("selfdrive/loggerd", ["./loggerd"]),
"logmessaged": "selfdrive.logmessaged",
"tombstoned": "selfdrive.tombstoned",
@@ -135,7 +139,8 @@ def get_running():
'visiond',
'proclogd',
'ubloxd',
- 'orbd'
+ 'orbd',
+ 'mapd',
]
def register_managed_process(name, desc, car_started=False):
@@ -474,6 +479,12 @@ def main():
params.put("IsDriverMonitoringEnabled", "1")
if params.get("IsGeofenceEnabled") is None:
params.put("IsGeofenceEnabled", "-1")
+ if params.get("SpeedLimitOffset") is None:
+ params.put("SpeedLimitOffset", "0")
+ if params.get("LongitudinalControl") is None:
+ params.put("LongitudinalControl", "0")
+ if params.get("LimitSetSpeed") is None:
+ params.put("LimitSetSpeed", "0")
# is this chffrplus?
if os.getenv("PASSIVE") is not None:
diff --git a/selfdrive/mapd/__init__.py b/selfdrive/mapd/__init__.py
new file mode 100644
index 00000000000000..e69de29bb2d1d6
diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py
new file mode 100755
index 00000000000000..e1a9595e8c0c84
--- /dev/null
+++ b/selfdrive/mapd/mapd.py
@@ -0,0 +1,276 @@
+#!/usr/bin/env python
+
+# Add phonelibs openblas to LD_LIBRARY_PATH if import fails
+try:
+ from scipy import spatial
+except ImportError as e:
+ import os
+ import sys
+ from common.basedir import BASEDIR
+
+ openblas_path = os.path.join(BASEDIR, "phonelibs/openblas/")
+ os.environ['LD_LIBRARY_PATH'] += ':' + openblas_path
+
+ args = [sys.executable]
+ args.extend(sys.argv)
+ os.execv(sys.executable, args)
+
+import os
+import sys
+import time
+import zmq
+import threading
+import numpy as np
+import overpy
+from collections import defaultdict
+
+from common.params import Params
+from common.transformations.coordinates import geodetic2ecef
+from selfdrive.services import service_list
+import selfdrive.messaging as messaging
+from mapd_helpers import LOOKAHEAD_TIME, MAPS_LOOKAHEAD_DISTANCE, Way, circle_through_points
+import selfdrive.crash as crash
+from selfdrive.version import version, dirty
+
+
+OVERPASS_API_URL = "https://overpass.kumi.systems/api/interpreter"
+OVERPASS_HEADERS = {
+ 'User-Agent': 'NEOS (comma.ai)'
+}
+
+last_gps = None
+query_lock = threading.Lock()
+last_query_result = None
+last_query_pos = None
+
+
+def setup_thread_excepthook():
+ """
+ Workaround for `sys.excepthook` thread bug from:
+ http://bugs.python.org/issue1230540
+ Call once from the main thread before creating any threads.
+ Source: https://stackoverflow.com/a/31622038
+ """
+ init_original = threading.Thread.__init__
+
+ def init(self, *args, **kwargs):
+ init_original(self, *args, **kwargs)
+ run_original = self.run
+
+ def run_with_except_hook(*args2, **kwargs2):
+ try:
+ run_original(*args2, **kwargs2)
+ except Exception:
+ sys.excepthook(*sys.exc_info())
+
+ self.run = run_with_except_hook
+
+ threading.Thread.__init__ = init
+
+
+def build_way_query(lat, lon, radius=50):
+ """Builds a query to find all highways within a given radius around a point"""
+ pos = " (around:%f,%f,%f)" % (radius, lat, lon)
+ q = """(
+ way
+ """ + pos + """
+ [highway][highway!~"^(footway|path|bridleway|steps|cycleway|construction|bus_guideway|escape)$"];
+ >;);out;
+ """
+ return q
+
+
+def query_thread():
+ global last_query_result, last_query_pos
+ api = overpy.Overpass(url=OVERPASS_API_URL, headers=OVERPASS_HEADERS, timeout=10.)
+
+ while True:
+ time.sleep(1)
+ if last_gps is not None:
+ fix_ok = last_gps.flags & 1
+ if not fix_ok:
+ continue
+
+ if last_query_pos is not None:
+ cur_ecef = geodetic2ecef((last_gps.latitude, last_gps.longitude, last_gps.altitude))
+ prev_ecef = geodetic2ecef((last_query_pos.latitude, last_query_pos.longitude, last_query_pos.altitude))
+ dist = np.linalg.norm(cur_ecef - prev_ecef)
+ if dist < 1000:
+ continue
+
+ q = build_way_query(last_gps.latitude, last_gps.longitude, radius=2000)
+ try:
+ new_result = api.query(q)
+
+ # Build kd-tree
+ nodes = []
+ real_nodes = []
+ node_to_way = defaultdict(list)
+
+ for n in new_result.nodes:
+ nodes.append((float(n.lat), float(n.lon), 0))
+ real_nodes.append(n)
+
+ for way in new_result.ways:
+ for n in way.nodes:
+ node_to_way[n.id].append(way)
+
+ nodes = np.asarray(nodes)
+ nodes = geodetic2ecef(nodes)
+ tree = spatial.cKDTree(nodes)
+
+ query_lock.acquire()
+ last_query_result = new_result, tree, real_nodes, node_to_way
+ last_query_pos = last_gps
+ query_lock.release()
+
+ except Exception as e:
+ print e
+ query_lock.acquire()
+ last_query_result = None
+ query_lock.release()
+
+
+def mapsd_thread():
+ global last_gps
+
+ context = zmq.Context()
+ gps_sock = messaging.sub_sock(context, service_list['gpsLocation'].port, conflate=True)
+ gps_external_sock = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True)
+ map_data_sock = messaging.pub_sock(context, service_list['liveMapData'].port)
+
+ cur_way = None
+ curvature_valid = False
+ curvature = None
+ upcoming_curvature = 0.
+ dist_to_turn = 0.
+ road_points = None
+
+ xx = np.arange(0, MAPS_LOOKAHEAD_DISTANCE, 10)
+
+ while True:
+ gps = messaging.recv_one(gps_sock)
+ gps_ext = messaging.recv_one_or_none(gps_external_sock)
+
+ if gps_ext is not None:
+ gps = gps_ext.gpsLocationExternal
+ else:
+ gps = gps.gpsLocation
+
+ last_gps = gps
+
+ fix_ok = gps.flags & 1
+ if not fix_ok or last_query_result is None:
+ cur_way = None
+ curvature = None
+ curvature_valid = False
+ upcoming_curvature = 0.
+ dist_to_turn = 0.
+ road_points = None
+ else:
+ lat = gps.latitude
+ lon = gps.longitude
+ heading = gps.bearing
+ speed = gps.speed
+
+ query_lock.acquire()
+ cur_way = Way.closest(last_query_result, lat, lon, heading, cur_way)
+ if cur_way is not None:
+ pnts, curvature_valid = cur_way.get_lookahead(last_query_result, lat, lon, heading, MAPS_LOOKAHEAD_DISTANCE)
+
+ xs = pnts[:, 0]
+ ys = pnts[:, 1]
+ road_points = map(float, xs), map(float, ys)
+
+ if speed < 10:
+ curvature_valid = False
+
+ # The curvature is valid when at least MAPS_LOOKAHEAD_DISTANCE of road is found
+ if curvature_valid and pnts.shape[0] > 3:
+ # Compute the curvature for each point
+ with np.errstate(divide='ignore'):
+ circles = [circle_through_points(*p) for p in zip(pnts, pnts[1:], pnts[2:])]
+ circles = np.asarray(circles)
+ radii = np.nan_to_num(circles[:, 2])
+ radii[radii < 10] = np.inf
+ curvature = 1. / radii
+
+ # Index of closest point
+ closest = np.argmin(np.linalg.norm(pnts, axis=1))
+ dist_to_closest = pnts[closest, 0] # We can use x distance here since it should be close
+
+ # Compute distance along path
+ dists = list()
+ dists.append(0)
+ for p, p_prev in zip(pnts, pnts[1:, :]):
+ dists.append(dists[-1] + np.linalg.norm(p - p_prev))
+ dists = np.asarray(dists)
+ dists = dists - dists[closest] + dist_to_closest
+
+ # TODO: Determine left or right turn
+ curvature = np.nan_to_num(curvature)
+ curvature_interp = np.interp(xx, dists[1:-1], curvature)
+ curvature_lookahead = curvature_interp[:int(speed * LOOKAHEAD_TIME / 10)]
+
+ # Outlier rejection
+ new_curvature = np.percentile(curvature_lookahead, 90)
+
+ k = 0.9
+ upcoming_curvature = k * upcoming_curvature + (1 - k) * new_curvature
+ in_turn_indices = curvature_interp > 0.8 * new_curvature
+ if np.any(in_turn_indices):
+ dist_to_turn = np.min(xx[in_turn_indices])
+ else:
+ dist_to_turn = 999
+ query_lock.release()
+
+ dat = messaging.new_message()
+ dat.init('liveMapData')
+
+ if last_gps is not None:
+ dat.liveMapData.lastGps = last_gps
+
+ if cur_way is not None:
+ dat.liveMapData.wayId = cur_way.id
+
+ # Seed limit
+ max_speed = cur_way.max_speed
+ if max_speed is not None:
+ dat.liveMapData.speedLimitValid = True
+ dat.liveMapData.speedLimit = max_speed
+
+ # Curvature
+ dat.liveMapData.curvatureValid = curvature_valid
+ dat.liveMapData.curvature = float(upcoming_curvature)
+ dat.liveMapData.distToTurn = float(dist_to_turn)
+ if road_points is not None:
+ dat.liveMapData.roadX, dat.liveMapData.roadY = road_points
+ if curvature is not None:
+ dat.liveMapData.roadCurvatureX = map(float, xx)
+ dat.liveMapData.roadCurvature = map(float, curvature_interp)
+
+ map_data_sock.send(dat.to_bytes())
+
+
+def main(gctx=None):
+ params = Params()
+ dongle_id = params.get("DongleId")
+ crash.bind_user(id=dongle_id)
+ crash.bind_extra(version=version, dirty=dirty, is_eon=True)
+ crash.install()
+
+ setup_thread_excepthook()
+ main_thread = threading.Thread(target=mapsd_thread)
+ main_thread.daemon = True
+ main_thread.start()
+
+ q_thread = threading.Thread(target=query_thread)
+ q_thread.daemon = True
+ q_thread.start()
+
+ while True:
+ time.sleep(0.1)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/selfdrive/mapd/mapd_helpers.py b/selfdrive/mapd/mapd_helpers.py
new file mode 100644
index 00000000000000..6d84fbd7d504ca
--- /dev/null
+++ b/selfdrive/mapd/mapd_helpers.py
@@ -0,0 +1,229 @@
+import math
+import numpy as np
+from datetime import datetime
+
+from selfdrive.config import Conversions as CV
+from common.transformations.coordinates import LocalCoord, geodetic2ecef
+
+LOOKAHEAD_TIME = 10.
+MAPS_LOOKAHEAD_DISTANCE = 50 * LOOKAHEAD_TIME
+
+
+def circle_through_points(p1, p2, p3):
+ """Fits a circle through three points
+ Formulas from: http://www.ambrsoft.com/trigocalc/circle3d.htm"""
+ x1, y1, _ = p1
+ x2, y2, _ = p2
+ x3, y3, _ = p3
+
+ A = x1 * (y2 - y3) - y1 * (x2 - x3) + x2 * y3 - x3 * y2
+ B = (x1**2 + y1**2) * (y3 - y2) + (x2**2 + y2**2) * (y1 - y3) + (x3**2 + y3**2) * (y2 - y1)
+ C = (x1**2 + y1**2) * (x2 - x3) + (x2**2 + y2**2) * (x3 - x1) + (x3**2 + y3**2) * (x1 - x2)
+ D = (x1**2 + y1**2) * (x3 * y2 - x2 * y3) + (x2**2 + y2**2) * (x1 * y3 - x3 * y1) + (x3**2 + y3**2) * (x2 * y1 - x1 * y2)
+
+ return (-B / (2 * A), - C / (2 * A), np.sqrt((B**2 + C**2 - 4 * A * D) / (4 * A**2)))
+
+
+def parse_speed_unit(max_speed):
+ """Converts a maxspeed string to m/s based on the unit present in the input.
+ OpenStreetMap defaults to kph if no unit is present. """
+
+ conversion = CV.KPH_TO_MS
+ if 'mph' in max_speed:
+ max_speed = max_speed.replace(' mph', '')
+ conversion = CV.MPH_TO_MS
+
+ return float(max_speed) * conversion
+
+
+class Way:
+ def __init__(self, way):
+ self.id = way.id
+ self.way = way
+
+ points = list()
+
+ for node in self.way.get_nodes(resolve_missing=False):
+ points.append((float(node.lat), float(node.lon), 0.))
+
+ self.points = np.asarray(points)
+
+ @classmethod
+ def closest(cls, query_results, lat, lon, heading, prev_way=None):
+ results, tree, real_nodes, node_to_way = query_results
+
+ cur_pos = geodetic2ecef((lat, lon, 0))
+ nodes = tree.query_ball_point(cur_pos, 500)
+
+ # If no nodes within 500m, choose closest one
+ if not nodes:
+ nodes = [tree.query(cur_pos)[1]]
+
+ ways = []
+ for n in nodes:
+ real_node = real_nodes[n]
+ ways += node_to_way[real_node.id]
+ ways = set(ways)
+
+ closest_way = None
+ best_score = None
+ for way in ways:
+ way = Way(way)
+ points = way.points_in_car_frame(lat, lon, heading)
+
+ on_way = way.on_way(lat, lon, heading, points)
+ if not on_way:
+ continue
+
+ # Create mask of points in front and behind
+ x = points[:, 0]
+ y = points[:, 1]
+ angles = np.arctan2(y, x)
+ front = np.logical_and((-np.pi / 2) < angles,
+ angles < (np.pi / 2))
+ behind = np.logical_not(front)
+
+ dists = np.linalg.norm(points, axis=1)
+
+ # Get closest point behind the car
+ dists_behind = np.copy(dists)
+ dists_behind[front] = np.NaN
+ closest_behind = points[np.nanargmin(dists_behind)]
+
+ # Get closest point in front of the car
+ dists_front = np.copy(dists)
+ dists_front[behind] = np.NaN
+ closest_front = points[np.nanargmin(dists_front)]
+
+ # fit line: y = a*x + b
+ x1, y1, _ = closest_behind
+ x2, y2, _ = closest_front
+ a = (y2 - y1) / max((x2 - x1), 1e-5)
+ b = y1 - a * x1
+
+ # With a factor of 60 a 20m offset causes the same error as a 20 degree heading error
+ # (A 20 degree heading offset results in an a of about 1/3)
+ score = abs(a) * 60. + abs(b)
+
+ # Prefer same type of road
+ if prev_way is not None:
+ if way.way.tags.get('highway', '') == prev_way.way.tags.get('highway', ''):
+ score *= 0.5
+
+ if closest_way is None or score < best_score:
+ closest_way = way
+ best_score = score
+
+ return closest_way
+
+ def __str__(self):
+ return "%s %s" % (self.id, self.way.tags)
+
+ @property
+ def max_speed(self):
+ """Extracts the (conditional) speed limit from a way"""
+ if not self.way:
+ return None
+
+ tags = self.way.tags
+ max_speed = None
+
+ if 'maxspeed' in tags:
+ max_speed = parse_speed_unit(tags['maxspeed'])
+
+ if 'maxspeed:conditional' in tags:
+ max_speed_cond, cond = tags['maxspeed:conditional'].split(' @ ')
+ cond = cond[1:-1]
+
+ start, end = cond.split('-')
+ now = datetime.now() # TODO: Get time and timezone from gps fix so this will work correctly on replays
+ start = datetime.strptime(start, "%H:%M").replace(year=now.year, month=now.month, day=now.day)
+ end = datetime.strptime(end, "%H:%M").replace(year=now.year, month=now.month, day=now.day)
+
+ if start <= now <= end:
+ max_speed = parse_speed_unit(max_speed_cond)
+
+ return max_speed
+
+ def on_way(self, lat, lon, heading, points=None):
+ if points is None:
+ points = self.points_in_car_frame(lat, lon, heading)
+ x = points[:, 0]
+ return np.min(x) < 0. and np.max(x) > 0.
+
+ def closest_point(self, lat, lon, heading, points=None):
+ if points is None:
+ points = self.points_in_car_frame(lat, lon, heading)
+ i = np.argmin(np.linalg.norm(points, axis=1))
+ return points[i]
+
+ def distance_to_closest_node(self, lat, lon, heading, points=None):
+ if points is None:
+ points = self.points_in_car_frame(lat, lon, heading)
+ return np.min(np.linalg.norm(points, axis=1))
+
+ def points_in_car_frame(self, lat, lon, heading):
+ lc = LocalCoord.from_geodetic([lat, lon, 0.])
+
+ # Build rotation matrix
+ heading = math.radians(-heading + 90)
+ c, s = np.cos(heading), np.sin(heading)
+ rot = np.array([[c, s, 0.], [-s, c, 0.], [0., 0., 1.]])
+
+ # Convert to local coordinates
+ points_carframe = lc.geodetic2ned(self.points).T
+
+ # Rotate with heading of car
+ points_carframe = np.dot(rot, points_carframe[(1, 0, 2), :]).T
+
+ return points_carframe
+
+ def next_way(self, query_results, lat, lon, heading, backwards=False):
+ results, tree, real_nodes, node_to_way = query_results
+
+ if backwards:
+ node = self.way.nodes[0]
+ else:
+ node = self.way.nodes[-1]
+
+ ways = node_to_way[node.id]
+
+ way = None
+ try:
+ # Simple heuristic to find next way
+ ways = [w for w in ways if w.id != self.id and w.tags['highway'] == self.way.tags['highway']]
+ if len(ways) == 1:
+ way = Way(ways[0])
+ except KeyError:
+ pass
+
+ return way
+
+ def get_lookahead(self, query_results, lat, lon, heading, lookahead):
+ pnts = None
+ way = self
+ valid = False
+
+ for i in range(5):
+ # Get new points and append to list
+ new_pnts = way.points_in_car_frame(lat, lon, heading)
+
+ if pnts is None:
+ pnts = new_pnts
+ else:
+ pnts = np.vstack([pnts, new_pnts])
+
+ # Check current lookahead distance
+ max_dist = np.linalg.norm(pnts[-1, :])
+ if max_dist > lookahead:
+ valid = True
+
+ if max_dist > 2 * lookahead:
+ break
+
+ # Find next way
+ way = way.next_way(query_results, lat, lon, heading)
+ if not way:
+ break
+
+ return pnts, valid
diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd
index 9c48a5f6ac02f3..d38869ce22075e 100755
Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ
diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord
index 84137a9b8c2af2..84194bb06c9be6 100755
Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ
diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py
index 4238273d97ec7d..78c4aa1490043f 100755
--- a/selfdrive/thermald.py
+++ b/selfdrive/thermald.py
@@ -84,6 +84,7 @@ def set_eon_fan(val):
# max fan speed only allowed if battery is hot
_BAT_TEMP_THERSHOLD = 45.
+
def handle_fan(max_cpu_temp, bat_temp, fan_speed):
new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_cpu_temp)
new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_cpu_temp)
@@ -103,6 +104,23 @@ def handle_fan(max_cpu_temp, bat_temp, fan_speed):
return fan_speed
+
+def check_car_battery_voltage(should_start, health, charging_disabled):
+
+ # charging disallowed if:
+ # - there are health packets from panda, and;
+ # - 12V battery voltage is too low, and;
+ # - onroad isn't started
+ if charging_disabled and (health is None or health.health.voltage > 11500):
+ charging_disabled = False
+ os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled')
+ elif not charging_disabled and health is not None and health.health.voltage < 11000 and not should_start:
+ charging_disabled = True
+ os.system('echo "0" > /sys/class/power_supply/battery/charging_enabled')
+
+ return charging_disabled
+
+
class LocationStarter(object):
def __init__(self):
self.last_good_loc = 0
@@ -133,6 +151,7 @@ def update(self, started_ts, location):
cloudlog.event("location_start", location=location.to_dict() if location else None)
return location.speed*3.6 > 10
+
def thermald_thread():
setup_eon_fan()
@@ -156,6 +175,10 @@ def thermald_thread():
health_sock.RCVTIMEO = 1500
current_filter = FirstOrderFilter(0., CURRENT_TAU, 1.)
+ # Make sure charging is enabled
+ charging_disabled = False
+ os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled')
+
params = Params()
while 1:
@@ -178,11 +201,10 @@ def thermald_thread():
msg.thermal.batteryCurrent = int(f.read())
with open("/sys/class/power_supply/battery/voltage_now") as f:
msg.thermal.batteryVoltage = int(f.read())
- with open("/sys/class/power_supply/usb/online") as f:
+ with open("/sys/class/power_supply/usb/present") as f:
msg.thermal.usbOnline = bool(int(f.read()))
current_filter.update(msg.thermal.batteryCurrent / 1e6)
- msg.thermal.chargerDisabled = current_filter.x > 1.0 # if current is ? 1A out, then charger might be off
# TODO: add car battery voltage check
max_cpu_temp = max(msg.thermal.cpu0, msg.thermal.cpu1,
@@ -268,6 +290,10 @@ def thermald_thread():
started_seen and (sec_since_boot() - off_ts) > 60:
os.system('LD_LIBRARY_PATH="" svc power shutdown')
+ charging_disabled = check_car_battery_voltage(should_start, health, charging_disabled)
+
+ msg.thermal.chargingDisabled = charging_disabled
+ msg.thermal.chargingError = current_filter.x > 1.0 # if current is > 1A out, then charger might be off
msg.thermal.started = started_ts is not None
msg.thermal.startedTs = int(1e9*(started_ts or 0))
diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c
index ce57dd46517e75..dddf15f7e7167e 100644
--- a/selfdrive/ui/ui.c
+++ b/selfdrive/ui/ui.c
@@ -87,6 +87,8 @@ const int alert_sizes[] = {
[ALERTSIZE_FULL] = vwp_h,
};
+const int SET_SPEED_NA = 255;
+
// TODO: this is also hardcoded in common/transformations/camera.py
const mat3 intrinsic_matrix = (mat3){{
910., 0., 582.,
@@ -224,9 +226,13 @@ typedef struct UIState {
int awake_timeout;
int volume_timeout;
+ int speed_lim_off_timeout;
+ int is_metric_timeout;
int status;
bool is_metric;
+ float speed_lim_off;
+ bool is_ego_over_limit;
bool passive;
char alert_type[64];
char alert_sound[64];
@@ -282,6 +288,26 @@ static void set_do_exit(int sig) {
do_exit = 1;
}
+static void read_speed_lim_off(UIState *s) {
+ char *speed_lim_off = NULL;
+ read_db_value(NULL, "SpeedLimitOffset", &speed_lim_off, NULL);
+ s->speed_lim_off = 0.;
+ if (speed_lim_off) {
+ s->speed_lim_off = strtod(speed_lim_off, NULL);
+ free(speed_lim_off);
+ }
+ s->speed_lim_off_timeout = 2 * 60; // 2Hz
+}
+
+static void read_is_metric(UIState *s) {
+ char *is_metric;
+ const int result = read_db_value(NULL, "IsMetric", &is_metric, NULL);
+ if (result == 0) {
+ s->is_metric = is_metric[0] == '1';
+ free(is_metric);
+ }
+ s->is_metric_timeout = 2 * 60; // 2Hz
+}
static const char frame_vertex_shader[] =
"attribute vec4 aPosition;\n"
@@ -530,12 +556,9 @@ static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs,
0.0, 0.0, 0.0, 1.0,
}};
- char *value;
- const int result = read_db_value(NULL, "IsMetric", &value, NULL);
- if (result == 0) {
- s->is_metric = value[0] == '1';
- free(value);
- }
+ read_speed_lim_off(s);
+ read_is_metric(s);
+ s->is_metric_timeout = 60; // offset so values isn't read together with limit offset
}
static void ui_draw_transformed_box(UIState *s, uint32_t color) {
@@ -915,40 +938,80 @@ 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;
- const int viz_maxspeed_x = (ui_viz_rx + (bdr_s*2));
- const int viz_maxspeed_y = (box_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);
+ float maxspeed = s->scene.v_cruise;
+ int maxspeed_calc = maxspeed * 0.6225 + 0.5;
+ float speedlimit = s->scene.speedlimit;
+ int speedlim_calc = speedlimit * 2.2369363 + 0.5;
+ int speed_lim_off = s->speed_lim_off * 2.2369363 + 0.5;
+ if (s->is_metric) {
+ maxspeed_calc = maxspeed + 0.5;
+ speedlim_calc = speedlimit * 3.6 + 0.5;
+ speed_lim_off = s->speed_lim_off * 3.6 + 0.5;
+ }
+
+ bool is_cruise_set = (maxspeed != 0 && maxspeed != SET_SPEED_NA);
+ bool is_speedlim_valid = s->scene.speedlimit_valid;
+ bool is_set_over_limit = is_speedlim_valid && s->scene.engaged &&
+ is_cruise_set && maxspeed_calc > (speedlim_calc + speed_lim_off);
+ int viz_maxspeed_w = 184;
+ int viz_maxspeed_h = 202;
+ int viz_maxspeed_x = (ui_viz_rx + (bdr_s*2));
+ int viz_maxspeed_y = (box_y + (bdr_s*1.5));
+ int viz_maxspeed_xo = 180;
+ viz_maxspeed_w += viz_maxspeed_xo;
+ viz_maxspeed_x += viz_maxspeed_w - (viz_maxspeed_xo * 2);
+
+ // Draw Background
+ nvgBeginPath(s->vg);
+ nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 30);
+ if (is_set_over_limit) {
+ nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 180));
+ } else {
+ nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 100));
+ }
+ nvgFill(s->vg);
+
+ // Draw Border
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);
+ if (is_set_over_limit) {
+ nvgStrokeColor(s->vg, nvgRGBA(218, 111, 37, 255));
+ } else if (is_speedlim_valid && !s->is_ego_over_limit) {
+ nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ } else if (is_speedlim_valid && s->is_ego_over_limit) {
+ nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 20));
+ } else {
+ nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 100));
+ }
+ nvgStrokeWidth(s->vg, 10);
nvgStroke(s->vg);
+ // Draw "MAX" Text
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);
+ if (is_cruise_set) {
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200));
+ } else {
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100));
+ }
+ nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(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));
+ // Draw Speed Text
+ nvgFontFace(s->vg, "sans-bold");
+ nvgFontSize(s->vg, 48*2.5);
if (is_cruise_set) {
- if (s->is_metric) {
- snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(maxspeed + 0.5));
- } else {
- 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);
+ snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", maxspeed_calc);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 242, maxspeed_str, NULL);
} else {
+ nvgFontFace(s->vg, "sans-semibold");
nvgFontSize(s->vg, 42*2.5);
- nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, 242, "N/A", NULL);
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100));
+ nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 242, "N/A", NULL);
}
}
@@ -957,69 +1020,84 @@ static void ui_draw_vision_speedlimit(UIState *s) {
int ui_viz_rx = scene->ui_viz_rx;
int ui_viz_rw = scene->ui_viz_rw;
- if (!s->scene.speedlimit_valid){
- return;
- }
-
+ char speedlim_str[32];
float speedlimit = s->scene.speedlimit;
+ int speedlim_calc = speedlimit * 2.2369363 + 0.5;
+ if (s->is_metric) {
+ speedlim_calc = speedlimit * 3.6 + 0.5;
+ }
- const int viz_maxspeed_w = 180;
- const int viz_maxspeed_h = 202;
-
- 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_maxspeed_x = viz_event_x + (viz_event_w-viz_maxspeed_w);
- const int viz_maxspeed_y = (footer_y + ((footer_h - viz_maxspeed_h) / 2)) - 20;
+ bool is_speedlim_valid = s->scene.speedlimit_valid;
+ float hysteresis_offset = 0.5;
+ if (s->is_ego_over_limit) {
+ hysteresis_offset = 0.0;
+ }
+ s->is_ego_over_limit = is_speedlim_valid && s->scene.v_ego > (speedlimit + s->speed_lim_off + hysteresis_offset);
+
+ int viz_speedlim_w = 180;
+ int viz_speedlim_h = 202;
+ int viz_speedlim_x = (ui_viz_rx + (bdr_s*2));
+ int viz_speedlim_y = (box_y + (bdr_s*1.5));
+ if (!is_speedlim_valid) {
+ viz_speedlim_w -= 5;
+ viz_speedlim_h -= 10;
+ viz_speedlim_x += 9;
+ viz_speedlim_y += 5;
+ }
+ int viz_speedlim_bdr = is_speedlim_valid ? 30 : 15;
- char maxspeed_str[32];
+ // Draw Background
+ nvgBeginPath(s->vg);
+ nvgRoundedRect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, viz_speedlim_bdr);
+ if (is_speedlim_valid && s->is_ego_over_limit) {
+ nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 180));
+ } else if (is_speedlim_valid) {
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ } else {
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100));
+ }
+ nvgFill(s->vg);
- if (s->is_metric) {
+ // Draw Border
+ if (is_speedlim_valid) {
+ nvgStrokeWidth(s->vg, 10);
+ nvgStroke(s->vg);
nvgBeginPath(s->vg);
- nvgCircle(s->vg, viz_maxspeed_x + viz_maxspeed_w / 2, viz_maxspeed_y + viz_maxspeed_h / 2, 127);
- nvgFillColor(s->vg, nvgRGBA(195, 0, 0, 255));
- nvgFill(s->vg);
+ nvgRoundedRect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, 20);
+ if (s->is_ego_over_limit) {
+ nvgStrokeColor(s->vg, nvgRGBA(218, 111, 37, 255));
+ } else if (is_speedlim_valid) {
+ nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ }
+ }
- nvgBeginPath(s->vg);
- nvgCircle(s->vg, viz_maxspeed_x + viz_maxspeed_w / 2, viz_maxspeed_y + viz_maxspeed_h / 2, 100);
+ // Draw "Speed Limit" Text
+ nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
+ nvgFontFace(s->vg, "sans-semibold");
+ nvgFontSize(s->vg, 50);
+ nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255));
+ if (is_speedlim_valid && s->is_ego_over_limit) {
nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
- nvgFill(s->vg);
+ }
+ nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2 + (is_speedlim_valid ? 6 : 0), viz_speedlim_y + (is_speedlim_valid ? 50 : 45), "SPEED", NULL);
+ nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2 + (is_speedlim_valid ? 6 : 0), viz_speedlim_y + (is_speedlim_valid ? 90 : 85), "LIMIT", NULL);
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- nvgFontFace(s->vg, "sans-bold");
- nvgFontSize(s->vg, 130);
+ // Draw Speed Text
+ nvgFontFace(s->vg, "sans-bold");
+ nvgFontSize(s->vg, 48*2.5);
+ if (s->is_ego_over_limit) {
+ nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
+ } else {
nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255));
-
- snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(speedlimit * 3.6 + 0.5));
- nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 135, maxspeed_str, NULL);
+ }
+ if (is_speedlim_valid) {
+ snprintf(speedlim_str, sizeof(speedlim_str), "%d", speedlim_calc);
+ nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), speedlim_str, NULL);
} else {
- const int border = 10;
- nvgBeginPath(s->vg);
- nvgRoundedRect(s->vg, viz_maxspeed_x - border, viz_maxspeed_y - border, viz_maxspeed_w + 2 * border, viz_maxspeed_h + 2 * border, 30);
- nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255));
- nvgFill(s->vg);
-
- nvgBeginPath(s->vg);
- nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 20);
- nvgStrokeColor(s->vg, nvgRGBA(0, 0, 0, 255));
- nvgStrokeWidth(s->vg, 8);
- nvgStroke(s->vg);
-
-
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
nvgFontFace(s->vg, "sans-semibold");
- nvgFontSize(s->vg, 50);
- nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255));
- nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 50, "SPEED", NULL);
- nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 90, "LIMIT", NULL);
-
- nvgFontFace(s->vg, "sans-bold");
- nvgFontSize(s->vg, 120);
- nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255));
-
- snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", (int)(speedlimit * 2.2369363 + 0.5));
- nvgText(s->vg, viz_maxspeed_x+viz_maxspeed_w/2, viz_maxspeed_y + 170, maxspeed_str, NULL);
- }
+ nvgFontSize(s->vg, 42*2.5);
+ nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), "N/A", NULL);
+ }
}
static void ui_draw_vision_speed(UIState *s) {
@@ -1137,6 +1215,7 @@ static void ui_draw_vision_header(UIState *s) {
nvgFill(s->vg);
ui_draw_vision_maxspeed(s);
+ ui_draw_vision_speedlimit(s);
ui_draw_vision_speed(s);
ui_draw_vision_wheel(s);
}
@@ -1151,8 +1230,6 @@ static void ui_draw_vision_footer(UIState *s) {
// Driver Monitoring
ui_draw_vision_face(s);
-
- ui_draw_vision_speedlimit(s);
}
static void ui_draw_vision_alert(UIState *s, int va_size, int va_color,
@@ -1710,7 +1787,7 @@ static void ui_update(UIState *s) {
struct cereal_LiveMapData datad;
cereal_read_LiveMapData(&datad, eventd.liveMapData);
s->scene.speedlimit = datad.speedLimit;
- s->scene.speedlimit_valid = datad.valid;
+ s->scene.speedlimit_valid = datad.speedLimitValid;
}
capn_free(&ctx);
zmq_msg_close(&msg);
@@ -1975,6 +2052,18 @@ int main() {
set_volume(s, volume);
}
+ if (s->speed_lim_off_timeout > 0) {
+ s->speed_lim_off_timeout--;
+ } else {
+ read_speed_lim_off(s);
+ }
+
+ if (s->is_metric_timeout > 0) {
+ s->is_metric_timeout--;
+ } else {
+ read_is_metric(s);
+ }
+
pthread_mutex_unlock(&s->lock);
// the bg thread needs to be scheduled, so the main thread needs time without the lock
diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond
index 40259afc55c789..caf5de38ae68a7 100755
Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ