diff --git a/README.md b/README.md index 3037274e7ca5aa..c8762963c09cc2 100644 --- a/README.md +++ b/README.md @@ -10,7 +10,7 @@ The openpilot codebase has been written to be concise and enable rapid prototypi Community ------ -openpilot is supported by [comma.ai](https://comma.ai/). +openpilot is developed by [comma.ai](https://comma.ai/) and users like you. We have a [Twitter you should follow](https://twitter.com/comma_ai). @@ -41,57 +41,62 @@ Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` dur Supported Cars ------ -| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | -| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- | -| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph* | 25mph | -| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph* | 25mph | -| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph* | 12mph | -| GM | Volt 2017 | Driver Confidence II | Yes | Yes | 0mph | 0mph | -| GM | Volt 2018 | Driver Confidence II | Yes | Yes | 0mph | 0mph | -| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | -| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | CR-V 2015 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | CR-V 2016 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph | -| Lexus | RX Hybrid 2017 | All | Yes | Yes | 0mph | 0mph | -| Lexus | RX Hybrid 2018 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Corolla 2017 | All | Yes | Yes | 20mph | 0mph | -| Toyota | Corolla 2018 | All | Yes | Yes | 20mph | 0mph | -| Toyota | Prius 2016 | TSS-P | Yes | Yes | 0mph | 0mph | -| Toyota | Prius 2017 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Prius 2018 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Prius Prime 2017 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Prius Prime 2018 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Rav4 2016 | TSS-P | Yes | Yes | 20mph | 0mph | -| Toyota | Rav4 2017 | All | Yes | Yes | 20mph | 0mph | -| Toyota | Rav4 2018 | All | Yes | Yes | 20mph | 0mph | -| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes | 0mph | 0mph | -| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes | 0mph | 0mph | - - -*[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)*** +| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | +| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- | +| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | +| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | +| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | +| GM3| Volt 2017 | Driver Confidence II | Yes | Yes | 0mph | 7mph | +| GM3| Volt 2018 | Driver Confidence II | Yes | Yes | 0mph | 7mph | +| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | +| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | CR-V 2015 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | CR-V 2016 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Lexus | RX Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | +| Lexus | RX Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | +| Toyota | C-HR 20184 | All | Yes | Stock | 0mph | 0mph | +| Toyota | Corolla 2017 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Corolla 2018 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius Prime 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius Prime 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 2017 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 2018 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | + + +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://www.zoneos.com/volt.htm) +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. Community Maintained Cars ------ -| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | -| ------- | -----------------------| -------------------- | ------- | ------------ | ----------- | ------------ | -| Tesla | Model S 2012 | All | Yes | Not yet | Not applicable | 0mph | -| Tesla | Model S 2013 | All | Yes | Not yet | Not applicable | 0mph | +| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | +| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- | +| Honda | Fit 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | -[[Tesla Pull Request]](https://github.com/commaai/openpilot/pull/246) +[[Honda Fit Pull Request]](https://github.com/commaai/openpilot/pull/266). -*Community Maintained Cars are not confirmed by comma.ai to meet our safety model. Be extra cautious using them. +Community Maintained Cars are not confirmed by comma.ai to meet our safety model. Be extra cautious using them. In Progress Cars ------ @@ -107,7 +112,7 @@ How can I add support for my car? If your car has adaptive cruise control and lane keep assist, you are in luck. Using a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle/) and [cabana](https://community.comma.ai/cabana/), you can understand how to make your car drive by wire. -We've written a [porting guide](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) for Toyota that might help you after you have the basics figured out. +We've written guides for [Brand](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84) and [Model](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) ports. These guides might help you after you have the basics figured out. - BMW, Audi, Volvo, and Mercedes all use [FlexRay](https://en.wikipedia.org/wiki/FlexRay) and are unlikely to be supported any time soon. - We put time into a Ford port, but the steering has a 10 second cutout limitation that makes it unusable. @@ -174,7 +179,7 @@ Contributing ------ We welcome both pull requests and issues on -[github](http://github.com/commaai/openpilot). Bug fixes and new car support encouraged. +[github](http://github.com/commaai/openpilot). Bug fixes and new car ports encouraged. Want to get paid to work on openpilot? [comma.ai is hiring](https://comma.ai/jobs/) diff --git a/RELEASES.md b/RELEASES.md index a515873642a5ca..0a81ac30ed248f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,10 @@ +Version 0.5.1 (2018-08-01) +======================== + * Fix radar error on Civic sedan 2018 + * Improve thermal management logic + * Alpha Toyota C-HR and Camry support! + * Auto-switch Driver Monitoring to 3 min counter when inaccurate + Version 0.5 (2018-07-11) ======================== * Driver Monitoring (beta) option in settings! diff --git a/SAFETY.md b/SAFETY.md index 0c8ae7e51eeb9a..a2f77a55093901 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -6,7 +6,10 @@ Like other ACC and LKA systems, openpilot requires the driver to be alert and to pay attention at all times. We repeat, **driver alertness is necessary, but not sufficient, for openpilot to be used safely**. -Even with an attentive driver, we must make further efforts for the system to be +In order to enforce driver alertness, openpilot includes a driver monitoring feature +that alerts the driver when distracted. + +However, even with an attentive driver, we must make further efforts for the system to be safe. We have designed openpilot with two other safety considerations. 1. The driver must always be capable to immediately retake manual control of the vehicle, @@ -20,7 +23,7 @@ Following are details of the car specific safety implementations: Honda/Acura ------ - - While the system is engaged, gas, brake and steer limits are subject to the same limits used by + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by the stock system. - Without an interceptor, the gas is controlled by the Powertrain Control Module (PCM). @@ -28,16 +31,16 @@ Honda/Acura interceptor, the gas is clipped to 60%. - The brake is controlled by the 0x1FA CAN message. This message allows full - braking, although the board and the software clip it to 1/4th of the max. - This is around .3g of braking. + braking, although the panda firmware and openpilot clip it to 1/4th of the max. + This is approximately 0.3g of braking. - Steering is controlled by the 0xE4 CAN message. The Electronic Power Steering (EPS) controller in the car limits the torque to a very small amount, so regardless of the message, the controller cannot jerk the wheel. - Brake and gas pedal pressed signals are contained in the 0x17C CAN message. A rising edge of - either signal triggers a disengagement, which is enforced by the board and in software. The - green led on the board signifies if the board is allowing control messages. + either signals triggers a disengagement, which is enforced by the panda firmware and by openpilot. The + white led on the panda signifies if the panda is allowing control messages. - Honda CAN uses both a counter and a checksum to ensure integrity and prevent replay of the same message. @@ -45,29 +48,62 @@ Honda/Acura Toyota/Lexus ------ - - While the system is engaged, gas, brake and steer limits are subject to the same limits used by + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by the stock system. - - With the stock Driving Support Unit (DSU) enabled, the acceleration is controlled - by the stock system and is subject to the stock adaptive cruise control limits. Without the - stock DSU connected, the acceleration command is controlled by the 0x343 CAN message and its - value is limited by the board and the software to between .3g of deceleration and .15g of - acceleration. The acceleration command is ignored by the Engine Control Module (ECM) while the - cruise control system is disengaged. - - - Steering torque is controlled through the 0x2E4 CAN message and it's limited by the board and in - software to a value of -1500 and 1500. In addition, the vehicle EPS unit will not respond to - commands outside these limits. A steering torque rate limit is enforced by the board and in - software so that the commanded steering torque must rise from 0 to max value no faster than - 1.5s. Commanded steering torque is limited by the board and in software to be no more than 350 + - With the stock Driving Support Unit (DSU) connected (or in DSU-less models like Camry and C-HR), + the acceleration is controlled by the stock system and is subject to the stock adaptive cruise + control limits. Without the stock DSU connected, the acceleration command is controlled by the + 0x343 CAN message and its value is limited between .3g of deceleration and .15g of acceleration + by the panda firmware and by openpilot. The acceleration command is ignored by the Engine Control + Module (ECM) while the cruise control system is disengaged. + + - Steering torque is controlled through the 0x2E4 CAN message and it's limited by the panda firmware and by + openpilot to a value between -1500 and 1500. In addition, the vehicle EPS unit will not respond to + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 1.5s. Commanded steering torque is limited by the panda firmware and by openpilot to be no more than 350 units above the actual EPS generated motor torque to ensure limited differences between commanded and actual torques. - Brake and gas pedal pressed signals are contained in the 0x224 and 0x1D2 CAN messages, - respectively. A rising edge of either signal triggers a disengagement, which is enforced by the - board and in software. Additionally, the cruise control system disengages on the rising edge of + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of the brake pedal pressed signal. - The cruise control system state is contained in the 0x1D2 message. No control messages are - allowed if the cruise control system is not active. This is enforced by the software and the - board. The green led on the board signifies if the board is allowing control messages. + allowed if the cruise control system is not active. This is enforced by openpilot and the + panda firmware. The white led on the panda signifies if the panda is allowing control messages. + +GM/Chevrolet +------ + + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by + the stock system. + + - The gas and regen are controlled by the 0x2CB message and it's limited by the panda firmware and by + openpilot to a value between 1404 and 3072. the minimum value correspond to a mild decel due to regen, + while 3072 correspond to approximately 0.18g of acceleration from stop. + + - The friction brakes are controlled by the 0x315 message and its value is limited by the panda firmware + and openpilot to 350. This is approximately 0.3g of braking. + + - Steering torque is controlled through the 0x180 CAN message and it's limited by the panda firmware and by + openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will not fault when + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 0.75s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's + torque exceeds 12 units in the opposite dicrection to ensure limited applied torque against the + driver's will. + + - Brake pedal and gas pedal potentiometer signals are contained in the 0xF1 and 0x1A1 CAN messages, + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of + the brake pedal pressed signal. The regen paddle pressed signal is in the 0xBD message. When the + regen paddle is pressed, a disengagement is enforced by both the firmware and by openpilot. + + - GM CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +**Extra note"**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or + not fully meeting the above requirements. diff --git a/apk/ai.comma.plus.frame.apk b/apk/ai.comma.plus.frame.apk index eaf67b1c70390f..5b9dc2666ba331 100644 Binary files a/apk/ai.comma.plus.frame.apk and b/apk/ai.comma.plus.frame.apk differ diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk index db4a96af8b18d4..489bdd7e73d6c9 100644 Binary files a/apk/ai.comma.plus.offroad.apk and b/apk/ai.comma.plus.offroad.apk differ diff --git a/cereal/car.capnp b/cereal/car.capnp index ffc79e6476dc69..65ec3ee957d444 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -63,6 +63,11 @@ struct CarEvent @0x9b1657f34caf3ad3 { promptDriverDistracted @38; driverDistracted @39; geofence @40; + driverMonitorOn @41; + driverMonitorOff @42; + preDriverUnresponsive @43; + promptDriverUnresponsive @44; + driverUnresponsive @45; } } @@ -302,6 +307,8 @@ struct CarParams { hondaBosch @5; ford @6; cadillac @7; + hyundai @8; + chrysler @9; } # things about the car in the manual diff --git a/cereal/log.capnp b/cereal/log.capnp index 474c0d2410bd47..fbb00a2a194407 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -21,6 +21,8 @@ struct Map(Key, Value) { struct InitData { kernelArgs @0 :List(Text); + kernelVersion @15 :Text; + gctx @1 :Text; dongleId @2 :Text; @@ -32,6 +34,7 @@ struct InitData { androidBuildInfo @5 :AndroidBuildInfo; androidSensors @6 :List(AndroidSensor); + androidProperties @16 :Map(Text, Text); chffrAndroidExtra @7 :ChffrAndroidExtra; iosBuildInfo @14 :IosBuildInfo; @@ -399,6 +402,7 @@ struct Live100Data { angleOffset @27 :Float32; gpsPlannerActive @40 :Bool; engageable @41 :Bool; # can OP be engaged? + driverMonitoringOn @43 :Bool; enum ControlState { disabled @0; @@ -1533,6 +1537,13 @@ struct OrbKeyFrame { struct DriverMonitoring { frameId @0 :UInt32; descriptor @1 :List(Float32); + std @2 :Float32; +} + +struct Boot { + wallTimeNanos @0 :UInt64; + lastKmsg @1 :Data; + lastPmsg @2 :Data; } struct Event { @@ -1599,5 +1610,6 @@ struct Event { uiLayoutState @57 :UiLayoutState; orbFeaturesSummary @58 :OrbFeaturesSummary; driverMonitoring @59 :DriverMonitoring; + boot @60 :Boot; } } diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 1cd7a8e9d560db..568fb9bf2b3f4e 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -12,12 +12,14 @@ e1sq = 6.73949674228 * 0.001 -def geodetic2ecef(geodetic): +def geodetic2ecef(geodetic, radians=False): geodetic = np.array(geodetic) input_shape = geodetic.shape geodetic = np.atleast_2d(geodetic) - lat = (np.pi/180)*geodetic[:,0] - lon = (np.pi/180)*geodetic[:,1] + + ratio = 1.0 if radians else (np.pi / 180.0) + lat = ratio*geodetic[:,0] + lon = ratio*geodetic[:,1] alt = geodetic[:,2] xi = np.sqrt(1 - esq * np.sin(lat)**2) @@ -28,41 +30,41 @@ def geodetic2ecef(geodetic): return ecef.reshape(input_shape) -def ecef2geodetic(ecef): +def ecef2geodetic(ecef, radians=False): """ Convert ECEF coordinates to geodetic using ferrari's method """ - def ferrari(x, y, z): - # ferrari's method - r = np.sqrt(x * x + y * y) - Esq = a * a - b * b - F = 54 * b * b * z * z - G = r * r + (1 - esq) * z * z - esq * Esq - C = (esq * esq * F * r * r) / (pow(G, 3)) - S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) - P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) - Q = np.sqrt(1 + 2 * esq * esq * P) - r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) - U = np.sqrt(pow((r - esq * r_0), 2) + z * z) - V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) - Z_0 = b * b * z / (a * V) - h = U * (1 - b * b / (a * V)) - lat = (180/np.pi)*np.arctan((z + e1sq * Z_0) / r) - lon = (180/np.pi)*np.arctan2(y, x) - return lat, lon, h - - geodetic = [] - ecef = np.array(ecef) + # Save shape and export column + ecef = np.atleast_1d(ecef) input_shape = ecef.shape ecef = np.atleast_2d(ecef) - for p in ecef: - geodetic.append(ferrari(*p)) - geodetic = np.array(geodetic) + x, y, z = ecef[:, 0], ecef[:, 1], ecef[:, 2] + + ratio = 1.0 if radians else (180.0 / np.pi) + + # Conver from ECEF to geodetic using Ferrari's methods + # https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution + r = np.sqrt(x * x + y * y) + Esq = a * a - b * b + F = 54 * b * b * z * z + G = r * r + (1 - esq) * z * z - esq * Esq + C = (esq * esq * F * r * r) / (pow(G, 3)) + S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) + P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) + Q = np.sqrt(1 + 2 * esq * esq * P) + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) + U = np.sqrt(pow((r - esq * r_0), 2) + z * z) + V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) + Z_0 = b * b * z / (a * V) + h = U * (1 - b * b / (a * V)) + lat = ratio*np.arctan((z + e1sq * Z_0) / r) + lon = ratio*np.arctan2(y, x) + + # stack the new columns and return to the original shape + geodetic = np.column_stack((lat, lon, h)) return geodetic.reshape(input_shape) - - class LocalCoord(object): """ Allows conversions to local frames. In this case NED. diff --git a/opendbc/acura_ilx_2016_nidec.dbc b/opendbc/acura_ilx_2016_nidec.dbc index 4d8738a0aa14a2..e73fcc422177be 100644 --- a/opendbc/acura_ilx_2016_nidec.dbc +++ b/opendbc/acura_ilx_2016_nidec.dbc @@ -182,4 +182,4 @@ BO_TX_BU_ 769 : NEO,ADAS; CM_ SG_ 1024 RADAR_STATE "need to find out more diagnostic values"; -VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted"; +VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted" 105 "wrong_config"; diff --git a/opendbc/chrysler_pacifica_2017_hybrid.dbc b/opendbc/chrysler_pacifica_2017_hybrid.dbc index 7cd13b745f5ce0..a56ccfaaa38ee1 100644 --- a/opendbc/chrysler_pacifica_2017_hybrid.dbc +++ b/opendbc/chrysler_pacifica_2017_hybrid.dbc @@ -37,12 +37,15 @@ BU_: XXX BO_ 258 STEERING: 8 XXX + SG_ INCREMENTING_STEERING : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_STEERING : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_STEERING : 48|3@1+ (1,0) [0|15] "" XXX + SG_ STEERING_RATE : 20|13@0+ (0.3187251,-1305.498) [0|8191] "deg/s" XXX SG_ STEER_ANGLE : 4|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX - SG_ STEERING_RATE : 20|13@0+ (1,-4096) [0|8191] "" XXX -BO_ 514 SPEED: 4 XXX - SG_ SPEED_LEFT : 7|16@0+ (0.07,0) [0|65535] "m/s" XXX - SG_ SPEED_RIGHT : 23|16@0+ (0.07,0) [0|1023] "m/s" XXX +BO_ 514 SPEED_1: 4 XXX + SG_ SPEED_LEFT : 7|12@0+ (0.071028,0) [0|65535] "m/s" XXX + SG_ SPEED_RIGHT : 23|12@0+ (0.071028,0) [0|1023] "m/s" XXX BO_ 653 BRAKE_MODULE: 2 XXX SG_ BRAKE_PRESSURE : 15|8@0+ (1,0) [0|255] "" XXX @@ -59,49 +62,365 @@ BO_ 820 DOORS: 8 XXX SG_ HIGH_BEAM_DISPLAY : 58|1@1+ (1,0) [0|1] "" XXX BO_ 746 GEAR: 5 XXX - SG_ PRNDL : 0|3@1+ (1,0) [0|7] "" XXX + SG_ PRNDL : 2|3@0+ (1,0) [0|7] "" XXX + SG_ GEAR_CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR_INCREMENTING : 31|4@0+ (1,0) [0|15] "" XXX -BO_ 284 NEW_MSG_1: 8 XXX - SG_ BRAKE_RELATED : 3|12@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_RELATED_2 : 17|10@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 37|14@0+ (1,0) [0|255] "" XXX +BO_ 284 BRAKE_1: 8 XXX + SG_ SPEED_RELATED_1 : 37|14@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_RELATED_1_2 : 18|11@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_RELATED_1_1 : 3|12@0+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_BRAKE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_BRAKE : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 320 NEW_MSG_2: 8 XXX - SG_ SPEED_RELATED : 47|8@0+ (1,0) [0|63] "" XXX - SG_ BRAKE_PRESSED : 2|3@0+ (1,0) [0|7] "" XXX +BO_ 320 BRAKE_2: 8 XXX + SG_ SPEED_RELATED_2 : 47|8@0+ (1,0) [0|63] "" XXX + SG_ INCREMENTING_140 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_140 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRESSED_2 : 2|3@0+ (1,0) [0|7] "" XXX + SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX BO_ 736 TRIP: 8 XXX - SG_ DISTANCE_COUNTER : 7|16@0+ (0,0) [0|65535] "Meters" XXX + SG_ DISTANCE_COUNTER : 7|16@0+ (1,0) [0|65535] "Meters" XXX SG_ DISTANCE_COUNTER_2 : 23|16@0+ (1,0) [0|65535] "Meters" XXX BO_ 344 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FL : 1|10@0+ (1,0) [0|65535] "" XXX - SG_ WHEEL_SPEED_FR : 17|10@0+ (1,0) [0|255] "" XXX - SG_ WHEEL_SPEED_RL : 33|10@0+ (1,0) [0|3] "" XXX - SG_ WHEEL_SPEED_RR : 49|10@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_SPEED_FL : 3|12@0+ (0.0189408,0) [0|65535] "m/s" XXX + SG_ WHEEL_SPEED_RR : 51|12@0+ (0.0189408,0) [0|255] "m/s" XXX + SG_ WHEEL_SPEED_RL : 35|12@0+ (0.0189408,0) [0|3] "m/s" XXX + SG_ WHEEL_SPEED_FR : 19|12@0+ (0.0189408,0) [0|255] "m/s" XXX BO_ 792 STEERING_LEVERS: 8 XXX + SG_ HIGH_BEAM_PUSHED_IN : 2|1@0+ (1,0) [0|3] "" XXX SG_ TURN_SIGNALS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ HIGH_BEAM_PUSHED_IN : 2|1@1+ (1,0) [0|3] "" XXX - SG_ HIGH_BEAM_FLASH : 3|1@1+ (1,0) [0|3] "" XXX + SG_ HIGH_BEAM_FLASH : 3|1@0+ (1,0) [0|3] "" XXX BO_ 264 ACCEL_PEDAL_MSG: 8 XXX - SG_ ACCEL_PEDAL : 32|4@1+ (1,-7) [0|15] "" XXX + SG_ INCREMENTING_ACCEL_PEDAL : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_ACCEL_PEDAL : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_PEDAL : 35|1@0+ (1,0) [0|1] "" XXX +BO_ 464 SEATBELT_STATUS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 13|1@0+ (1,0) [0|1] "" XXX +BO_ 544 LKAS_INDICATOR_1: 8 XXX + SG_ LKAS_IS_GREEN : 23|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_1 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_2 : 51|1@1+ (1,0) [0|1] "" XXX + SG_ INCREMENTING_220 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_220 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_220_2 : 34|11@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_220_1 : 19|12@0+ (1,0) [0|4095] "" XXX + SG_ UNKNOWN_220_0 : 2|11@0+ (1,0) [0|63] "" XXX +BO_ 658 LKAS_INDICATOR_2: 6 XXX + SG_ LKAS_INCREMENTING : 39|4@0+ (1,0) [0|15] "" XXX + SG_ LKAS_CHECKSUM_2 : 40|8@1+ (1,0) [0|255] "" XXX + SG_ LKAS_STEERING_TORQUE_MAYBE : 3|12@0- (1,0) [0|63] "" XXX +BO_ 678 LKAS_INDICATOR_3: 8 XXX + SG_ WARNING_PLACE_HANDS : 22|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_WHITE_OR_YELLOW : 0|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_IS_YELLOW_2 : 19|1@1+ (1,0) [0|1] "" XXX + +BO_ 705 AUTO_PARK_BUTTON: 8 XXX + SG_ AUTO_PARK_TOGGLE_2 : 8|1@1+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_TOGGLE_1 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ INCREASING_UNKNOWN : 32|7@1+ (1,0) [0|15] "" XXX + +BO_ 719 AUTO_PARK_SIGNALS_1: 8 XXX + SG_ AUTO_PARK_UNKNOWN_1 : 7|16@0+ (1,0) [0|31] "" XXX + +BO_ 671 AUTO_PARK_SIGNALS_2: 8 XXX + SG_ AUTO_PARK_PARALLEL : 21|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_PERPENDICULAR_1 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ INCREMENTING : 55|4@0+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_MAYBE_TURNING : 3|12@0+ (1,0) [0|1023] "" XXX + SG_ AUTO_PARK_TURNING_STATUS : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 784 AUTO_PARK_LESS_INTERESTING: 8 XXX + SG_ INCREASING_UNKNOWN : 48|8@1+ (1,0) [0|7] "" XXX + SG_ AUTO_PARK_PERPENDICULAR_2 : 61|1@0+ (1,0) [0|255] "" XXX + +BO_ 826 AUTO_PARK_SIGNALS_3: 8 XXX + SG_ AUTO_PARK_HAS_CONTROL_3 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HUMAN_HAS_CONTROL : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_GEAR_1 : 27|4@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_GEAR_2 : 32|4@1+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_GEAR_3 : 48|4@1+ (1,0) [0|15] "" XXX + +BO_ 332 STEERING_2: 8 XXX + SG_ INCREMENTING_14C : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ENERGY_RELATED : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ STEER_ANGLE_2 : 7|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX + +BO_ 720 BLIND_SPOT_WARNINGS: 6 XXX + SG_ BLIND_SPOT_RIGHT : 5|1@0+ (1,0) [0|1] "" XXX + SG_ BLIND_SPOT_LEFT : 2|1@1+ (1,0) [0|1] "" XXX + +BO_ 331 BRAKE_3: 8 XXX + SG_ BRAKE_RELATED_3 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ INCREMENTING_14B : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_14B : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 PARKSENSE_SIGNAL: 8 XXX + SG_ PARKSENSE_DISABLED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ INCREMENTING_260 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_260 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ IN_REVERSE : 10|1@1+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_1 : 16|1@1+ (1,0) [0|255] "" XXX + SG_ HUMAN_HAS_CONTROL : 17|1@1+ (1,0) [0|3] "" XXX + +BO_ 729 LKAS_STATUS_1: 5 XXX + SG_ LKAS_STATUS_OK : 31|16@0+ (1,0) [0|65535] "" XXX + +BO_ 274 NEW_MSG_112: 2 XXX + +BO_ 290 NEW_MSG_122: 6 XXX + +BO_ 376 NEW_MSG_178: 3 XXX + +BO_ 288 ACCEL_RELATED_120: 7 XXX + SG_ UNKNOWN_INCREMENTING_120 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ UNKNOWN_CHECKSUM_120 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL : 16|8@1+ (1,0) [0|255] "" XXX + SG_ GAS_ENGINE_RPM_MAYBE : 31|16@0+ (1,0) [0|65535] "" XXX + +BO_ 257 ACCEL_RELATED_101: 5 XXX + SG_ ENERGY_OR_RPM : 24|8@1+ (1,0) [0|255] "" XXX + +BO_ 388 NEW_MSG_184: 4 XXX + +BO_ 448 NEW_MSG_1c0: 6 XXX + +BO_ 456 NEW_MSG_1c8: 4 XXX + +BO_ 560 NEW_MSG_230: 4 XXX + +BO_ 564 NEW_MSG_234: 4 XXX + +BO_ 571 WHEEL_BUTTONS: 3 XXX + SG_ CHECKSUM_23B : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ACC_FOLLOW_DEC : 1|1@1+ (1,0) [0|3] "" XXX + SG_ ACC_SPEED_INC : 2|1@0+ (1,0) [0|255] "" XXX + SG_ ACC_SPEED_DEC : 3|1@1+ (1,0) [0|3] "" XXX + SG_ ACC_FOLLOW_INC : 8|1@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 669 NEW_MSG_29d: 3 XXX + SG_ INCREMENTING_29D : 15|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_29D : 16|8@1+ (1,0) [0|255] "" XXX + +BO_ 825 NEW_MSG_339: 2 XXX + +BO_ 856 NEW_MSG_358: 4 XXX + +BO_ 860 NEW_MSG_35c: 6 XXX + +BO_ 924 NEW_MSG_39c: 3 XXX + +BO_ 969 NEW_MSG_3c9: 4 XXX + +BO_ 974 NEW_MSG_3ce: 5 XXX + +BO_ 993 NEW_MSG_3e1: 7 XXX + +BO_ 838 NEW_MSG_346: 2 XXX + +BO_ 926 NEW_MSG_39e: 3 XXX + +BO_ 168 ACCEL_RELATED_a8: 8 XXX + SG_ ACCEL_RELATED : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ INCREMENTING_A8 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_A8 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 270 ACCEL_RELATED_10e: 8 XXX + SG_ ACCEL_OR_RPM : 7|16@0+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_ACCEL : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_ACCEL : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ELECTRIC_MOTOR : 23|16@0+ (1,0) [0|65535] "" XXX + +BO_ 291 ENERGY_RELATED_123: 8 XXX + SG_ ENERGY_GAIN_LOSS : 18|11@0- (1,0) [0|255] "" XXX + SG_ INCREMENTING_123 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_123 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_SMOOTHER_CURVE : 35|12@0+ (1,0) [0|2047] "" XXX + +BO_ 294 ENERGY_RELATED_126: 8 XXX + SG_ CHECKSUM_126 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_126_1 : 3|12@0+ (1,0) [0|4095] "" XXX + SG_ INCREMENTING_126 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ UNKNOWN_126_2 : 35|12@0+ (1,0) [0|4095] "" XXX + SG_ ENERGY_GAIN_LOSS_NOISY : 19|12@0+ (1,0) [0|2047] "" XXX + +BO_ 300 NEW_MSG_12C: 8 XXX + +BO_ 308 ACCEL_GAS_134: 8 XXX + SG_ INCREMENTING_134 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ACCEL_134 : 40|4@1+ (1,0) [0|15] "" XXX + +BO_ 532 ENERGY_RELATED_214: 8 XXX + SG_ NOISY_SLOWLY_DECREASING : 16|9@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_RELATED : 0|9@0+ (1,0) [0|255] "" XXX + +BO_ 559 ACCEL_GAS_22F: 8 XXX + SG_ ACCEL_22F : 0|4@1+ (1,0) [0|255] "" XXX + SG_ INCREMENTING_22F : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_22F : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 655 CHARGING_MAYBE_28F: 8 XXX + SG_ CHARGING : 0|2@1+ (1,0) [0|3] "" XXX + +BO_ 660 BRAKE_RELATED_294: 8 XXX + SG_ INCREMENTING_294 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM_294 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PERHAPS_294 : 24|8@1+ (1,0) [0|255] "" XXX + +BO_ 764 ACCEL_RELATED_2FC: 8 XXX + SG_ ACCEL_2FC : 8|6@1+ (1,0) [0|255] "" XXX + +BO_ 816 TRACTION_BUTTON: 8 XXX + SG_ TRACTION_OFF : 19|1@1+ (1,0) [0|3] "" XXX + +BO_ 878 ACCEL_RELATED_36E: 8 XXX + SG_ ACCEL_OR_RPM_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_OR_RPM_1 : 0|8@1+ (1,0) [0|255] "" XXX + +BO_ 324 SPEED_2: 8 XXX + SG_ SPEED_2 : 31|16@0+ (0.01,0) [0|255] "m/s" XXX + +BO_ 501 DASHBOARD: 8 XXX + SG_ ACC_SPEED_CONFIG_KPH : 15|8@0+ (1,0) [0|3] "km/h" XXX + SG_ ACC_SPEED_CONFIG_MPH : 23|8@0+ (1,0) [0|3] "mph" XXX + SG_ ACC_DISTANCE_CONFIG_1 : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX + SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX + +BO_ 639 NEW_MSG_27f: 8 XXX + SG_ INCREASING : 40|8@1+ (1,0) [0|255] "" XXX + +BO_ 701 NEW_MSG_2bd: 8 XXX + SG_ unknown_1 : 32|8@1+ (1,0) [0|255] "" XXX + +BO_ 832 UNKNOWN_340: 8 XXX + SG_ SPEED_DIGITAL : 56|8@1+ (1,0) [0|255] "mph" XXX + +BO_ 848 UNKNOWN_350: 8 XXX + SG_ INCREASING_LSB : 0|6@1+ (1,0) [0|255] "" XXX + SG_ INCREASING_MSB : 12|5@0+ (1,0) [0|31] "" XXX + +BO_ 908 NEW_MSG_38c: 8 XXX + SG_ INCREASING_MSB : 44|5@0+ (1,0) [0|31] "" XXX + SG_ INCREASING_LSB : 56|6@1+ (1,0) [0|255] "" XXX + +BO_ 938 NEW_MSG_3aa: 8 XXX + SG_ INCREASING_UNKNOWN_1 : 32|8@1+ (1,0) [0|255] "" XXX + SG_ INCREASING_UNKNOWN_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 940 NEW_MSG_3ac: 8 XXX + SG_ INCREASING_1 : 32|4@1+ (1,0) [0|15] "" XXX + SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 941 NEW_MSG_3ad: 8 XXX + SG_ INCREASING_1 : 32|5@1+ (1,0) [0|31] "" XXX + SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 500 ACC_2: 8 XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ACC_STATUS_1 : 7|3@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_MAYBE : 18|11@0+ (1,0) [0|255] "" XXX + SG_ ACC_STATUS_2 : 21|3@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX + +BO_ 625 ACC_1: 8 XXX + SG_ SPEED : 24|8@1+ (1,0) [0|255] "km/h" XXX + SG_ ACCEL_PERHAPS : 39|16@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 268 ACC_10c: 8 XXX + SG_ BRAKE_PERHAPS : 48|1@1+ (1,0) [0|3] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 384 NEW_MSG_180: 8 XXX + SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 32|8@1+ (1,0) [0|3] "" XXX + +BO_ 853 NEW_MSG_355: 8 XXX + +BO_ 939 NEW_MSG_3ab: 8 XXX + +BO_ 512 NEW_MSG_200: 8 XXX + SG_ NEW_SIGNAL_1 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ INCREASING : 27|12@0+ (1,0) [0|127] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + + + + +CM_ SG_ 258 UNKNOWN_STEERING "never goes above 4. see if human-applied torque"; CM_ SG_ 258 STEER_ANGLE "positive is left (counter-clockwise)"; CM_ SG_ 514 SPEED_LEFT "TODO find upper limit"; CM_ SG_ 653 BRAKE_PRESSURE "max seems to be 148"; CM_ SG_ 820 TURN_LIGHT_LEFT "oscillates with the light blinking"; CM_ SG_ 820 TURN_LIGHT_RIGHT "hazard blinks both right and left lights"; CM_ SG_ 746 PRNDL "4=D, 3=N, 2=R, 1=P"; -CM_ SG_ 284 BRAKE_RELATED "Correlates with braking"; -CM_ SG_ 284 SPEED "Another Speed Signal, Maybe RPMs?"; -CM_ SG_ 320 BRAKE_PRESSED "Value is 5 when brake is pressed"; +CM_ SG_ 746 GEAR_CHECKSUM "different than the LKAS checksum. unknown non-simple algorithm. just build a lookup table for it."; +CM_ SG_ 284 SPEED_RELATED_1 "Another Speed Signal, Maybe RPMs?"; +CM_ SG_ 284 BRAKE_RELATED_1_1 "Correlates with braking"; +CM_ SG_ 320 BRAKE_PRESSED_2 "Value is 5 when brake is pressed by human, 1 when ACC brake"; +CM_ SG_ 320 BRAKE_PRESSED_ACC "set when ACC brakes"; CM_ SG_ 792 TURN_SIGNALS "1=Left, 2=Right"; CM_ SG_ 792 HIGH_BEAM_FLASH "use this for genericToggle"; CM_ SG_ 264 ACCEL_PEDAL "not in ACC so seems to be actual pedal. Use for gasPressed"; +CM_ SG_ 544 AUTO_PARK_HAS_CONTROL_1 "set when autopark has control"; +CM_ SG_ 658 LKAS_INCREMENTING "each message increments, 0..f"; +CM_ SG_ 658 LKAS_CHECKSUM_2 "checksum calculated with https://gist.github.com/adhintz/94bf8d19b9075539f50172ab0fb24ba1"; +CM_ SG_ 658 LKAS_STEERING_TORQUE_MAYBE "1024 is straight. most sent by stock system is 1024+-230. + is left. typically changes by 2 or 3 each 0.01s"; +CM_ SG_ 678 WARNING_PLACE_HANDS "set when warning displays place hands on steering wheel"; +CM_ SG_ 678 LKAS_WHITE_OR_YELLOW "set when indicator is yellow or white. could indicate lkas not on track."; +CM_ SG_ 678 LKAS_IS_YELLOW_2 "set when indicator is yellow. could indicate lkas is steering."; +CM_ SG_ 705 AUTO_PARK_TOGGLE_1 "set briefly when turning on or off self-parking"; +CM_ SG_ 705 INCREASING_UNKNOWN "sometimes decreasing"; +CM_ SG_ 671 AUTO_PARK_PARALLEL "parallel parking mode"; +CM_ SG_ 671 AUTO_PARK_PERPENDICULAR_1 "perpendicular parking mode"; +CM_ SG_ 671 AUTO_PARK_MAYBE_TURNING "something with autopark turning the steering wheel maybe."; +CM_ SG_ 671 AUTO_PARK_TURNING_STATUS "0 when not steering. when steering starts, 4 for two packets, and then 5 for the rest"; +CM_ SG_ 784 INCREASING_UNKNOWN "perhaps distance traveled"; +CM_ SG_ 826 AUTO_PARK_GEAR_1 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_2 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_3 "Reverse=0, Forward=f"; +CM_ SG_ 332 STEER_ANGLE_2 "slightly lags the other steer_angle signal. also more noisy."; +CM_ SG_ 720 BLIND_SPOT_RIGHT "yellow triangle alert on side view mirror when a car is in your blind spot"; +CM_ SG_ 608 PARKSENSE_DISABLED "set if parksense is disabled"; +CM_ SG_ 729 LKAS_STATUS_OK "Set to 0x0820 when LKAS system is plugged in."; +CM_ SG_ 288 UNKNOWN_CHECKSUM_120 "not the LKAS checksum"; +CM_ SG_ 288 GAS_ENGINE_RPM_MAYBE "lags acceleration, perhaps gas engine"; +CM_ SG_ 257 ENERGY_OR_RPM "perhaps energy consumption or RPMs"; +CM_ SG_ 270 ELECTRIC_MOTOR "0x7fff indicates electric motor not in use"; +CM_ SG_ 291 ENERGY_GAIN_LOSS "unsure what this actually is"; +CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unusre what it is, but smoother"; +CM_ SG_ 532 NOISY_SLOWLY_DECREASING "perhaps battery but do not know"; +CM_ SG_ 816 TRACTION_OFF "set when traction off button is enabled"; +CM_ SG_ 324 SPEED_2 "signal is approx half other speeds"; +CM_ SG_ 501 ACC_SPEED_CONFIG_KPH "speed configured for ACC"; +CM_ SG_ 501 ACC_SPEED_CONFIG_MPH "speed configured for ACC"; +CM_ SG_ 639 INCREASING "perhaps number of seconds divided by two for this drive"; +CM_ SG_ 848 INCREASING_LSB "lower part of time counter"; +CM_ SG_ 848 INCREASING_MSB "upper part of time counter"; +CM_ SG_ 908 INCREASING_MSB "time based"; +CM_ SG_ 500 ACC_STATUS_1 "2 briefly (9 packets) when ACC goes to green, 1 help when ACC coming to a stop and at a stop"; +CM_ SG_ 500 BRAKE_MAYBE "2046 in non-ACC and non-decel. Signal on deceleration. 818 for already stopped break."; +CM_ SG_ 500 ACC_STATUS_2 "set to 1 in non-ACC, 3 when ACC enabled (white icon), and 7 when ACC in use (green icon)"; +CM_ SG_ 500 BRAKE_BOOL_1 "set to 1 when ACC decel. 0 on non-ACC and accel."; +CM_ SG_ 625 SPEED "zero on non-acc drives"; +CM_ SG_ 625 ACCEL_PERHAPS "set to 7767 on non-ACC drives. ACC drive 40k is constant speed, 42k is accelerating"; +CM_ SG_ 268 BRAKE_PERHAPS "triggers only on ACC braking"; +CM_ SG_ 384 NEW_SIGNAL_1 "set in ACC gas driving. not set in electric human. not sure about gas human driving."; VAL_ 746 PRNDL 4 "Drive" 3 "Neutral" 2 "Reverse" 1 "Park" ; VAL_ 792 TURN_SIGNALS 2 "Right" 1 "Left" ; diff --git a/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc b/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc new file mode 100644 index 00000000000000..0c5d01c79deec4 --- /dev/null +++ b/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc @@ -0,0 +1,230 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 544 a_1: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 576 b_1: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 a_2: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 640 b_2: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 644 a_3: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 648 b_3: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 652 a_4: 8 XXX + SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX + SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX + SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX + SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX + SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX + SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 656 b_4: 8 XXX + SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 512 unknown_200: 8 XXX + SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ increasing : 31|16@0+ (1,0) [0|255] "" XXX + SG_ zeros_0 : 3|12@0+ (1,0) [0|63] "" XXX + SG_ zeros_1 : 47|12@0+ (1,0) [0|63] "" XXX + SG_ status0 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ unknown_0 : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 514 unknown_202: 8 XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|15] "" XXX + SG_ sig3 : 31|8@0+ (1,0) [0|65535] "" XXX + SG_ increasing : 39|12@0+ (1,0) [0|15] "" XXX + +BO_ 706 c_1: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + +BO_ 708 c_2: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 710 c_3: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 712 c_4: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 714 c_5: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 716 c_6: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 718 c_7: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 720 c_8: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 722 c_9: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 724 c_10: 8 XXX + SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX + SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 674 d_1: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 676 d_2: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 678 d_3: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 680 d_4: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 682 d_5: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 684 d_6: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 686 d_7: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 688 d_8: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 690 d_9: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 692 d_10: 8 XXX + SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX + +BO_ 672 NEW_MSG_5: 8 XXX + SG_ NEW_SIGNAL_1 : 9|10@0+ (1,0) [0|1023] "" XXX + SG_ NEW_SIGNAL_2 : 45|10@0+ (1,0) [0|1023] "" XXX + + + + +CM_ SG_ 544 track_id "for message a_1 track_id is always 1, similar for other messages and track_id"; +CM_ SG_ 544 REL_ACCEL "perhaps REL_ACCEL because it responds faster and before REL_SPEED"; +CM_ SG_ 544 sig2 "perhaps distance to object. LONG_DIST or REL_ACCEL or REL_SPEED"; +CM_ SG_ 576 zeros "not always zero, sometimes has value when another car changes lanes"; +CM_ SG_ 706 LAT_DIST "positive is to the right, negative is to the left"; diff --git a/opendbc/generator/honda/honda_fit_ex_2018_can.dbc b/opendbc/generator/honda/honda_fit_ex_2018_can.dbc new file mode 100644 index 00000000000000..32b5718e6d1e17 --- /dev/null +++ b/opendbc/generator/honda/honda_fit_ex_2018_can.dbc @@ -0,0 +1,97 @@ +CM_ "IMPORT _honda_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc new file mode 100644 index 00000000000000..c86fcaaf659c86 --- /dev/null +++ b/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc @@ -0,0 +1,36 @@ +CM_ "IMPORT _toyota_2017.dbc" +CM_ "IMPORT _comma.dbc" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/honda_fit_ex_2018_can_generated.dbc b/opendbc/honda_fit_ex_2018_can_generated.dbc new file mode 100644 index 00000000000000..e2187497f8c333 --- /dev/null +++ b/opendbc/honda_fit_ex_2018_can_generated.dbc @@ -0,0 +1,326 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _honda_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 LOCK_STATUS: 8 XXX + SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON + SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "honda_fit_ex_2018_can.dbc starts here" + + + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/kia_sorento_2018.dbc b/opendbc/kia_sorento_2018.dbc new file mode 100644 index 00000000000000..919da4cc2dd90c --- /dev/null +++ b/opendbc/kia_sorento_2018.dbc @@ -0,0 +1,1391 @@ +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/toyota_chr_hybrid_2018_pt_generated.dbc b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc new file mode 100644 index 00000000000000..f4e8e4443d6a1c --- /dev/null +++ b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc @@ -0,0 +1,247 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +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"; + + +CM_ "Imported file _toyota_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU + SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1041 ACC_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; +CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; +VAL_ 614 STATE 3 "enabled" 1 "disabled"; +VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; +VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none"; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_chr_hybrid_2018_pt.dbc starts here" + + + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/panda/VERSION b/panda/VERSION index efdb8b180122a5..32e7334ebd618e 100644 --- a/panda/VERSION +++ b/panda/VERSION @@ -1 +1 @@ -v1.1.2 \ No newline at end of file +v1.1.3 \ No newline at end of file diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 7cbeafcb96f65d..d51a12a441292e 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -1,32 +1,34 @@ -struct sample_t torque_meas; // last 3 motor torques produced by the eps +int toyota_no_dsu_car = 0; // ch-r and camry don't have the DSU +int toyota_giraffe_switch_1 = 0; // is giraffe switch 1 high? // global torque limit -const int MAX_TORQUE = 1500; // max torque cmd allowed ever +const int TOYOTA_MAX_TORQUE = 1500; // max torque cmd allowed ever // rate based torque limit + stay within actually applied // packet is sent at 100hz, so this limit is 1000/sec -const int MAX_RATE_UP = 10; // ramp up slow -const int MAX_RATE_DOWN = 25; // ramp down fast -const int MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor +const int TOYOTA_MAX_RATE_UP = 10; // ramp up slow +const int TOYOTA_MAX_RATE_DOWN = 25; // ramp down fast +const int TOYOTA_MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor // real time torque limit to prevent controls spamming // the real time limit is 1500/sec -const int MAX_RT_DELTA = 375; // max delta torque allowed for real time checks -const int RT_INTERVAL = 250000; // 250ms between real time checks +const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real time checks +const int TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks // longitudinal limits -const int MAX_ACCEL = 1500; // 1.5 m/s2 -const int MIN_ACCEL = -3000; // 3.0 m/s2 +const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2 +const int TOYOTA_MIN_ACCEL = -3000; // 3.0 m/s2 // global actuation limit state -int actuation_limits = 1; // by default steer limits are imposed -int dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file +int toyota_actuation_limits = 1; // by default steer limits are imposed +int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file // state of torque limits -int desired_torque_last = 0; // last desired steer torque -int rt_torque_last = 0; // last desired torque for real time check -uint32_t ts_last = 0; -int cruise_engaged_last = 0; // cruise state +int toyota_desired_torque_last = 0; // last desired steer torque +int toyota_rt_torque_last = 0; // last desired torque for real time check +uint32_t toyota_ts_last = 0; +int toyota_cruise_engaged_last = 0; // cruise state +struct sample_t toyota_torque_meas; // last 3 motor torques produced by the eps static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { @@ -36,26 +38,38 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { torque_meas_new = to_signed(torque_meas_new, 16); // scale by dbc_factor - torque_meas_new = (torque_meas_new * dbc_eps_torque_factor) / 100; + torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100; // increase torque_meas by 1 to be conservative on rounding torque_meas_new += (torque_meas_new > 0 ? 1 : -1); // update array of sample - update_sample(&torque_meas, torque_meas_new); + update_sample(&toyota_torque_meas, torque_meas_new); } // enter controls on rising edge of ACC, exit controls on ACC off if ((to_push->RIR>>21) == 0x1D2) { // 4 bits: 55-52 int cruise_engaged = to_push->RDHR & 0xF00000; - if (cruise_engaged && !cruise_engaged_last) { + if (cruise_engaged && !toyota_cruise_engaged_last) { controls_allowed = 1; } else if (!cruise_engaged) { controls_allowed = 0; } - cruise_engaged_last = cruise_engaged; + toyota_cruise_engaged_last = cruise_engaged; } + + int bus = (to_push->RDTR >> 4) & 0xF; + // 0x680 is a radar msg only found in dsu-less cars + if ((to_push->RIR>>21) == 0x680 && (bus == 1)) { + toyota_no_dsu_car = 1; + } + + // 0x2E4 is lkas cmd. If it is on bus 0, then giraffe switch 1 is high + if ((to_push->RIR>>21) == 0x2E4 && (bus == 0)) { + toyota_giraffe_switch_1 = 1; + } + } static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { @@ -70,8 +84,8 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { if ((to_send->RIR>>21) == 0x343) { int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF); desired_accel = to_signed(desired_accel, 16); - if (controls_allowed && actuation_limits) { - int violation = max_limit_check(desired_accel, MAX_ACCEL, MIN_ACCEL); + if (controls_allowed && toyota_actuation_limits) { + int violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL); if (violation) return 0; } else if (!controls_allowed && (desired_accel != 0)) { return 0; @@ -87,25 +101,26 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { uint32_t ts = TIM2->CNT; // only check if controls are allowed and actuation_limits are imposed - if (controls_allowed && actuation_limits) { + if (controls_allowed && toyota_actuation_limits) { // *** global torque limit check *** - violation |= max_limit_check(desired_torque, MAX_TORQUE, -MAX_TORQUE); + violation |= max_limit_check(desired_torque, TOYOTA_MAX_TORQUE, -TOYOTA_MAX_TORQUE); // *** torque rate limit check *** - violation |= dist_to_meas_check(desired_torque, desired_torque_last, &torque_meas, MAX_RATE_UP, MAX_RATE_DOWN, MAX_TORQUE_ERROR); + violation |= dist_to_meas_check(desired_torque, toyota_desired_torque_last, + &toyota_torque_meas, TOYOTA_MAX_RATE_UP, TOYOTA_MAX_RATE_DOWN, TOYOTA_MAX_TORQUE_ERROR); // used next time - desired_torque_last = desired_torque; + toyota_desired_torque_last = desired_torque; // *** torque real time rate limit check *** - violation |= rt_rate_limit_check(desired_torque, rt_torque_last, MAX_RT_DELTA); + violation |= rt_rate_limit_check(desired_torque, toyota_rt_torque_last, TOYOTA_MAX_RT_DELTA); // every RT_INTERVAL set the new limits - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_last); - if (ts_elapsed > RT_INTERVAL) { - rt_torque_last = desired_torque; - ts_last = ts; + uint32_t ts_elapsed = get_ts_elapsed(ts, toyota_ts_last); + if (ts_elapsed > TOYOTA_RT_INTERVAL) { + toyota_rt_torque_last = desired_torque; + toyota_ts_last = ts; } } @@ -116,9 +131,9 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { // reset to 0 if either controls is not allowed or there's a violation if (violation || !controls_allowed) { - desired_torque_last = 0; - rt_torque_last = 0; - ts_last = ts; + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = ts; } if (violation) { @@ -138,11 +153,19 @@ static int toyota_tx_lin_hook(int lin_num, uint8_t *data, int len) { static void toyota_init(int16_t param) { controls_allowed = 0; - actuation_limits = 1; - dbc_eps_torque_factor = param; + toyota_actuation_limits = 1; + toyota_giraffe_switch_1 = 0; + toyota_dbc_eps_torque_factor = param; } static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + + // forward cam to radar and viceversa if car is dsu-less, except lkas cmd and hud + if ((bus_num == 0 || bus_num == 2) && toyota_no_dsu_car && !toyota_giraffe_switch_1) { + int addr = to_fwd->RIR>>21; + bool is_lkas_msg = (addr == 0x2E4 || addr == 0x412) && bus_num == 2; + return is_lkas_msg? -1 : (uint8_t)(~bus_num & 0x2); + } return -1; } @@ -157,8 +180,9 @@ const safety_hooks toyota_hooks = { static void toyota_nolimits_init(int16_t param) { controls_allowed = 0; - actuation_limits = 0; - dbc_eps_torque_factor = param; + toyota_actuation_limits = 0; + toyota_giraffe_switch_1 = 0; + toyota_dbc_eps_torque_factor = param; } const safety_hooks toyota_nolimits_hooks = { diff --git a/panda/board/safety/safety_toyota_ipas.h b/panda/board/safety/safety_toyota_ipas.h index 35b7e2b5974a64..dc265fa03e55c7 100644 --- a/panda/board/safety/safety_toyota_ipas.h +++ b/panda/board/safety/safety_toyota_ipas.h @@ -2,7 +2,7 @@ // TODO: refactor to repeat less code // IPAS override -const int32_t IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value +const int32_t TOYOTA_IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value struct lookup_t { float x[3]; @@ -92,7 +92,7 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { // every RT_INTERVAL or when controls are turned on, set the new limits uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_last); - if ((ts_elapsed > RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) { + if ((ts_elapsed > TOYOTA_RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) { rt_angle_last = angle_meas_new; ts_angle_last = ts; } @@ -118,8 +118,8 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { } // exit controls on high steering override - if (angle_control && ((torque_driver.min > IPAS_OVERRIDE_THRESHOLD) || - (torque_driver.max < -IPAS_OVERRIDE_THRESHOLD) || + if (angle_control && ((torque_driver.min > TOYOTA_IPAS_OVERRIDE_THRESHOLD) || + (torque_driver.max < -TOYOTA_IPAS_OVERRIDE_THRESHOLD) || (ipas_state==5))) { controls_allowed = 0; } diff --git a/panda/examples/tesla_tester.py b/panda/examples/tesla_tester.py index b2cbb4d789e18d..99d8d92854423b 100644 --- a/panda/examples/tesla_tester.py +++ b/panda/examples/tesla_tester.py @@ -29,11 +29,11 @@ def tesla_tester(): # BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock: print("Unlocking Tesla...") - p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", bus_num) + p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num) #Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both) print("Opening Frunk...") - p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", bus_num) + p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num) #Back to safety... print("Disabling output on Panda...") @@ -41,7 +41,6 @@ def tesla_tester(): print("Reading VIN from 0x568. This is painfully slow and can take up to 3 minutes (1 minute per message; 3 messages needed for full VIN)...") - cnt = 0 vin = {} while True: #Read the VIN @@ -53,11 +52,10 @@ def tesla_tester(): vin_string = binascii.hexlify(dat)[2:] #rest of the string is the actual VIN data vin[vin_index] = vin_string.decode("hex") print("Got VIN index " + str(vin_index) + " data " + vin[vin_index]) - cnt += 1 #if we have all 3 parts of the VIN, print it and break out of our while loop - if cnt == 3: + if 0 in vin and 1 in vin and 2 in vin: print("VIN: " + vin[0] + vin[1] + vin[2][:3]) break if __name__ == "__main__": - tesla_tester() \ No newline at end of file + tesla_tester() diff --git a/panda/tests/safety/libpandasafety_py.py b/panda/tests/safety/libpandasafety_py.py index 8840c66f315dd1..0af95ae47a4e3d 100644 --- a/panda/tests/safety/libpandasafety_py.py +++ b/panda/tests/safety/libpandasafety_py.py @@ -38,13 +38,13 @@ int get_controls_allowed(void); void init_tests_toyota(void); void set_timer(int t); -void set_torque_meas(int min, int max); +void set_toyota_torque_meas(int min, int max); void set_cadillac_torque_driver(int min, int max); void set_gm_torque_driver(int min, int max); -void set_rt_torque_last(int t); -void set_desired_torque_last(int t); -int get_torque_meas_min(void); -int get_torque_meas_max(void); +void set_toyota_rt_torque_last(int t); +void set_toyota_desired_torque_last(int t); +int get_toyota_torque_meas_min(void); +int get_toyota_torque_meas_max(void); void init_tests_honda(void); int get_ego_speed(void); diff --git a/panda/tests/safety/test.c b/panda/tests/safety/test.c index f0f2af506da58b..3d4288116e4a47 100644 --- a/panda/tests/safety/test.c +++ b/panda/tests/safety/test.c @@ -22,7 +22,7 @@ typedef struct uint32_t CNT; } TIM_TypeDef; -struct sample_t torque_meas; +struct sample_t toyota_torque_meas; struct sample_t cadillac_torque_driver; struct sample_t gm_torque_driver; @@ -60,9 +60,9 @@ void set_timer(int t){ timer.CNT = t; } -void set_torque_meas(int min, int max){ - torque_meas.min = min; - torque_meas.max = max; +void set_toyota_torque_meas(int min, int max){ + toyota_torque_meas.min = min; + toyota_torque_meas.max = max; } void set_cadillac_torque_driver(int min, int max){ @@ -75,16 +75,16 @@ void set_gm_torque_driver(int min, int max){ gm_torque_driver.max = max; } -int get_torque_meas_min(void){ - return torque_meas.min; +int get_toyota_torque_meas_min(void){ + return toyota_torque_meas.min; } -int get_torque_meas_max(void){ - return torque_meas.max; +int get_toyota_torque_meas_max(void){ + return toyota_torque_meas.max; } -void set_rt_torque_last(int t){ - rt_torque_last = t; +void set_toyota_rt_torque_last(int t){ + toyota_rt_torque_last = t; } void set_cadillac_rt_torque_last(int t){ @@ -95,8 +95,8 @@ void set_gm_rt_torque_last(int t){ gm_rt_torque_last = t; } -void set_desired_torque_last(int t){ - desired_torque_last = t; +void set_toyota_desired_torque_last(int t){ + toyota_desired_torque_last = t; } void set_cadillac_desired_torque_last(int t){ @@ -129,11 +129,11 @@ void set_bosch_hardware(bool c){ } void init_tests_toyota(void){ - torque_meas.min = 0; - torque_meas.max = 0; - desired_torque_last = 0; - rt_torque_last = 0; - ts_last = 0; + toyota_torque_meas.min = 0; + toyota_torque_meas.max = 0; + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = 0; set_timer(0); } diff --git a/panda/tests/safety/test_toyota.py b/panda/tests/safety/test_toyota.py index ad86be63beb64b..b4d23af65df321 100644 --- a/panda/tests/safety/test_toyota.py +++ b/panda/tests/safety/test_toyota.py @@ -41,9 +41,9 @@ def setUp(cls): cls.safety.init_tests_toyota() def _set_prev_torque(self, t): - self.safety.set_desired_torque_last(t) - self.safety.set_rt_torque_last(t) - self.safety.set_torque_meas(t, t) + self.safety.set_toyota_desired_torque_last(t) + self.safety.set_toyota_rt_torque_last(t) + self.safety.set_toyota_torque_meas(t, t) def _torque_meas_msg(self, torque): to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') @@ -158,9 +158,9 @@ def test_torque_absolute_limits(self): for controls_allowed in [True, False]: for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP): self.safety.set_controls_allowed(controls_allowed) - self.safety.set_rt_torque_last(torque) - self.safety.set_torque_meas(torque, torque) - self.safety.set_desired_torque_last(torque - MAX_RATE_UP) + self.safety.set_toyota_rt_torque_last(torque) + self.safety.set_toyota_torque_meas(torque, torque) + self.safety.set_toyota_desired_torque_last(torque - MAX_RATE_UP) if controls_allowed: send = (-MAX_TORQUE <= torque <= MAX_TORQUE) @@ -181,14 +181,14 @@ def test_non_realtime_limit_up(self): def test_non_realtime_limit_down(self): self.safety.set_controls_allowed(True) - self.safety.set_rt_torque_last(1000) - self.safety.set_torque_meas(500, 500) - self.safety.set_desired_torque_last(1000) + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN))) - self.safety.set_rt_torque_last(1000) - self.safety.set_torque_meas(500, 500) - self.safety.set_desired_torque_last(1000) + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN + 1))) def test_exceed_torque_sensor(self): @@ -210,14 +210,14 @@ def test_realtime_limit_up(self): self._set_prev_torque(0) for t in np.arange(0, 380, 10): t *= sign - self.safety.set_torque_meas(t, t) + self.safety.set_toyota_torque_meas(t, t) self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * 380))) self._set_prev_torque(0) for t in np.arange(0, 370, 10): t *= sign - self.safety.set_torque_meas(t, t) + self.safety.set_toyota_torque_meas(t, t) self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) # Increase timer to update rt_torque_last @@ -233,16 +233,16 @@ def test_torque_measurements(self): self.safety.toyota_rx_hook(self._torque_meas_msg(0)) self.safety.toyota_rx_hook(self._torque_meas_msg(0)) - self.assertEqual(-51, self.safety.get_torque_meas_min()) - self.assertEqual(51, self.safety.get_torque_meas_max()) + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) + self.assertEqual(51, self.safety.get_toyota_torque_meas_max()) self.safety.toyota_rx_hook(self._torque_meas_msg(0)) - self.assertEqual(-1, self.safety.get_torque_meas_max()) - self.assertEqual(-51, self.safety.get_torque_meas_min()) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) self.safety.toyota_rx_hook(self._torque_meas_msg(0)) - self.assertEqual(-1, self.safety.get_torque_meas_max()) - self.assertEqual(-1, self.safety.get_torque_meas_min()) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_min()) def test_ipas_override(self): diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/img_driver_face.png new file mode 100644 index 00000000000000..ddde478cd789ec Binary files /dev/null and b/selfdrive/assets/img_driver_face.png differ diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 6a64183425e0ea..1f0e36e0dc23ef 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -1,6 +1,6 @@ #!/usr/bin/env python from common.realtime import sec_since_boot -from cereal import car +from cereal import car, log from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event @@ -209,7 +209,7 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, c.hudControl.visualAlert, c.cruiseControl.cancel) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 59b6e35c748312..7c0c63f54631ce 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -4,7 +4,8 @@ from selfdrive.config import Conversions as CV from selfdrive.can.parser import CANParser from selfdrive.car.gm.values import DBC, CAR, parse_gear_shifter, \ - CruiseButtons, is_eps_status_ok + CruiseButtons, is_eps_status_ok, \ + STEER_THRESHOLD def get_powertrain_can_parser(CP, canbus): # this function generates lists for signal, messages and initial values @@ -91,7 +92,7 @@ def update(self, pt_cp): self.user_gas_pressed = self.pedal_gas > 0 self.steer_torque_driver = pt_cp.vl["PSCMStatus"]['LKADriverAppldTrq'] - self.steer_override = abs(self.steer_torque_driver) > 1.0 + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD # 0 - inactive, 1 - active, 2 - temporary limited, 3 - failed self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus'] diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 53dc8b68e78ee9..3d0a49feeeb423 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -1,5 +1,5 @@ #!/usr/bin/env python -from cereal import car +from cereal import car, log from common.realtime import sec_since_boot from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET @@ -308,7 +308,7 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): hud_v_cruise = c.hudControl.setSpeed if hud_v_cruise > 70: hud_v_cruise = 0 diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 314bb4a3f645fd..b69109f356735d 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -47,6 +47,7 @@ def parse_gear_shifter(can_gear): }], } +STEER_THRESHOLD = 1.0 DBC = { CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 0875a67234a02d..b1b72321efc7d4 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -1,3 +1,4 @@ +from cereal import car from collections import namedtuple from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.controls.lib.drive_helpers import rate_limit @@ -61,11 +62,12 @@ def __init__(self, dbc_name, enable_camera=True): self.brake_last = 0. self.enable_camera = enable_camera self.packer = CANPacker(dbc_name) + self.new_radar_config = False def update(self, sendcan, enabled, CS, frame, actuators, \ pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ - hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \ - snd_beep, snd_chime): + radar_error, hud_v_cruise, hud_show_lanes, hud_show_car, \ + hud_alert, snd_beep, snd_chime): """ Controls thread """ @@ -167,6 +169,8 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ if (frame % radar_send_step) == 0: idx = (frame/radar_send_step) % 4 - can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.CP.carFingerprint, idx)) + if not self.new_radar_config: # only change state once + self.new_radar_config = car.RadarState.Error.wrongConfig in radar_error + can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.CP.carFingerprint, self.new_radar_config, idx)) sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 36dea1f7ff1fbb..466259c20ac10f 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -2,7 +2,7 @@ from common.kalman.simple_kalman import KF1D from selfdrive.can.parser import CANParser from selfdrive.config import Conversions as CV -from selfdrive.car.honda.values import CAR, DBC +from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD def parse_gear_shifter(can_gear_shifter, car_fingerprint): @@ -284,10 +284,8 @@ def update(self, cp): else: self.car_gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] - #rdx has different steer override threshold - steer_thrsld = 400 if self.CP.carFingerprint == CAR.ACURA_RDX else 1200 - self.steer_override = abs(cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR']) > steer_thrsld self.steer_torque_driver = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD[self.CP.carFingerprint] self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 92e74cd6868155..8dc5e1d9b5d0de 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -117,7 +117,7 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, idx): return commands -def create_radar_commands(v_ego, car_fingerprint, idx): +def create_radar_commands(v_ego, car_fingerprint, new_radar_config, idx): """Creates an iterable of CAN messages for the radar system.""" commands = [] v_ego_kph = np.clip(int(round(v_ego * CV.MS_TO_KPH)), 0, 255) @@ -129,7 +129,8 @@ def create_radar_commands(v_ego, car_fingerprint, idx): if car_fingerprint == CAR.CIVIC: msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" - commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) # add 8 on idx. + idx_offset = 0xc if new_radar_config else 0x8 # radar in civic 2018 requires 0xc + commands.append(make_can_msg(0x300, msg_0x300, idx + idx_offset, 1)) else: if car_fingerprint == CAR.CRV: msg_0x301 = "\x00\x00\x50\x02\x51\x00\x00" diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index db02a9725a969e..4cac8c092a7c0f 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,7 +1,7 @@ #!/usr/bin/env python import os import numpy as np -from cereal import car +from cereal import car, log from common.numpy_fast import clip, interp from common.realtime import sec_since_boot from selfdrive.swaglog import cloudlog @@ -567,7 +567,7 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): if c.hudControl.speedVisible: hud_v_cruise = c.hudControl.setSpeed * CV.MS_TO_KPH else: @@ -600,6 +600,7 @@ def apply(self, c): c.cruiseControl.override, \ c.cruiseControl.cancel, \ pcm_accel, \ + perception_state.radarErrors, \ hud_v_cruise, c.hudControl.lanesVisible, \ hud_show_car = c.hudControl.leadVisible, \ hud_alert = hud_alert, \ diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index 3081474487540d..7d30265c2f471e 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -28,6 +28,7 @@ def __init__(self, CP): self.pts = {} self.track_id = 0 self.radar_fault = False + self.radar_wrong_config = False self.radar_off_can = CP.radarOffCan self.delay = 0.1 # Delay of radar @@ -61,6 +62,7 @@ def update(self): if ii == 0x400: # check for radar faults self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 elif cpt['LONG_DIST'] < 255: if ii not in self.pts or cpt['NEW_TRACK']: self.pts[ii] = car.RadarState.RadarPoint.new_message() @@ -81,6 +83,8 @@ def update(self): errors.append("commIssue") if self.radar_fault: errors.append("fault") + if self.radar_wrong_config: + errors.append("wrongConfig") ret.errors = errors ret.canMonoTimes = canMonoTimes diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 71bb495e26976e..5188ca576e147b 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -104,5 +104,19 @@ class CAR: CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'), } + +STEER_THRESHOLD = { + CAR.ACCORD: 1200, + CAR.ACURA_ILX: 1200, + CAR.ACURA_RDX: 400, + CAR.CIVIC: 1200, + CAR.CIVIC_HATCH: 1200, + CAR.CRV: 1200, + CAR.CRV_5G: 1200, + CAR.ODYSSEY: 1200, + CAR.PILOT: 1200, + CAR.RIDGELINE: 1200, +} + # TODO: get these from dbc file HONDA_BOSCH = [CAR.ACCORD, CAR.CIVIC_HATCH, CAR.CRV_5G] diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index db3b8b6a53dac3..5edbcbbd113f78 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -1,6 +1,6 @@ #!/usr/bin/env python import zmq -from cereal import car +from cereal import car, log from selfdrive.config import Conversions as CV from selfdrive.services import service_list from selfdrive.swaglog import cloudlog @@ -117,6 +117,6 @@ def update(self, c): return ret.as_reader() - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): # in mock no carcontrols return False diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 7752add1b23c2a..a8e317b1ebaaf2 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -4,7 +4,7 @@ create_steer_command, create_ui_command, \ create_ipas_steer_command, create_accel_command, \ create_fcw_command -from selfdrive.car.toyota.values import ECU, STATIC_MSGS +from selfdrive.car.toyota.values import ECU, STATIC_MSGS, NO_DSU_CAR from selfdrive.can.packer import CANPacker # Accel limits @@ -209,7 +209,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, else: can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False)) - if frame % 10 == 0 and ECU.CAM in self.fake_ecus: + if frame % 10 == 0 and ECU.CAM in self.fake_ecus and self.car_fingerprint not in NO_DSU_CAR: 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 28bfc0fb5761a7..53ff3aaa8a17c4 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -1,4 +1,4 @@ -from selfdrive.car.toyota.values import CAR, DBC +from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD from selfdrive.can.parser import CANParser from selfdrive.config import Conversions as CV from common.kalman.simple_kalman import KF1D @@ -7,7 +7,7 @@ def parse_gear_shifter(can_gear, car_fingerprint): # TODO: Use values from DBC to parse this field - if car_fingerprint == CAR.PRIUS: + if car_fingerprint in [CAR.PRIUS, CAR.CHRH, CAR.CAMRYH]: if can_gear == 0x0: return "park" elif can_gear == 0x1: @@ -19,7 +19,7 @@ def parse_gear_shifter(can_gear, car_fingerprint): elif can_gear == 0x4: return "brake" elif car_fingerprint in [CAR.RAV4, CAR.RAV4H, - CAR.LEXUS_RXH, CAR.COROLLA]: + CAR.LEXUS_RXH, CAR.COROLLA, CAR.CHR, CAR.CAMRY]: if can_gear == 0x20: return "park" elif can_gear == 0x10: @@ -147,8 +147,6 @@ def update(self, cp): self.left_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1 self.right_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2 - # we could use the override bit from dbc, but it's triggered at too high torque values - self.steer_override = abs(cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']) > 100 # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE'] self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] not in [1, 5] @@ -156,6 +154,8 @@ def update(self, cp): self.brake_error = 0 self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER'] self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS'] + # we could use the override bit from dbc, but it's triggered at too high torque values + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD self.user_brake = 0 self.v_cruise_pcm = cp.vl["PCM_CRUISE_2"]['SET_SPEED'] diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 0170c4c942b990..6a1585978181bd 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -1,6 +1,6 @@ #!/usr/bin/env python from common.realtime import sec_since_boot -from cereal import car +from cereal import car, log from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -75,8 +75,8 @@ def get_params(candidate, fingerprint): if candidate == CAR.PRIUS: ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file ret.wheelbase = 2.70 - ret.steerRatio = 15.59 # unknown end-to-end spec - tire_stiffness_factor = 0.7933 + ret.steerRatio = 15.00 # unknown end-to-end spec + tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3045 * CV.LB_TO_KG + std_cargo ret.steerKpV, ret.steerKiV = [[0.4], [0.01]] ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 @@ -110,6 +110,24 @@ def get_params(candidate, fingerprint): ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + elif candidate in [CAR.CHR, CAR.CHRH]: + ret.safetyParam = 100 + ret.wheelbase = 2.63906 + ret.steerRatio = 13.6 + tire_stiffness_factor = 0.7933 + ret.mass = 3300. * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.723], [0.0428]] + ret.steerKf = 0.00006 + + elif candidate in [CAR.CAMRY, CAR.CAMRYH]: + ret.safetyParam = 100 + ret.wheelbase = 2.82448 + ret.steerRatio = 13.7 + tire_stiffness_factor = 0.7933 + ret.mass = 3400 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] + ret.steerKf = 0.00006 + ret.steerRateCost = 1. ret.centerToFront = ret.wheelbase * 0.44 @@ -118,7 +136,7 @@ def get_params(candidate, 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. - if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH]: # rav4 hybrid can do stop and go + if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]: # rav4 hybrid can do stop and go 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 @@ -150,9 +168,9 @@ def get_params(candidate, fingerprint): ret.brakeMaxBP = [5., 20.] ret.brakeMaxV = [1., 0.8] - ret.enableCamera = not check_ecu_msgs(fingerprint, candidate, ECU.CAM) - ret.enableDsu = not check_ecu_msgs(fingerprint, candidate, ECU.DSU) - ret.enableApgs = False #not check_ecu_msgs(fingerprint, candidate, ECU.APGS) + ret.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) cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) cloudlog.warn("ECU DSU Simulated: %r", ret.enableDsu) cloudlog.warn("ECU APGS Simulated: %r", ret.enableApgs) @@ -304,7 +322,7 @@ def update(self, c): # pass in a car.CarControl # to be called @ 100hz - def apply(self, c): + def apply(self, c, perception_state=log.Live20Data.new_message()): self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 9af6aed47bf9c3..25bbfbfb39e53b 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -1,11 +1,13 @@ #!/usr/bin/env python import os +import zmq +import time from selfdrive.can.parser import CANParser from cereal import car from common.realtime import sec_since_boot -import zmq from selfdrive.services import service_list import selfdrive.messaging as messaging +from selfdrive.car.toyota.values import NO_DSU_CAR RADAR_MSGS = list(range(0x210, 0x220)) @@ -30,15 +32,21 @@ def __init__(self, CP): self.delay = 0.0 # Delay of radar - # Nidec self.rcp = _create_radard_can_parser() + self.no_dsu_car = CP.carFingerprint in NO_DSU_CAR context = zmq.Context() self.logcan = messaging.sub_sock(context, service_list['can'].port) def update(self): - canMonoTimes = [] + ret = car.RadarState.new_message() + if self.no_dsu_car: + # TODO: make a adas dbc file for dsu-less models + time.sleep(0.05) + return ret + + canMonoTimes = [] updated_messages = set() while 1: tm = int(sec_since_boot() * 1e9) @@ -47,7 +55,6 @@ def update(self): if 0x21f in updated_messages: break - ret = car.RadarState.new_message() errors = [] if not self.rcp.can_valid: errors.append("commIssue") diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 649146073f6518..2e0cf3e6fee842 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -2,10 +2,14 @@ class CAR: PRIUS = "TOYOTA PRIUS 2017" - RAV4H = "TOYOTA RAV4 2017 HYBRID" + RAV4H = "TOYOTA RAV4 HYBRID 2017" RAV4 = "TOYOTA RAV4 2017" COROLLA = "TOYOTA COROLLA 2017" LEXUS_RXH = "LEXUS RX HYBRID 2017" + CHR = "TOYOTA C-HR 2018" + CHRH = "TOYOTA C-HR HYBRID 2018" + CAMRY = "TOYOTA CAMRY 2018" + CAMRYH = "TOYOTA CAMRY HYBRID 2018" class ECU: @@ -59,14 +63,16 @@ class ECU: (0x470, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 1, 100, '\x00\x00\x02\x7a'), ] +ECU_FINGERPRINT = { + ECU.CAM: 0x2e4, # steer torque cmd + ECU.DSU: 0x343, # accel cmd + ECU.APGS: 0x835, # angle cmd +} -def check_ecu_msgs(fingerprint, candidate, ecu): - # return True if fingerprint contains messages normally sent by a given ecu - ecu_msgs = [x[0] for x in STATIC_MSGS if (x[1] == ecu and - candidate in x[2] and - x[3] == 0)] - return any(msg for msg in fingerprint if msg in ecu_msgs) +def check_ecu_msgs(fingerprint, ecu): + # return True if fingerprint contains messages normally sent by a given ecu + return ECU_FINGERPRINT[ecu] in fingerprint FINGERPRINTS = { @@ -97,8 +103,25 @@ def check_ecu_msgs(fingerprint, candidate, ecu): 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 }], + 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 + }], + 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, 643: 7, 713: 8, 740: 5, 800: 8, 810: 2, 812: 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, 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, 1114: 8, 1161: 8, 1162: 8, 1163: 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 + }], + CAR.CAMRY: [ + #XLE and LE + { + 36: 8, 37: 8, 119: 6, 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, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CAMRYH: [ + #LE + { + 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, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 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, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 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, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572:8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], } +STEER_THRESHOLD = 100 DBC = { CAR.RAV4H: dbc_dict('toyota_rav4_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), @@ -106,4 +129,10 @@ def check_ecu_msgs(fingerprint, candidate, ecu): CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_prius_2017_adas'), CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_prius_2017_adas'), CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHR: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHRH: dbc_dict('toyota_chr_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRY: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRYH: dbc_dict('toyota_camry_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), } + +NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH] diff --git a/selfdrive/common/efd.c b/selfdrive/common/efd.c new file mode 100644 index 00000000000000..78a7c098949b56 --- /dev/null +++ b/selfdrive/common/efd.c @@ -0,0 +1,56 @@ +#include +#include + +#ifdef __linux__ +#include +#else +#include +#include +#define EVENT_IDENT 42 +#endif + +#include "efd.h" + + +int efd_init() { +#ifdef __linux__ + return eventfd(0, EFD_CLOEXEC); +#else + int fd = kqueue(); + assert(fd >= 0); + + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, EV_ADD | EV_CLEAR, 0, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); + + return fd; +#endif +} + +void efd_write(int fd) { +#ifdef __linux__ + eventfd_write(fd, 1); +#else + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, 0, NOTE_TRIGGER, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); +#endif +} + +void efd_clear(int fd) { +#ifdef __linux__ + eventfd_t efd_cnt; + eventfd_read(fd, &efd_cnt); +#else + struct kevent kev; + struct timespec timeout = {0, 0}; + int nfds = kevent(fd, NULL, 0, &kev, 1, &timeout); + assert(nfds != -1); +#endif +} diff --git a/selfdrive/common/efd.h b/selfdrive/common/efd.h new file mode 100644 index 00000000000000..056482ffa51f3e --- /dev/null +++ b/selfdrive/common/efd.h @@ -0,0 +1,17 @@ +#ifndef EFD_H +#define EFD_H + +#ifdef __cplusplus +extern "C" { +#endif + +// event fd: a semaphore that can be poll()'d +int efd_init(); +void efd_write(int fd); +void efd_clear(int fd); + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 2b226fc6e0cd8c..664167ebcedb2a 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.5-release" +#define COMMA_VERSION "0.5.1-release" diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 1b8ad21282a78c..f75f4c70a1b331 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -292,7 +292,7 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, return actuators, v_cruise_kph, driver_status, angle_offset -def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, +def data_send(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): @@ -323,7 +323,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_ CC.hudControl.audibleAlert = AM.audible_alert # send car controls over can - CI.apply(CC) + CI.apply(CC, perception_state) # ***** publish state to logger ***** # publish controls state at 100Hz @@ -337,6 +337,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_ "alertStatus": AM.alert_status, "alertBlinkingRate": AM.alert_rate, "awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0, + "driverMonitoringOn": bool(driver_status.monitor_on), "canMonoTimes": list(CS.canMonoTimes), "planMonoTime": plan_ts, "enabled": isEnabled(state), @@ -446,7 +447,6 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.): CP.safetyModel = car.CarParams.SafetyModels.noOutput fcw_enabled = params.get("IsFcwEnabled") == "1" - driver_monitor_on = params.get("IsDriverMonitoringEnabled") == "1" geofence = None try: from selfdrive.controls.lib.geofence import Geofence @@ -460,7 +460,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.): VM = VehicleModel(CP) LaC = LatControl(VM) AM = AlertManager() - driver_status = DriverStatus(driver_monitor_on) + driver_status = DriverStatus() if not passive: AM.add("startup", False) @@ -516,7 +516,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.): prof.checkpoint("State Control") # publish data - CC = data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, + 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) prof.checkpoint("Sent") diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 9d053c211fb496..2fd716c3d2134a 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -74,7 +74,7 @@ class AlertManager(object): Priority.MID, None, "beepSingle", .2, 0., 0.), "fcw": Alert( - "Brake!", + "BRAKE!", "Risk of Collision", AlertStatus.critical, AlertSize.full, Priority.HIGHEST, "fcw", "chimeRepeated", 1., 2., 2.), @@ -98,23 +98,53 @@ class AlertManager(object): Priority.LOW, None, None, .2, .2, .2), "preDriverDistracted": Alert( - "TAKE CONTROL: User Appears Distracted", + "KEEP EYES ON ROAD: User Appears Distracted", "", AlertStatus.normal, AlertSize.small, Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), "promptDriverDistracted": Alert( - "TAKE CONTROL", + "KEEP EYES ON ROAD", "User Appears Distracted", AlertStatus.userPrompt, AlertSize.mid, Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), "driverDistracted": Alert( - "DISENGAGEMENT REQUIRED", + "DISENGAGE IMMEDIATELY", "User Was Distracted", AlertStatus.critical, AlertSize.full, Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), + "preDriverUnresponsive": Alert( + "TOUCH STEERING WHEEL: No Driver Monitoring", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), + + "promptDriverUnresponsive": Alert( + "TOUCH STEERING WHEEL", + "User Is Unresponsive", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), + + "driverUnresponsive": Alert( + "DISENGAGE IMMEDIATELY", + "User Was Unresponsive", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), + + "driverMonitorOff": Alert( + "DRIVER MONITOR IS UNAVAILABLE", + "Accuracy Is Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, None, .4, 0., 4.), + + "driverMonitorOn": Alert( + "DRIVER MONITOR IS AVAILABLE", + "Accuracy Is High", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, None, .4, 0., 4.), + "geofence": Alert( "DISENGAGEMENT REQUIRED", "Not in Geofenced Area", diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py index a593f1091dc6f9..a70eb498455c6f 100644 --- a/selfdrive/controls/lib/driver_monitor.py +++ b/selfdrive/controls/lib/driver_monitor.py @@ -18,11 +18,21 @@ _PITCH_WEIGHT = 1.5 # pitch matters a lot more _METRIC_THRESHOLD = 0.4 _PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch -_DTM = 0.2 # driver monitor runs at 5Hz -_DISTRACTED_FILTER_F = 0.3 # 0.3Hz -_DISTRACTED_FILTER_K = 2 * np.pi * _DISTRACTED_FILTER_F * _DTM / (1 + 2 * np.pi * _DISTRACTED_FILTER_F * _DTM) +_DTM = 0.1 # driver monitor runs at 10Hz _PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up +_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid +_DISTRACTED_FILTER_F = 0.6 # 0.6Hz, 0.25s ts +_DISTRACTED_FILTER_K = 2 * np.pi * _DISTRACTED_FILTER_F * _DTM / (1 + 2 * np.pi * _DISTRACTED_FILTER_F * _DTM) +_VARIANCE_FILTER_F = 0.008 # 0.008Hz, 20s ts +_VARIANCE_FILTER_K = 2 * np.pi * _VARIANCE_FILTER_F * _DTM / (1 + 2 * np.pi * _VARIANCE_FILTER_F * _DTM) + +class MonitorChangeEvent: + NO_CHANGE = 0 + PARAM_ON = 1 + PARAM_OFF = 2 + VARIANCE_HIGH = 3 + VARIANCE_LOW = 4 class _DriverPose(): def __init__(self): @@ -32,16 +42,30 @@ def __init__(self): self.yaw_offset = 0. self.pitch_offset = 0. +def _monitor_hysteresys(variance_level, monitor_valid_prev): + var_thr = 0.63 if monitor_valid_prev else 0.37 + return variance_level < var_thr + class DriverStatus(): - def __init__(self, monitor_on): + def __init__(self, monitor_on=False): self.pose = _DriverPose() self.monitor_on = monitor_on + self.monitor_param_on = monitor_on + self.monitor_valid = True # variance needs to be low + self.monitor_change_event = MonitorChangeEvent.NO_CHANGE self.awareness = 1. self.driver_distracted = False self.driver_distraction_level = 0. + self.variance_high = False + self.variance_level = 0. self.ts_last_check = 0. self._set_timers() + def _reset_filters(self): + self.driver_distraction_level = 0. + self.variance_level = 0. + self.monitor_valid = True + def _set_timers(self): if self.monitor_on: self.threshold_pre = _DISTRACTED_PRE_TIME / _DISTRACTED_TIME @@ -64,14 +88,23 @@ def _is_driver_distracted(self, pose): #print "%02.4f" % np.degrees(pose.pitch), "%02.4f" % np.degrees(pitch_error), "%03.4f" % np.degrees(pose.pitch_offset), metric return 1 if metric > _METRIC_THRESHOLD else 0 - def get_pose(self, driver_monitoring, params): - ts = sec_since_boot() - # don's check for param too often as it's a kernel call - if ts - self.ts_last_check > 1.: - self.monitor_on = params.get("IsDriverMonitoringEnabled") == "1" - self._set_timers() - self.ts_last_check = ts + def _monitor_change_check(self, monitor_param_on_prev, monitor_valid_prev, monitor_on_prev): + if not monitor_param_on_prev and self.monitor_param_on: + self._reset_filters() + return MonitorChangeEvent.PARAM_ON + elif monitor_param_on_prev and not self.monitor_param_on: + self._reset_filters() + return MonitorChangeEvent.PARAM_OFF + elif monitor_on_prev and not self.monitor_valid: + return MonitorChangeEvent.VARIANCE_HIGH + elif self.monitor_param_on and not monitor_valid_prev and self.monitor_valid: + return MonitorChangeEvent.VARIANCE_LOW + else: + return MonitorChangeEvent.NO_CHANGE + + + def get_pose(self, driver_monitoring, params): self.pose.pitch = driver_monitoring.descriptor[0] self.pose.yaw = driver_monitoring.descriptor[1] @@ -79,9 +112,28 @@ def get_pose(self, driver_monitoring, params): self.pose.yaw_offset = (driver_monitoring.descriptor[3] * _CAMERA_X_CONV + _CAMERA_OFFSET_X) * _CAMERA_FOV_X self.pose.pitch_offset = -driver_monitoring.descriptor[4] * _CAMERA_FOV_Y # positive y is down self.driver_distracted = self._is_driver_distracted(self.pose) - # first order filter + # first order filters self.driver_distraction_level = (1. - _DISTRACTED_FILTER_K) * self.driver_distraction_level + \ _DISTRACTED_FILTER_K * self.driver_distracted + self.variance_high = driver_monitoring.std > _STD_THRESHOLD + self.variance_level = (1. - _VARIANCE_FILTER_K) * self.variance_level + \ + _VARIANCE_FILTER_K * self.variance_high + + monitor_param_on_prev = self.monitor_param_on + monitor_valid_prev = self.monitor_valid + monitor_on_prev = self.monitor_on + + # don't check for param too often as it's a kernel call + ts = sec_since_boot() + if ts - self.ts_last_check > 1.: + self.monitor_param_on = params.get("IsDriverMonitoringEnabled") == "1" + self.ts_last_check = ts + + self.monitor_valid = _monitor_hysteresys(self.variance_level, monitor_valid_prev) + self.monitor_on = self.monitor_valid and self.monitor_param_on + self.monitor_change_event = self._monitor_change_check(monitor_param_on_prev, monitor_valid_prev, monitor_on_prev) + self._set_timers() + def update(self, events, driver_engaged, ctrl_active, standstill): @@ -90,20 +142,28 @@ def update(self, events, driver_engaged, ctrl_active, standstill): if (driver_engaged and self.awareness > 0.) or not ctrl_active: # always reset if driver is in control (unless we are in red alert state) or op isn't active self.awareness = 1. + if not ctrl_active: + # hold monitor_level constant when control isn't active + self.variance_level = 0. if self.monitor_valid else 1. if (not self.monitor_on or (self.driver_distraction_level > 0.63 and self.driver_distracted)) and \ not (standstill and self.awareness - self.step_change <= self.threshold_prompt): self.awareness = max(self.awareness - self.step_change, -0.1) + alert = None if self.awareness <= 0.: # terminal red alert: disengagement required - events.append(create_event('driverDistracted', [ET.WARNING])) + alert = 'driverDistracted' if self.monitor_on else 'driverUnresponsive' elif self.awareness <= self.threshold_prompt: # prompt orange alert - events.append(create_event('promptDriverDistracted', [ET.WARNING])) + alert = 'promptDriverDistracted' if self.monitor_on else 'promptDriverUnresponsive' elif self.awareness <= self.threshold_pre: # pre green alert - events.append(create_event('preDriverDistracted', [ET.WARNING])) + alert = 'preDriverDistracted' if self.monitor_on else 'preDriverUnresponsive' + if alert is not None: + events.append(create_event(alert, [ET.WARNING])) + + self.monitor_change_event = MonitorChangeEvent.NO_CHANGE return events diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 11d1d847db08ad..451330fe0643a8 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -1,11 +1,11 @@ #!/usr/bin/env python import os import zmq - -import numpy as np import math +import numpy as np +from copy import copy +from cereal import log from collections import defaultdict - from common.realtime import sec_since_boot from common.numpy_fast import interp import selfdrive.messaging as messaging @@ -303,6 +303,7 @@ def __init__(self, CP, fcw_enabled): self.last_gps_planner_plan = None self.gps_planner_active = False + self.perception_state = log.Live20Data.new_message() def choose_solution(self, v_cruise_setpoint, enabled): if enabled: @@ -374,6 +375,7 @@ def update(self, CS, LaC, LoC, v_cruise_kph, force_slow_decel): self.PP.c_prob = 1.0 if l20 is not None: + self.perception_state = copy(l20.live20) self.last_l20_ts = l20.logMonoTime self.last_l20 = cur_time self.radar_dead = False diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 5f69085cf2b5e2..301d04c6476598 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -26,6 +26,7 @@ XV, SPEEDV = 0, 1 VISION_POINT = -1 + class EKFV1D(EKF): def __init__(self): super(EKFV1D, self).__init__(False) @@ -137,7 +138,8 @@ def radard_thread(gctx=None): # run kalman filter only if prob is high enough if PP.lead_prob > 0.7: - ekfv.update(speedSensorV.read(PP.lead_dist, covar=PP.lead_var)) + reading = speedSensorV.read(PP.lead_dist, covar=np.matrix(PP.lead_var)) + ekfv.update_scalar(reading) ekfv.predict(tsv) ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])), float(ekfv.state[SPEEDV]), False) @@ -145,6 +147,7 @@ def radard_thread(gctx=None): ekfv.state[XV] = PP.lead_dist ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) ekfv.state[SPEEDV] = 0. + if VISION_POINT in ar_pts: del ar_pts[VISION_POINT] diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd index 7ed8ac45d5a288..67d21aad9b07a7 100755 Binary files a/selfdrive/loggerd/loggerd and b/selfdrive/loggerd/loggerd differ diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 5c2d3a4108bf18..81a4bd981e86d8 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -118,7 +118,6 @@ def get_running(): 'uploader', 'ui', 'gpsd', - 'ubloxd', 'updated', ] @@ -129,7 +128,7 @@ def get_running(): 'radard', 'visiond', 'proclogd', - 'orbd', + 'ubloxd', ] def register_managed_process(name, desc, car_started=False): @@ -298,6 +297,9 @@ def manager_thread(): cloudlog.info("manager start") cloudlog.info({"environ": os.environ}) + # save boot log + subprocess.call(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd")) + for p in persistent_processes: start_managed_process(p) diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd index 20e5332795d31b..84705bbc8c4d47 100755 Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index 58f9d233c70ba6..49d7db520572c3 100755 Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py index 97e63b143892c0..6db8b61bc1e666 100755 --- a/selfdrive/thermald.py +++ b/selfdrive/thermald.py @@ -2,7 +2,7 @@ import os import zmq from smbus2 import SMBus - +from cereal import log from selfdrive.version import training_version from selfdrive.swaglog import cloudlog import selfdrive.messaging as messaging @@ -10,9 +10,9 @@ from selfdrive.loggerd.config import ROOT from common.params import Params from common.realtime import sec_since_boot +from common.numpy_fast import clip -import cereal -ThermalStatus = cereal.log.ThermalData.ThermalStatus +ThermalStatus = log.ThermalData.ThermalStatus def read_tz(x): with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: @@ -71,12 +71,12 @@ def set_eon_fan(val): _TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] # fan speed options _FAN_SPEEDS = [0, 16384, 32768, 65535] -# max fan speed only allowed if battery if hot +# max fan speed only allowed if battery is hot _BAT_TEMP_THERSHOLD = 45. -def handle_fan(max_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_temp) - new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_temp) +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) if new_speed_h > fan_speed: # update speed if using the high thresholds results in fan speed increment @@ -164,31 +164,32 @@ def thermald_thread(): msg.thermal.usbOnline = bool(int(f.read())) # TODO: add car battery voltage check - max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, - msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + max_cpu_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, + msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + max_comp_temp = max(max_cpu_temp, msg.thermal.mem / 10., msg.thermal.gpu / 10.) bat_temp = msg.thermal.bat/1000. - fan_speed = handle_fan(max_temp, bat_temp, fan_speed) + fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed) msg.thermal.fanSpeed = fan_speed - # thermal logic here - - if max_temp < 70.0: - thermal_status = ThermalStatus.green - if max_temp > 85.0: - cloudlog.warning("over temp: %r", max_temp) - thermal_status = ThermalStatus.yellow - - # from controls - overtemp_proc = any(t > 950 for t in - (msg.thermal.cpu0, msg.thermal.cpu1, msg.thermal.cpu2, - msg.thermal.cpu3, msg.thermal.mem, msg.thermal.gpu)) - overtemp_bat = msg.thermal.bat > 60000 # 60c - if overtemp_proc or overtemp_bat: - # TODO: hysteresis - thermal_status = ThermalStatus.red - - if max_temp > 107.0 or msg.thermal.bat >= 63000: + # thermal logic with hysterisis + if max_cpu_temp > 107. or bat_temp >= 63.: + # onroad not allowed thermal_status = ThermalStatus.danger + elif max_comp_temp > 95. or bat_temp > 60.: + # hysteresis between onroad not allowed and engage not allowed + thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger) + elif max_cpu_temp > 90.0: + # hysteresis between engage not allowed and uploader not allowed + thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red) + elif max_cpu_temp > 85.0: + # uploader not allowed + thermal_status = ThermalStatus.yellow + elif max_cpu_temp > 75.0: + # hysteresis between uploader not allowed and all good + thermal_status = clip(thermal_status, ThermalStatus.green, ThermalStatus.yellow) + else: + # all good + thermal_status = ThermalStatus.green # **** starting logic **** @@ -225,7 +226,7 @@ def thermald_thread(): # if any CPU gets above 107 or the battery gets above 63, kill all processes # controls will warn with CPU above 95 or battery above 60 - if msg.thermal.thermalStatus >= ThermalStatus.danger: + if thermal_status >= ThermalStatus.danger: # TODO: Add a better warning when this is happening should_start = False diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index 6948a492f546c0..bc53a6a41f7dd6 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -65,6 +65,8 @@ const int box_w = vwp_w-sbr_w-(bdr_s*2); const int box_h = vwp_h-(bdr_s*2); const int viz_w = vwp_w-(bdr_s*2); const int header_h = 420; +const int footer_h = 280; +const int footer_y = vwp_h-bdr_s-footer_h; const uint8_t bg_colors[][4] = { [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff}, @@ -110,6 +112,7 @@ typedef struct UIScene { float curvature; int engaged; bool engageable; + bool monitoring_active; bool uilayout_sidebarcollapsed; bool uilayout_mapenabled; @@ -158,6 +161,7 @@ typedef struct UIState { int font_sans_semibold; int font_sans_bold; int img_wheel; + int img_face; zsock_t *thermal_sock; void *thermal_sock_raw; @@ -379,6 +383,9 @@ static void ui_init(UIState *s) { assert(s->img_wheel >= 0); s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1); + assert(s->img_face >= 0); + s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1); + // init gl s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader); assert(s->frame_program); @@ -981,6 +988,31 @@ static void ui_draw_vision_wheel(UIState *s) { nvgFill(s->vg); } +static void ui_draw_vision_face(UIState *s) { + const UIScene *scene = &s->scene; + const int face_size = 96; + const int face_x = (scene->ui_viz_rx + face_size + (bdr_s * 2)); + const int face_y = (footer_y + ((footer_h - face_size) / 2)); + const int face_img_size = (face_size * 1.5); + const int face_img_x = (face_x - (face_img_size / 2)); + const int face_img_y = (face_y - (face_size / 4)); + float face_img_alpha = scene->monitoring_active ? 1.0f : 0.15f; + float face_bg_alpha = scene->monitoring_active ? 0.3f : 0.1f; + NVGcolor face_bg = nvgRGBA(0, 0, 0, (255 * face_bg_alpha)); + NVGpaint face_img = nvgImagePattern(s->vg, face_img_x, face_img_y, + face_img_size, face_img_size, 0, s->img_face, face_img_alpha); + + nvgBeginPath(s->vg); + nvgCircle(s->vg, face_x, (face_y + (bdr_s * 1.5)), face_size); + nvgFillColor(s->vg, face_bg); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + nvgRect(s->vg, face_img_x, face_img_y, face_img_size, face_img_size); + nvgFillPaint(s->vg, face_img); + nvgFill(s->vg); +} + static void ui_draw_vision_header(UIState *s) { const UIScene *scene = &s->scene; int ui_viz_rx = scene->ui_viz_rx; @@ -1000,6 +1032,18 @@ static void ui_draw_vision_header(UIState *s) { ui_draw_vision_wheel(s); } +static void ui_draw_vision_footer(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + nvgBeginPath(s->vg); + nvgRect(s->vg, ui_viz_rx, footer_y, ui_viz_rw, footer_h); + + // Driver Monitoring + ui_draw_vision_face(s); +} + static void ui_draw_vision_alert(UIState *s, int va_size, int va_color, const char* va_text1, const char* va_text2) { const UIScene *scene = &s->scene; @@ -1109,8 +1153,11 @@ static void ui_draw_vision(UIState *s) { } else if (scene->cal_status == CALIBRATION_UNCALIBRATED) { // Calibration Status ui_draw_calibration_status(s); + } else { + ui_draw_vision_footer(s); } + nvgEndFrame(s->vg); glDisable(GL_BLEND); } @@ -1399,6 +1446,7 @@ static void ui_update(UIState *s) { s->scene.engaged = datad.enabled; s->scene.engageable = datad.engageable; s->scene.gps_planner_active = datad.gpsPlannerActive; + s->scene.monitoring_active = datad.driverMonitoringOn; // printf("recv %f\n", datad.vEgo); s->scene.frontview = datad.rearViewCam; @@ -1634,12 +1682,6 @@ static void* light_sensor_thread(void *args) { int SENSOR_LIGHT = 7; - struct stat buffer; - if (stat("/sys/bus/i2c/drivers/cyccg", &buffer) == 0) { - LOGD("LeEco light sensor detected"); - SENSOR_LIGHT = 5; - } - device->activate(device, SENSOR_LIGHT, 0); device->activate(device, SENSOR_LIGHT, 1); device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); @@ -1653,9 +1695,7 @@ static void* light_sensor_thread(void *args) { LOG_100("light_sensor_poll failed: %d", n); } if (n > 0) { - if (SENSOR_LIGHT == 5) s->light_sensor = buffer[0].light * 2; - else s->light_sensor = buffer[0].light; - //printf("new light sensor value: %f\n", s->light_sensor); + s->light_sensor = buffer[0].light; } } diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 1a4867061edaad..89ad0fcdff3a6a 100755 Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ