diff --git a/README.md b/README.md index 01ca0d824831b0..256271eebc710a 100644 --- a/README.md +++ b/README.md @@ -29,6 +29,9 @@ Supported Cars - Honda CR-V Touring 2015-2016 - Can only be enabled above 25 mph +- Honda Odyssey 2018 with Honda Sensing (alpha!) + - Can only be enabled above 25 mph + - Toyota RAV-4 2016+ non-hybrid with TSS-P - By default it uses stock Toyota ACC for longitudinal control - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can be enabled above 20 mph @@ -42,6 +45,10 @@ Supported Cars - By default it uses stock Toyota ACC for longitudinal control - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Rav4_.28for_openpilot.29) and can do stop and go +- Toyota Corolla 2017 (alpha!) + - By default it uses stock Toyota ACC for longitudinal control + - openpilot longitudinal control available after unplugging the [Driving Support ECU](https://community.comma.ai/wiki/index.php/Toyota#Corolla_.28for_openpilot.29) and can be enabled above 20 mph + In Progress Cars ------ - Probably all TSS-P Toyota with Steering Assist. @@ -55,8 +62,6 @@ Community WIP Cars - [Classic Tesla Model S (pre-AP)](https://github.com/commaai/openpilot/pull/145) -- [Honda Odyssey 2018 with Honda Sensing](https://github.com/commaai/openpilot/pull/155) - - [Honda Pilot 2017 with Honda Sensing](https://github.com/commaai/openpilot/pull/161) - [Acura RDX 2018 with AcuraWatch Plus](https://github.com/commaai/openpilot/pull/162) @@ -79,7 +84,6 @@ Directory structure - logcatd -- Android logcat as a service - loggerd -- Logger and uploader of car data - proclogd -- Logs information from proc - - radar -- Code that talks to the radar and implements RadarInterface - sensord -- IMU / GPS interface code - test/plant -- Car simulator running code through virtual maneuvers - ui -- The UI diff --git a/RELEASES.md b/RELEASES.md index 24e80ad68b0a01..4e0c81fe84a429 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,9 @@ +Version 0.4.1 (2018-01-30) +========================== + * Add alpha support for 2017 Toyota Corolla + * Add alpha support for Grey Panda + * Refactored car abstraction layer to make car ports easier + Version 0.4.0.2 (2018-01-18) ========================== * Add focus adjustment slider diff --git a/cereal/car.capnp b/cereal/car.capnp index 63857ed744c631..be31f6628d8efe 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -97,6 +97,11 @@ struct CarState { buttonEvents @11 :List(ButtonEvent); leftBlinker @20 :Bool; rightBlinker @21 :Bool; + genericToggle @23 :Bool; + + # lock info + doorOpen @24 :Bool; + seatbeltUnlatched @25 :Bool; # which packets this state came from canMonoTimes @12: List(UInt64); @@ -250,7 +255,7 @@ struct CarControl { struct CarParams { carName @0 :Text; - radarName @1 :Text; + radarNameDEPRECATED @1 :Text; carFingerprint @2 :Text; enableSteer @3 :Bool; @@ -263,6 +268,7 @@ struct CarParams { minEnableSpeed @17 :Float32; safetyModel @18 :Int16; + safetyParam @41 :Int16; steerMaxBP @19 :List(Float32); steerMaxV @20 :List(Float32); diff --git a/cereal/log.capnp b/cereal/log.capnp index 70dcdab7628008..f6df60cd5a5464 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -573,6 +573,16 @@ struct LiveLocationData { accuracy @13 :Accuracy; + source @14 :SensorSource; + # if we are fixing a location in the past + fixMonoTime @15 :UInt64; + + gpsWeek @16 :Int32; + timeOfWeek @17 :Float64; + + positionECEF @18 :List(Float64); + poseQuatECEF @19 :List(Float32); + struct Accuracy { pNEDError @0 :List(Float32); vNEDError @1 :List(Float32); @@ -583,6 +593,13 @@ struct LiveLocationData { ellipsoidSemiMinorError @6 :Float32; ellipsoidOrientationError @7 :Float32; } + + enum SensorSource { + applanix @0; + kalman @1; + orbslam @2; + timing @3; + } } struct EthernetPacket { @@ -1331,6 +1348,34 @@ struct GPSPlannerPlan { valid @0 :Bool; poly @1 :List(Float32); trackName @2 :Text; + speed @3 :Float32; +} + +struct TrafficSigns { + type @0 :Type; + distance @1 :Float32; + action @2 :Action; + resuming @3 :Bool; + + enum Type { + light @0; + } + + enum Action { + none @0; + yield @1; + stop @2; + } + +} + +struct OrbslamCorrection { + correctionMonoTime @0 :UInt64; + prePositionECEF @1 :List(Float64); + postPositionECEF @2 :List(Float64); + prePoseQuatECEF @3 :List(Float32); + postPoseQuatECEF @4 :List(Float32); + numInliers @5 :UInt32; } struct Event { @@ -1379,5 +1424,10 @@ struct Event { ubloxRaw @39 :Data; gpsPlannerPoints @40 :GPSPlannerPoints; gpsPlannerPlan @41 :GPSPlannerPlan; + applanixRaw @42 :Data; + trafficSigns @43 :List(TrafficSigns); + liveLocationTiming @44 :LiveLocationData; + orbslamCorrection @45 :OrbslamCorrection; + liveLocationCorrected @46 :LiveLocationData; } } diff --git a/common/dbc.py b/common/dbc.py index 8865ae0f582611..8be1eed13cdffa 100755 --- a/common/dbc.py +++ b/common/dbc.py @@ -2,6 +2,8 @@ import os import struct import bitstring +import sys +import numbers from collections import namedtuple def int_or_float(s): @@ -49,6 +51,8 @@ def __init__(self, fn): name = dat.group(2) size = int(dat.group(3)) ids = int(dat.group(1), 0) # could be hex + if ids in self.msgs: + sys.exit("Duplicate address detected %d %s" % (ids, self.name)) self.msgs[ids] = ((name, size), []) @@ -80,6 +84,16 @@ def __init__(self, fn): for msg in self.msgs.viewvalues(): msg[1].sort(key=lambda x: x.start_bit) + self.msg_name_to_address = {} + for address, m in self.msgs.items(): + name = m[0][0] + self.msg_name_to_address[name] = address + + def lookup_msg_id(self, msg_id): + if not isinstance(msg_id, numbers.Number): + msg_id = self.msg_name_to_address[msg_id] + return msg_id + def encode(self, msg_id, dd): """Encode a CAN message using the dbc. @@ -87,6 +101,8 @@ def encode(self, msg_id, dd): msg_id: The message ID. dd: A dictionary mapping signal name to signal data. """ + msg_id = self.lookup_msg_id(msg_id) + # TODO: Stop using bitstring, which is super slow. msg_def = self.msgs[msg_id] size = msg_def[0][1] @@ -134,7 +150,7 @@ def decode(self, x, arr=None, debug=False): Returns (None, None) if the message could not be decoded. """ - + if arr is None: out = {} else: @@ -193,10 +209,10 @@ def decode(self, x, arr=None, debug=False): out[arr.index(s[0])] = ival return name, out - def get_signals(self, msg): + msg = self.lookup_msg_id(msg) return [sgs.name for sgs in self.msgs[msg][1]] - + if __name__ == "__main__": import sys import os diff --git a/common/fingerprints.py b/common/fingerprints.py index 952528560d0e55..462c33b57eca32 100644 --- a/common/fingerprints.py +++ b/common/fingerprints.py @@ -1,33 +1,57 @@ -import os +class HONDA: + CIVIC = "HONDA CIVIC 2016 TOURING" + ACURA_ILX = "ACURA ILX 2016 ACURAWATCH PLUS" + CRV = "HONDA CR-V 2016 TOURING" + ODYSSEY = "HONDA ODYSSEY 2018 EX-L" + + +class TOYOTA: + PRIUS = "TOYOTA PRIUS 2017" + RAV4H = "TOYOTA RAV4 2017 HYBRID" + RAV4 = "TOYOTA RAV4 2017" + COROLLA = "TOYOTA COROLLA 2017" + _FINGERPRINTS = { - "ACURA ILX 2016 ACURAWATCH PLUS": { + HONDA.ACURA_ILX: { 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 929L: 4, 1057L: 5, 777L: 8, 1034L: 5, 1036L: 8, 398L: 3, 399L: 7, 145L: 8, 660L: 8, 985L: 3, 923L: 2, 542L: 7, 773L: 7, 800L: 8, 432L: 7, 419L: 8, 420L: 8, 1030L: 5, 422L: 8, 808L: 8, 428L: 8, 304L: 8, 819L: 7, 821L: 5, 57L: 3, 316L: 8, 545L: 4, 464L: 8, 1108L: 8, 597L: 8, 342L: 6, 983L: 8, 344L: 8, 804L: 8, 1039L: 8, 476L: 4, 892L: 8, 490L: 8, 1064L: 7, 882L: 2, 884L: 7, 887L: 8, 888L: 8, 380L: 8, 1365L: 5, # sent messages 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, }, - "HONDA CIVIC 2016 TOURING": { + HONDA.CIVIC: { 1024L: 5, 513L: 5, 1027L: 5, 1029L: 8, 777L: 8, 1036L: 8, 1039L: 8, 1424L: 5, 401L: 8, 148L: 8, 662L: 4, 985L: 3, 795L: 8, 773L: 7, 800L: 8, 545L: 6, 420L: 8, 806L: 8, 808L: 8, 1322L: 5, 427L: 3, 428L: 8, 304L: 8, 432L: 7, 57L: 3, 450L: 8, 929L: 8, 330L: 8, 1302L: 8, 464L: 8, 1361L: 5, 1108L: 8, 597L: 8, 470L: 2, 344L: 8, 804L: 8, 399L: 7, 476L: 7, 1633L: 8, 487L: 4, 892L: 8, 490L: 8, 493L: 5, 884L: 8, 891L: 8, 380L: 8, 1365L: 5, # sent messages 0xe4: 5, 0x1fa: 8, 0x200: 3, 0x30c: 8, 0x33d: 5, 0x35e: 8, 0x39f: 8, }, - "HONDA CR-V 2016 TOURING": { + HONDA.CRV: { 57L: 3, 145L: 8, 316L: 8, 340L: 8, 342L: 6, 344L: 8, 380L: 8, 398L: 3, 399L: 6, 401L: 8, 420L: 8, 422L: 8, 426L: 8, 432L: 7, 464L: 8, 474L: 5, 476L: 4, 487L: 4, 490L: 8, 493L: 3, 507L: 1, 542L: 7, 545L: 4, 597L: 8, 660L: 8, 661L: 4, 773L: 7, 777L: 8, 800L: 8, 804L: 8, 808L: 8, 882L: 2, 884L: 7, 888L: 8, 891L: 8, 892L: 8, 923L: 2, 929L: 8, 983L: 8, 985L: 3, 1024L: 5, 1027L: 5, 1029L: 8, 1033L: 5, 1036L: 8, 1039L: 8, 1057L: 5, 1064L: 7, 1108L: 8, 1125L: 8, 1296L: 8, 1365L: 5, 1424L: 5, 1600L: 5, 1601L: 8, # sent messages 0x194: 4, 0x1fa: 8, 0x30c: 8, 0x33d: 5, }, - "HONDA ODYSSEY 2018 EX-L": { + HONDA.ODYSSEY: { 57L: 3, 148L: 8, 228L: 5, 229L: 4, 316L: 8, 342L: 6, 344L: 8, 380L: 8, 399L: 7, 411L: 5, 419L: 8, 420L: 8, 427L: 3, 432L: 7, 450L: 8, 463L: 8, 464L: 8, 476L: 4, 490L: 8, 506L: 8, 542L: 7, 545L: 6, 597L: 8, 662L: 4, 773L: 7, 777L: 8, 780L: 8, 795L: 8, 800L: 8, 804L: 8, 806L: 8, 808L: 8, 817L: 4, 819L: 7, 821L: 5, 825L: 4, 829L: 5, 837L: 5, 856L: 7, 862L: 8, 871L: 8, 881L: 8, 882L: 4, 884L: 8, 891L: 8, 892L: 8, 905L: 8, 923L: 2, 927L: 8, 929L: 8, 963L: 8, 965L: 8, 966L: 8, 967L: 8, 983L: 8, 985L: 3, 1029L: 8, 1036L: 8, 1052L: 8, 1064L: 7, 1088L: 8, 1089L: 8, 1092L: 1, 1108L: 8, 1110L: 8, 1125L: 8, 1296L: 8, 1302L: 8, 1600L: 5, 1601L: 8, 1612L: 5, 1613L: 5, 1614L: 5, 1615L: 8, 1616L: 5, 1619L: 5, 1623L: 5, 1668L: 5 }, - "TOYOTA RAV4 2017": { + TOYOTA.RAV4: { 36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 552L: 4, 562L: 4, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 725L: 2, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 918L: 7, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 951L: 8, 955L: 4, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1008L: 2, 1014L: 8, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1593L: 8, 1595L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1656L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 }, - "TOYOTA RAV4 2017 HYBRID": { + TOYOTA.RAV4H: { 36L: 8, 37L: 8, 170L: 8, 180L: 8, 186L: 4, 426L: 6, 452L: 8, 464L: 8, 466L: 8, 467L: 8, 547L: 8, 548L: 8, 552L: 4, 562L: 4, 608L: 8, 610L: 5, 643L: 7, 705L: 8, 725L: 2, 740L: 5, 800L: 8, 835L: 8, 836L: 8, 849L: 4, 869L: 7, 870L: 7, 871L: 2, 896L: 8, 897L: 8, 900L: 6, 902L: 6, 905L: 8, 911L: 8, 916L: 3, 918L: 7, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 951L: 8, 955L: 8, 956L: 8, 979L: 2, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1008L: 2, 1014L: 8, 1017L: 8, 1041L: 8, 1042L: 8, 1043L: 8, 1044L: 8, 1056L: 8, 1059L: 1, 1114L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1176L: 8, 1177L: 8, 1178L: 8, 1179L: 8, 1180L: 8, 1181L: 8, 1190L: 8, 1191L: 8, 1192L: 8, 1196L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1263L: 8, 1279L: 8, 1408L: 8, 1409L: 8, 1410L: 8, 1552L: 8, 1553L: 8, 1554L: 8, 1555L: 8, 1556L: 8, 1557L: 8, 1561L: 8, 1562L: 8, 1568L: 8, 1569L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1584L: 8, 1589L: 8, 1592L: 8, 1593L: 8, 1595L: 8, 1596L: 8, 1597L: 8, 1600L: 8, 1656L: 8, 1664L: 8, 1728L: 8, 1745L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8, 581L: 5, 296: 8, 552L: 8, 560L: 7, 552L: 4, 713L: 8, 550L: 8, 608L: 8, 37L: 8, 36L: 8, 950L: 8, 1198L: 8, 1197L: 8, 1199L: 8, 1212L: 8, 953L: 3, 1264L: 8, 1184L: 8, 1005L: 2, 1185L: 8, 1232L: 8, 1186L: 8 }, - "TOYOTA PRIUS 2017": { + TOYOTA.PRIUS: [{ 36L: 8, 37L: 8, 166L: 8, 170L: 8, 180L: 8, 295L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 6, 581L: 5, 608L: 8, 610L: 8, 614L: 8, 643L: 7, 658L: 8, 713L: 8, 740L: 5, 742L: 8, 743L: 8, 800L: 8, 810L: 2, 814L: 8, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 863L: 8, 869L: 7, 870L: 7, 871L: 2, 898L: 8, 900L: 6, 902L: 6, 905L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1279L: 8, 1552L: 8, 1553L: 8, 1556L: 8, 1557L: 8, 1568L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1595L: 8, 1777L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 }, + # Prius Prime + { + 36L: 8, 37L: 8, 166L: 8, 170L: 8, 180L: 8, 295L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 6, 581L: 5, 608L: 8, 610L: 8, 614L: 8, 643L: 7, 658L: 8, 713L: 8, 740L: 5, 742L: 8, 743L: 8, 800L: 8, 810L: 2, 814L: 8, 824L: 2, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 863L: 8, 869L: 7, 870L: 7, 871L: 2,898L: 8, 900L: 6, 902L: 6, 905L: 8, 913L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 974L: 8, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1076L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1164L: 8, 1165L: 8, 1166L: 8, 1167L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1279L: 8, 1552L: 8, 1553L: 8, 1556L: 8, 1557L: 8, 1568L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1595L: 8, 1777L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 + }, + # Taiwanese Prius Prime + { + 36L: 8, 37L: 8, 166L: 8, 170L: 8, 180L: 8, 295L: 8, 296L: 8, 426L: 6, 452L: 8, 466L: 8, 467L: 8, 550L: 8, 552L: 4, 560L: 7, 562L: 6, 581L: 5, 608L: 8, 610L: 8, 614L: 8, 643L: 7, 658L: 8, 713L: 8, 740L: 5, 742L: 8, 743L: 8, 800L: 8, 810L: 2, 814L: 8, 824L: 2, 829L: 2, 830L: 7, 835L: 8, 836L: 8, 863L: 8, 869L: 7, 870L: 7, 871L: 2,898L: 8, 900L: 6, 902L: 6, 905L: 8, 913L: 8, 918L: 8, 921L: 8, 933L: 8, 944L: 8, 945L: 8, 950L: 8, 951L: 8, 953L: 8, 955L: 8, 956L: 8, 971L: 7, 974L: 8, 975L: 5, 993L: 8, 998L: 5, 999L: 7, 1000L: 8, 1001L: 8, 1014L: 8, 1017L: 8, 1020L: 8, 1041L: 8, 1042L: 8, 1044L: 8, 1056L: 8, 1057L: 8, 1059L: 1, 1071L: 8, 1076L: 8, 1077L: 8, 1082L: 8, 1083L: 8, 1084L: 8, 1085L: 8, 1086L: 8, 1114L: 8, 1132L: 8, 1161L: 8, 1162L: 8, 1163L: 8, 1164L: 8, 1165L: 8, 1166L: 8, 1167L: 8, 1175L: 8, 1227L: 8, 1228L: 8, 1235L: 8, 1237L: 8, 1279L: 8, 1552L: 8, 1553L: 8, 1556L: 8, 1557L: 8, 1568L: 8, 1570L: 8, 1571L: 8, 1572L: 8, 1595L: 8, 1777L: 8, 1779L: 8, 1904L: 8, 1912L: 8, 1990L: 8, 1998L: 8 + } + ], + TOYOTA.COROLLA: { + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, } # support additional internal only fingerprints @@ -37,6 +61,12 @@ except ImportError: pass + +def is_valid_for_fingerprint(msg, car_fingerprint): + adr = msg.address + return msg.src != 0 or (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) + + def eliminate_incompatible_cars(msg, candidate_cars): """Removes cars that could not have sent msg. @@ -49,16 +79,18 @@ def eliminate_incompatible_cars(msg, candidate_cars): """ compatible_cars = [] for car_name in candidate_cars: - adr = msg.address - if msg.src != 0 or (adr in _FINGERPRINTS[car_name] and - _FINGERPRINTS[car_name][adr] == len(msg.dat)): - compatible_cars.append(car_name) - else: - pass - #isin = adr in _FINGERPRINTS[car_name] - #print "eliminate", car_name, hex(adr), isin, len(msg.dat), msg.dat.encode("hex") + car_fingerprints = _FINGERPRINTS[car_name] + if not isinstance(car_fingerprints, list): + car_fingerprints = [car_fingerprints] + + for fingerprint in car_fingerprints: + if is_valid_for_fingerprint(msg, fingerprint): + compatible_cars.append(car_name) + break + return compatible_cars + def all_known_cars(): """Returns a list of all known car strings.""" return _FINGERPRINTS.keys() diff --git a/common/numpy_fast.py b/common/numpy_fast.py index 646a8bb1ab37de..a71757d32f546b 100644 --- a/common/numpy_fast.py +++ b/common/numpy_fast.py @@ -1,3 +1,7 @@ +def int_rnd(x): + return int(round(x)) + + def clip(x, lo, hi): return max(lo, min(hi, x)) diff --git a/opendbc/README.md b/opendbc/README.md index 39185bb86728f9..ee14f01f4627bc 100644 --- a/opendbc/README.md +++ b/opendbc/README.md @@ -16,15 +16,19 @@ Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/ind Use [panda](https://github.com/commaai/panda) to connect your car to a computer. +### DBC file preprocessor + +DBC files for different models of the same brand have a lot of overlap. Therefore, we wrote a preprocessor to create DBC files from a brand DBC file and a model specific DBC file. The source DBC files can be found in the generator folder. After changing one of the files run the generator.py script to regenerate the output files. These output files will be placed in the root of the opendbc repository and are suffixed by _generated. + ### Good practices for contributing to opendbc -- Comments: the best way to store comments is to add them directly to the DBC files. For example: +- Comments: the best way to store comments is to add them directly to the DBC files. For example: ``` CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; ``` is a comment that refers to signal `LONG_ACCEL` in message `490`. Using comments is highly recommended, especially for doubts and uncertainties. [cabana](https://community.comma.ai/cabana/) can easily display/add/edit comments to signals and messages. -- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. +- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. For example: ``` SG_ VEHICLE_SPEED : 7|15@0+ (0.00278,0) [0|70] "m/s" PCM @@ -36,7 +40,7 @@ For example: However, the cleanest option is really: ``` SG_ VEHICLE_SPEED : 7|15@0+ (0.01,0) [0|250] "kph" PCM - ``` + ``` - Signal's size: always use the smallest amount of bits possible. For example, let's say I'm reverse engineering the gas pedal position and I've determined that it's in a 3 bytes message. For 0% pedal position I read a message value of `0x00 0x00 0x00`, while for 100% of pedal position I read `0x64 0x00 0x00`: clearly, the gas pedal position is within the first byte of the message and I might be tempted to define the signal `GAS_POS` as: ``` diff --git a/opendbc/acura_ilx_2016_can.dbc b/opendbc/acura_ilx_2016_can.dbc deleted file mode 100644 index 3f31205ab3c4dc..00000000000000 --- a/opendbc/acura_ilx_2016_can.dbc +++ /dev/null @@ -1,323 +0,0 @@ -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 398 XXX_3: 3 XXX - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 419 GEARBOX: 8 PCM - SG_ GEAR : 7|8@0+ (1,0) [0|256] "" NEO - SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_5: 4 XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 542 XXX_6: 7 XXX - -BO_ 545 XXX_7: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_8: 8 XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 800 XXX_9: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_10: 8 XXX - -BO_ 819 XXX_11: 7 XXX - -BO_ 821 XXX_12: 5 XXX - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 882 XXX_13: 2 XXX - -BO_ 884 XXX_14: 7 XXX - -BO_ 887 XXX_15: 8 XXX - -BO_ 888 XXX_16: 8 XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - -BO_ 923 XXX_18: 2 XXX - -BO_ 929 XXX_19: 4 XXX - -BO_ 983 XXX_20: 8 XXX - -BO_ 985 XXX_21: 3 XXX - -BO_ 1024 XXX_22: 5 XXX - -BO_ 1027 XXX_23: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1030 XXX_24: 5 VSA - -BO_ 1034 XXX_25: 5 XXX - -BO_ 1036 XXX_26: 8 XXX - -BO_ 1039 XXX_27: 8 XXX - -BO_ 1057 XXX_28: 5 EPS - -BO_ 1064 XXX_29: 7 XXX - -BO_ 1108 XXX_30: 8 XXX - -BO_ 1365 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; - -CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc new file mode 100644 index 00000000000000..204a25c92337f9 --- /dev/null +++ b/opendbc/acura_ilx_2016_can_generated.dbc @@ -0,0 +1,293 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _honda_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|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+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|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_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + 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.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 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_ 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_ "acura_ilx_2016_can.dbc starts here" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_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 + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_rdx_2018_can.dbc b/opendbc/acura_rdx_2018_can.dbc deleted file mode 100644 index 11f00188d10f19..00000000000000 --- a/opendbc/acura_rdx_2018_can.dbc +++ /dev/null @@ -1,315 +0,0 @@ -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - -BO_ 316 XXX_3: 8 PCM - -BO_ 340 XXX_4: 8 PCM - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 392 GEARBOX: 6 XXX - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX - SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" NEO - SG_ GEAR : 36|5@0+ (1,0) [0|31] "" NEO - -BO_ 398 XXX_5: 3 PCM - -BO_ 399 STEER_STATUS: 6 EPS - SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - -BO_ 404 STEERING_CONTROL: 4 NEO - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ PARKING_BREAK_LIGHT : 2|1@0+ (1,0) [0|1] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 426 XXX_6: 8 VSA - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 474 XXX_7: 5 VSA - -BO_ 476 XXX_8: 5 XXX - -BO_ 487 XXX_9: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 493 XXX_10: 3 VSA - -BO_ 506 BRAKE_COMMAND: 8 NEO - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 507 XXX_11: 1 NEO - -BO_ 542 XXX_12: 7 XXX - -BO_ 545 XXX_13: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 661 XXX_14: 4 XXX - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 XXX_15: 8 XXX - -BO_ 780 ACC_HUD: 8 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -BO_ 800 XXX_16: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 808 XXX_17: 8 XXX - -BO_ 829 LKAS_HUD_2: 5 CAM - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 882 XXX_18: 2 XXX - -BO_ 884 XXX_19: 7 XXX - -BO_ 888 XXX_20: 8 XXX - -BO_ 891 XXX_21: 8 XXX - -BO_ 923 XXX_23: 2 XXX - -BO_ 929 XXX_24: 8 XXX - -BO_ 983 XXX_25: 8 XXX - -BO_ 985 XXX_26: 3 XXX - -BO_ 1024 XXX_27: 5 XXX - -BO_ 1027 XXX_28: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1033 XXX_29: 5 XXX - -BO_ 1036 XXX_30: 8 XXX - -BO_ 1039 XXX_31: 8 XXX - -BO_ 1057 XXX_32: 5 XXX - -BO_ 1064 XXX_32: 7 XXX - -BO_ 1108 XXX_33: 8 XXX - -BO_ 1125 XXX_34: 8 XXX - -BO_ 1296 XXX_35: 8 XXX - -BO_ 1365 XXX_36: 5 XXX - -BO_ 1424 XXX_37: 5 XXX - -BO_ 1600 XXX_38: 5 XXX - -BO_ 1601 XXX_39: 8 XXX - -BO_TX_BU_ 399 : NEO,CAM; -BO_TX_BU_ 506 : NEO,CAM; -BO_TX_BU_ 780 : NEO,CAM; -BO_TX_BU_ 829 : NEO,CAM; - - -CM_ SG_ 422 PARKING_BREAK_LIGHT "Believe this is just the dash light for the parking break"; -VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; -VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc new file mode 100644 index 00000000000000..dc30eb22aa2cf8 --- /dev/null +++ b/opendbc/acura_rdx_2018_can_generated.dbc @@ -0,0 +1,75 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +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|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "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|15] "" EON + +BO_ 392 GEARBOX: 6 XXX + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX + SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" EON + SG_ GEAR : 36|5@0+ (1,0) [0|31] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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_ PARKING_BREAK_LIGHT : 2|1@0+ (1,0) [0|1] "" 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|15] "" EON + +BO_ 487 XXX_9: 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_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 422 PARKING_BREAK_LIGHT "Believe this is just the dash light for the parking break"; +VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; +VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/generator.py b/opendbc/generator/generator.py new file mode 100755 index 00000000000000..81e3b1ce9bab7c --- /dev/null +++ b/opendbc/generator/generator.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python2 +import os +import re + +cur_path = os.path.dirname(os.path.realpath(__file__)) +generator_path = os.path.join(cur_path, '../') + +for dir_name, _, _ in os.walk(cur_path): + if dir_name == cur_path: + continue + + print dir_name + + for filename in os.listdir(dir_name): + if filename.startswith('_'): + continue + + print filename + dbc_file = open(os.path.join(dir_name, filename)).read() + include = re.search(r'CM_ "IMPORT (.*?)"', dbc_file) + if include is not None: + dbc_file = dbc_file.replace(include.group(0), '\nCM_ "%s starts here"' % filename) + include_path = os.path.join(dir_name, include.group(1)) + + # Load included file + include_file = open(include_path).read() + include_file = 'CM_ "Imported file %s starts here"\n' % include.group(1) + include_file + dbc_file = include_file + dbc_file + + dbc_file = 'CM_ "AUTOGENERATED FILE, DO NOT EDIT"\n' + dbc_file + + output_filename = filename.replace('.dbc', '_generated.dbc') + output_dbc_file = open(os.path.join(generator_path, output_filename), 'w') + output_dbc_file.write(dbc_file) + output_dbc_file.close() diff --git a/opendbc/generator/honda/_honda_2017.dbc b/opendbc/generator/honda/_honda_2017.dbc new file mode 100644 index 00000000000000..30cda985363e85 --- /dev/null +++ b/opendbc/generator/honda/_honda_2017.dbc @@ -0,0 +1,214 @@ +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.002759506,0) [0|70] "m/s" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|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+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|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_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + 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.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 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_ 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" ; diff --git a/opendbc/generator/honda/acura_ilx_2016_can.dbc b/opendbc/generator/honda/acura_ilx_2016_can.dbc new file mode 100644 index 00000000000000..df5b543fc844f1 --- /dev/null +++ b/opendbc/generator/honda/acura_ilx_2016_can.dbc @@ -0,0 +1,76 @@ +CM_ "IMPORT _honda_2017.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 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 + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/acura_rdx_2018_can.dbc b/opendbc/generator/honda/acura_rdx_2018_can.dbc new file mode 100644 index 00000000000000..7b33013d45c77b --- /dev/null +++ b/opendbc/generator/honda/acura_rdx_2018_can.dbc @@ -0,0 +1,74 @@ +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|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "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|15] "" EON + +BO_ 392 GEARBOX: 6 XXX + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX + SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" EON + SG_ GEAR : 36|5@0+ (1,0) [0|31] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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_ PARKING_BREAK_LIGHT : 2|1@0+ (1,0) [0|1] "" 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|15] "" EON + +BO_ 487 XXX_9: 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_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 422 PARKING_BREAK_LIGHT "Believe this is just the dash light for the parking break"; +VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; +VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc new file mode 100644 index 00000000000000..85643cbe2fc500 --- /dev/null +++ b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc @@ -0,0 +1,142 @@ +CM_ "IMPORT _honda_2017.dbc" + +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 450 EPB_STATE "3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged""; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/honda/honda_crv_touring_2016_can.dbc b/opendbc/generator/honda/honda_crv_touring_2016_can.dbc new file mode 100644 index 00000000000000..753958f90feb6a --- /dev/null +++ b/opendbc/generator/honda/honda_crv_touring_2016_can.dbc @@ -0,0 +1,74 @@ +CM_ "IMPORT _honda_2017.dbc" + +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|15] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" 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_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +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" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; + +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"; \ No newline at end of file diff --git a/opendbc/generator/honda/honda_odyssey_exl_2018.dbc b/opendbc/generator/honda/honda_odyssey_exl_2018.dbc new file mode 100644 index 00000000000000..ae0363387fc313 --- /dev/null +++ b/opendbc/generator/honda/honda_odyssey_exl_2018.dbc @@ -0,0 +1,115 @@ +CM_ "IMPORT _honda_2017.dbc" + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 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_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + +CM_ "CHFFR_METRIC 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/honda/honda_pilot_touring_2017_can.dbc b/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc new file mode 100644 index 00000000000000..eecfea24e838c9 --- /dev/null +++ b/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc @@ -0,0 +1,66 @@ +CM_ "IMPORT _honda_2017.dbc" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 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 + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/generator/toyota/_toyota_2017.dbc b/opendbc/generator/toyota/_toyota_2017.dbc new file mode 100644 index 00000000000000..3e2b5ec86fa3b6 --- /dev/null +++ b/opendbc/generator/toyota/_toyota_2017.dbc @@ -0,0 +1,177 @@ +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,0) [0|16777215] "" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 8 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1041 ACC_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +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"; diff --git a/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc new file mode 100644 index 00000000000000..bf29cbc314acd7 --- /dev/null +++ b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc @@ -0,0 +1,29 @@ +CM_ "IMPORT _toyota_2017.dbc" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1.0,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/generator/toyota/toyota_prius_2017_pt.dbc b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc new file mode 100644 index 00000000000000..7f00b34e7eda44 --- /dev/null +++ b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc @@ -0,0 +1,33 @@ +CM_ "IMPORT _toyota_2017.dbc" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc new file mode 100644 index 00000000000000..fe98779c435866 --- /dev/null +++ b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc @@ -0,0 +1,29 @@ +CM_ "IMPORT _toyota_2017.dbc" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc new file mode 100644 index 00000000000000..fb62c09fd3e1c1 --- /dev/null +++ b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc @@ -0,0 +1,30 @@ +CM_ "IMPORT _toyota_2017.dbc" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 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: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/honda_accord_touring_2016_can.dbc b/opendbc/honda_accord_touring_2016_can.dbc index 4339619a8a3778..d615a19a9696ac 100644 --- a/opendbc/honda_accord_touring_2016_can.dbc +++ b/opendbc/honda_accord_touring_2016_can.dbc @@ -174,14 +174,14 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" NEO SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@1+ (1,0) [0|15] "" XXX BO_ 660 SCM_COMMANDS: 8 SCM SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 56|4@1+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@1+ (1,0) [0|15] "" XXX BO_ 661 XXX_10: 4 XXX SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" XXX diff --git a/opendbc/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/honda_civic_hatchback_ex_2017_can.dbc index e19f2e9139deb7..73a7758d32afa2 100644 --- a/opendbc/honda_civic_hatchback_ex_2017_can.dbc +++ b/opendbc/honda_civic_hatchback_ex_2017_can.dbc @@ -57,7 +57,7 @@ BO_ 232 XXX_3: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 304 GAS_PEDAL: 8 PCM +BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO @@ -76,7 +76,7 @@ BO_ 340 XXX_4: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 344 POWERTRAIN_DATA: 8 PCM +BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO @@ -84,7 +84,7 @@ BO_ 344 POWERTRAIN_DATA: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 380 POWERTRAIN_DATA2: 8 PCM +BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO @@ -142,11 +142,11 @@ BO_ 441 XXX_7: 5 VSA SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 446 XXX_7: 3 VSA +BO_ 446 XXX_8: 3 VSA SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX -BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB +BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX @@ -159,19 +159,19 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 470 XXX_8: 2 XXX +BO_ 470 XXX_9: 2 XXX SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 11|4@0+ (1,0) [0|15] "" XXX -BO_ 474 XXX_9: 8 XXX +BO_ 474 XXX_10: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 476 XXX_9: 7 XXX +BO_ 476 XXX_11: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO -BO_ 477 XXX_10: 8 XXX +BO_ 477 XXX_12: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX @@ -185,14 +185,10 @@ BO_ 479 ACC_CONTROL: 8 NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 XXX_11: 8 XXX +BO_ 490 XXX_13: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 493 XXX_12: 5 XXX - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 32|4@1+ (1,0) [0|15] "" XXX - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -204,11 +200,11 @@ BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX -BO_ 506 XXX_13: 8 XXX +BO_ 506 XXX_15: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 545 XXX_14: 6 SCM +BO_ 545 XXX_16: 6 SCM SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY @@ -225,7 +221,7 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 662 CRUISE_BUTTONS: 4 SCM +BO_ 662 SCM_BUTTONS: 4 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO @@ -272,15 +268,15 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 795 XXX_15: 8 XXX +BO_ 795 XXX_17: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 800 XXX_16: 8 XXX +BO_ 800 XXX_18: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 TRIP: 8 PCM +BO_ 804 CRUISE: 8 PCM SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO @@ -298,15 +294,15 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 808 XXX_17: 8 XXX +BO_ 808 XXX_19: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 814 XXX_18: 4 XXX +BO_ 814 XXX_20: 4 XXX SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO -BO_ 829 LKAS_HUD_2: 5 ADAS +BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY @@ -337,7 +333,7 @@ BO_ 862 CAMERA_MESSAGES: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS_1: 8 XXX +BO_ 884 STALK_STATUS: 8 XXX SG_ LIGHT_SWITCH_AUTO : 46|1@0+ (1,0) [0|1] "" XXX SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" XXX SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" XXX @@ -370,19 +366,19 @@ BO_ 927 RADAR_HUD: 8 RADAR SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 929 XXX_23: 8 XXX +BO_ 929 XXX_21: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 985 XXX_24: 3 XXX +BO_ 985 XXX_22: 3 XXX SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX -BO_ 1024 XXX_25: 5 XXX +BO_ 1024 XXX_23: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1027 XXX_26: 5 XXX +BO_ 1027 XXX_24: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX @@ -395,55 +391,55 @@ BO_ 1029 DOORS_STATUS: 8 BDY SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 1036 XXX_27: 8 XXX +BO_ 1036 XXX_25: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1039 XXX_28: 8 XXX +BO_ 1039 XXX_26: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1108 XXX_29: 8 XXX +BO_ 1108 XXX_27: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1302 XXX_30: 8 XXX +BO_ 1302 XXX_28: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1322 XXX_31: 5 XXX +BO_ 1322 XXX_29: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1361 XXX_32: 5 XXX +BO_ 1361 XXX_30: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1365 XXX_33: 5 XXX +BO_ 1365 XXX_31: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1424 XXX_34: 5 XXX +BO_ 1424 XXX_32: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1600 XXX_35: 5 XXX +BO_ 1600 XXX_33: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1601 XXX_36: 8 XXX +BO_ 1601 XXX_34: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1618 XXX_37: 5 XXX +BO_ 1618 XXX_35: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX -BO_ 1633 XXX_38: 8 XXX +BO_ 1633 XXX_36: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1670 XXX_39: 5 XXX +BO_ 1670 XXX_37: 5 XXX SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" XXX diff --git a/opendbc/honda_civic_touring_2016_can.dbc b/opendbc/honda_civic_touring_2016_can.dbc deleted file mode 100644 index 24a498c0f03d44..00000000000000 --- a/opendbc/honda_civic_touring_2016_can.dbc +++ /dev/null @@ -1,435 +0,0 @@ -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 148 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" NEO - SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" NEO - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ TRIP_DISTANCE : 55|8@0+ (0.010588,0) [0|255] "km" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 43|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 427 XXX_3: 3 VSA - SG_ CHECKSUM : 19|4@0+ (1,0) [0|6] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" NEO - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 450 XXX_5: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 470 XXX_6: 2 VSA - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 8|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_7: 7 XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - -BO_ 487 XXX_8: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 493 XXX_9: 5 VSA - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 545 XXX_10: 6 XXX - SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" NEO - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|6] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" NEO - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_11: 8 XXX - SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" NEO - SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 795 XXX_12: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 800 XXX_13: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" NEO - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" NEO - SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_14: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 862 XXX_15: 8 ADAS - SG_ UI_ALERTS : 7|56@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" NEO - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" NEO - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" NEO - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 891 XXX_17: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - -BO_ 927 XXX_19: 8 ADAS - SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY - SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY - SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY - SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY - SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY - SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 929 XXX_20: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 985 XXX_21: 3 XXX - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" NEO - -BO_ 1024 XXX_22: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1027 XXX_23: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1036 XXX_24: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1039 XXX_25: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1108 XXX_26: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1302 XXX_27: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1322 XXX_28: 5 XXX - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - -BO_ 1361 XXX_29: 5 XXX - -BO_ 1365 XXX_30: 5 XXX - -BO_ 1424 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_ 1633 XXX_34: 8 XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; -BO_TX_BU_ 862 : NEO,ADAS; -BO_TX_BU_ 927 : NEO,ADAS; - -CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; -VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; -VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; -CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc new file mode 100644 index 00000000000000..677f34bb66e60f --- /dev/null +++ b/opendbc/honda_civic_touring_2016_can_generated.dbc @@ -0,0 +1,359 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _honda_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|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+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|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_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + 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.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 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_ 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_civic_touring_2016_can.dbc starts here" + +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 884 STALK_STATUS: 8 XXX + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 450 EPB_STATE "3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged""; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; +VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + +CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_clarity_hybrid_2018_can.dbc b/opendbc/honda_clarity_hybrid_2018_can.dbc index 3146f36bce4472..86272de0bea3f2 100644 --- a/opendbc/honda_clarity_hybrid_2018_can.dbc +++ b/opendbc/honda_clarity_hybrid_2018_can.dbc @@ -98,7 +98,7 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO -BO_ 401 GEARBOX: 8 PCM +BO_ 401 GEARBOX_1: 8 PCM SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO SG_ GEAR : 43|4@0+ (1,0) [0|15] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO @@ -141,10 +141,6 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO -BO_ 470 XXX_6: 2 VSA - SG_ COUNTER : 13|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 8|4@0+ (1,0) [0|3] "" NEO - BO_ 476 XXX_7: 7 XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO @@ -399,7 +395,7 @@ BO_ 1633 XXX_34: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO -BO_ 419 GEARBOX: 8 XXX +BO_ 419 GEARBOX_2: 8 XXX SG_ GEAR : 29|6@0+ (1,0) [0|63] "" NEO SG_ GEAR_SHIFTER : 34|3@0+ (1,0) [0|7] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO diff --git a/opendbc/honda_crv_ex_2017_can.dbc b/opendbc/honda_crv_ex_2017_can.dbc index d218ca5276b7a4..1e8b4031f6e22c 100644 --- a/opendbc/honda_crv_ex_2017_can.dbc +++ b/opendbc/honda_crv_ex_2017_can.dbc @@ -61,7 +61,7 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 304 GAS_PEDAL: 8 PCM +BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO @@ -80,7 +80,7 @@ BO_ 340 XXX_4: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 344 POWERTRAIN_DATA: 8 PCM +BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO @@ -88,7 +88,7 @@ BO_ 344 POWERTRAIN_DATA: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO -BO_ 380 POWERTRAIN_DATA2: 8 PCM +BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO @@ -143,7 +143,7 @@ BO_ 446 XXX_7: 3 VSA SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX -BO_ 450 ELECTRONIC_PARKING_BRAKE: 8 EPB +BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" NEO SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX @@ -207,7 +207,7 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX -BO_ 662 CRUISE_BUTTONS: 4 SCM +BO_ 662 SCM_BUTTONS: 4 SCM SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" NEO SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO @@ -255,7 +255,7 @@ BO_ 800 XXX_16: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 TRIP: 8 PCM +BO_ 804 CRUISE: 8 PCM SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO SG_ ENGINE_TEMPERATURE : 0|8@0+ (1,0) [0|65535] "" XXX SG_ BOH_2 : 32|23@0+ (1,0) [0|255] "" NEO @@ -280,7 +280,7 @@ BO_ 814 XXX_18: 4 XXX SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" NEO SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" NEO -BO_ 829 LKAS_HUD_2: 5 ADAS +BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY diff --git a/opendbc/honda_crv_touring_2016_can.dbc b/opendbc/honda_crv_touring_2016_can.dbc deleted file mode 100644 index 7b8c14168de58b..00000000000000 --- a/opendbc/honda_crv_touring_2016_can.dbc +++ /dev/null @@ -1,312 +0,0 @@ -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: INTERCEPTOR EBCM NEO CAM PCM EPS VSA SCM BDY XXX EPB - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - -BO_ 316 XXX_3: 8 PCM - -BO_ 340 XXX_4: 8 PCM - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 398 XXX_5: 3 PCM - -BO_ 399 STEER_STATUS: 6 EPS - SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" NEO - SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 401 GEARBOX: 8 PCM - SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 35|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 404 STEERING_CONTROL: 4 NEO - SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS - SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" EPS - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" EPS - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 426 XXX_6: 8 VSA - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 474 XXX_7: 5 VSA - -BO_ 476 XXX_8: 5 XXX - -BO_ 487 XXX_9: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" NEO - SG_ CHECKSUM : 29|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 27|4@0+ (1,0) [0|15] "" NEO - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 493 XXX_10: 3 VSA - -BO_ 506 BRAKE_COMMAND: 8 NEO - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|1@0+ (1,0) [0|3] "" EBCM - SG_ ZEROS_BOH3 : 42|2@0+ (1,0) [0|0] "" EBCM - SG_ FCW2 : 40|1@0+ (1,0) [0|0] "" EBCM - SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 507 XXX_11: 1 NEO - -BO_ 542 XXX_12: 7 XXX - -BO_ 545 XXX_13: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 661 XXX_14: 4 XXX - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" NEO - -BO_ 777 XXX_15: 8 XXX - -BO_ 780 ACC_HUD: 8 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -BO_ 800 XXX_16: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ ENGINE_TEMPERATURE : 7|8@0+ (1,0) [0|255] "" NEO - SG_ BOH : 15|8@0+ (1,0) [0|255] "" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 808 XXX_17: 8 XXX - -BO_ 829 LKAS_HUD_2: 5 CAM - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 882 XXX_18: 2 XXX - -BO_ 884 XXX_19: 7 XXX - -BO_ 888 XXX_20: 8 XXX - -BO_ 891 XXX_21: 8 XXX - -BO_ 923 XXX_23: 2 XXX - -BO_ 929 XXX_24: 8 XXX - -BO_ 983 XXX_25: 8 XXX - -BO_ 985 XXX_26: 3 XXX - -BO_ 1024 XXX_27: 5 XXX - -BO_ 1027 XXX_28: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" NEO - -BO_ 1033 XXX_29: 5 XXX - -BO_ 1036 XXX_30: 8 XXX - -BO_ 1039 XXX_31: 8 XXX - -BO_ 1057 XXX_32: 5 XXX - -BO_ 1064 XXX_32: 7 XXX - -BO_ 1108 XXX_33: 8 XXX - -BO_ 1125 XXX_34: 8 XXX - -BO_ 1296 XXX_35: 8 XXX - -BO_ 1365 XXX_36: 5 XXX - -BO_ 1424 XXX_37: 5 XXX - -BO_ 1600 XXX_38: 5 XXX - -BO_ 1601 XXX_39: 8 XXX - -BO_TX_BU_ 399 : NEO,CAM; -BO_TX_BU_ 506 : NEO,CAM; -BO_TX_BU_ 780 : NEO,CAM; -BO_TX_BU_ 829 : NEO,CAM; - -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc new file mode 100644 index 00000000000000..92665dbb227e04 --- /dev/null +++ b/opendbc/honda_crv_touring_2016_can_generated.dbc @@ -0,0 +1,291 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _honda_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|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+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|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_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + 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.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 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_ 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_crv_touring_2016_can.dbc starts here" + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" 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|15] "" 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_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +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" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; + +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"; \ No newline at end of file diff --git a/opendbc/honda_odyssey_exl_2018.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc similarity index 67% rename from opendbc/honda_odyssey_exl_2018.dbc rename to opendbc/honda_odyssey_exl_2018_generated.dbc index cab4acab1cb984..8639f48444014a 100644 --- a/opendbc/honda_odyssey_exl_2018.dbc +++ b/opendbc/honda_odyssey_exl_2018_generated.dbc @@ -1,72 +1,49 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _honda_2017.dbc starts here" VERSION "" NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: EBCM EON CAM PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 148 XXX_2: 8 XXX - -BO_ 228 STEERING_CONTROL: 5 CAM - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 229 XXX_3: 4 XXX - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON - -BO_ 344 POWERTRAIN_DATA: 8 PCM + 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.002759506,0) [0|70] "m/s" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX + 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_DATA2: 8 PCM +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 @@ -79,62 +56,27 @@ BO_ 380 POWERTRAIN_DATA2: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 411 XXX_4: 5 XXX - -BO_ 419 GEARBOX: 8 PCM - SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON - SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX - -BO_ 427 XXX_5: 3 XXX - BO_ 432 STANDSTILL: 7 VSA + SG_ 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_ 450 XXX_6: 8 XXX - SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX - SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 463 XXX_7: 8 XXX - BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ 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_ 476 XXX_8: 4 XXX - BO_ 490 VEHICLE_DYNAMICS: 8 VSA SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + 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 CAM +BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM @@ -144,43 +86,56 @@ BO_ 506 BRAKE_COMMAND: 8 CAM SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM -BO_ 542 XXX_9: 7 XXX +BO_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR -BO_ 545 XXX_10: 4 XXX +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" EON - -BO_ 662 CRUISE_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + 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 XXX_11: 8 XXX +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 CAM - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.002759506,0) [0|100] "m/s" BDY SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY @@ -202,10 +157,6 @@ BO_ 780 ACC_HUD: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 795 XXX_12: 8 XXX - -BO_ 800 XXX_13: 8 XXX - BO_ 804 CRUISE: 8 PCM SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON @@ -216,28 +167,9 @@ BO_ 804 CRUISE: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON - SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 808 XXX_14: 8 XXX - -BO_ 817 XXX_15: 4 XXX - -BO_ 819 XXX_16: 7 XXX - -BO_ 821 XXX_17: 5 XXX - -BO_ 825 XXX_18: 4 XXX - -BO_ 829 LKAS_HUD: 5 CAM +BO_ 829 LKAS_HUD: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ 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 @@ -245,6 +177,7 @@ BO_ 829 LKAS_HUD: 5 CAM 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 @@ -252,63 +185,12 @@ BO_ 829 LKAS_HUD: 5 CAM SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 837 XXX_19: 5 XXX - -BO_ 856 XXX_20: 7 XXX - -BO_ 862 XXX_21: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 871 XXX_22: 8 XXX - -BO_ 881 XXX_23: 8 XXX - -BO_ 882 XXX_24: 4 XXX - -BO_ 884 XXX_25: 8 XXX - -BO_ 891 XXX_26: 8 XXX + 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 - -BO_ 905 XXX_27: 8 XXX - -BO_ 923 XXX_28: 2 XXX - -BO_ 927 ACC_HUD_2: 8 CAM - SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY - SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY - SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY - SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY - SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY - SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 929 XXX_29: 8 XXX - -BO_ 963 XXX_30: 8 XXX - -BO_ 965 XXX_31: 8 XXX - -BO_ 966 XXX_32: 8 XXX - -BO_ 967 XXX_33: 8 XXX - -BO_ 983 XXX_34: 8 XXX - -BO_ 985 XXX_35: 3 XXX + 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 @@ -319,68 +201,132 @@ BO_ 1029 DOORS_STATUS: 8 BDY SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1036 XXX_36: 8 XXX - -BO_ 1052 XXX_37: 8 XXX - -BO_ 1064 XXX_38: 7 XXX - -BO_ 1088 XXX_39: 8 XXX - -BO_ 1089 XXX_40: 8 XXX - -BO_ 1092 XXX_41: 1 XXX - -BO_ 1108 XXX_42: 8 XXX +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..."; -BO_ 1110 XXX_43: 8 XXX -BO_ 1125 XXX_44: 8 XXX +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" ; -BO_ 1296 XXX_45: 8 XXX +CM_ "honda_odyssey_exl_2018.dbc starts here" -BO_ 1302 XXX_46: 8 XXX +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS -BO_ 1600 XXX_47: 5 XXX +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON -BO_ 1601 XXX_48: 8 XXX +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_ 1612 XXX_49: 5 XXX +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_ 1613 XXX_50: 5 XXX +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1614 XXX_51: 5 XXX +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX -BO_ 1615 XXX_52: 8 XXX +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX -BO_ 1616 XXX_53: 5 XXX +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON -BO_ 1619 XXX_54: 5 XXX +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 1623 XXX_55: 5 XXX +BO_ 891 WIPERS: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1668 XXX_56: 5 XXX +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_TX_BU_ 228 : EON,CAM; -BO_TX_BU_ 506 : EON,CAM; -BO_TX_BU_ 780 : EON,CAM; -BO_TX_BU_ 829 : EON,CAM; -BO_TX_BU_ 862 : EON,CAM; -BO_TX_BU_ 927 : EON,CAM; +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; -CM_ SG_ 450 EPB_STATE "3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged""; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; + VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; + CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_pilot_touring_2017_can.dbc b/opendbc/honda_pilot_touring_2017_can.dbc deleted file mode 100644 index 459109c6dfaf32..00000000000000 --- a/opendbc/honda_pilot_touring_2017_can.dbc +++ /dev/null @@ -1,322 +0,0 @@ -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: INTERCEPTOR EBCM NEO ADAS PCM EPS VSA SCM BDY XXX - - -BO_ 57 XXX_1: 3 XXX - -BO_ 145 XXX_2: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" NEO - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 304 GAS_PEDAL2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" NEO - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" NEO - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" NEO - SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" NEO - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" NEO - -BO_ 344 POWERTRAIN_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ ODOMETER : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 380 POWERTRAIN_DATA2: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" NEO - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" NEO - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" NEO - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" NEO - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" NEO - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" NEO - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 398 XXX_3: 3 XXX - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" NEO - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" NEO - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" NEO - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" NEO - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" NEO - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" NEO - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" NEO - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" NEO - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 428 XXX_4: 8 XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" NEO - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.002759506,0) [0|70] "m/s" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 476 XXX_5: 4 XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" NEO - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (0.003906248,0) [0|1] "" EBCM - SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH4 : 31|8@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_BOH5 : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ CRUISE_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ CRUISE_BOH7 : 41|10@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EBCM - -BO_ 512 GAS_COMMAND: 3 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR - SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 5 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" NEO - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" NEO - -BO_ 542 XXX_6: 7 XXX - -BO_ 545 XXX_7: 4 XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" NEO - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" NEO - SG_ SET_TO_X55 : 47|8@0+ (1,0) [0|255] "" NEO - -BO_ 660 SCM_COMMANDS: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" NEO - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" NEO - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" NEO - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" NEO - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" NEO - -BO_ 777 XXX_8: 8 XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.002763889,0) [0|100] "m/s" BDY - SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY - SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 800 XXX_9: 8 XXX - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" NEO - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" NEO - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" NEO - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" NEO - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" NEO - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 808 XXX_10: 8 XXX - -BO_ 819 XXX_11: 7 XXX - -BO_ 821 XXX_12: 5 XXX - -BO_ 829 LKAS_HUD_2: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" BDY - -BO_ 882 XXX_13: 2 XXX - -BO_ 884 XXX_14: 7 XXX - -BO_ 887 XXX_15: 8 XXX - -BO_ 888 XXX_16: 8 XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" NEO - -BO_ 923 XXX_18: 2 XXX - -BO_ 929 XXX_19: 4 XXX - -BO_ 983 XXX_20: 8 XXX - -BO_ 985 XXX_21: 3 XXX - -BO_ 1024 XXX_22: 5 XXX - -BO_ 1027 XXX_23: 5 XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" NEO - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" NEO - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" NEO - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" NEO - -BO_ 1030 XXX_24: 5 VSA - -BO_ 1034 XXX_25: 5 XXX - -BO_ 1036 XXX_26: 8 XXX - -BO_ 1039 XXX_27: 8 XXX - -BO_ 1057 XXX_28: 5 EPS - -BO_ 1064 XXX_29: 7 XXX - -BO_ 1108 XXX_30: 8 XXX - -BO_ 1365 XXX_31: 5 XXX - -BO_ 1600 XXX_32: 5 XXX - -BO_ 1601 XXX_33: 8 XXX - -BO_TX_BU_ 228 : NEO,ADAS; -BO_TX_BU_ 506 : NEO,ADAS; -BO_TX_BU_ 780 : NEO,ADAS; -BO_TX_BU_ 829 : NEO,ADAS; - - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; -VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; -VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc new file mode 100644 index 00000000000000..360b362d7ac024 --- /dev/null +++ b/opendbc/honda_pilot_touring_2017_can_generated.dbc @@ -0,0 +1,283 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _honda_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.002759506,0) [0|70] "m/s" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|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+ (0.003906248,0) [0|1] "" EBCM + SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST_2 : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|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_ 512 GAS_COMMAND: 3 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" INTERCEPTOR + SG_ CHECKSUM : 19|4@0+ (1,0) [0|3] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 5 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + 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.002759506,0) [0|100] "m/s" BDY + SG_ PCM_GAS : 23|7@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH : 16|1@0+ (1,0) [0|255] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 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_ 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_pilot_touring_2017_can.dbc starts here" + +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 304 GAS_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 + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; + +CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0"; diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc new file mode 100644 index 00000000000000..18d758120dec63 --- /dev/null +++ b/opendbc/toyota_corolla_2017_pt_generated.dbc @@ -0,0 +1,209 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _toyota_2017.dbc starts here" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 8 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1041 ACC_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +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_corolla_2017_pt.dbc starts here" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1.0,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/toyota_prius_2017_pt.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc similarity index 98% rename from opendbc/toyota_prius_2017_pt.dbc rename to opendbc/toyota_prius_2017_pt_generated.dbc index 6da549fe41eb55..bb5e0df32ba1ab 100644 --- a/opendbc/toyota_prius_2017_pt.dbc +++ b/opendbc/toyota_prius_2017_pt_generated.dbc @@ -1,3 +1,5 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _toyota_2017.dbc starts here" VERSION "" @@ -55,12 +57,6 @@ BO_ 180 SPEED: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX -BO_ 295 GEAR_PACKET: 8 XXX - SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX - BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX @@ -68,11 +64,6 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX @@ -80,20 +71,6 @@ BO_ 552 ACCELEROMETER: 8 XXX BO_ 560 BRAKE_MODULE2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 610 EPS_STATUS: 8 EPS - SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX @@ -175,11 +152,8 @@ CM_ SG_ 36 ACCEL_Y "unit is tbd"; CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -190,11 +164,8 @@ CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disenga CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 1553 UNITS 1 "km" 2 "miles"; @@ -206,3 +177,37 @@ 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_prius_2017_pt.dbc starts here" + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/toyota_rav4_2017_pt.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc similarity index 96% rename from opendbc/toyota_rav4_2017_pt.dbc rename to opendbc/toyota_rav4_2017_pt_generated.dbc index 6c297751768dbf..df47a58b8a0a9f 100644 --- a/opendbc/toyota_rav4_2017_pt.dbc +++ b/opendbc/toyota_rav4_2017_pt_generated.dbc @@ -1,3 +1,5 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _toyota_2017.dbc starts here" VERSION "" @@ -62,10 +64,6 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 548 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX - SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX - BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX @@ -73,21 +71,6 @@ BO_ 552 ACCELEROMETER: 8 XXX BO_ 560 BRAKE_MODULE2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX -BO_ 705 GAS_PEDAL: 8 XXX - SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX @@ -138,10 +121,6 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX @@ -173,11 +152,8 @@ CM_ SG_ 36 ACCEL_Y "unit is tbd"; CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 560 BRAKE_PRESSED "another brake press?"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -188,11 +164,8 @@ CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disenga CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; VAL_ 1553 UNITS 1 "km" 2 "miles"; @@ -204,3 +177,33 @@ 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_rav4_2017_pt.dbc starts here" + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; diff --git a/opendbc/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc similarity index 97% rename from opendbc/toyota_rav4_hybrid_2017_pt.dbc rename to opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc index 295b211eeb54be..f02b231317a721 100644 --- a/opendbc/toyota_rav4_hybrid_2017_pt.dbc +++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc @@ -1,3 +1,5 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" +CM_ "Imported file _toyota_2017.dbc starts here" VERSION "" @@ -62,11 +64,6 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - BO_ 552 ACCELEROMETER: 8 XXX SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX @@ -74,20 +71,6 @@ BO_ 552 ACCELEROMETER: 8 XXX BO_ 560 BRAKE_MODULE2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX @@ -138,9 +121,6 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - BO_ 1041 ACC_HUD: 8 DSU SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX @@ -172,11 +152,8 @@ CM_ SG_ 36 ACCEL_Y "unit is tbd"; CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -189,11 +166,8 @@ CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; -VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 50 "temporary_fault"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 1553 UNITS 1 "km" 2 "miles"; VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; @@ -203,3 +177,34 @@ 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_rav4_hybrid_2017_pt.dbc starts here" + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + 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: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 50 "temporary_fault"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/panda/VERSION b/panda/VERSION index 3b9e5dbc906834..6df8b1143050c4 100644 --- a/panda/VERSION +++ b/panda/VERSION @@ -1 +1 @@ -v1.0.4 \ No newline at end of file +v1.0.6 \ No newline at end of file diff --git a/panda/board/build.mk b/panda/board/build.mk index 7b3e271915ec12..069a00e1a04058 100644 --- a/panda/board/build.mk +++ b/panda/board/build.mk @@ -17,7 +17,7 @@ DFU_UTIL = "dfu-util" # this no longer pushes the bootstub flash: obj/$(PROJ_NAME).bin - PYTHONPATH=../ python -c "from panda import Panda; Panda().flash('obj/$(PROJ_NAME).bin')" + PYTHONPATH=../ python -c "from python import Panda; Panda().flash('obj/$(PROJ_NAME).bin')" ota: obj/$(PROJ_NAME).bin curl http://192.168.0.10/stupdate --upload-file $< @@ -26,7 +26,7 @@ bin: obj/$(PROJ_NAME).bin # this flashes everything recover: obj/bootstub.$(PROJ_NAME).bin obj/$(PROJ_NAME).bin - -PYTHONPATH=../ python -c "from panda import Panda; Panda().reset(enter_bootloader=True)" + -PYTHONPATH=../ python -c "from python import Panda; Panda().reset(enter_bootloader=True)" sleep 1.0 $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.$(PROJ_NAME).bin diff --git a/panda/board/drivers/drivers.h b/panda/board/drivers/drivers.h index 871ee8fcf1f88a..ce1e860ceb8a80 100644 --- a/panda/board/drivers/drivers.h +++ b/panda/board/drivers/drivers.h @@ -57,13 +57,13 @@ void usb_cb_enumeration_complete(); // ********************* UART ********************* // IRQs: USART1, USART2, USART3, UART5 -#define FIFO_SIZE 0x100 +#define FIFO_SIZE 0x400 typedef struct uart_ring { - uint8_t w_ptr_tx; - uint8_t r_ptr_tx; + uint16_t w_ptr_tx; + uint16_t r_ptr_tx; uint8_t elems_tx[FIFO_SIZE]; - uint8_t w_ptr_rx; - uint8_t r_ptr_rx; + uint16_t w_ptr_rx; + uint16_t r_ptr_rx; uint8_t elems_rx[FIFO_SIZE]; USART_TypeDef *uart; void (*callback)(struct uart_ring*); diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index 2a21ffa23b8ef6..9c01416920d230 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -52,7 +52,7 @@ void uart_ring_process(uart_ring *q) { if (q->w_ptr_tx != q->r_ptr_tx) { if (sr & USART_SR_TXE) { q->uart->DR = q->elems_tx[q->r_ptr_tx]; - q->r_ptr_tx += 1; + q->r_ptr_tx = (q->r_ptr_tx + 1) % FIFO_SIZE; } else { // push on interrupt later q->uart->CR1 |= USART_CR1_TXEIE; @@ -64,11 +64,13 @@ void uart_ring_process(uart_ring *q) { if (sr & USART_SR_RXNE || sr & USART_SR_ORE) { uint8_t c = q->uart->DR; // TODO: can drop packets - uint8_t next_w_ptr = q->w_ptr_rx + 1; - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback) q->callback(q); + if (q != &esp_ring) { + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + if (q->callback) q->callback(q); + } } } @@ -92,7 +94,7 @@ int getc(uart_ring *q, char *elem) { enter_critical_section(); if (q->w_ptr_rx != q->r_ptr_rx) { *elem = q->elems_rx[q->r_ptr_rx]; - q->r_ptr_rx += 1; + q->r_ptr_rx = (q->r_ptr_rx + 1) % FIFO_SIZE; ret = 1; } exit_critical_section(); @@ -102,10 +104,10 @@ int getc(uart_ring *q, char *elem) { int injectc(uart_ring *q, char elem) { int ret = 0; - uint8_t next_w_ptr; + uint16_t next_w_ptr; enter_critical_section(); - next_w_ptr = q->w_ptr_rx + 1; + next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; if (next_w_ptr != q->r_ptr_rx) { q->elems_rx[q->w_ptr_rx] = elem; q->w_ptr_rx = next_w_ptr; @@ -118,10 +120,10 @@ int injectc(uart_ring *q, char elem) { int putc(uart_ring *q, char elem) { int ret = 0; - uint8_t next_w_ptr; + uint16_t next_w_ptr; enter_critical_section(); - next_w_ptr = q->w_ptr_tx + 1; + next_w_ptr = (q->w_ptr_tx + 1) % FIFO_SIZE; if (next_w_ptr != q->r_ptr_tx) { q->elems_tx[q->w_ptr_tx] = elem; q->w_ptr_tx = next_w_ptr; @@ -159,6 +161,51 @@ void uart_set_baud(USART_TypeDef *u, int baud) { } } +#define USART1_DMA_LEN 0x20 +char usart1_dma[USART1_DMA_LEN]; + +void uart_dma_drain() { + uart_ring *q = &esp_ring; + + enter_critical_section(); + + if (DMA2->HISR & DMA_HISR_TCIF5 || DMA2->HISR & DMA_HISR_HTIF5 || DMA2_Stream5->NDTR != USART1_DMA_LEN) { + // disable DMA + q->uart->CR3 &= ~USART_CR3_DMAR; + DMA2_Stream5->CR &= ~DMA_SxCR_EN; + while (DMA2_Stream5->CR & DMA_SxCR_EN); + + int i; + for (i = 0; i < USART1_DMA_LEN - DMA2_Stream5->NDTR; i++) { + char c = usart1_dma[i]; + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + } + } + + // reset DMA len + DMA2_Stream5->NDTR = USART1_DMA_LEN; + + // clear interrupts + DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; + //DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; + + // enable DMA + DMA2_Stream5->CR |= DMA_SxCR_EN; + q->uart->CR3 |= USART_CR3_DMAR; + } + + exit_critical_section(); +} + +void DMA2_Stream5_IRQHandler(void) { + //set_led(LED_BLUE, 1); + uart_dma_drain(); + //set_led(LED_BLUE, 0); +} + void uart_init(USART_TypeDef *u, int baud) { // enable uart and tx+rx mode u->CR1 = USART_CR1_UE; @@ -170,9 +217,23 @@ void uart_init(USART_TypeDef *u, int baud) { // ** UART is ready to work ** // enable interrupts - u->CR1 |= USART_CR1_RXNEIE; + if (u != USART1) { + u->CR1 |= USART_CR1_RXNEIE; + } if (u == USART1) { + // DMA2, stream 2, channel 3 + DMA2_Stream5->M0AR = (uint32_t)usart1_dma; + DMA2_Stream5->NDTR = USART1_DMA_LEN; + DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); + + // channel4, increment memory, periph -> memory, enable + DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_EN; + + // this one uses DMA receiver + u->CR3 = USART_CR3_DMAR; + + NVIC_EnableIRQ(DMA2_Stream5_IRQn); NVIC_EnableIRQ(USART1_IRQn); } else if (u == USART2) { NVIC_EnableIRQ(USART2_IRQn); diff --git a/panda/board/gpio.h b/panda/board/gpio.h index 0e15e3ba4578d7..775a88df54c00c 100644 --- a/panda/board/gpio.h +++ b/panda/board/gpio.h @@ -15,6 +15,7 @@ int has_external_debug_serial = 0; int is_giant_panda = 0; int is_entering_bootmode = 0; int revision = PANDA_REV_AB; +int is_grey_panda = 0; int detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { set_gpio_mode(GPIO, pin, MODE_INPUT); @@ -45,9 +46,14 @@ void detect() { // check if the ESP is trying to put me in boot mode is_entering_bootmode = !detect_with_pull(GPIOB, 0, PULL_UP); + + // check if it's a grey panda by seeing if the SPI lines are floating + // TODO: is this reliable? + is_grey_panda = !(detect_with_pull(GPIOA, 4, PULL_DOWN) | detect_with_pull(GPIOA, 5, PULL_DOWN) | detect_with_pull(GPIOA, 6, PULL_DOWN) | detect_with_pull(GPIOA, 7, PULL_DOWN)); #else // need to do this for early detect is_giant_panda = 0; + is_grey_panda = 0; revision = PANDA_REV_AB; is_entering_bootmode = 0; #endif diff --git a/panda/board/main.c b/panda/board/main.c index 402fd73e2bdaf2..e46a38856317e8 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -175,6 +175,11 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { puts(" err: "); puth(can_err_cnt); puts("\n"); break; + // **** 0xc1: is grey panda + case 0xc1: + resp[0] = is_grey_panda; + resp_len = 1; + break; // **** 0xd0: fetch serial number case 0xd0: #ifdef PANDA @@ -229,6 +234,8 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { case 0xd9: if (setup->b.wValue.w == 1) { set_esp_mode(ESP_ENABLED); + } else if (setup->b.wValue.w == 2) { + set_esp_mode(ESP_BOOTMODE); } else { set_esp_mode(ESP_DISABLED); } @@ -267,7 +274,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { // and it's blocked over WiFi // Allow ELM security mode to be set over wifi. if (hardwired || setup->b.wValue.w == SAFETY_NOOUTPUT || setup->b.wValue.w == SAFETY_ELM327) { - safety_set_mode(setup->b.wValue.w); + safety_set_mode(setup->b.wValue.w, (int16_t)setup->b.wIndex.w); switch (setup->b.wValue.w) { case SAFETY_NOOUTPUT: can_silent = ALL_CAN_SILENT; @@ -304,6 +311,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { case 0xe0: ur = get_ring_by_number(setup->b.wValue.w); if (!ur) break; + if (ur == &esp_ring) uart_dma_drain(); // read while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) && getc(ur, (char*)&resp[resp_len])) { @@ -489,6 +497,7 @@ int main() { #endif puts(has_external_debug_serial ? " real serial\n" : " USB serial\n"); puts(is_giant_panda ? " GIANTpanda detected\n" : " not GIANTpanda\n"); + puts(is_grey_panda ? " gray panda detected!\n" : " white panda\n"); puts(is_entering_bootmode ? " ESP wants bootmode\n" : " no bootmode\n"); gpio_init(); @@ -500,9 +509,12 @@ int main() { } #ifdef PANDA - // enable ESP uart - uart_init(USART1, 115200); - + if (is_grey_panda) { + uart_init(USART1, 9600); + } else { + // enable ESP uart + uart_init(USART1, 115200); + } // enable LIN uart_init(UART5, 10400); UART5->CR2 |= USART_CR2_LINEN; @@ -522,7 +534,7 @@ int main() { usb_init(); // default to silent mode to prevent issues with Ford - safety_set_mode(SAFETY_NOOUTPUT); + safety_set_mode(SAFETY_NOOUTPUT, 0); can_silent = ALL_CAN_SILENT; can_init_all(); @@ -552,6 +564,8 @@ int main() { for (cnt=0;;cnt++) { can_live = pending_can_live; + //puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n"); + #ifdef PANDA int current = adc_get(ADCCHAN_CURRENT); diff --git a/panda/board/safety.h b/panda/board/safety.h index dc4631f4606de8..8842141544a686 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -2,7 +2,7 @@ void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); -typedef void (*safety_hook_init)(); +typedef void (*safety_hook_init)(int16_t param); typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push); typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send); typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); @@ -60,11 +60,11 @@ const safety_hook_config safety_hook_registry[] = { #define HOOK_CONFIG_COUNT (sizeof(safety_hook_registry)/sizeof(safety_hook_config)) -int safety_set_mode(uint16_t mode) { +int safety_set_mode(uint16_t mode, int16_t param) { for (int i = 0; i < HOOK_CONFIG_COUNT; i++) { if (safety_hook_registry[i].id == mode) { current_hooks = safety_hook_registry[i].hooks; - if (current_hooks->init) current_hooks->init(); + if (current_hooks->init) current_hooks->init(param); return 0; } } diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 86155f32b9a68e..b7b4d37295c9c9 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -2,7 +2,7 @@ void default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {} // *** no output safety mode *** -static void nooutput_init() { +static void nooutput_init(int16_t param) { controls_allowed = 0; } @@ -23,7 +23,7 @@ const safety_hooks nooutput_hooks = { // *** all output safety mode *** -static void alloutput_init() { +static void alloutput_init(int16_t param) { controls_allowed = 1; } diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h index ddacc27be0131f..b9af35ebdc5016 100644 --- a/panda/board/safety/safety_elm327.h +++ b/panda/board/safety/safety_elm327.h @@ -27,7 +27,7 @@ static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { return true; } -static void elm327_init() { +static void elm327_init(int16_t param) { controls_allowed = 1; } diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 55ef003e5fee1e..bf30d847079e09 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -115,7 +115,7 @@ static int honda_tx_lin_hook(int lin_num, uint8_t *data, int len) { return true; } -static void honda_init() { +static void honda_init(int16_t param) { controls_allowed = 0; } diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 0dab4b91cb9564..9ddaf172bb47ee 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -9,7 +9,7 @@ const int32_t MAX_TORQUE = 1500; // max torque cmd allowed ever // packet is sent at 100hz, so this limit is 1000/sec const int32_t MAX_RATE_UP = 10; // ramp up slow const int32_t MAX_RATE_DOWN = 25; // ramp down fast -const int32_t MAX_TORQUE_ERROR = 500; // max torque cmd in excess of torque motor +const int32_t 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 @@ -22,6 +22,7 @@ const int16_t MIN_ACCEL = -3000; // 3.0 m/s2 // global actuation limit state int actuation_limits = 1; // by default steer limits are imposed +int16_t dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file // state of torque limits int16_t desired_torque_last = 0; // last desired steer torque @@ -31,10 +32,10 @@ uint32_t ts_last = 0; static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { // get eps motor torque (0.66 factor in dbc) if ((to_push->RIR>>21) == 0x260) { - int16_t torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF)); + int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF)); // increase torque_meas by 1 to be conservative on rounding - torque_meas_new = (torque_meas_new / 3 + (torque_meas_new > 0 ? 1 : -1)) * 2; + torque_meas_new = (torque_meas_new * dbc_eps_torque_factor / 100) + (torque_meas_new > 0 ? 1 : -1); // shift the array for (int i = sizeof(torque_meas)/sizeof(torque_meas[0]) - 1; i > 0; i--) { @@ -154,9 +155,10 @@ static int toyota_tx_lin_hook(int lin_num, uint8_t *data, int len) { return true; } -static void toyota_init() { +static void toyota_init(int16_t param) { controls_allowed = 0; actuation_limits = 1; + dbc_eps_torque_factor = param; } const safety_hooks toyota_hooks = { @@ -166,9 +168,10 @@ const safety_hooks toyota_hooks = { .tx_lin = toyota_tx_lin_hook, }; -static void toyota_nolimits_init() { +static void toyota_nolimits_init(int16_t param) { controls_allowed = 0; actuation_limits = 0; + dbc_eps_torque_factor = param; } const safety_hooks toyota_nolimits_hooks = { diff --git a/panda/examples/isotp.py b/panda/examples/isotp.py index 12cef80a968885..fd300da751c2d5 100644 --- a/panda/examples/isotp.py +++ b/panda/examples/isotp.py @@ -9,7 +9,27 @@ def msg(x): assert False return ret.ljust(8, "\x00") -def isotp_send(panda, x, addr, bus=0): +kmsgs = [] +def recv(panda, cnt, addr, nbus): + global kmsgs + ret = [] + + while len(ret) < cnt: + kmsgs += panda.can_recv() + nmsgs = [] + for ids, ts, dat, bus in kmsgs: + if ids == addr and bus == nbus and len(ret) < cnt: + ret.append(dat) + else: + # leave around + nmsgs.append((ids, ts, dat, bus)) + kmsgs = nmsgs[-256:] + return map(str, ret) + +def isotp_send(panda, x, addr, bus=0, recvaddr=None): + if recvaddr is None: + recvaddr = addr+8 + if len(x) <= 7: panda.can_send(addr, msg(x), bus) else: @@ -24,25 +44,9 @@ def isotp_send(panda, x, addr, bus=0): # actually send panda.can_send(addr, ss, bus) - rr = recv(panda, 1, addr+8, bus)[0] + rr = recv(panda, 1, recvaddr, bus)[0] panda.can_send_many([(addr, None, s, 0) for s in sends]) -kmsgs = [] -def recv(panda, cnt, addr, nbus): - global kmsgs - ret = [] - - while len(ret) < cnt: - kmsgs += panda.can_recv() - nmsgs = [] - for ids, ts, dat, bus in kmsgs: - if ids == addr and bus == nbus and len(ret) < cnt: - ret.append(dat) - else: - pass - kmsgs = nmsgs - return map(str, ret) - def isotp_recv(panda, addr, bus=0, sendaddr=None): msg = recv(panda, 1, addr, bus)[0] diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 48f6bf17a63800..011263fff9e06f 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -18,6 +18,8 @@ BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") +DEBUG = os.getenv("PANDADEBUG") is not None + # *** wifi mode *** def build_st(target, mkfile="Makefile"): @@ -34,7 +36,10 @@ def parse_can_buffer(dat): address = f1 >> 3 else: address = f1 >> 21 - ret.append((address, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xFF)) + dddat = ddat[8:8+(f2&0xF)] + if DEBUG: + print(" R %x: %s" % (address, str(dddat).encode("hex"))) + ret.append((address, f2>>16, dddat, (f2>>4)&0xFF)) return ret class PandaWifiStreaming(object): @@ -369,6 +374,8 @@ def can_send_many(self, arr): extended = 4 for addr, _, dat, bus in arr: assert len(dat) <= 8 + if DEBUG: + print(" W %x: %s" % (addr, dat.encode("hex"))) if addr >= 0x800: rir = (addr << 3) | transmit | extended else: @@ -425,7 +432,10 @@ def serial_read(self, port_number): return b''.join(ret) def serial_write(self, port_number, ln): - return self._handle.bulkWrite(2, struct.pack("B", port_number) + ln) + ret = 0 + for i in range(0, len(ln), 0x20): + ret += self._handle.bulkWrite(2, struct.pack("B", port_number) + ln[i:i+0x20]) + return ret def serial_clear(self, port_number): """Clears all messages (tx and rx) from the specified internal uart diff --git a/panda/tests/location_listener.py b/panda/tests/location_listener.py index 59f83cf59d7c09..cbbb00d794f5e3 100755 --- a/panda/tests/location_listener.py +++ b/panda/tests/location_listener.py @@ -27,7 +27,6 @@ def add_nmea_checksum(msg): print ser.read(1024) # upping baud rate - # 460800 has issues baudrate = 460800 print "upping baud rate" diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt index 95a40c06426eed..2779fab8e7ffb2 100644 --- a/requirements_openpilot.txt +++ b/requirements_openpilot.txt @@ -11,5 +11,7 @@ simplejson==3.8.2 pyyaml==3.12 cffi==1.7.0 enum34==1.1.1 +sympy==1.1.1 +filterpy==1.0.0 smbus2==0.2.0 -e git+https://github.com/commaai/le_python.git#egg=Logentries diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 13bd9c98410055..29ae70f4b9b00e 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -50,6 +50,11 @@ bool loopback_can = false; bool has_pigeon = false; pthread_t safety_setter_thread_handle = -1; +pthread_t pigeon_thread_handle = -1; +bool pigeon_needs_init; + +void pigeon_init(); +void *pigeon_thread(void *crap); void *safety_setter_thread(void *s) { char *value; @@ -73,7 +78,8 @@ void *safety_setter_thread(void *s) { cereal::CarParams::Reader car_params = cmsg.getRoot(); auto safety_model = car_params.getSafetyModel(); - LOGW("setting safety model: %d", safety_model); + auto safety_param = car_params.getSafetyParam(); + LOGW("setting safety model: %d with param %d", safety_model, safety_param); int safety_setting = 0; switch (safety_model) { @@ -98,18 +104,17 @@ void *safety_setter_thread(void *s) { // set in the mutex to avoid race safety_setter_thread_handle = -1; - libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_setting, 0, NULL, 0, TIMEOUT); + libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_setting, safety_param, NULL, 0, TIMEOUT); pthread_mutex_unlock(&usb_lock); return NULL; } -void pigeon_init(); - // must be called before threads or with mutex bool usb_connect() { int err; + unsigned char is_pigeon[1] = {0}; dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); if (dev_handle == NULL) { goto fail; } @@ -143,9 +148,19 @@ bool usb_connect() { if (safety_setter_thread_handle == -1) { err = pthread_create(&safety_setter_thread_handle, NULL, safety_setter_thread, NULL); + assert(err == 0); } - if (has_pigeon) pigeon_init(); + libusb_control_transfer(dev_handle, 0xc0, 0xc1, 0, 0, is_pigeon, 1, TIMEOUT); + + if (is_pigeon[0]) { + LOGW("grey panda detected"); + pigeon_needs_init = true; + if (pigeon_thread_handle == -1) { + err = pthread_create(&pigeon_thread_handle, NULL, pigeon_thread, NULL); + assert(err == 0); + } + } return true; fail: @@ -418,42 +433,72 @@ void *can_health_thread(void *crap) { #define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) +void hexdump(unsigned char *d, int l) { + for (int i = 0; i < l; i++) { + if (i!=0 && i%0x10 == 0) printf("\n"); + printf("%2.2X ", d[i]); + } + printf("\n"); +} + void _pigeon_send(const char *dat, int len) { int sent; unsigned char a[0x20]; int err; a[0] = 1; - for (int i=0; i 0) { // create message capnp::MallocMessageBuilder msg; cereal::Event::Builder event = msg.initRoot(); event.setLogMonoTime(nanos_since_boot()); - auto ublox_raw = event.initUbloxRaw(len); - memcpy(ublox_raw.begin(), dat, len); + auto ublox_raw = event.initUbloxRaw(alen); + memcpy(ublox_raw.begin(), dat, alen); // send to ubloxRaw auto words = capnp::messageToFlatArray(msg); auto bytes = words.asBytes(); zmq_send(publisher, bytes.begin(), bytes.size(), 0); - - if (len < 0x40) break; } // 10ms usleep(10*1000); + cnt++; } return NULL; @@ -541,10 +610,6 @@ int main() { loopback_can = true; } - if (getenv("PIGEON")) { - has_pigeon = true; - } - // init libusb err = libusb_init(&ctx); assert(err == 0); @@ -575,15 +640,6 @@ int main() { thermal_thread, NULL); assert(err == 0); - if (has_pigeon) { - pthread_t pigeon_thread_handle; - err = pthread_create(&pigeon_thread_handle, NULL, - pigeon_thread, NULL); - assert(err == 0); - err = pthread_join(pigeon_thread_handle, NULL); - assert(err == 0); - } - // join threads err = pthread_join(thermal_thread_handle, NULL); @@ -598,6 +654,8 @@ int main() { err = pthread_join(can_health_thread_handle, NULL); assert(err == 0); + //while (!do_exit) usleep(1000); + // destruct libusb libusb_close(dev_handle); diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile index 8a1c6f6b7aa644..a1f12619634454 100644 --- a/selfdrive/can/Makefile +++ b/selfdrive/can/Makefile @@ -65,3 +65,5 @@ dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc process_dbc.py dbc_template.cc clean: rm -rf libdbc.so* rm -f dbc_out/*.cc + rm -f dbcs.txt + rm -f dbcs.csv diff --git a/selfdrive/can/dbc.cc b/selfdrive/can/dbc.cc index c8295d1e0c8157..95d5e4d791394a 100644 --- a/selfdrive/can/dbc.cc +++ b/selfdrive/can/dbc.cc @@ -24,3 +24,9 @@ const DBC* dbc_lookup(const std::string& dbc_name) { void dbc_register(const DBC* dbc) { get_dbcs().push_back(dbc); } + +extern "C" { + const DBC* dbc_lookup(const char* dbc_name) { + return dbc_lookup(std::string(dbc_name)); + } +} diff --git a/selfdrive/can/libdbc_py.py b/selfdrive/can/libdbc_py.py index 7a5ae475911b0e..4914dca6b25c99 100644 --- a/selfdrive/can/libdbc_py.py +++ b/selfdrive/can/libdbc_py.py @@ -11,24 +11,60 @@ ffi = FFI() ffi.cdef(""" -typedef struct SignalParseOptions { +typedef struct { + const char* name; + double value; +} SignalPackValue; + +typedef struct { uint32_t address; const char* name; double default_value; } SignalParseOptions; -typedef struct MessageParseOptions { +typedef struct { uint32_t address; int check_frequency; } MessageParseOptions; -typedef struct SignalValue { +typedef struct { uint32_t address; uint16_t ts; const char* name; double value; } SignalValue; + +typedef enum { + DEFAULT, + HONDA_CHECKSUM, + HONDA_COUNTER, + TOYOTA_CHECKSUM, +} SignalType; + +typedef struct { + const char* name; + int b1, b2, bo; + bool is_signed; + double factor, offset; + SignalType type; +} Signal; + +typedef struct { + const char* name; + uint32_t address; + unsigned int size; + size_t num_sigs; + const Signal *sigs; +} Msg; + +typedef struct { + const char* name; + size_t num_msgs; + const Msg *msgs; +} DBC; + + void* can_init(int bus, const char* dbc_name, size_t num_message_options, const MessageParseOptions* message_options, size_t num_signal_options, const SignalParseOptions* signal_options); @@ -37,11 +73,7 @@ size_t can_query(void* can, uint64_t sec, bool *out_can_valid, size_t out_values_size, SignalValue* out_values); - -typedef struct SignalPackValue { - const char* name; - double value; -} SignalPackValue; +const DBC* dbc_lookup(const char* dbc_name); void* canpack_init(const char* dbc_name); diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py index ff52e165e2f5bd..81458f59aeaffa 100644 --- a/selfdrive/can/packer.py +++ b/selfdrive/can/packer.py @@ -29,7 +29,7 @@ def pack_bytes(self, addr, values): if __name__ == "__main__": - cp = CANPacker("honda_civic_touring_2016_can") + cp = CANPacker("honda_civic_touring_2016_can_generated") s = cp.pack_bytes(0x30c, [ ("PCM_SPEED", 123), ("PCM_GAS", 10), diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py index b58abe1be6b838..c15fe59e4437f2 100644 --- a/selfdrive/can/parser.py +++ b/selfdrive/can/parser.py @@ -1,6 +1,7 @@ import os import time from collections import defaultdict +import numbers from selfdrive.can.libdbc_py import libdbc, ffi @@ -10,8 +11,39 @@ def __init__(self, dbc_name, signals, checks=[], bus=0): self.vl = defaultdict(dict) self.ts = defaultdict(dict) + self.dbc = libdbc.dbc_lookup(dbc_name) + self.msg_name_to_addres = {} + self.address_to_msg_name = {} + + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + + name = ffi.string(msg.name) + address = msg.address + + self.msg_name_to_addres[name] = address + self.address_to_msg_name[address] = name + + # Convert message names into adresses + for i in range(len(signals)): + s = signals[i] + if not isinstance(s[1], numbers.Number): + s = (s[0], self.msg_name_to_addres[s[1]], s[2]) + signals[i] = s + + for i in range(len(checks)): + c = checks[i] + if not isinstance(c[0], numbers.Number): + c = (self.msg_name_to_addres[c[0]], c[1]) + checks[i] = c + sig_names = dict((name, ffi.new("char[]", name)) for name, _, _ in signals) + # Set default values by name + for sig_name, sig_address, sig_default in signals: + self.vl[self.address_to_msg_name[sig_address]][sig_name] = sig_default + signal_options_c = ffi.new("SignalParseOptions[]", [ { 'address': sig_address, @@ -21,7 +53,7 @@ def __init__(self, dbc_name, signals, checks=[], bus=0): message_options = dict((address, 0) for _, address, _ in signals) message_options.update(dict(checks)) - + message_options_c = ffi.new("MessageParseOptions[]", [ { 'address': address, @@ -54,6 +86,10 @@ def update_vl(self, sec): name = ffi.string(cv.name) self.vl[address][name] = cv.value self.ts[address][name] = cv.ts + + sig_name = self.address_to_msg_name[address] + self.vl[sig_name][name] = cv.value + self.ts[sig_name][name] = cv.ts ret.add(address) return ret @@ -74,7 +110,7 @@ def update(self, sec, wait): # signals = [ - # ("XMISSION_SPEED", 0x158, 0), #sig_name, sig_address, default + # ("XMISSION_SPEED", 0x158, 0), #sig_name, sig_address, default # ("WHEEL_SPEED_FL", 0x1d0, 0), # ("WHEEL_SPEED_FR", 0x1d0, 0), # ("WHEEL_SPEED_RL", 0x1d0, 0), @@ -123,7 +159,7 @@ def update(self, sec, wait): # (0x405, 3), # ] - # cp = CANParser("honda_civic_touring_2016_can", signals, checks, 0) + # cp = CANParser("honda_civic_touring_2016_can_generated", signals, checks, 0) signals = [ @@ -164,7 +200,7 @@ def update(self, sec, wait): (608, 50), ] - cp = CANParser("toyota_rav4_2017_pt", signals, checks, 0) + cp = CANParser("toyota_rav4_2017_pt_generated", signals, checks, 0) # print cp.vl diff --git a/selfdrive/can/process_dbc.py b/selfdrive/can/process_dbc.py index c48afc85668b3d..9acf125ab4df28 100755 --- a/selfdrive/can/process_dbc.py +++ b/selfdrive/can/process_dbc.py @@ -4,7 +4,7 @@ import jinja2 -import opendbc +from collections import Counter from common.dbc import dbc if len(sys.argv) != 3: @@ -31,6 +31,13 @@ else: checksum_type = None + +# Fail on duplicate messgae names +c = Counter([msg_name for address, msg_name, msg_size, sigs in msgs]) +for name, count in c.items(): + if count > 1: + sys.exit("Duplicate message name in DBC file %s" % name) + parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, len=len) with open(out_fn, "w") as out_f: diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 76916cb5b49d60..c5668bcdffa057 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -9,6 +9,7 @@ from selfdrive.car.honda.interface import CarInterface as HondaInterface from selfdrive.car.toyota.interface import CarInterface as ToyotaInterface from selfdrive.car.mock.interface import CarInterface as MockInterface +from common.fingerprints import HONDA, TOYOTA try: from .simulator.interface import CarInterface as SimInterface @@ -22,26 +23,23 @@ interfaces = { - "HONDA CIVIC 2016 TOURING": HondaInterface, - "ACURA ILX 2016 ACURAWATCH PLUS": HondaInterface, - "HONDA ACCORD 2016 TOURING": HondaInterface, - "HONDA CR-V 2016 TOURING": HondaInterface, - "HONDA ODYSSEY 2018 EX-L": HondaInterface, - "TOYOTA PRIUS 2017": ToyotaInterface, - "TOYOTA RAV4 2017": ToyotaInterface, - "TOYOTA RAV4 2017 HYBRID": ToyotaInterface, - - "simulator": SimInterface, - "simulator2": Sim2Interface, + HONDA.CIVIC: HondaInterface, + HONDA.ACURA_ILX: HondaInterface, + HONDA.CRV: HondaInterface, + HONDA.ODYSSEY: HondaInterface, + + TOYOTA.PRIUS: ToyotaInterface, + TOYOTA.RAV4: ToyotaInterface, + TOYOTA.RAV4H: ToyotaInterface, + TOYOTA.COROLLA: ToyotaInterface, + "simulator2": Sim2Interface, "mock": MockInterface } # **** for use live only **** def fingerprint(logcan, timeout): - if os.getenv("SIMULATOR") is not None or logcan is None: - return ("simulator", None) - elif os.getenv("SIMULATOR2") is not None: + if os.getenv("SIMULATOR2") is not None: return ("simulator2", None) finger_st = sec_since_boot() @@ -77,7 +75,6 @@ def fingerprint(logcan, timeout): def get_car(logcan, sendcan=None, passive=True): - # TODO: timeout only useful for replays so controlsd can start before unlogger timeout = 1. if passive else None candidate, fingerprints = fingerprint(logcan, timeout) diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index d2f69936e55e29..5372a44de41836 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -1,18 +1,15 @@ from collections import namedtuple import os -import common.numpy_fast as np -from common.numpy_fast import clip, interp -from common.realtime import sec_since_boot - -from selfdrive.config import CruiseButtons from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.controls.lib.drive_helpers import rate_limit - +from common.realtime import sec_since_boot +from common.numpy_fast import clip from . import hondacan from .values import AH +from common.fingerprints import HONDA as CAR -def actuator_hystereses(brake, braking, brake_steady, v_ego, civic, odyssey): +def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint): # hyst params... TODO: move these to VehicleParams brake_hyst_on = 0.02 # to activate brakes exceed this value brake_hyst_off = 0.005 # to deactivate brakes below this value @@ -32,7 +29,7 @@ def actuator_hystereses(brake, braking, brake_steady, v_ego, civic, odyssey): brake_steady = brake + brake_hyst_gap brake = brake_steady - if (not civic and not odyssey) and brake > 0.0: + if (car_fingerprint in (CAR.ACURA_ILX, CAR.CRV)) and brake > 0.0: brake += 0.15 return brake, braking, brake_steady @@ -71,14 +68,14 @@ 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): + """ Controls thread """ - # TODO: Make the accord work. - if CS.accord or not self.enable_camera: + if not self.enable_camera: return # *** apply brake hysteresis *** - brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.civic, CS.odyssey) + brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.CP.carFingerprint) # *** no output if not enabled *** if not enabled and CS.pcm_acc_status: @@ -121,11 +118,11 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ tt = sec_since_boot() GAS_MAX = 1004 BRAKE_MAX = 1024/4 - if CS.civic or CS.odyssey: + if CS.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY): is_fw_modified = os.getenv("DONGLE_ID") in ['b0f5a01cf604185c'] STEER_MAX = 0x1FFF if is_fw_modified else 0x1000 elif CS.crv: - STEER_MAX = 0x300 # CR-V only uses 12-bits and requires a lower value + STEER_MAX = 0x3e8 # CR-V only uses 12-bits and requires a lower value (max value from energee) else: STEER_MAX = 0xF00 GAS_OFFSET = 328 @@ -143,12 +140,8 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ can_sends = [] # Send steering command. - if CS.accord: - idx = frame % 2 - can_sends.append(hondacan.create_accord_steering_control(apply_steer, idx)) - else: - idx = frame % 4 - can_sends.extend(hondacan.create_steering_control(apply_steer, CS.crv, idx)) + idx = frame % 4 + can_sends.extend(hondacan.create_steering_control(apply_steer, CS.CP.carFingerprint, idx)) # Send gas and brake commands. if (frame % 2) == 0: @@ -165,16 +158,16 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ # Send dashboard UI commands. if (frame % 10) == 0: idx = (frame/10) % 4 - can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.civic, CS.accord, CS.crv, CS.odyssey, idx)) + can_sends.extend(hondacan.create_ui_commands(pcm_speed, hud, CS.CP.carFingerprint, idx)) # radar at 20Hz, but these msgs need to be sent at 50Hz on ilx (seems like an Acura bug) - if CS.acura: + if CS.CP.carFingerprint == CAR.ACURA_ILX: radar_send_step = 2 else: radar_send_step = 5 if (frame % radar_send_step) == 0: idx = (frame/radar_send_step) % 4 - can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.civic, CS.accord, CS.crv, CS.odyssey, idx)) + can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.CP.carFingerprint, 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 d056b146ec99db..4d896a1e174742 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -4,24 +4,26 @@ import selfdrive.messaging as messaging from selfdrive.can.parser import CANParser from selfdrive.config import Conversions as CV +from common.kalman.simple_kalman import KF1D +from common.fingerprints import HONDA as CAR import numpy as np -def parse_gear_shifter(can_gear_shifter, is_acura, is_odyssey): +def parse_gear_shifter(can_gear_shifter, car_fingerprint): + # TODO: Use values from DBC to parse this field if can_gear_shifter == 0x1: return "park" elif can_gear_shifter == 0x2: return "reverse" - if is_acura or is_odyssey: + if car_fingerprint in (CAR.ACURA_ILX, CAR.ODYSSEY): if can_gear_shifter == 0x3: return "neutral" elif can_gear_shifter == 0x4: return "drive" elif can_gear_shifter == 0xa: return "sport" - - else: + elif car_fingerprint in (CAR.CIVIC, CAR.CRV): if can_gear_shifter == 0x4: return "neutral" elif can_gear_shifter == 0x8: @@ -33,9 +35,6 @@ def parse_gear_shifter(can_gear_shifter, is_acura, is_odyssey): return "unknown" -_K0 = -0.3 -_K1 = -0.01879 -_K2 = 0.01013 def calc_cruise_offset(offset, speed): # euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed @@ -43,311 +42,102 @@ def calc_cruise_offset(offset, speed): # - speed = 0m/s, out = -0.3 # - speed = 34m/s, offset = 20, out = -0.25 # - speed = 34m/s, offset = -2.5, out = -1.8 + _K0 = -0.3 + _K1 = -0.01879 + _K2 = 0.01013 return min(_K0 + _K1 * speed + _K2 * speed * offset, 0.) + def get_can_signals(CP): # this function generates lists for signal, messages and initial values - if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": - dbc_f = 'honda_civic_touring_2016_can.dbc' - signals = [ - # sig_name, sig_address, default - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x14a, 0), - ("STEER_ANGLE_RATE", 0x14a, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - ("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x296, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x326, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x296, 0), - ("LEFT_BLINKER", 0x326, 0), - ("RIGHT_BLINKER", 0x326, 0), - ("CRUISE_SPEED_OFFSET", 0x37c, 0), - ("EPB_STATE", 0x1c2, 0), - ("BRAKE_HOLD_ACTIVE", 0x1A4, 0), - ] - checks = [ - # address, frequency - (0x14a, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x326, 10), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x37c, 10), - (0x405, 3), - ] - - elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": - dbc_f = 'acura_ilx_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x1a3, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - ("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x1a3, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ("CRUISE_SPEED_OFFSET", 0x37c, 0) - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x1a3, 50), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x37c, 10), - (0x405, 3), - ] - elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": - dbc_f = 'honda_accord_touring_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - #("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - #("CAR_GAS", 0x130, 0), - ("PEDAL_GAS", 0x17C, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - #("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x405, 3), - ] - elif CP.carFingerprint == "HONDA CR-V 2016 TOURING": - dbc_f = 'honda_crv_touring_2016_can.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x191, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - #("CAR_GAS", 0x130, 0), - ("CRUISE_BUTTONS", 0x1a6, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x191, 0), - ("MAIN_ON", 0x1a6, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x1a6, 0), - ("LEFT_BLINKER", 0x294, 0), - ("RIGHT_BLINKER", 0x294, 0), - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x191, 100), - (0x1a4, 50), - (0x1a6, 50), - (0x1b0, 50), - (0x1d0, 50), - (0x305, 10), - (0x324, 10), - (0x405, 3), - ] - elif CP.carFingerprint == "HONDA ODYSSEY 2018 EX-L": - dbc_f = 'honda_odyssey_exl_2018.dbc' - signals = [ - ("XMISSION_SPEED", 0x158, 0), - ("WHEEL_SPEED_FL", 0x1d0, 0), - ("WHEEL_SPEED_FR", 0x1d0, 0), - ("WHEEL_SPEED_RL", 0x1d0, 0), - ("WHEEL_SPEED_RR", 0x1d0, 0), - ("STEER_ANGLE", 0x156, 0), - ("STEER_ANGLE_RATE", 0x156, 0), - ("STEER_TORQUE_SENSOR", 0x18f, 0), - ("GEAR", 0x1a3, 0), - ("WHEELS_MOVING", 0x1b0, 1), - ("DOOR_OPEN_FL", 0x405, 1), - ("DOOR_OPEN_FR", 0x405, 1), - ("DOOR_OPEN_RL", 0x405, 1), - ("DOOR_OPEN_RR", 0x405, 1), - ("CRUISE_SPEED_PCM", 0x324, 0), - ("SEATBELT_DRIVER_LAMP", 0x305, 1), - ("SEATBELT_DRIVER_LATCHED", 0x305, 0), - ("BRAKE_PRESSED", 0x17c, 0), - ("BRAKE_SWITCH", 0x17c, 0), - ("CRUISE_BUTTONS", 0x296, 0), - ("ESP_DISABLED", 0x1a4, 1), - ("HUD_LEAD", 0x30c, 0), - ("USER_BRAKE", 0x1a4, 0), - ("STEER_STATUS", 0x18f, 5), - ("BRAKE_ERROR_1", 0x1b0, 1), - ("BRAKE_ERROR_2", 0x1b0, 1), - ("GEAR_SHIFTER", 0x1a3, 0), - ("MAIN_ON", 0x326, 0), - ("ACC_STATUS", 0x17c, 0), - ("PEDAL_GAS", 0x17c, 0), - ("CRUISE_SETTING", 0x296, 0), - ("LEFT_BLINKER", 0x326, 0), - ("RIGHT_BLINKER", 0x326, 0), - ("CRUISE_SPEED_OFFSET", 0x37c, 0), - ("EPB_STATE", 0x1c2, 0), - ("BRAKE_HOLD_ACTIVE", 0x1a4, 0), - ] - checks = [ - (0x156, 100), - (0x158, 100), - (0x17c, 100), - (0x1a3, 50), - (0x1a4, 50), - (0x1b0, 50), - (0x1c2, 50), - (0x1d0, 50), - (0x296, 25), - (0x305, 10), - (0x324, 10), - (0x326, 10), - (0x37c, 10), - (0x405, 3), - ] + signals = [ + ("XMISSION_SPEED", "ENGINE_DATA", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("STEER_ANGLE", "STEERING_SENSORS", 0), + ("STEER_ANGLE_RATE", "STEERING_SENSORS", 0), + ("STEER_TORQUE_SENSOR", "STEER_STATUS", 0), + ("DOOR_OPEN_FL", "DOORS_STATUS", 1), + ("DOOR_OPEN_FR", "DOORS_STATUS", 1), + ("DOOR_OPEN_RL", "DOORS_STATUS", 1), + ("DOOR_OPEN_RR", "DOORS_STATUS", 1), + ("LEFT_BLINKER", "SCM_FEEDBACK", 0), + ("RIGHT_BLINKER", "SCM_FEEDBACK", 0), + ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0), + ("GEAR", "GEARBOX", 0), + ("WHEELS_MOVING", "STANDSTILL", 1), + ("BRAKE_ERROR_1", "STANDSTILL", 1), + ("BRAKE_ERROR_2", "STANDSTILL", 1), + ("CRUISE_SPEED_PCM", "CRUISE", 0), + ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0), + ("BRAKE_PRESSED", "POWERTRAIN_DATA", 0), + ("BRAKE_SWITCH", "POWERTRAIN_DATA", 0), + ("CRUISE_BUTTONS", "SCM_BUTTONS", 0), + ("ESP_DISABLED", "VSA_STATUS", 1), + ("HUD_LEAD", "ACC_HUD", 0), + ("USER_BRAKE", "VSA_STATUS", 0), + ("STEER_STATUS", "STEER_STATUS", 5), + ("GEAR_SHIFTER", "GEARBOX", 0), + ("PEDAL_GAS", "POWERTRAIN_DATA", 0), + ("CRUISE_SETTING", "SCM_BUTTONS", 0), + ("ACC_STATUS", "POWERTRAIN_DATA", 0), + ] + + checks = [ + ("ENGINE_DATA", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING_SENSORS", 100), + ("DOORS_STATUS", 3), + ("SCM_FEEDBACK", 10), + ("CRUISE_PARAMS", 10), + ("GEARBOX", 100), + ("STANDSTILL", 50), + ("SEATBELT_STATUS", 10), + ("CRUISE", 10), + ("POWERTRAIN_DATA", 100), + ("VSA_STATUS", 50), + ("SCM_BUTTONS", 25), + ] + + if CP.carFingerprint == CAR.CIVIC: + dbc_f = 'honda_civic_touring_2016_can_generated.dbc' + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + elif CP.carFingerprint == CAR.ACURA_ILX: + dbc_f = 'acura_ilx_2016_can_generated.dbc' + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint == CAR.CRV: + dbc_f = 'honda_crv_touring_2016_can_generated.dbc' + signals += [("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint == CAR.ODYSSEY: + dbc_f = 'honda_odyssey_exl_2018_generated.dbc' + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + checks += [("EPB_STATUS", 50)] + # add gas interceptor reading if we are using it if CP.enableGas: - signals.append(("INTERCEPTOR_GAS", 0x201, 0)) - checks.append((0x201, 50)) + signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0)) + checks.append(("GAS_SENSOR", 50)) return dbc_f, signals, checks + def get_can_parser(CP): dbc_f, signals, checks = get_can_signals(CP) return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) + class CarState(object): def __init__(self, CP): - self.acura = False - self.civic = False - self.accord = False - self.crv = False - self.odyssey = False - if CP.carFingerprint == "HONDA CIVIC 2016 TOURING": - self.civic = True - elif CP.carFingerprint == "ACURA ILX 2016 ACURAWATCH PLUS": - self.acura = True - elif CP.carFingerprint == "HONDA ACCORD 2016 TOURING": - self.accord = True - elif CP.carFingerprint == "HONDA CR-V 2016 TOURING": - self.crv = True - elif CP.carFingerprint == "HONDA ODYSSEY 2018 EX-L": - self.odyssey = True - else: - raise ValueError("unsupported car %s" % CP.carFingerprint) - self.brake_only = CP.enableCruise self.CP = CP @@ -364,16 +154,13 @@ def __init__(self, CP): # vEgo kalman filter dt = 0.01 - self.v_ego_x = np.matrix([[0.0], [0.0]]) - self.v_ego_A = np.matrix([[1.0, dt], [0.0, 1.0]]) - self.v_ego_C = np.matrix([1.0, 0.0]) - self.v_ego_Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - self.v_ego_R = 1e3 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) self.v_ego = 0.0 - # import control - # (x, l, K) = control.dare(np.transpose(A), np.transpose(C), Q, R) - # self.v_ego_K = np.transpose(K) - self.v_ego_K = np.matrix([[0.12287673], [0.29666309]]) def update(self, cp): @@ -381,7 +168,7 @@ def update(self, cp): self.can_valid = cp.can_valid # car params - v_weight_v = [0., 1. ] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero # update prevs, update must run once per loop @@ -393,149 +180,90 @@ def update(self, cp): self.prev_right_blinker_on = self.right_blinker_on # ******************* parse out can ******************* - self.door_all_closed = not any([cp.vl[0x405]['DOOR_OPEN_FL'], cp.vl[0x405]['DOOR_OPEN_FR'], - cp.vl[0x405]['DOOR_OPEN_RL'], cp.vl[0x405]['DOOR_OPEN_RR']]) - self.seatbelt = not cp.vl[0x305]['SEATBELT_DRIVER_LAMP'] and cp.vl[0x305]['SEATBELT_DRIVER_LATCHED'] - # error 2 = temporary - # error 4 = temporary, hit a bump - # error 5 (permanent) - # error 6 = temporary - # error 7 (permanent) - #self.steer_error = cp.vl[0x18F]['STEER_STATUS'] in [5,7] - # whitelist instead of blacklist, safer at the expense of disengages - if self.accord: - self.steer_error = False - self.steer_not_allowed = False - else: - self.steer_error = cp.vl[0x18F]['STEER_STATUS'] not in [0,2,4,6] - self.steer_not_allowed = cp.vl[0x18F]['STEER_STATUS'] != 0 - self.brake_error = cp.vl[0x1B0]['BRAKE_ERROR_1'] or cp.vl[0x1B0]['BRAKE_ERROR_2'] - self.esp_disabled = cp.vl[0x1A4]['ESP_DISABLED'] + self.door_all_closed = not any([cp.vl["DOORS_STATUS"]['DOOR_OPEN_FL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_FR'], + cp.vl["DOORS_STATUS"]['DOOR_OPEN_RL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LAMP'] and cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LATCHED'] + + # 2 = temporary 4 = temporary, hit a bump 5 (permanent) 6 = temporary 7 (permanent) + # TODO: Use values from DBC to parse this field + self.steer_error = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 2, 4, 6] + self.steer_not_allowed = cp.vl["STEER_STATUS"]['STEER_STATUS'] != 0 + self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2'] + self.esp_disabled = cp.vl["VSA_STATUS"]['ESP_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners - self.v_wheel_fl = cp.vl[0x1D0]['WHEEL_SPEED_FL'] - self.v_wheel_fr = cp.vl[0x1D0]['WHEEL_SPEED_FR'] - self.v_wheel_rl = cp.vl[0x1D0]['WHEEL_SPEED_RL'] - self.v_wheel_rr = cp.vl[0x1D0]['WHEEL_SPEED_RR'] + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. # blend in transmission speed at low speed, since it has more low speed accuracy self.v_weight = interp(self.v_wheel, v_weight_bp, v_weight_v) - speed = (1. - self.v_weight) * cp.vl[0x158]['XMISSION_SPEED'] + self.v_weight * self.v_wheel + speed = (1. - self.v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] + self.v_weight * self.v_wheel if abs(speed - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed self.v_ego_x = np.matrix([[speed], [0.0]]) - self.v_ego_x = np.dot((self.v_ego_A - np.dot(self.v_ego_K, self.v_ego_C)), self.v_ego_x) + np.dot(self.v_ego_K, speed) self.v_ego_raw = speed - self.v_ego = float(self.v_ego_x[0]) - self.a_ego = float(self.v_ego_x[1]) + v_ego_x = self.v_ego_kf.update(speed) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + # this is a hack for the interceptor. This is now only used in the simulation + # TODO: Replace tests by toyota so this can go away if self.CP.enableGas: - # this is a hack - self.user_gas = cp.vl[0x201]['INTERCEPTOR_GAS'] + self.user_gas = cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change - #print self.user_gas, self.user_gas_pressed - if self.civic: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x14A]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x14A]['STEER_ANGLE_RATE'] - self.gear = 0 # TODO: civic has CVT... needs rev engineering - self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x326]['MAIN_ON'] - self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x326]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x326]['RIGHT_BLINKER'] - self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) - self.park_brake = cp.vl[0x1c2]['EPB_STATE'] != 0 - self.brake_hold = cp.vl[0x1A4]['BRAKE_HOLD_ACTIVE'] - elif self.accord: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = 0 # TODO: accord has CVT... needs rev engineering - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = -0.3 - self.park_brake = 0 # TODO - self.brake_hold = 0 # TODO - elif self.crv: - can_gear_shifter = cp.vl[0x191]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = cp.vl[0x191]['GEAR'] - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = -0.3 - self.park_brake = 0 # TODO - self.brake_hold = 0 # TODO - elif self.odyssey: - can_gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = cp.vl[0x1A3]['GEAR'] - self.cruise_setting = cp.vl[0x296]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x296]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x326]['MAIN_ON'] - self.blinker_on = cp.vl[0x326]['LEFT_BLINKER'] or cp.vl[0x326]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x326]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x326]['RIGHT_BLINKER'] - self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) - self.park_brake = cp.vl[0x1c2]['EPB_STATE'] != 0 - self.brake_hold = cp.vl[0x1a4]['BRAKE_HOLD_ACTIVE'] - elif self.acura: - can_gear_shifter = cp.vl[0x1A3]['GEAR_SHIFTER'] - self.angle_steers = cp.vl[0x156]['STEER_ANGLE'] - self.angle_steers_rate = cp.vl[0x156]['STEER_ANGLE_RATE'] - self.gear = cp.vl[0x1A3]['GEAR'] - self.cruise_setting = cp.vl[0x1A6]['CRUISE_SETTING'] - self.cruise_buttons = cp.vl[0x1A6]['CRUISE_BUTTONS'] - self.main_on = cp.vl[0x1A6]['MAIN_ON'] - self.blinker_on = cp.vl[0x294]['LEFT_BLINKER'] or cp.vl[0x294]['RIGHT_BLINKER'] - self.left_blinker_on = cp.vl[0x294]['LEFT_BLINKER'] - self.right_blinker_on = cp.vl[0x294]['RIGHT_BLINKER'] - self.cruise_speed_offset = calc_cruise_offset(cp.vl[0x37c]['CRUISE_SPEED_OFFSET'], self.v_ego) + + can_gear_shifter = cp.vl["GEARBOX"]['GEAR_SHIFTER'] + self.gear = 0 if self.CP.carFingerprint == CAR.CIVIC else cp.vl["GEARBOX"]['GEAR'] + self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE'] + self.angle_steers_rate = cp.vl["STEERING_SENSORS"]['STEER_ANGLE_RATE'] + + self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl["SCM_BUTTONS"]['CRUISE_BUTTONS'] + + self.blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] or cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + self.left_blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] + self.right_blinker_on = cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY): + self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0 + self.brake_hold = cp.vl["VSA_STATUS"]['BRAKE_HOLD_ACTIVE'] + self.main_on = cp.vl["SCM_FEEDBACK"]['MAIN_ON'] + else: self.park_brake = 0 # TODO self.brake_hold = 0 # TODO + self.main_on = cp.vl["SCM_BUTTONS"]['MAIN_ON'] - self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.acura, self.odyssey) + self.cruise_speed_offset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]['CRUISE_SPEED_OFFSET'], self.v_ego) + self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.CP.carFingerprint) - if self.accord: - # on the accord, this doesn't seem to include cruise control - self.car_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.steer_override = False - elif self.crv or self.odyssey: - # like accord, crv doesn't include cruise control - self.car_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 + self.pedal_gas = cp.vl["POWERTRAIN_DATA"]['PEDAL_GAS'] + # crv doesn't include cruise control + if self.CP.carFingerprint != CAR.CRV: + self.car_gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] else: - self.car_gas = cp.vl[0x130]['CAR_GAS'] - self.steer_override = abs(cp.vl[0x18F]['STEER_TORQUE_SENSOR']) > 1200 - self.steer_torque_driver = cp.vl[0x18F]['STEER_TORQUE_SENSOR'] + self.car_gas = self.pedal_gas + + self.steer_override = abs(cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR']) > 1200 + self.steer_torque_driver = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR'] # brake switch has shown some single time step noise, so only considered when # switch is on for at least 2 consecutive CAN samples - self.brake_switch = cp.vl[0x17C]['BRAKE_SWITCH'] - self.brake_pressed = cp.vl[0x17C]['BRAKE_PRESSED'] or \ + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + self.brake_pressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] or \ (self.brake_switch and self.brake_switch_prev and \ - cp.ts[0x17C]['BRAKE_SWITCH'] != self.brake_switch_ts) + cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) self.brake_switch_prev = self.brake_switch - self.brake_switch_ts = cp.ts[0x17C]['BRAKE_SWITCH'] - - self.user_brake = cp.vl[0x1A4]['USER_BRAKE'] - self.standstill = not cp.vl[0x1B0]['WHEELS_MOVING'] - self.v_cruise_pcm = cp.vl[0x324]['CRUISE_SPEED_PCM'] - self.pcm_acc_status = cp.vl[0x17C]['ACC_STATUS'] - self.pedal_gas = cp.vl[0x17C]['PEDAL_GAS'] - self.hud_lead = cp.vl[0x30C]['HUD_LEAD'] + self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + + self.user_brake = cp.vl["VSA_STATUS"]['USER_BRAKE'] + self.standstill = not cp.vl["STANDSTILL"]['WHEELS_MOVING'] + self.v_cruise_pcm = cp.vl["CRUISE"]['CRUISE_SPEED_PCM'] + self.pcm_acc_status = cp.vl["POWERTRAIN_DATA"]['ACC_STATUS'] + self.hud_lead = cp.vl["ACC_HUD"]['HUD_LEAD'] # carstate standalone tester diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 0c53f243d92759..81ae038099c050 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -2,6 +2,7 @@ import common.numpy_fast as np from selfdrive.config import Conversions as CV +from common.fingerprints import HONDA as CAR # *** Honda specific *** @@ -15,16 +16,19 @@ def can_cksum(mm): s %= 0x10 return s + def fix(msg, addr): msg2 = msg[0:-1] + chr(ord(msg[-1]) | can_cksum(struct.pack("I", addr)+msg)) return msg2 + def make_can_msg(addr, dat, idx, alt): if idx is not None: dat += chr(idx << 4) dat = fix(dat, addr) return [addr, 0, dat, alt] + def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx): """Creates a CAN message for the Honda DBC BRAKE_COMMAND.""" pump_on = apply_brake > 0 @@ -39,39 +43,17 @@ def create_brake_command(apply_brake, pcm_override, pcm_cancel_cmd, chime, idx): brakelights << 7) + chr(chime) + "\x00" return make_can_msg(0x1fa, msg, idx, 0) + def create_gas_command(gas_amount, idx): """Creates a CAN message for the Honda DBC GAS_COMMAND.""" msg = struct.pack("!H", gas_amount) return make_can_msg(0x200, msg, idx, 0) -def create_accord_steering_control(apply_steer, idx): - # TODO: doesn't work for some reason - if apply_steer == 0: - dat = [0, 0, 0x40, 0] - else: - dat = [0,0,0,0] - rp = np.clip(apply_steer/0xF, -0xFF, 0xFF) - if rp < 0: - rp += 512 - dat[0] |= (rp >> 5) & 0xf - dat[1] |= (rp) & 0x1f - if idx == 1: - dat[0] |= 0x20 - dat[1] |= 0x20 # always - dat[3] = -(dat[0]+dat[1]+dat[2]) & 0x7f - - # not first byte - dat[1] |= 0x80 - dat[2] |= 0x80 - dat[3] |= 0x80 - dat = ''.join(map(chr, dat)) - - return [0,0,dat,8] - -def create_steering_control(apply_steer, crv, idx): + +def create_steering_control(apply_steer, car_fingerprint, idx): """Creates a CAN message for the Honda DBC STEERING_CONTROL.""" commands = [] - if crv: + if car_fingerprint == CAR.CRV: msg_0x194 = struct.pack("!h", apply_steer << 4) + ("\x80" if apply_steer != 0 else "\x00") commands.append(make_can_msg(0x194, msg_0x194, idx, 0)) else: @@ -79,7 +61,8 @@ def create_steering_control(apply_steer, crv, idx): commands.append(make_can_msg(0xe4, msg_0xe4, idx, 0)) return commands -def create_ui_commands(pcm_speed, hud, civic, accord, crv, odyssey, idx): + +def create_ui_commands(pcm_speed, hud, car_fingerprint, idx): """Creates an iterable of CAN messages for the UIs.""" commands = [] pcm_speed_real = np.clip(int(round(pcm_speed / 0.002759506)), 0, @@ -90,43 +73,36 @@ def create_ui_commands(pcm_speed, hud, civic, accord, crv, odyssey, idx): msg_0x33d = chr(hud.X5) + chr(hud.lanes) + chr(hud.beep) + chr(hud.X8) commands.append(make_can_msg(0x33d, msg_0x33d, idx, 0)) - if civic or odyssey: # 2 more msgs + if car_fingerprint in (CAR.CIVIC, CAR.ODYSSEY): msg_0x35e = chr(0) * 7 commands.append(make_can_msg(0x35e, msg_0x35e, idx, 0)) - if civic or accord or odyssey: - msg_0x39f = ( - chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0) - ) + msg_0x39f = (chr(0) * 2 + chr(hud.acc_alert) + chr(0) + chr(0xff) + chr(0x7f) + chr(0)) commands.append(make_can_msg(0x39f, msg_0x39f, idx, 0)) return commands -def create_radar_commands(v_ego, civic, accord, crv, odyssey, idx): + +def create_radar_commands(v_ego, car_fingerprint, 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) speed = struct.pack('!B', v_ego_kph) - msg_0x300 = ("\xf9" + speed + "\x8a\xd0" +\ - ("\x20" if idx == 0 or idx == 3 else "\x00") +\ - "\x00\x00") - if civic: + msg_0x300 = ("\xf9" + speed + "\x8a\xd0" + + ("\x20" if idx == 0 or idx == 3 else "\x00") + + "\x00\x00") + + if car_fingerprint == CAR.CIVIC: msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00" - # add 8 on idx. - commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) - elif accord: - # 0300( 768)( 69) f9008ad0100000ef - # 0301( 769)( 69) 0ed8522256000029 - msg_0x301 = "\x0e\xd8\x52\x22\x56\x00\x00" - # add 0xc on idx? WTF is this? - commands.append(make_can_msg(0x300, msg_0x300, idx + 0xc, 1)) - elif crv: + commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) # add 8 on idx. + elif car_fingerprint == CAR.CRV: msg_0x301 = "\x00\x00\x50\x02\x51\x00\x00" commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) - elif odyssey: + elif car_fingerprint == CAR.ODYSSEY: msg_0x301 = "\x00\x00\x56\x02\x55\x00\x00" commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) - else: + elif car_fingerprint == CAR.ACURA_ILX: msg_0x301 = "\x0f\x18\x51\x02\x5a\x00\x00" commands.append(make_can_msg(0x300, msg_0x300, idx, 1)) + commands.append(make_can_msg(0x301, msg_0x301, idx, 1)) return commands diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index c443740926d325..e6725cb4491bbe 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,17 +1,16 @@ #!/usr/bin/env python import os import numpy as np +from cereal import car from common.numpy_fast import clip, interp 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, get_events from selfdrive.controls.lib.vehicle_model import VehicleModel -from cereal import car -from selfdrive.services import service_list -import selfdrive.messaging as messaging from selfdrive.car.honda.carstate import CarState, get_can_parser from selfdrive.car.honda.values import CruiseButtons, CM, BP, AH from selfdrive.controls.lib.planner import A_ACC_MAX +from common.fingerprints import HONDA as CAR try: from .carcontroller import CarController @@ -100,11 +99,7 @@ def __init__(self, CP, sendcan=None): self.sendcan = sendcan self.CC = CarController(CP.enableCamera) - if self.CS.accord: - # self.accord_msg = [] - raise NotImplementedError - - if not self.CS.civic and not self.CS.odyssey: + if self.CS.CP.carFingerprint == CAR.ACURA_ILX: self.compute_gb = get_compute_gb_acura() else: self.compute_gb = compute_gb_honda @@ -132,7 +127,6 @@ def get_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carName = "honda" - ret.radarName = "nidec" ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.honda @@ -157,7 +151,7 @@ def get_params(candidate, fingerprint): tireStiffnessFront_civic = 85400 tireStiffnessRear_civic = 90000 - if candidate == "HONDA CIVIC 2016 TOURING": + if candidate == CAR.CIVIC: stop_and_go = True ret.mass = mass_civic ret.wheelbase = wheelbase_civic @@ -171,7 +165,7 @@ def get_params(candidate, fingerprint): ret.longitudinalKpV = [3.6, 2.4, 1.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.54, 0.36] - elif candidate == "ACURA ILX 2016 ACURAWATCH PLUS": + elif candidate == CAR.ACURA_ILX: stop_and_go = False ret.mass = 3095./2.205 + std_cargo ret.wheelbase = 2.67 @@ -185,19 +179,7 @@ def get_params(candidate, fingerprint): ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.18, 0.12] - elif candidate == "HONDA ACCORD 2016 TOURING": - stop_and_go = False - ret.mass = 3580./2.205 + std_cargo - ret.wheelbase = 2.74 - ret.centerToFront = ret.wheelbase * 0.38 - ret.steerRatio = 15.3 - ret.steerKp, ret.steerKi = 0.8, 0.24 - - ret.longitudinalKpBP = [0., 5., 35.] - ret.longitudinalKpV = [1.2, 0.8, 0.5] - ret.longitudinalKiBP = [0., 35.] - ret.longitudinalKiV = [0.18, 0.12] - elif candidate == "HONDA CR-V 2016 TOURING": + elif candidate == CAR.CRV: stop_and_go = False ret.mass = 3572./2.205 + std_cargo ret.wheelbase = 2.62 @@ -209,7 +191,7 @@ def get_params(candidate, fingerprint): ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.18, 0.12] - elif candidate == "HONDA ODYSSEY 2018 EX-L": + elif candidate == CAR.ODYSSEY: stop_and_go = False ret.mass = 4354./2.205 + std_cargo ret.wheelbase = 3.00 @@ -303,7 +285,7 @@ def update(self, c): ret.brake = self.CS.user_brake ret.brakePressed = self.CS.brake_pressed != 0 # FIXME: read sendcan for brakelights - brakelights_threshold = 0.02 if self.CS.civic else 0.1 + brakelights_threshold = 0.02 if self.CS.CP.carFingerprint == CAR.CIVIC else 0.1 ret.brakeLights = bool(self.CS.brake_switch or c.actuators.brake > brakelights_threshold) @@ -329,6 +311,9 @@ def update(self, c): ret.leftBlinker = bool(self.CS.left_blinker_on) ret.rightBlinker = bool(self.CS.right_blinker_on) + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: be = car.CarState.ButtonEvent.new_message() be.type = 'leftBlinker' @@ -393,9 +378,9 @@ def update(self, c): events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) if not ret.gearShifter == 'drive': events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.door_all_closed: + if ret.doorOpen: events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.seatbelt: + if ret.seatbeltUnlatched: events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if self.CS.esp_disabled: events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) @@ -424,7 +409,7 @@ def update(self, c): # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert if self.CP.enableCruise and not ret.cruiseState.enabled and c.actuators.brake <= 0.: events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) - if not self.CS.civic and ret.vEgo < 0.001: + if self.CS.CP.carFingerprint != CAR.CIVIC and ret.vEgo < 0.001: events.append(create_event('manualRestart', [ET.WARNING])) cur_time = sec_since_boot() diff --git a/selfdrive/radar/nidec/interface.py b/selfdrive/car/honda/radar_interface.py similarity index 100% rename from selfdrive/radar/nidec/interface.py rename to selfdrive/car/honda/radar_interface.py diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 6acad5e5a99a2e..4f55800c3fc123 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -47,7 +47,6 @@ def get_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carName = "mock" - ret.radarName = "mock" ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.noOutput diff --git a/selfdrive/radar/mock/interface.py b/selfdrive/car/mock/radar_interface.py similarity index 100% rename from selfdrive/radar/mock/interface.py rename to selfdrive/car/mock/radar_interface.py diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 5b56e2a6f29582..9649fa41d2a8ed 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -6,7 +6,8 @@ create_steer_command, create_ui_command, \ create_ipas_steer_command, create_accel_command, \ create_fcw_command -from selfdrive.car.toyota.values import CAR, ECU, STATIC_MSGS +from selfdrive.car.toyota.values import ECU, STATIC_MSGS +from common.fingerprints import TOYOTA as CAR ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value @@ -17,10 +18,7 @@ STEER_MAX = 1500 STEER_DELTA_UP = 10 # 1.5s time to peak torque STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) -STEER_ERROR_MAX = 500 # max delta between torque cmd and torque motor - -STEER_IPAS_MAX = 340 -STEER_IPAS_DELTA_MAX = 3 +STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor TARGET_IDS = [0x340, 0x341, 0x342, 0x343, 0x344, 0x345, 0x363, 0x364, 0x365, 0x370, 0x371, 0x372, diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index e85902f944b9e5..4444ead5f5ee2a 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -1,12 +1,14 @@ import os import selfdrive.messaging as messaging -from selfdrive.car.toyota.values import CAR +from common.fingerprints import TOYOTA as CAR from selfdrive.can.parser import CANParser from selfdrive.config import Conversions as CV +from common.kalman.simple_kalman import KF1D import numpy as np -def parse_gear_shifter(can_gear, car_fingerprint): +def parse_gear_shifter(can_gear, car_fingerprint): + # TODO: Use values from DBC to parse this field if car_fingerprint == CAR.PRIUS: if can_gear == 0x0: return "park" @@ -18,7 +20,7 @@ def parse_gear_shifter(can_gear, car_fingerprint): return "drive" elif can_gear == 0x4: return "brake" - elif car_fingerprint in [CAR.RAV4, CAR.RAV4H]: + elif car_fingerprint in [CAR.RAV4, CAR.RAV4H, CAR.COROLLA]: if can_gear == 0x20: return "park" elif can_gear == 0x10: @@ -36,74 +38,54 @@ def parse_gear_shifter(can_gear, car_fingerprint): def get_can_parser(CP): # this function generates lists for signal, messages and initial values if CP.carFingerprint == CAR.PRIUS: - dbc_f = 'toyota_prius_2017_pt.dbc' - signals = [ - ("GEAR", 295, 0), - ("BRAKE_PRESSED", 550, 0), - ("GAS_PEDAL", 581, 0), - ] - checks = [ - (550, 40), - (581, 33) - ] + dbc_f = 'toyota_prius_2017_pt_generated.dbc' elif CP.carFingerprint == CAR.RAV4H: - dbc_f = 'toyota_rav4_hybrid_2017_pt.dbc' - signals = [ - ("GEAR", 956, 0), - ("BRAKE_PRESSED", 550, 0), - ("GAS_PEDAL", 581, 0), - ] - checks = [ - (550, 40), - (581, 33) - ] + dbc_f = 'toyota_rav4_hybrid_2017_pt_generated.dbc' elif CP.carFingerprint == CAR.RAV4: - dbc_f = 'toyota_rav4_2017_pt.dbc' - signals = [ - ("GEAR", 956, 0x20), - ("BRAKE_PRESSED", 548, 0), - ("GAS_PEDAL", 705, 0), - ] - checks = [ - (548, 40), - (705, 33) - ] - - # TODO: DOORS, GAS_PEDAL, BRAKE_PRESSED for RAV4 - signals += [ + dbc_f = 'toyota_rav4_2017_pt_generated.dbc' + elif CP.carFingerprint == CAR.COROLLA: + dbc_f = 'toyota_corolla_2017_pt_generated.dbc' + + signals = [ # sig_name, sig_address, default - ("WHEEL_SPEED_FL", 170, 0), - ("WHEEL_SPEED_FR", 170, 0), - ("WHEEL_SPEED_RL", 170, 0), - ("WHEEL_SPEED_RR", 170, 0), - ("DOOR_OPEN_FL", 1568, 1), - ("DOOR_OPEN_FR", 1568, 1), - ("DOOR_OPEN_RL", 1568, 1), - ("DOOR_OPEN_RR", 1568, 1), - ("SEATBELT_DRIVER_UNLATCHED", 1568, 1), - ("TC_DISABLED", 951, 1), - ("STEER_ANGLE", 37, 0), - ("STEER_FRACTION", 37, 0), - ("STEER_RATE", 37, 0), - ("GAS_RELEASED", 466, 0), - ("CRUISE_STATE", 466, 0), - ("MAIN_ON", 467, 0), - ("SET_SPEED", 467, 0), - ("LOW_SPEED_LOCKOUT", 467, 0), - ("STEER_TORQUE_DRIVER", 608, 0), - ("STEER_TORQUE_EPS", 608, 0), - ("TURN_SIGNALS", 1556, 3), # 3 is no blinkers - ("LKA_STATE", 610, 0), - ("BRAKE_LIGHTS_ACC", 951, 0), + ("GEAR", "GEAR_PACKET", 0), + ("BRAKE_PRESSED", "BRAKE_MODULE", 0), + ("GAS_PEDAL", "GAS_PEDAL", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("DOOR_OPEN_FL", "SEATS_DOORS", 1), + ("DOOR_OPEN_FR", "SEATS_DOORS", 1), + ("DOOR_OPEN_RL", "SEATS_DOORS", 1), + ("DOOR_OPEN_RR", "SEATS_DOORS", 1), + ("SEATBELT_DRIVER_UNLATCHED", "SEATS_DOORS", 1), + ("TC_DISABLED", "ESP_CONTROL", 1), + ("STEER_ANGLE", "STEER_ANGLE_SENSOR", 0), + ("STEER_FRACTION", "STEER_ANGLE_SENSOR", 0), + ("STEER_RATE", "STEER_ANGLE_SENSOR", 0), + ("GAS_RELEASED", "PCM_CRUISE", 0), + ("CRUISE_STATE", "PCM_CRUISE", 0), + ("MAIN_ON", "PCM_CRUISE_2", 0), + ("SET_SPEED", "PCM_CRUISE_2", 0), + ("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0), + ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), + ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR", 0), + ("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers + ("LKA_STATE", "EPS_STATUS", 0), + ("BRAKE_LIGHTS_ACC", "ESP_CONTROL", 0), + ("AUTO_HIGH_BEAM", "LIGHT_STALK", 0), ] - checks += [ - (170, 80), - (37, 80), - (466, 33), - (467, 33), - (608, 50), - (610, 25), + checks = [ + ("BRAKE_MODULE", 40), + ("GAS_PEDAL", 33), + ("WHEEL_SPEEDS", 80), + ("STEER_ANGLE_SENSOR", 80), + ("PCM_CRUISE", 33), + ("PCM_CRUISE_2", 33), + ("STEER_TORQUE_SENSOR", 50), + ("EPS_STATUS", 25), ] return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 0) @@ -121,82 +103,69 @@ def __init__(self, CP): # vEgo kalman filter dt = 0.01 - self.v_ego_x = np.matrix([[0.0], [0.0]]) - self.v_ego_A = np.matrix([[1.0, dt], [0.0, 1.0]]) - self.v_ego_C = np.matrix([1.0, 0.0]) - self.v_ego_Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - self.v_ego_R = 1e3 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) self.v_ego = 0.0 - # import control - # (x, l, K) = control.dare(np.transpose(A), np.transpose(C), Q, R) - # self.v_ego_K = np.transpose(K) - self.v_ego_K = np.matrix([[0.12287673], [0.29666309]]) def update(self, cp): - # copy can_valid self.can_valid = cp.can_valid - if self.car_fingerprint == CAR.PRIUS: - can_gear = cp.vl[295]['GEAR'] - self.brake_pressed = cp.vl[550]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[581]['GAS_PEDAL'] - elif self.car_fingerprint == CAR.RAV4H: - can_gear = cp.vl[956]['GEAR'] - self.brake_pressed = cp.vl[550]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[581]['GAS_PEDAL'] - elif self.car_fingerprint == CAR.RAV4: - can_gear = cp.vl[956]['GEAR'] - self.brake_pressed = cp.vl[548]['BRAKE_PRESSED'] - self.pedal_gas = cp.vl[705]['GAS_PEDAL'] - # update prevs, update must run once per loop self.prev_left_blinker_on = self.left_blinker_on self.prev_right_blinker_on = self.right_blinker_on - # ******************* parse out can ******************* - self.door_all_closed = not any([cp.vl[1568]['DOOR_OPEN_FL'], cp.vl[1568]['DOOR_OPEN_FR'], - cp.vl[1568]['DOOR_OPEN_RL'], cp.vl[1568]['DOOR_OPEN_RR']]) - self.seatbelt = not cp.vl[1568]['SEATBELT_DRIVER_UNLATCHED'] - # whitelist instead of blacklist, safer at the expense of disengages + self.door_all_closed = not any([cp.vl["SEATS_DOORS"]['DOOR_OPEN_FL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_FR'], + cp.vl["SEATS_DOORS"]['DOOR_OPEN_RL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATS_DOORS"]['SEATBELT_DRIVER_UNLATCHED'] + self.steer_error = False self.brake_error = 0 - self.esp_disabled = cp.vl[951]['TC_DISABLED'] + + can_gear = cp.vl["GEAR_PACKET"]['GEAR'] + self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] + self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL'] + self.car_gas = self.pedal_gas + self.esp_disabled = cp.vl["ESP_CONTROL"]['TC_DISABLED'] + # calc best v_ego estimate, by averaging two opposite corners - self.v_wheel_fl = cp.vl[170]['WHEEL_SPEED_FL'] - self.v_wheel_fr = cp.vl[170]['WHEEL_SPEED_FR'] - self.v_wheel_rl = cp.vl[170]['WHEEL_SPEED_RL'] - self.v_wheel_rr = cp.vl[170]['WHEEL_SPEED_RR'] - self.v_wheel = ( - cp.vl[170]['WHEEL_SPEED_FL'] + cp.vl[170]['WHEEL_SPEED_FR'] + - cp.vl[170]['WHEEL_SPEED_RL'] + cp.vl[170]['WHEEL_SPEED_RR']) / 4. * CV.KPH_TO_MS + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS + self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. # Kalman filter if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) - self.v_ego_x = np.dot((self.v_ego_A - np.dot(self.v_ego_K, self.v_ego_C)), self.v_ego_x) + np.dot(self.v_ego_K, self.v_wheel) + self.v_ego_raw = self.v_wheel - self.v_ego = float(self.v_ego_x[0]) - self.a_ego = float(self.v_ego_x[1]) + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) self.standstill = not self.v_wheel > 0.001 - self.angle_steers = cp.vl[37]['STEER_ANGLE'] + cp.vl[37]['STEER_FRACTION'] - self.angle_steers_rate = cp.vl[37]['STEER_RATE'] + self.angle_steers = cp.vl["STEER_ANGLE_SENSOR"]['STEER_ANGLE'] + cp.vl["STEER_ANGLE_SENSOR"]['STEER_FRACTION'] + self.angle_steers_rate = cp.vl["STEER_ANGLE_SENSOR"]['STEER_RATE'] self.gear_shifter = parse_gear_shifter(can_gear, self.car_fingerprint) - self.main_on = cp.vl[467]['MAIN_ON'] - self.left_blinker_on = cp.vl[1556]['TURN_SIGNALS'] == 1 - self.right_blinker_on = cp.vl[1556]['TURN_SIGNALS'] == 2 + self.main_on = cp.vl["PCM_CRUISE_2"]['MAIN_ON'] + 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[608]['STEER_TORQUE_DRIVER']) > 100 - self.steer_error = cp.vl[610]['LKA_STATE'] == 50 - self.steer_torque_driver = cp.vl[608]['STEER_TORQUE_DRIVER'] - self.steer_torque_motor = cp.vl[608]['STEER_TORQUE_EPS'] + self.steer_override = abs(cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']) > 100 + self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] == 50 + self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER'] + self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS'] self.user_brake = 0 - self.v_cruise_pcm = cp.vl[467]['SET_SPEED'] - self.pcm_acc_status = cp.vl[466]['CRUISE_STATE'] - self.car_gas = self.pedal_gas - self.gas_pressed = not cp.vl[466]['GAS_RELEASED'] - self.low_speed_lockout = cp.vl[467]['LOW_SPEED_LOCKOUT'] == 2 - self.brake_lights = bool(cp.vl[951]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) + self.v_cruise_pcm = cp.vl["PCM_CRUISE_2"]['SET_SPEED'] + self.pcm_acc_status = cp.vl["PCM_CRUISE"]['CRUISE_STATE'] + self.gas_pressed = not cp.vl["PCM_CRUISE"]['GAS_RELEASED'] + self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2 + self.brake_lights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) + self.generic_toggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM']) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index c490c1db23d4d0..20cf8e8db0c387 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -9,12 +9,15 @@ from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.car.toyota.carstate import CarState, get_can_parser -from selfdrive.car.toyota.values import CAR, ECU, check_ecu_msgs +from selfdrive.car.toyota.values import ECU, check_ecu_msgs +from common.fingerprints import TOYOTA as CAR + try: from selfdrive.car.toyota.carcontroller import CarController except ImportError: CarController = None + class CarInterface(object): def __init__(self, CP, sendcan=None): self.CP = CP @@ -53,7 +56,6 @@ def get_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carName = "toyota" - ret.radarName = "toyota" ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.toyota @@ -74,12 +76,30 @@ def get_params(candidate, fingerprint): tireStiffnessFront_civic = 85400 tireStiffnessRear_civic = 90000 - ret.mass = 3045./2.205 + std_cargo - ret.wheelbase = 2.70 if candidate == CAR.PRIUS else 2.65 + if candidate == CAR.PRIUS: + ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 14.5 #TODO: find exact value for Prius + ret.mass = 3045./2.205 + std_cargo + elif candidate in [CAR.RAV4, CAR.RAV4H]: + ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.65 + ret.steerRatio = 14.5 # Rav4 2017 + ret.mass = 3650./2.205 + std_cargo # mean between normal and hybrid + elif candidate == CAR.COROLLA: + ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 17.8 + ret.mass = 2860./2.205 + std_cargo # mean between normal and hybrid + ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 14.5 #Rav4 2017, TODO: find exact value for Prius - ret.steerKp, ret.steerKi = 0.6, 0.05 - ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + + if candidate == CAR.COROLLA: + ret.steerKp, ret.steerKi = 0.2, 0.05 + ret.steerKf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594 + else: + ret.steerKp, ret.steerKi = 0.6, 0.05 + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 ret.longPidDeadzoneBP = [0., 9.] ret.longPidDeadzoneV = [0., .15] @@ -88,7 +108,7 @@ def get_params(candidate, fingerprint): # to a negative value, so it won't matter. if candidate in [CAR.PRIUS, CAR.RAV4H]: # rav4 hybrid can do stop and go ret.minEnableSpeed = -1. - elif candidate == CAR.RAV4: # TODO: hack ICE Rav4 to do stop and go + elif candidate in [CAR.RAV4, CAR.COROLLA]: # TODO: hack ICE to do stop and go ret.minEnableSpeed = 19. * CV.MPH_TO_MS centerToRear = ret.wheelbase - ret.centerToFront @@ -134,9 +154,9 @@ def get_params(candidate, fingerprint): ret.longitudinalKiBP = [0., 35.] ret.longitudinalKiV = [0.54, 0.36] - if candidate == CAR.PRIUS: + if candidate in [CAR.PRIUS]: ret.steerRateCost = 2. - elif candidate in [CAR.RAV4, CAR.RAV4H]: + elif candidate in [CAR.RAV4, CAR.RAV4H, CAR.COROLLA]: ret.steerRateCost = 1. return ret @@ -181,7 +201,7 @@ def update(self, c): ret.steeringAngle = self.CS.angle_steers ret.steeringRate = self.CS.angle_steers_rate - ret.steeringTorque = 0 + ret.steeringTorque = self.CS.steer_torque_driver ret.steeringPressed = self.CS.steer_override # cruise state @@ -194,7 +214,7 @@ def update(self, c): # receiving any special command ret.cruiseState.standstill = False else: - ret.cruiseState.standstill = self.CS.pcm_acc_status == 7 + ret.cruiseState.standstill = self.CS.pcm_acc_status == 7 # TODO: button presses buttonEvents = [] @@ -215,6 +235,11 @@ def update(self, c): ret.leftBlinker = bool(self.CS.left_blinker_on) ret.rightBlinker = bool(self.CS.right_blinker_on) + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + ret.genericToggle = self.CS.generic_toggle + # events events = [] if not self.CS.can_valid: @@ -225,9 +250,9 @@ def update(self, c): self.can_invalid_count = 0 if not ret.gearShifter == 'drive' and self.CP.enableDsu: events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.door_all_closed: + if ret.doorOpen: events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) - if not self.CS.seatbelt: + if ret.seatbeltUnlatched: events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if self.CS.esp_disabled and self.CP.enableDsu: events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) diff --git a/selfdrive/radar/toyota/interface.py b/selfdrive/car/toyota/radar_interface.py similarity index 100% rename from selfdrive/radar/toyota/interface.py rename to selfdrive/car/toyota/radar_interface.py diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index d8fa0c699e5453..b481abdc4ddc0d 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1,64 +1,61 @@ -class CAR: - PRIUS = "TOYOTA PRIUS 2017" - RAV4H = "TOYOTA RAV4 2017 HYBRID" - RAV4 = "TOYOTA RAV4 2017" +from common.fingerprints import TOYOTA as CAR +class ECU: + CAM = 0 # camera + DSU = 1 # driving support unit + APGS = 2 # advanced parking guidance system -class ECU: - CAM = 0 # camera - DSU = 1 # driving support unit - APGS = 2 # advanced parking guidance system +# addr: (ecu, cars, bus, 1/freq*100, vl) +STATIC_MSGS = {0x141: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 2, '\x00\x00\x00\x46'), + 0x128: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 3, '\xf4\x01\x90\x83\x00\x37'), -# addr, [ecu, bus, 1/freq*100, vl] -STATIC_MSGS = {0x141: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 2, '\x00\x00\x00\x46'), - 0x128: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 3, '\xf4\x01\x90\x83\x00\x37'), - - 0x292: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 3, '\x00\x00\x00\x00\x00\x00\x00\x9e'), - 0x283: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 3, '\x00\x00\x00\x00\x00\x00\x8c'), + 0x292: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 3, '\x00\x00\x00\x00\x00\x00\x00\x9e'), + 0x283: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 3, '\x00\x00\x00\x00\x00\x00\x8c'), 0x2E6: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 3, '\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), 0x2E7: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 3, '\xa8\x9c\x31\x9c\x00\x00\x00\x02'), - 0x240: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x241: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x244: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x245: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), - 0x248: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 5, '\x00\x00\x00\x00\x00\x00\x01'), - 0x344: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'), + 0x240: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + 0x241: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + 0x244: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + 0x245: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + 0x248: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 5, '\x00\x00\x00\x00\x00\x00\x01'), + 0x344: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'), - 0x160: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'), - 0x161: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 7, '\x00\x1e\x00\x00\x00\x80\x07'), + 0x160: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'), + 0x161: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 7, '\x00\x1e\x00\x00\x00\x80\x07'), - 0x32E: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 20, '\x00\x00\x00\x00\x00\x00\x00\x00'), + 0x32E: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 20, '\x00\x00\x00\x00\x00\x00\x00\x00'), 0x33E: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x0f\xff\x26\x40\x00\x1f\x00'), 0x365: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'), - 0x365: (ECU.DSU, (CAR.RAV4,), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'), + 0x365: (ECU.DSU, (CAR.RAV4, CAR.COROLLA), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'), 0x366: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 0, 20, '\x00\x00\x4d\x82\x40\x02\x00'), - 0x366: (ECU.DSU, (CAR.RAV4,), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'), + 0x366: (ECU.DSU, (CAR.RAV4, CAR.COROLLA), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'), - 0x367: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 40, '\x06\x00'), + 0x367: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 40, '\x06\x00'), - 0x414: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x17\x00'), - 0x489: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), - 0x48a: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), - 0x48b: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'), - 0x4d3: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x1C\x00\x00\x01\x00\x00\x00\x00'), - 0x130: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 100, '\x00\x00\x00\x00\x00\x00\x38'), + 0x414: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x00\x00\x00\x00\x00\x00\x17\x00'), + 0x489: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + 0x48a: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + 0x48b: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'), + 0x4d3: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x1C\x00\x00\x01\x00\x00\x00\x00'), + 0x130: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 1, 100, '\x00\x00\x00\x00\x00\x00\x38'), 0x466: (ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 1, 100, '\x20\x20\xAD'), - 0x396: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\xBD\x00\x00\x00\x60\x0F\x02\x00'), - 0x43A: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x84\x00\x00\x00\x00\x00\x00\x00'), - 0x43B: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), - 0x497: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), - 0x4CC: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x0D\x00\x00\x00\x00\x00\x00\x00'), - 0x4CB: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4), 0, 100, '\x0c\x00\x00\x00\x00\x00\x00\x00'), + 0x466: (ECU.CAM, (CAR.COROLLA), 1, 100, '\x24\x20\xB1'), + 0x396: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\xBD\x00\x00\x00\x60\x0F\x02\x00'), + 0x43A: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x84\x00\x00\x00\x00\x00\x00\x00'), + 0x43B: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + 0x497: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + 0x4CC: (ECU.APGS, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x0D\x00\x00\x00\x00\x00\x00\x00'), + 0x4CB: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.RAV4, CAR.COROLLA), 0, 100, '\x0c\x00\x00\x00\x00\x00\x00\x00'), 0x470: (ECU.DSU, (CAR.PRIUS, CAR.RAV4H,), 1, 100, '\x00\x00\x02\x7a'), } def check_ecu_msgs(fingerprint, candidate, ecu): # return True if fingerprint contains messages normally sent by a given ecu - ecu_msgs = [x for x in STATIC_MSGS if (ecu == STATIC_MSGS[x][0] and - candidate in STATIC_MSGS[x][1] and + ecu_msgs = [x for x in STATIC_MSGS if (ecu == STATIC_MSGS[x][0] and + candidate in STATIC_MSGS[x][1] and STATIC_MSGS[x][2] == 0)] return any(msg for msg in fingerprint if msg in ecu_msgs) diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index e6123f3592d107..b5ca9cccd47a63 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.4.0.2-openpilot" +#define COMMA_VERSION "0.4.1-openpilot" diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 72e98d732d1680..f02fb79e1baf58 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -3,6 +3,7 @@ import zmq import numpy as np import numpy.matlib +import importlib from collections import defaultdict from fastcluster import linkage_vector import selfdrive.messaging as messaging @@ -49,14 +50,13 @@ def radard_thread(gctx=None): # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) - mocked= CP.radarName == "mock" + mocked = CP.carName == "mock" VM = VehicleModel(CP) cloudlog.info("radard got CarParams") # import the radar from the fingerprint - cloudlog.info("radard is importing %s", CP.radarName) - exec('from selfdrive.radar.'+CP.radarName+'.interface import RadarInterface') - + cloudlog.info("radard is importing %s", CP.carName) + RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % CP.carName).RadarInterface context = zmq.Context() # *** subscribe to features and model from visiond diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 75ff7e944744e8..e1713d34f76c2f 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -16,6 +16,7 @@ parser.add_argument('--pipe', action='store_true') parser.add_argument('--raw', action='store_true') parser.add_argument('--json', action='store_true') + parser.add_argument('--dump-json', action='store_true') parser.add_argument('--addr', default='127.0.0.1') parser.add_argument("socket", type=str, nargs='*', help="socket name") args = parser.parse_args() @@ -41,6 +42,8 @@ hexdump(sock.recv()) elif args.json: print(json.loads(sock.recv())) + elif args.dump_json: + print json.dumps(messaging.recv_one(sock).to_dict()) else: print messaging.recv_one(sock) diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd index 320205cf72c6e4..d4f35f05833511 100755 Binary files a/selfdrive/loggerd/loggerd and b/selfdrive/loggerd/loggerd differ diff --git a/selfdrive/radar/__init__.py b/selfdrive/radar/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/radar/mock/__init__.py b/selfdrive/radar/mock/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/radar/nidec/__init__.py b/selfdrive/radar/nidec/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/radar/toyota/__init__.py b/selfdrive/radar/toyota/__init__.py deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd index 6df52a9092e3fe..d33c881179bc70 100755 Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index f72cbbe2baa481..bc3396ada48a63 100755 Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ diff --git a/selfdrive/service_list.yaml b/selfdrive/service_list.yaml index 449a5b66c021ad..0d726314bac01e 100644 --- a/selfdrive/service_list.yaml +++ b/selfdrive/service_list.yaml @@ -53,6 +53,12 @@ trimbleGnss: [8041, true] ubloxRaw: [8042, true] gpsPlannerPoints: [8043, true] gpsPlannerPlan: [8044, true] +applanixRaw: [8046, true] +orbLocation: [8047, true] +trafficSigns: [8048, true] +liveLocationTiming: [8049, true] +orbslamCorrection: [8050, true] +liveLocationCorrected: [8051, true] testModel: [8040, false] testLiveLocation: [8045, false] diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py index 43b0667726a2e8..28eceeb161d93a 100755 --- a/selfdrive/test/plant/plant.py +++ b/selfdrive/test/plant/plant.py @@ -8,11 +8,12 @@ from opendbc import DBC_PATH from common.realtime import Ratekeeper - +from selfdrive.config import Conversions as CV import selfdrive.messaging as messaging from selfdrive.services import service_list from selfdrive.config import CruiseButtons from selfdrive.car.honda.hondacan import fix +from common.fingerprints import HONDA as CAR from selfdrive.car.honda.carstate import get_can_signals from selfdrive.boardd.boardd import can_capnp_to_can_list, can_list_to_can_capnp @@ -21,10 +22,10 @@ from cereal import car from common.dbc import dbc -honda = dbc(os.path.join(DBC_PATH, "honda_civic_touring_2016_can.dbc")) +honda = dbc(os.path.join(DBC_PATH, "honda_civic_touring_2016_can_generated.dbc")) # Trick: set 0x201 (interceptor) in fingerprints for gas is controlled like if there was an interceptor -CP = CarInterface.get_params("HONDA CIVIC 2016 TOURING", {0x201}) +CP = CarInterface.get_params(CAR.CIVIC, {0x201}) def car_plant(pos, speed, grade, gas, brake): @@ -66,7 +67,7 @@ def car_plant(pos, speed, grade, gas, brake): return speed, acceleration def get_car_can_parser(): - dbc_f = 'honda_civic_touring_2016_can.dbc' + dbc_f = 'honda_civic_touring_2016_can_generated.dbc' signals = [ ("STEER_TORQUE", 0xe4, 0), ("STEER_TORQUE_REQUEST", 0xe4, 0), @@ -92,7 +93,6 @@ class Plant(object): def __init__(self, lead_relevancy=False, rate=100, speed=0.0, distance_lead=2.0): self.rate = rate - self.civic = True self.brake_only = False if not Plant.messaging_initialized: @@ -143,7 +143,7 @@ def speed_sensor(self, speed): if speed<0.3: return 0 else: - return speed + return speed * CV.MS_TO_KPH def current_time(self): return float(self.rk.frame) / self.rate @@ -217,15 +217,32 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) # ******** publish the car ******** vls = [self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), - self.angle_steer, self.angle_steer_rate, 0, self.gear_choice, speed!=0, - 0, 0, 0, 0, - self.v_cruise, not self.seatbelt, self.seatbelt, self.brake_pressed, 0., - self.user_gas, cruise_buttons, self.esp_disabled, 0, - self.user_brake, self.steer_error, self.brake_error, - self.brake_error, self.gear_shifter, self.main_on, self.acc_status, - self.pedal_gas, self.cruise_setting, - # append one more zero for gas interceptor - 0,0,0,0,0,0] + self.angle_steer, self.angle_steer_rate, 0, + 0, 0, 0, 0, # Doors + 0, 0, # Blinkers + 0, # Cruise speed offset + self.gear_choice, + speed != 0, + self.brake_error, self.brake_error, + self.v_cruise, + not self.seatbelt, self.seatbelt, # Seatbelt + self.brake_pressed, 0., + cruise_buttons, + self.esp_disabled, + 0, # HUD lead + self.user_brake, + self.steer_error, + self.gear_shifter, + self.pedal_gas, + self.cruise_setting, + self.acc_status, + self.user_gas, + self.main_on, + 0, # EPB State + 0, # Brake hold + 0, # Interceptor feedback + # 0, + ] # TODO: publish each message at proper frequency can_msgs = [] @@ -238,6 +255,7 @@ def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True) if "COUNTER" in honda.get_signals(msg): msg_struct["COUNTER"] = self.rk.frame % 4 + msg = honda.lookup_msg_id(msg) msg_data = honda.encode(msg, msg_struct) if "CHECKSUM" in honda.get_signals(msg): @@ -302,4 +320,3 @@ def plant_thread(rate=100): if __name__ == "__main__": plant_thread() - diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 5ee87c794e53f4..96396d8d0c0eb4 100755 Binary files a/selfdrive/visiond/visiond and b/selfdrive/visiond/visiond differ