From 185172b045976b76f183820c6f6720864dec1e85 Mon Sep 17 00:00:00 2001 From: Arne Schwarck Date: Sat, 9 Jan 2021 14:51:52 +0100 Subject: [PATCH 1/4] Update dp_common.py --- common/dp_common.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/common/dp_common.py b/common/dp_common.py index 2915a0de91ab78..5213d0057580b4 100644 --- a/common/dp_common.py +++ b/common/dp_common.py @@ -15,11 +15,11 @@ else: PARAM_PATH = "/data/params/d/" LAST_MODIFIED = str(PARAM_PATH) + "dp_last_modified" -if not os.path.exists(LAST_MODIFIED): - os.makedirs(str(os.environ.get('HOME')) + "/.comma/params/d/", exist_ok=True) - print("dp_last_modified is " + str(floor(time.time()))) - params.put('dp_last_modified',str(floor(time.time()))) - init_params_vals(params) +#if not os.path.exists(LAST_MODIFIED): +# os.makedirs(str(os.environ.get('HOME')) + "/.comma/params/d/", exist_ok=True) +# print("dp_last_modified is " + str(floor(time.time()))) +# params.put('dp_last_modified',str(floor(time.time()))) +# init_params_vals(params) def is_online(): try: From 97c668b7550bdf41fe2a02207e0b606110f3cb9e Mon Sep 17 00:00:00 2001 From: Arne Schwarck Date: Sat, 9 Jan 2021 15:44:00 +0100 Subject: [PATCH 2/4] Update dp_common.py --- common/dp_common.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/common/dp_common.py b/common/dp_common.py index 5213d0057580b4..6345efdb1ec366 100644 --- a/common/dp_common.py +++ b/common/dp_common.py @@ -4,11 +4,11 @@ from common.params import Params from common.realtime import sec_since_boot import os -import time -from math import floor +#import time +#from math import floor params = Params() from common.travis_checker import travis -from common.dp_conf import init_params_vals +#from common.dp_conf import init_params_vals if travis: PARAM_PATH = str(os.environ.get('HOME')) + "/.comma/params/d/" From 9dbb2772ae7c74a328da9b0fe2b9338b4ecd0c37 Mon Sep 17 00:00:00 2001 From: Kumar <36933347+rav4kumar@users.noreply.github.com> Date: Sat, 9 Jan 2021 11:55:24 -0700 Subject: [PATCH 3/4] RSA, Distance button and briskspirit longcontrol (#762) * toyota rsa logic * no arne messaging and add opedit * add gas_press, smartspeed and spdval1 to carstate * more fixes * new_message * thats right we dont have anglelater code yet. * revert to working mapd code? and pylint ignore mapd * flake8 ignore. * flake8 e701 fix * control df with distance button? * wrong struct * Update carstate.py * update missing * start MessagedArneThread * Update carstate.py * pubmaster? * message * update carstate.py * no .status * pm * use dp_dynamic_follow to send DF status * sntax * encoding='utf8' * Update carstate.py * Update carstate.py * pyopencl pipenv * change the order so we can display right thing with distance toggle * doesnt work well with dg * Revert "change the order so we can display right thing with distance toggle" This reverts commit ee4522ae5cc6857a8bb3423609a9296598afbd6b. * turn off distance button for now. * Parametrize MIN_CAN_SPEED in car interfaces * Parametrize stoppingBrakeRate * Parametrize startingBrakeRate * add the parameter to cereal . * Update dp_common.py Co-authored-by: Arne Schwarck Co-authored-by: George Hotz Co-authored-by: Igor --- Pipfile | 1 + Pipfile.lock | 191 ++++++++++++----------- cereal/car.capnp | 3 + common/op_params.py | 4 +- selfdrive/car/honda/interface.py | 1 + selfdrive/car/hyundai/interface.py | 6 +- selfdrive/car/interfaces.py | 3 + selfdrive/car/mazda/interface.py | 1 - selfdrive/car/nissan/interface.py | 1 + selfdrive/car/subaru/interface.py | 2 +- selfdrive/car/toyota/carcontroller.py | 14 +- selfdrive/car/toyota/carstate.py | 82 +++++++++- selfdrive/car/toyota/toyotacan.py | 6 +- selfdrive/car/volkswagen/interface.py | 1 + selfdrive/controls/lib/longcontrol.py | 22 ++- selfdrive/controls/lib/planner.py | 6 +- selfdrive/mapd/mapd.py | 71 +++++---- selfdrive/mapd/mapd_helpers.py | 6 +- selfdrive/test/process_replay/ref_commit | 2 +- 19 files changed, 262 insertions(+), 161 deletions(-) diff --git a/Pipfile b/Pipfile index d2c4ac8608c29a..09ff914fc3779d 100644 --- a/Pipfile +++ b/Pipfile @@ -77,6 +77,7 @@ torch = "*" torchsummary = "*" blosc = "==1.9.2" segmentation-models-pytorch = "==0.1.2" +pyopencl = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index ac485692a942de..7d36762eb28178 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "d9f887b06f1b0277c76e82aa84c64a3abb079bb2728e7605896c25f53431ce92" + "sha256": "c9508491a5f78a344e6e520802030e24d6a69cedb4db032d8caeacd33b151e27" }, "pipfile-spec": 6, "requires": { @@ -644,54 +644,54 @@ }, "pyyaml": { "hashes": [ - "sha256:ad9c67312c84def58f3c04504727ca879cb0013b2517c85a9a253f0cb6380c0a", - "sha256:7739fc0fa8205b3ee8808aea45e968bc90082c10aef6ea95e855e10abf4a37b2", - "sha256:b8eac752c5e14d3eca0e6dd9199cd627518cb5ec06add0de9d32baeee6fe645d", - "sha256:69f00dca373f240f842b2931fb2c7e14ddbacd1397d57157a9b005a6a9942648", - "sha256:6034f55dab5fea9e53f436aa68fa3ace2634918e8b5994d82f3621c04ff5ed2e", - "sha256:cc8955cfbfc7a115fa81d85284ee61147059a753344bc51098f3ccd69b0d7e0c", - "sha256:95f71d2af0ff4227885f7a6605c37fd53d3a106fcab511b8860ecca9fcf400ee", "sha256:06a0d7ba600ce0b2d2fe2e78453a470b5a6e000a985dd4a4e54e436cc36b0e97", - "sha256:73f099454b799e05e5ab51423c7bcf361c58d3206fa7b0d555426b1f4d9a3eaf", "sha256:240097ff019d7c70a4922b6869d8a86407758333f02203e0fc6ff79c5dcede76", - "sha256:d13155f591e6fcc1ec3b30685d50bf0711574e2c0dfffd7644babf8b5102ca1a", + "sha256:4f4b913ca1a7319b33cfb1369e91e50354d6f07a135f3b901aca02aa95940bd2", + "sha256:6034f55dab5fea9e53f436aa68fa3ace2634918e8b5994d82f3621c04ff5ed2e", + "sha256:69f00dca373f240f842b2931fb2c7e14ddbacd1397d57157a9b005a6a9942648", + "sha256:73f099454b799e05e5ab51423c7bcf361c58d3206fa7b0d555426b1f4d9a3eaf", "sha256:74809a57b329d6cc0fdccee6318f44b9b8649961fa73144a98735b0aaf029f1f", - "sha256:4f4b913ca1a7319b33cfb1369e91e50354d6f07a135f3b901aca02aa95940bd2" + "sha256:7739fc0fa8205b3ee8808aea45e968bc90082c10aef6ea95e855e10abf4a37b2", + "sha256:95f71d2af0ff4227885f7a6605c37fd53d3a106fcab511b8860ecca9fcf400ee", + "sha256:ad9c67312c84def58f3c04504727ca879cb0013b2517c85a9a253f0cb6380c0a", + "sha256:b8eac752c5e14d3eca0e6dd9199cd627518cb5ec06add0de9d32baeee6fe645d", + "sha256:cc8955cfbfc7a115fa81d85284ee61147059a753344bc51098f3ccd69b0d7e0c", + "sha256:d13155f591e6fcc1ec3b30685d50bf0711574e2c0dfffd7644babf8b5102ca1a" ], "index": "pypi", "version": "==5.3.1" }, "pyzmq": { "hashes": [ - "sha256:824ad5888331aadeac772bce27e1c2fbcab82fade92edbd234542c4e12f0dca9", - "sha256:b62113eeb9a0649cebed9b21fd578f3a0175ef214a2a91dcb7b31bbf55805295", - "sha256:4d9259a5eb3f71abbaf61f165cacf42240bfeea3783bebd8255341abdfe206f1", - "sha256:53706f4a792cdae422121fb6a5e65119bad02373153364fc9d004cf6a90394de", - "sha256:f110a4d3f8f01209eec304ed542f6c8054cce9b0f16dfe3d571e57c290e4e133", - "sha256:d92c7f41a53ece82b91703ea433c7d34143248cf0cead33aa11c5fc621c764bf", - "sha256:c95dda497a7c1b1e734b5e8353173ca5dd7b67784d8821d13413a97856588057", - "sha256:cfa54a162a7b32641665e99b2c12084555afe9fc8fe80ec8b2f71a57320d10e1", - "sha256:2742e380d186673eee6a570ef83d4568741945434ba36d92b98d36cdbfedbd44", + "sha256:03638e46d486dd1c118e03c8bf9c634bdcae679600eac6573ae1e54906de7c2f", + "sha256:0af84f34f27b5c6a0e906c648bdf46d4caebf9c8e6e16db0728f30a58141cad6", "sha256:0e554fd390021edbe0330b67226325a820b0319c5b45e1b0a59bf22ccc36e793", "sha256:1e9b75a119606732023a305d1c214146c09a91f8116f6aff3e8b7d0a60b6f0ff", - "sha256:bf755905a7d30d2749079611b9a89924c1f2da2695dc09ce221f42122c9808e3", - "sha256:6e24907857c80dc67692e31f5bf3ad5bf483ee0142cec95b3d47e2db8c43bdda", - "sha256:d81184489369ec325bd50ba1c935361e63f31f578430b9ad95471899361a8253", - "sha256:c63fafd2556d218368c51d18588f8e6f8d86d09d493032415057faf6de869b34", - "sha256:cc09c5cd1a4332611c8564d65e6a432dc6db3e10793d0254da9fa1e31d9ffd6d", - "sha256:46250789730489009fe139cbf576679557c070a6a3628077d09a4153d52fd381", - "sha256:f0beef935efe78a63c785bb21ed56c1c24448511383e3994927c8bb2caf5e714", - "sha256:7113eb93dcd0a5750c65d123ed0099e036a3a3f2dcb48afedd025ffa125c983b", "sha256:225774a48ed7414c0395335e7123ef8c418dbcbe172caabdc2496133b03254c2", + "sha256:2742e380d186673eee6a570ef83d4568741945434ba36d92b98d36cdbfedbd44", "sha256:309d763d89ec1845c0e0fa14e1fb6558fd8c9ef05ed32baec27d7a8499cc7bb0", - "sha256:0af84f34f27b5c6a0e906c648bdf46d4caebf9c8e6e16db0728f30a58141cad6", - "sha256:63ee08e35be72fdd7568065a249a5b5cf51a2e8ab6ee63cf9f73786fcb9e710b", - "sha256:dc2f48b575dff6edefd572f1ac84cf0c3f18ad5fcf13384de32df740a010594a", - "sha256:bc7dd697356b31389d5118b9bcdef3e8d8079e8181800c4e8d72dccd56e1ff68", - "sha256:03638e46d486dd1c118e03c8bf9c634bdcae679600eac6573ae1e54906de7c2f", + "sha256:46250789730489009fe139cbf576679557c070a6a3628077d09a4153d52fd381", + "sha256:4d9259a5eb3f71abbaf61f165cacf42240bfeea3783bebd8255341abdfe206f1", "sha256:523d542823cabb94065178090e05347bd204365f6e7cb260f0071c995d392fc2", + "sha256:53706f4a792cdae422121fb6a5e65119bad02373153364fc9d004cf6a90394de", "sha256:5efe02bdcc5eafcac0aab531292294298f0ab8d28ed43be9e507d0e09173d1a4", - "sha256:895695be380f0f85d2e3ec5ccf68a93c92d45bd298567525ad5633071589872c" + "sha256:63ee08e35be72fdd7568065a249a5b5cf51a2e8ab6ee63cf9f73786fcb9e710b", + "sha256:6e24907857c80dc67692e31f5bf3ad5bf483ee0142cec95b3d47e2db8c43bdda", + "sha256:7113eb93dcd0a5750c65d123ed0099e036a3a3f2dcb48afedd025ffa125c983b", + "sha256:824ad5888331aadeac772bce27e1c2fbcab82fade92edbd234542c4e12f0dca9", + "sha256:895695be380f0f85d2e3ec5ccf68a93c92d45bd298567525ad5633071589872c", + "sha256:b62113eeb9a0649cebed9b21fd578f3a0175ef214a2a91dcb7b31bbf55805295", + "sha256:bc7dd697356b31389d5118b9bcdef3e8d8079e8181800c4e8d72dccd56e1ff68", + "sha256:bf755905a7d30d2749079611b9a89924c1f2da2695dc09ce221f42122c9808e3", + "sha256:c63fafd2556d218368c51d18588f8e6f8d86d09d493032415057faf6de869b34", + "sha256:c95dda497a7c1b1e734b5e8353173ca5dd7b67784d8821d13413a97856588057", + "sha256:cc09c5cd1a4332611c8564d65e6a432dc6db3e10793d0254da9fa1e31d9ffd6d", + "sha256:cfa54a162a7b32641665e99b2c12084555afe9fc8fe80ec8b2f71a57320d10e1", + "sha256:d81184489369ec325bd50ba1c935361e63f31f578430b9ad95471899361a8253", + "sha256:d92c7f41a53ece82b91703ea433c7d34143248cf0cead33aa11c5fc621c764bf", + "sha256:dc2f48b575dff6edefd572f1ac84cf0c3f18ad5fcf13384de32df740a010594a", + "sha256:f0beef935efe78a63c785bb21ed56c1c24448511383e3994927c8bb2caf5e714", + "sha256:f110a4d3f8f01209eec304ed542f6c8054cce9b0f16dfe3d571e57c290e4e133" ], "index": "pypi", "version": "==20.0.0" @@ -1102,18 +1102,18 @@ }, "boto3": { "hashes": [ - "sha256:4d502a842b81fdac4b950d3b88a5b9067ce118213b122b20f4192003cb067986", - "sha256:ea860397e6c635284533bbc16fc77cdcfd96a78242c5ab6f2ffe2b43722802ce" + "sha256:11dc492682cf2a4f8ff397b0a109837340ef93e77ca2e65715ce24ecf043717c", + "sha256:ca97e1d591fe4214bac09cf347a8425061d9eecc456c147692749e383a0f3dfe" ], "index": "pypi", - "version": "==1.16.50" + "version": "==1.16.51" }, "botocore": { "hashes": [ - "sha256:709090ba61bba7dfa831b437d61cb469a85298d8f3ce5b8e12cdf41bd2b2bc61", - "sha256:87efa9399a1a61c03d484d720d6f4ef0b76a3039f29953ff819ae0cb25e0e21c" + "sha256:76c0ce78fd2a7e9e08d038f2bba2ce10bee08e04546c7812a9654edb2dc4d496", + "sha256:b204c5b477b043c7f61cba5db479c6b25f684f7409b71a8ecdb5a6b3f57b5cb4" ], - "version": "==1.19.50" + "version": "==1.19.51" }, "cachetools": { "hashes": [ @@ -1656,11 +1656,11 @@ }, "jedi": { "hashes": [ - "sha256:18456d83f65f400ab0c2d3319e48520420ef43b23a086fdc05dff34132f0fb93", - "sha256:92550a404bad8afed881a137ec9a461fed49eca661414be45059329614ed0707" + "sha256:86ed7d9b750603e4ba582ea8edc678657fb4007894a12bcf6f4bb97892f31d20", + "sha256:98cc583fa0f2f8304968199b01b6b4b94f469a1f4a74c1560506ca2a211378b5" ], - "markers": "python_version >= '3.6'", - "version": "==0.18.0" + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", + "version": "==0.17.2" }, "jinja2": { "hashes": [ @@ -1711,11 +1711,11 @@ }, "jupyter-client": { "hashes": [ - "sha256:49e390b36fe4b4226724704ea28d9fb903f1a3601b6882ce3105221cd09377a1", - "sha256:c958d24d6eacb975c1acebb68ac9077da61b5f5c040f22f6849928ad7393b950" + "sha256:2cd2f201d0b237a61bbbf2e772c12b9971e095eb283244a8dfd7148b8d8152a9", + "sha256:a1b38ebc768cd28715934e82abbf35c51d2fcd026f30ab0d4b7fb2b754d1fca4" ], "markers": "python_version >= '3.5'", - "version": "==6.1.7" + "version": "==6.1.10" }, "jupyter-console": { "hashes": [ @@ -2295,11 +2295,11 @@ }, "parso": { "hashes": [ - "sha256:15b00182f472319383252c18d5913b69269590616c947747bc50bf4ac768f410", - "sha256:8519430ad07087d4c997fda3a7918f7cfa27cb58972a8c89c2a0295a1c940e9e" + "sha256:97218d9159b2520ff45eb78028ba8b50d2bc61dcc062a9682666f2dc4bd331ea", + "sha256:caba44724b994a8a5e086460bb212abc5a8bc46951bf4a9a1210745953622eb9" ], - "markers": "python_version >= '3.6'", - "version": "==0.8.1" + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", + "version": "==0.7.1" }, "pexpect": { "hashes": [ @@ -2394,11 +2394,11 @@ }, "prompt-toolkit": { "hashes": [ - "sha256:45b154489d89dc41cce86a069a65f3886206518e7ca93fa9d7dad70546c78d54", - "sha256:c5eeab58dd31b541442825d7870777f2a2f764eb5fda03334d5219cd84b9722f" + "sha256:ac329c69bd8564cb491940511957312c7b8959bb5b3cf3582b406068a51d5bb7", + "sha256:b8b3d0bde65da350290c46a8f54f336b3cbf5464a4ac11239668d986852e79d5" ], "markers": "python_full_version >= '3.6.1'", - "version": "==3.0.9" + "version": "==3.0.10" }, "protobuf": { "hashes": [ @@ -2664,6 +2664,16 @@ "index": "pypi", "version": "==1.15.0" }, + "pyopencl": { + "hashes": [ + "sha256:121a4486af3a04d1e6fb739ffb92e1d1b5e689860984e3f58777d62e1f44aa67", + "sha256:19703da491206f697cfcff13491f12e8e044fe7e79b177272d2cb07ae4c3d1ad", + "sha256:ab9e8f9f2fc9e8f795985225de47057e936b5d9bb61442d2a23f0ad7a38520a7", + "sha256:abc689307cf34d3dcc94d43815f64e2265469b50ecce6c903a3180589666fb36" + ], + "index": "pypi", + "version": "==2020.3.1" + }, "pyopenssl": { "hashes": [ "sha256:4c231c759543ba02560fcd2480c48dcec4dae34c9da7d3747c508227e0624b51", @@ -2763,6 +2773,13 @@ ], "version": "==5.0.4" }, + "pytools": { + "hashes": [ + "sha256:3645ed839cf4d79cb4bf030f37ddaeecd7fe5e2d6698438cc36c24a1d5168809" + ], + "markers": "python_version ~= '3.6'", + "version": "==2020.4.4" + }, "pytz": { "hashes": [ "sha256:16962c5fb8db4a8f63a26646d8886e9d769b6c511543557bc84e9569fb9a9cb4", @@ -2808,54 +2825,54 @@ }, "pyyaml": { "hashes": [ - "sha256:ad9c67312c84def58f3c04504727ca879cb0013b2517c85a9a253f0cb6380c0a", - "sha256:7739fc0fa8205b3ee8808aea45e968bc90082c10aef6ea95e855e10abf4a37b2", - "sha256:b8eac752c5e14d3eca0e6dd9199cd627518cb5ec06add0de9d32baeee6fe645d", - "sha256:69f00dca373f240f842b2931fb2c7e14ddbacd1397d57157a9b005a6a9942648", - "sha256:6034f55dab5fea9e53f436aa68fa3ace2634918e8b5994d82f3621c04ff5ed2e", - "sha256:cc8955cfbfc7a115fa81d85284ee61147059a753344bc51098f3ccd69b0d7e0c", - "sha256:95f71d2af0ff4227885f7a6605c37fd53d3a106fcab511b8860ecca9fcf400ee", "sha256:06a0d7ba600ce0b2d2fe2e78453a470b5a6e000a985dd4a4e54e436cc36b0e97", - "sha256:73f099454b799e05e5ab51423c7bcf361c58d3206fa7b0d555426b1f4d9a3eaf", "sha256:240097ff019d7c70a4922b6869d8a86407758333f02203e0fc6ff79c5dcede76", - "sha256:d13155f591e6fcc1ec3b30685d50bf0711574e2c0dfffd7644babf8b5102ca1a", + "sha256:4f4b913ca1a7319b33cfb1369e91e50354d6f07a135f3b901aca02aa95940bd2", + "sha256:6034f55dab5fea9e53f436aa68fa3ace2634918e8b5994d82f3621c04ff5ed2e", + "sha256:69f00dca373f240f842b2931fb2c7e14ddbacd1397d57157a9b005a6a9942648", + "sha256:73f099454b799e05e5ab51423c7bcf361c58d3206fa7b0d555426b1f4d9a3eaf", "sha256:74809a57b329d6cc0fdccee6318f44b9b8649961fa73144a98735b0aaf029f1f", - "sha256:4f4b913ca1a7319b33cfb1369e91e50354d6f07a135f3b901aca02aa95940bd2" + "sha256:7739fc0fa8205b3ee8808aea45e968bc90082c10aef6ea95e855e10abf4a37b2", + "sha256:95f71d2af0ff4227885f7a6605c37fd53d3a106fcab511b8860ecca9fcf400ee", + "sha256:ad9c67312c84def58f3c04504727ca879cb0013b2517c85a9a253f0cb6380c0a", + "sha256:b8eac752c5e14d3eca0e6dd9199cd627518cb5ec06add0de9d32baeee6fe645d", + "sha256:cc8955cfbfc7a115fa81d85284ee61147059a753344bc51098f3ccd69b0d7e0c", + "sha256:d13155f591e6fcc1ec3b30685d50bf0711574e2c0dfffd7644babf8b5102ca1a" ], "index": "pypi", "version": "==5.3.1" }, "pyzmq": { "hashes": [ - "sha256:824ad5888331aadeac772bce27e1c2fbcab82fade92edbd234542c4e12f0dca9", - "sha256:b62113eeb9a0649cebed9b21fd578f3a0175ef214a2a91dcb7b31bbf55805295", - "sha256:4d9259a5eb3f71abbaf61f165cacf42240bfeea3783bebd8255341abdfe206f1", - "sha256:53706f4a792cdae422121fb6a5e65119bad02373153364fc9d004cf6a90394de", - "sha256:f110a4d3f8f01209eec304ed542f6c8054cce9b0f16dfe3d571e57c290e4e133", - "sha256:d92c7f41a53ece82b91703ea433c7d34143248cf0cead33aa11c5fc621c764bf", - "sha256:c95dda497a7c1b1e734b5e8353173ca5dd7b67784d8821d13413a97856588057", - "sha256:cfa54a162a7b32641665e99b2c12084555afe9fc8fe80ec8b2f71a57320d10e1", - "sha256:2742e380d186673eee6a570ef83d4568741945434ba36d92b98d36cdbfedbd44", + "sha256:03638e46d486dd1c118e03c8bf9c634bdcae679600eac6573ae1e54906de7c2f", + "sha256:0af84f34f27b5c6a0e906c648bdf46d4caebf9c8e6e16db0728f30a58141cad6", "sha256:0e554fd390021edbe0330b67226325a820b0319c5b45e1b0a59bf22ccc36e793", "sha256:1e9b75a119606732023a305d1c214146c09a91f8116f6aff3e8b7d0a60b6f0ff", - "sha256:bf755905a7d30d2749079611b9a89924c1f2da2695dc09ce221f42122c9808e3", - "sha256:6e24907857c80dc67692e31f5bf3ad5bf483ee0142cec95b3d47e2db8c43bdda", - "sha256:d81184489369ec325bd50ba1c935361e63f31f578430b9ad95471899361a8253", - "sha256:c63fafd2556d218368c51d18588f8e6f8d86d09d493032415057faf6de869b34", - "sha256:cc09c5cd1a4332611c8564d65e6a432dc6db3e10793d0254da9fa1e31d9ffd6d", - "sha256:46250789730489009fe139cbf576679557c070a6a3628077d09a4153d52fd381", - "sha256:f0beef935efe78a63c785bb21ed56c1c24448511383e3994927c8bb2caf5e714", - "sha256:7113eb93dcd0a5750c65d123ed0099e036a3a3f2dcb48afedd025ffa125c983b", "sha256:225774a48ed7414c0395335e7123ef8c418dbcbe172caabdc2496133b03254c2", + "sha256:2742e380d186673eee6a570ef83d4568741945434ba36d92b98d36cdbfedbd44", "sha256:309d763d89ec1845c0e0fa14e1fb6558fd8c9ef05ed32baec27d7a8499cc7bb0", - "sha256:0af84f34f27b5c6a0e906c648bdf46d4caebf9c8e6e16db0728f30a58141cad6", - "sha256:63ee08e35be72fdd7568065a249a5b5cf51a2e8ab6ee63cf9f73786fcb9e710b", - "sha256:dc2f48b575dff6edefd572f1ac84cf0c3f18ad5fcf13384de32df740a010594a", - "sha256:bc7dd697356b31389d5118b9bcdef3e8d8079e8181800c4e8d72dccd56e1ff68", - "sha256:03638e46d486dd1c118e03c8bf9c634bdcae679600eac6573ae1e54906de7c2f", + "sha256:46250789730489009fe139cbf576679557c070a6a3628077d09a4153d52fd381", + "sha256:4d9259a5eb3f71abbaf61f165cacf42240bfeea3783bebd8255341abdfe206f1", "sha256:523d542823cabb94065178090e05347bd204365f6e7cb260f0071c995d392fc2", + "sha256:53706f4a792cdae422121fb6a5e65119bad02373153364fc9d004cf6a90394de", "sha256:5efe02bdcc5eafcac0aab531292294298f0ab8d28ed43be9e507d0e09173d1a4", - "sha256:895695be380f0f85d2e3ec5ccf68a93c92d45bd298567525ad5633071589872c" + "sha256:63ee08e35be72fdd7568065a249a5b5cf51a2e8ab6ee63cf9f73786fcb9e710b", + "sha256:6e24907857c80dc67692e31f5bf3ad5bf483ee0142cec95b3d47e2db8c43bdda", + "sha256:7113eb93dcd0a5750c65d123ed0099e036a3a3f2dcb48afedd025ffa125c983b", + "sha256:824ad5888331aadeac772bce27e1c2fbcab82fade92edbd234542c4e12f0dca9", + "sha256:895695be380f0f85d2e3ec5ccf68a93c92d45bd298567525ad5633071589872c", + "sha256:b62113eeb9a0649cebed9b21fd578f3a0175ef214a2a91dcb7b31bbf55805295", + "sha256:bc7dd697356b31389d5118b9bcdef3e8d8079e8181800c4e8d72dccd56e1ff68", + "sha256:bf755905a7d30d2749079611b9a89924c1f2da2695dc09ce221f42122c9808e3", + "sha256:c63fafd2556d218368c51d18588f8e6f8d86d09d493032415057faf6de869b34", + "sha256:c95dda497a7c1b1e734b5e8353173ca5dd7b67784d8821d13413a97856588057", + "sha256:cc09c5cd1a4332611c8564d65e6a432dc6db3e10793d0254da9fa1e31d9ffd6d", + "sha256:cfa54a162a7b32641665e99b2c12084555afe9fc8fe80ec8b2f71a57320d10e1", + "sha256:d81184489369ec325bd50ba1c935361e63f31f578430b9ad95471899361a8253", + "sha256:d92c7f41a53ece82b91703ea433c7d34143248cf0cead33aa11c5fc621c764bf", + "sha256:dc2f48b575dff6edefd572f1ac84cf0c3f18ad5fcf13384de32df740a010594a", + "sha256:f0beef935efe78a63c785bb21ed56c1c24448511383e3994927c8bb2caf5e714", + "sha256:f110a4d3f8f01209eec304ed542f6c8054cce9b0f16dfe3d571e57c290e4e133" ], "index": "pypi", "version": "==20.0.0" diff --git a/cereal/car.capnp b/cereal/car.capnp index 28c3feea75e810..416cf83d735fa5 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -417,6 +417,9 @@ struct CarParams { steerRateCost @33 :Float32; # Lateral MPC cost on steering rate steerControlType @34 :SteerControlType; radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN + minSpeedCan @51 :Float32; # Minimum vehicle speed from CAN (below this value drops to 0) + stoppingBrakeRate @52 :Float32; # brake_travel/s while trying to stop + startingBrakeRate @53 :Float32; # brake_travel/s while releasing on restart steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control? diff --git a/common/op_params.py b/common/op_params.py index 423429d3e23494..4280a09ffa05eb 100644 --- a/common/op_params.py +++ b/common/op_params.py @@ -94,7 +94,7 @@ def __init__(self): #'hotspot_on_boot': Param(False, bool, 'Enable Hotspot On Boot'), 'keep_openpilot_engaged': Param(True, bool, 'True is stock behavior in this fork. False lets you use the brake and cruise control stalk to disengage as usual'), #'lat_d': Param(9.0, VT.number, 'The lateral derivative gain, default is 9.0 for TSS2 Corolla. This is active at all speeds', live=True), - #'limit_rsa': Param(False, bool, "Switch off RSA above rsa_max_speed"), + 'limit_rsa': Param(False, bool, "Switch off RSA above rsa_max_speed"), #'ludicrous_mode': Param(False, bool, 'Double overall acceleration!'), 'mpc_offset': Param(0.0, VT.number, 'Offset model braking by how many m/s. Lower numbers equals more model braking', live=True), #'NoctuaMode': Param(False, bool, 'Noctua Fan are super quite and they run at full speed at all time.'), @@ -102,7 +102,7 @@ def __init__(self): 'osm': Param(True, bool, 'Whether to use OSM for drives'), 'prius_pid': Param(False, bool, 'This enables the PID lateral controller with new a experimental derivative tune\nFalse: stock INDI, True: TSS2-tuned PID'), 'rolling_stop': Param(False, bool, 'If you do not want stop signs to go down to 0 kph enable this for 9kph slow down'), - #'rsa_max_speed': Param(24.5, VT.number, 'Speed limit to ignore RSA in m/s'), + 'rsa_max_speed': Param(24.5, VT.number, 'Speed limit to ignore RSA in m/s'), 'smart_speed': Param(True, bool, 'Whether to use Smart Speed for drives above smart_speed_max_vego'), 'smart_speed_max_vego': Param(26.8, VT.number, 'Speed limit to ignore Smartspeed in m/s'), #'spairrowtuning': Param(False, bool, 'INDI Tuning for Corolla Tss2, set steer_up_15 param to True and flash panda'), diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 3a55475e28dfcc..3a746cf5fc6674 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -18,6 +18,7 @@ ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName + def compute_gb_honda(accel, speed): creep_brake = 0.0 creep_speed = 2.3 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 47548dc843cf62..17a0b722ad5231 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -104,9 +104,9 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD]: ret.lateralTuning.pid.kf = 0.00006 - ret.mass = 1490. + STD_CARGO_KG #weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx + ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec + ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] @@ -238,7 +238,7 @@ def update(self, c, can_strings, dragonconf): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid events = self.create_common_events(ret) - #TODO: addd abs(self.CS.angle_steers) > 90 to 'steerTempUnavailable' event + # TODO: addd abs(self.CS.angle_steers) > 90 to 'steerTempUnavailable' event if dragonconf.dpAtl: if ret.vEgo < self.CP.minSteerSpeed: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 03acb8bb6751b4..fd272740e2af09 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -72,6 +72,9 @@ def get_std_params(candidate, fingerprint, has_relay): ret.brakeMaxV = [1.] ret.openpilotLongitudinalControl = False ret.startAccel = 1.2 + ret.minSpeedCan = 0.3 + ret.stoppingBrakeRate = 0.2 # brake_travel/s while trying to stop + ret.startingBrakeRate = 0.8 # brake_travel/s while releasing on restart ret.stoppingControl = False ret.longitudinalTuning.deadzoneBP = [0.] ret.longitudinalTuning.deadzoneV = [0.] diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index a372c19ef5dfcd..27accdbc98c70c 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -54,7 +54,6 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] ret.lateralTuning.pid.kf = 0.00006 - # No steer below disable speed ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index d63dded10b693a..4faf217bc380c5 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -5,6 +5,7 @@ from selfdrive.car.interfaces import CarInterfaceBase from common.dp_common import common_interface_atl, common_interface_get_params_lqr + class CarInterface(CarInterfaceBase): def __init__(self, CP, CarController, CarState): super().__init__(CP, CarController, CarState) diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index d6cefd6a0c43ac..32f95de67c646d 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -66,7 +66,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] if candidate in [CAR.FORESTER_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018]: - ret.safetyParam = 1 # Outback 2018-2019 and Forester have reversed driver torque signal + ret.safetyParam = 1 # Outback 2018-2019 and Forester have reversed driver torque signal ret.mass = 1568 + STD_CARGO_KG ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.5 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index e92f238e1a4883..67a62bbb333d92 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -71,15 +71,15 @@ def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, hud_alert, apply_accel = actuators.gas - actuators.brake # dynamic acceleration - dynamic_accel_max = ACCEL_MAX - if CS.out.vEgo > 5.5: - if CS.out.vEgo >= 20: - dynamic_accel_max = 0.5 - else: - dynamic_accel_max = ACCEL_MAX - (((CS.out.vEgo - 5.5)/ 14.5)) + #dynamic_accel_max = ACCEL_MAX + #if CS.out.vEgo > 5.5: + #if CS.out.vEgo >= 20: + #dynamic_accel_max = 0.5 + #else: + #dynamic_accel_max = ACCEL_MAX - (((CS.out.vEgo - 5.5)/ 14.5)) apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled) - apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, dynamic_accel_max) + apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX) if CS.CP.enableGasInterceptor: if CS.out.gasPressed: diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index dba26b3bb142af..5209da4c6fb939 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -6,6 +6,13 @@ from selfdrive.config import Conversions as CV from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD, TSS2_CAR, NO_STOP_TIMER_CAR from common.params import Params +import cereal.messaging as messaging +from common.travis_checker import travis +from common.op_params import opParams + +op_params = opParams() +rsa_max_speed = op_params.get('rsa_max_speed') +limit_rsa = op_params.get('limit_rsa') class CarState(CarStateBase): @@ -22,8 +29,14 @@ def __init__(self, CP): self.setspeedcounter = 0 self.pcm_acc_active = False self.main_on = False + self.gas_pressed = False + self.smartspeed = 0 + self.spdval1 = 0 self.distance = 0 - + #self.read_distance_lines = 0 + if not travis: + self.pm = messaging.PubMaster(['liveTrafficData']) + self.sm = messaging.SubMaster(['liveMapData'])#',latControl',]) # On NO_DSU cars but not TSS2 cars the cp.vl["STEER_TORQUE_SENSOR"]['STEER_ANGLE'] # is zeroed to where the steering angle is at start. # Need to apply an offset as soon as the steering angle measurements are both received @@ -79,6 +92,15 @@ def update(self, cp, cp_cam): ret.steeringRate = cp.vl["STEER_ANGLE_SENSOR"]['STEER_RATE'] can_gear = int(cp.vl["GEAR_PACKET"]['GEAR']) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + #if self.read_distance_lines != cp.vl["PCM_CRUISE_SM"]['DISTANCE_LINES']: + #self.read_distance_lines = cp.vl["PCM_CRUISE_SM"]['DISTANCE_LINES'] + #Params().put('dp_dynamic_follow', str(int(max(self.read_distance_lines - 1, 0)))) + + if not travis: + self.sm.update(0) + self.smartspeed = self.sm['liveMapData'].speedLimit + ret.leftBlinker = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1 ret.rightBlinker = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2 @@ -131,6 +153,54 @@ def update(self, cp, cp_cam): ret.leftBlindspot = (cp.vl["BSM"]['L_ADJACENT'] == 1) or (cp.vl["BSM"]['L_APPROACHING'] == 1) ret.rightBlindspot = (cp.vl["BSM"]['R_ADJACENT'] == 1) or (cp.vl["BSM"]['R_APPROACHING'] == 1) + + self.tsgn1 = cp_cam.vl["RSA1"]['TSGN1'] + if self.spdval1 != cp_cam.vl["RSA1"]['SPDVAL1']: + self.rsa_ignored_speed = 0 + self.spdval1 = cp_cam.vl["RSA1"]['SPDVAL1'] + + self.splsgn1 = cp_cam.vl["RSA1"]['SPLSGN1'] + self.tsgn2 = cp_cam.vl["RSA1"]['TSGN2'] + #self.spdval2 = cp_cam.vl["RSA1"]['SPDVAL2'] + + self.splsgn2 = cp_cam.vl["RSA1"]['SPLSGN2'] + self.tsgn3 = cp_cam.vl["RSA2"]['TSGN3'] + self.splsgn3 = cp_cam.vl["RSA2"]['SPLSGN3'] + self.tsgn4 = cp_cam.vl["RSA2"]['TSGN4'] + self.splsgn4 = cp_cam.vl["RSA2"]['SPLSGN4'] + self.noovertake = self.tsgn1 == 65 or self.tsgn2 == 65 or self.tsgn3 == 65 or self.tsgn4 == 65 or self.tsgn1 == 66 or self.tsgn2 == 66 or self.tsgn3 == 66 or self.tsgn4 == 66 + if (self.spdval1 > 0) and not (self.spdval1 == 35 and self.tsgn1 == 1) and self.rsa_ignored_speed != self.spdval1: + dat = messaging.new_message('liveTrafficData') + if self.spdval1 > 0: + dat.liveTrafficData.speedLimitValid = True + if self.tsgn1 == 36: + dat.liveTrafficData.speedLimit = self.spdval1 * 1.60934 + elif self.tsgn1 == 1: + dat.liveTrafficData.speedLimit = self.spdval1 + else: + dat.liveTrafficData.speedLimit = 0 + else: + dat.liveTrafficData.speedLimitValid = False + #if self.spdval2 > 0: + # dat.liveTrafficData.speedAdvisoryValid = True + # dat.liveTrafficData.speedAdvisory = self.spdval2 + #else: + dat.liveTrafficData.speedAdvisoryValid = False + if limit_rsa and rsa_max_speed < ret.vEgo: + dat.liveTrafficData.speedLimitValid = False + if not travis: + self.pm.send('liveTrafficData', dat) + if ret.gasPressed and not self.gas_pressed: + self.engaged_when_gas_was_pressed = self.pcm_acc_active + if ((ret.gasPressed) or (self.gas_pressed and not ret.gasPressed)) and self.engaged_when_gas_was_pressed and ret.vEgo > self.smartspeed: + self.rsa_ignored_speed = self.spdval1 + dat = messaging.new_message('liveTrafficData') + dat.liveTrafficData.speedLimitValid = True + dat.liveTrafficData.speedLimit = ret.vEgo * 3.6 + if not travis: + self.pm.send('liveTrafficData', dat) + self.gas_pressed = ret.gasPressed + return ret @staticmethod @@ -236,6 +306,16 @@ def get_cam_can_parser(CP): signals = [ ("FORCE", "PRE_COLLISION", 0), ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0), + ("TSGN1", "RSA1", 0), + ("SPDVAL1", "RSA1", 0), + ("SPLSGN1", "RSA1", 0), + ("TSGN2", "RSA1", 0), + #("SPDVAL2", "RSA1", 0), + ("SPLSGN2", "RSA1", 0), + ("TSGN3", "RSA2", 0), + ("SPLSGN3", "RSA2", 0), + ("TSGN4", "RSA2", 0), + ("SPLSGN4", "RSA2", 0), ("DISTANCE", "ACC_CONTROL", 0), ] diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index 0fab79997ea6ab..5616ad26b804a9 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -76,8 +76,8 @@ def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_dep "SET_ME_X02": 0x02, "SET_ME_X01": 1, "SET_ME_X01_2": 1, - "REPEATED_BEEPS": 1 if steer else 0, - "TWO_BEEPS": 1 if chime else 0, - "LDA_ALERT": 1 if left_lane_depart or right_lane_depart else 0, + "REPEATED_BEEPS": 0, + "TWO_BEEPS": chime, + "LDA_ALERT": steer, } return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 9dbbfcfab5f1c2..48811e90bf1207 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -6,6 +6,7 @@ EventName = car.CarEvent.EventName + class CarInterface(CarInterfaceBase): def __init__(self, CP, CarController, CarState): super().__init__(CP, CarController, CarState) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index ac8ccddb88a26a..ea5c2e9b3e88ae 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -7,25 +7,23 @@ LongCtrlState = log.ControlsState.LongControlState STOPPING_EGO_SPEED = 0.5 -MIN_CAN_SPEED = 0.250 # TODO: parametrize this in car interface -STOPPING_TARGET_SPEED = MIN_CAN_SPEED + 0.01 +STOPPING_TARGET_SPEED_OFFSET = 0.01 STARTING_TARGET_SPEED = 0.5 BRAKE_THRESHOLD_TO_PID = 0.2 -STOPPING_BRAKE_RATE = 0.2 # brake_travel/s while trying to stop -STARTING_BRAKE_RATE = 0.8 # brake_travel/s while releasing on restart BRAKE_STOPPING_TARGET = 0.8 # apply at least this amount of brake to maintain the vehicle stationary RATE = 100.0 def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, - output_gb, brake_pressed, cruise_standstill, stop): + output_gb, brake_pressed, cruise_standstill, min_speed_can, stop): """Update longitudinal control state machine""" - stopping_condition = stop or (v_ego < 2.0 and cruise_standstill) or \ + stopping_target_speed = min_speed_can + STOPPING_TARGET_SPEED_OFFSET + stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ (v_ego < STOPPING_EGO_SPEED and - ((v_pid < STOPPING_TARGET_SPEED and v_target < STOPPING_TARGET_SPEED) or - brake_pressed)) + ((v_pid < stopping_target_speed and v_target < stopping_target_speed) or + brake_pressed)) starting_condition = v_target > STARTING_TARGET_SPEED and not cruise_standstill @@ -98,9 +96,9 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP, sm, hasLea stop = False self.long_control_state = long_control_state_trans(active, self.long_control_state, CS.vEgo, v_target_future, self.v_pid, output_gb, - CS.brakePressed, CS.cruiseState.standstill, stop) + CS.brakePressed, CS.cruiseState.standstill, CP.minSpeedCan, stop) - v_ego_pid = max(CS.vEgo, MIN_CAN_SPEED) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 + v_ego_pid = max(CS.vEgo, CP.minSpeedCan) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 if self.long_control_state == LongCtrlState.off or CS.gasPressed or CS.brakePressed: self.v_pid = v_ego_pid @@ -148,7 +146,7 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP, sm, hasLea if hasLead: factor = interp(dRel,[2.0,3.0,4.0,5.0,6.0,7.0,8.0], [3.0,2.1,1.5,1.0,0.6,0.29,0.0]) if not CS.standstill or output_gb > -BRAKE_STOPPING_TARGET: - output_gb -= STOPPING_BRAKE_RATE / RATE * factor + output_gb -= CP.stoppingBrakeRate / RATE * factor output_gb = clip(output_gb, -brake_max, gas_max) self.reset(CS.vEgo) @@ -159,7 +157,7 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP, sm, hasLea if hasLead: factor = interp(dRel,[0.0,2.0,4.0,6.0], [0.0,0.5,1.0,2.0]) if output_gb < -0.2: - output_gb += STARTING_BRAKE_RATE / RATE * factor + output_gb += CP.startingBrakeRate / RATE * factor self.v_pid = CS.vEgo self.pid.reset() diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 066cf01b447ab7..fee2399e8b2875 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -13,7 +13,7 @@ from selfdrive.swaglog import cloudlog from selfdrive.config import Conversions as CV from selfdrive.controls.lib.speed_smoother import speed_smoother -from selfdrive.controls.lib.longcontrol import LongCtrlState, MIN_CAN_SPEED +from selfdrive.controls.lib.longcontrol import LongCtrlState from selfdrive.controls.lib.fcw import FCWChecker from selfdrive.controls.lib.long_mpc import LongitudinalMpc from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX @@ -35,7 +35,7 @@ # lookup tables VS speed to determine min and max accels in cruise # make sure these accelerations are smaller than mpc limits _A_CRUISE_MIN_V = [-1.0, -.8, -.67, -.5, -.30] -_A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.] +_A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.] # need fast accel at very low speed for stop and go # make sure these accelerations are smaller than mpc limits @@ -349,7 +349,7 @@ def update(self, sm, pm, CP, VM, PP): else: starting = long_control_state == LongCtrlState.starting a_ego = min(sm['carState'].aEgo, 0.0) - reset_speed = MIN_CAN_SPEED if starting else v_ego + reset_speed = self.CP.minSpeedCan if starting else v_ego reset_accel = self.CP.startAccel if starting else a_ego self.v_acc = reset_speed self.a_acc = reset_accel diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py index fbeb74a6ca3af4..6eec287a4df050 100755 --- a/selfdrive/mapd/mapd.py +++ b/selfdrive/mapd/mapd.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 - +#pylint: skip-file +# flake8: noqa import time import math import overpy @@ -43,14 +44,14 @@ def save_gps_data(self, gps, osm_way_id): location = [gps.speed, gps.bearing, gps.latitude, gps.longitude, gps.altitude, gps.accuracy, time.time(), osm_way_id] with open("/data/openpilot/selfdrive/data_collection/gps-data", "a") as f: f.write("{}\n".format(location)) - except Exception: + except: self.logger.error("Unable to write gps data to external file") def run(self): pass # will be overridden in the child class class QueryThread(LoggerThread): - def __init__(self, threadID, name, sharedParams={}): # pylint: disable=dangerous-default-value + def __init__(self, threadID, name, sharedParams={}): # sharedParams is dict of params shared between two threads # invoke parent constructor https://stackoverflow.com/questions/2399307/how-to-invoke-the-super-constructor-in-python LoggerThread.__init__(self, threadID, name) self.sharedParams = sharedParams @@ -71,7 +72,7 @@ def is_connected_to_local(self, timeout=3.0): requests.get(self.OVERPASS_API_LOCAL, timeout=timeout) self.logger.debug("connection local active") return True - except Exception: + except: self.logger.error("No local server available.") return False @@ -80,7 +81,7 @@ def is_connected_to_internet(self, timeout=1.0): requests.get(self.OVERPASS_API_URL, timeout=timeout) self.logger.debug("connection 1 active") return True - except Exception: + except: self.logger.error("No internet connection available.") return False @@ -89,7 +90,7 @@ def is_connected_to_internet2(self, timeout=1.0): requests.get(self.OVERPASS_API_URL2, timeout=timeout) self.logger.debug("connection 2 active") return True - except Exception: + except: self.logger.error("No internet connection available.") return False @@ -110,11 +111,11 @@ def build_way_query(self, lat, lon, heading, radius=50): convert area ::id = id(), admin_level = t['admin_level'], name = t['name'], "ISO3166-1:alpha2" = t['ISO3166-1:alpha2'];out; """ - self.logger.debug('build_way_query : %s', str(q)) + self.logger.debug("build_way_query : %s" % str(q)) return q, lat, lon def run(self): - self.logger.debug('run method started for thread %s', self.name) + self.logger.debug("run method started for thread %s" % self.name) # for now we follow old logic, will be optimized later start = time.time() @@ -130,7 +131,7 @@ def run(self): self.logger.debug("Starting after sleeping for 1 second ...") last_gps = self.sharedParams.get('last_gps', None) - self.logger.debug('last_gps = %s', str(last_gps)) + self.logger.debug("last_gps = %s" % str(last_gps)) if last_gps is not None: fix_ok = last_gps.flags & 1 @@ -146,11 +147,9 @@ def run(self): self.prev_ecef = geodetic2ecef((last_query_pos.latitude, last_query_pos.longitude, last_query_pos.altitude)) dist = np.linalg.norm(cur_ecef - self.prev_ecef) - - self.logger.debug('parameters, cur_ecef = %s, prev_ecef = %s, dist=%s', str(cur_ecef), str(self.prev_ecef), str(dist)) - if dist < radius - self.distance_to_edge: #updated when we are close to the edge of the downloaded circle continue + self.logger.debug("parameters, cur_ecef = %s, prev_ecef = %s, dist=%s" % (str(cur_ecef), str(self.prev_ecef), str(dist))) if dist > radius: query_lock = self.sharedParams.get('query_lock', None) @@ -180,7 +179,7 @@ def run(self): else: continue new_result = api.query(q) - self.logger.debug('new_result = %s', str(new_result)) + self.logger.debug("new_result = %s" % str(new_result)) # Build kd-tree nodes = [] real_nodes = [] @@ -204,7 +203,7 @@ def run(self): nodes = np.asarray(nodes) nodes = geodetic2ecef(nodes) tree = spatial.KDTree(nodes) - self.logger.debug('query thread, ... %s %s', str(nodes), str(tree)) + self.logger.debug("query thread, ... %s %s" % (str(nodes), str(tree))) # write result query_lock = self.sharedParams.get('query_lock', None) @@ -223,7 +222,7 @@ def run(self): self.logger.error("There is not query_lock") except Exception as e: - self.logger.error('ERROR %d', str(e)) + self.logger.error("ERROR :" + str(e)) print(str(e)) query_lock = self.sharedParams.get('query_lock', None) query_lock.acquire() @@ -238,14 +237,14 @@ def run(self): self.logger.debug("end of one cycle in endless loop ...") class MapsdThread(LoggerThread): - def __init__(self, threadID, name, sharedParams={}): # pylint: disable=dangerous-default-value + def __init__(self, threadID, name, sharedParams={}): # invoke parent constructor LoggerThread.__init__(self, threadID, name) self.sharedParams = sharedParams self.pm = messaging.PubMaster(['liveMapData']) - self.logger.debug('entered mapsd_thread, ... %s', ( str(self.pm))) + self.logger.debug("entered mapsd_thread, ... %s" % ( str(self.pm))) def run(self): - self.logger.debug('Entered run method for thread %d', str(self.name)) + self.logger.debug("Entered run method for thread :" + str(self.name)) cur_way = None curvature_valid = False curvature = None @@ -260,7 +259,7 @@ def run(self): start = time.time() while True: if time.time() - start > 0.2: - print('Mapd MapsdThread lagging by: %s', str(time.time() - start - 0.1)) + print("Mapd MapsdThread lagging by: %s" % str(time.time() - start - 0.1)) if time.time() - start < 0.1: time.sleep(0.01) continue @@ -281,7 +280,7 @@ def run(self): if gps is None: continue fix_ok = gps.flags & 1 - self.logger.debug('fix_ok = %d', str(fix_ok)) + self.logger.debug("fix_ok = %s" % str(fix_ok)) if gps.accuracy > 2.5: if gps.accuracy > 5.0: @@ -303,7 +302,7 @@ def run(self): elif not had_good_gps: had_good_gps = True if not fix_ok or self.sharedParams['last_query_result'] is None or not self.sharedParams['cache_valid']: - self.logger.debug('fix_ok %s', fix_ok) + self.logger.debug("fix_ok %s" % fix_ok) self.logger.error("Error in fix_ok logic") cur_way = None curvature = None @@ -459,14 +458,14 @@ def run(self): self.pm.send('liveMapData', dat) class MessagedGPSThread(LoggerThread): - def __init__(self, threadID, name, sharedParams={}): # pylint: disable=dangerous-default-value + def __init__(self, threadID, name, sharedParams={}): # invoke parent constructor LoggerThread.__init__(self, threadID, name) self.sharedParams = sharedParams self.sm = messaging.SubMaster(['gpsLocationExternal']) - self.logger.debug('entered messagedGPS_thread, ... %s', (str(self.sm))) + self.logger.debug("entered messagedGPS_thread, ... %s" % (str(self.sm))) def run(self): - self.logger.debug('Entered run method for thread %d', str(self.name)) + self.logger.debug("Entered run method for thread :" + str(self.name)) gps = None start = time.time() while True: @@ -488,19 +487,19 @@ def run(self): query_lock.acquire() self.sharedParams['last_gps'] = gps query_lock.release() - self.logger.debug('setting last_gps to %s', str(gps)) + self.logger.debug("setting last_gps to %s" % str(gps)) -class MessagedThread(LoggerThread): - def __init__(self, threadID, name, sharedParams={}): # pylint: disable=dangerous-default-value +class MessagedArneThread(LoggerThread): + def __init__(self, threadID, name, sharedParams={}): # invoke parent constructor LoggerThread.__init__(self, threadID, name) self.sharedParams = sharedParams self.sm = messaging.SubMaster(['liveTrafficData'])#,'trafficModelEvent']) #self.logger.debug("entered messageArned_thread, ... %s" % str(self.arne_sm)) def run(self): - self.logger.debug('Entered run method for thread %d', str(self.name)) + self.logger.debug("Entered run method for thread :" + str(self.name)) last_not_none_signal = 'NONE' - #last_not_none_signal_counter = 0 + last_not_none_signal_counter = 0 traffic_confidence = 0 traffic_status = 'NONE' speedLimittraffic = 0 @@ -517,7 +516,7 @@ def run(self): else: start = time.time() self.logger.debug("starting new cycle in endless loop") - #self.arne_sm.update(0) + self.sm.update(0) #if self.arne_sm.updated['trafficModelEvent']: # traffic_status = self.arne_sm['trafficModelEvent'].status #traffic_confidence = round(self.arne_sm['trafficModelEvent'].confidence * 100, 2) @@ -582,21 +581,21 @@ def main(): speedLimittrafficAdvisory = 0 osm_way_id = 0 speedLimittrafficAdvisoryvalid = False - sharedParams = {'last_gps' : last_gps, 'query_lock' : query_lock, 'last_query_result' : last_query_result, - 'last_query_pos' : last_query_pos, 'cache_valid' : cache_valid, 'traffic_status' : traffic_status, - 'traffic_confidence' : traffic_confidence, 'last_not_none_signal' : last_not_none_signal, - 'speedLimittraffic' : speedLimittraffic, 'speedLimittrafficvalid' : speedLimittrafficvalid, + sharedParams = {'last_gps' : last_gps, 'query_lock' : query_lock, 'last_query_result' : last_query_result, \ + 'last_query_pos' : last_query_pos, 'cache_valid' : cache_valid, 'traffic_status' : traffic_status, \ + 'traffic_confidence' : traffic_confidence, 'last_not_none_signal' : last_not_none_signal, \ + 'speedLimittraffic' : speedLimittraffic, 'speedLimittrafficvalid' : speedLimittrafficvalid, \ 'speedLimittrafficAdvisory' : speedLimittrafficAdvisory, 'speedLimittrafficAdvisoryvalid' : speedLimittrafficAdvisoryvalid, 'osm_way_id' : osm_way_id} qt = QueryThread(1, "QueryThread", sharedParams=sharedParams) mt = MapsdThread(2, "MapsdThread", sharedParams=sharedParams) mggps = MessagedGPSThread(3, "MessagedGPSThread", sharedParams=sharedParams) - #mgarne = MessagedArneThread(4, "MessagedArneThread", sharedParams=sharedParams) + mgarne = MessagedArneThread(4, "MessagedArneThread", sharedParams=sharedParams) qt.start() mt.start() mggps.start() - #mgarne.start() + mgarne.start() if __name__ == "__main__": main() diff --git a/selfdrive/mapd/mapd_helpers.py b/selfdrive/mapd/mapd_helpers.py index 919e3028f9de47..1ff63e0d8cb6b1 100755 --- a/selfdrive/mapd/mapd_helpers.py +++ b/selfdrive/mapd/mapd_helpers.py @@ -187,7 +187,6 @@ def __init__(self, way, query_results): @classmethod def closest(cls, query_results, lat, lon, heading, prev_way=None): - #pylint: disable=unused-argument if query_results is None: return None else: @@ -325,7 +324,7 @@ def max_speed_ahead(self, current_speed_limit, lat, lon, heading, lookahead, tra speed_ahead_dist = None lookahead_ways = 5 way = self - for _ in range(lookahead_ways): + for i in range(lookahead_ways): way_pts = way.points_in_car_frame(lat, lon, heading, True) #print way_pts # Check current lookahead distance @@ -627,7 +626,6 @@ def points_in_car_frame(self, lat, lon, heading, flip): return points_carframe def next_way(self, heading): - #pylint: disable=unused-argument results, tree, real_nodes, node_to_way, location_info = self.query_results #print "way.id" #print self.id @@ -739,7 +737,7 @@ def get_lookahead(self, lat, lon, heading, lookahead): way = self valid = False - for _ in range(5): + for i in range(5): # Get new points and append to list new_pnts = way.points_in_car_frame(lat, lon, heading, True) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index cbc6a02b20e729..dea925dd526ace 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -643db5a2a2555f9b9be755362b04fc346a1222de +e3c1a9c4b81033c8dad810870eb974954e7660e9 From 68dcca82bddce9aa91fe999ee9bdbfdfe995887f Mon Sep 17 00:00:00 2001 From: SCshredder17 <57152954+SCshredder17@users.noreply.github.com> Date: Sun, 10 Jan 2021 20:10:23 -0800 Subject: [PATCH 4/4] corolla_TSS2: tune (#760) * Update interface.py updated corollatss2 tuning * Update toyota_nodsu_pt_generated.dbc * Update toyota_nodsu_hybrid_pt_generated.dbc * Update op_params.py * Create toyota_nodsu_pt_generated_corolla_tss2.dbc * Create toyota_nodsu_pt_generated_corollah_tss2.dbc * revert to stock. * revert to stock * point corolla and corollah to its own separate dbc. * add corolla and corollah dbc to release. * Update interface.py Co-authored-by: Kumar <36933347+rav4kumar@users.noreply.github.com> --- common/op_params.py | 16 +- ...toyota_nodsu_pt_generated_corolla_tss2.dbc | 434 ++++++++++++++++++ ...oyota_nodsu_pt_generated_corollah_tss2.dbc | 420 +++++++++++++++++ release/files_common | 2 + selfdrive/car/toyota/interface.py | 8 +- selfdrive/car/toyota/values.py | 4 +- 6 files changed, 870 insertions(+), 14 deletions(-) create mode 100644 opendbc/toyota_nodsu_pt_generated_corolla_tss2.dbc create mode 100644 opendbc/toyota_nodsu_pt_generated_corollah_tss2.dbc diff --git a/common/op_params.py b/common/op_params.py index 4280a09ffa05eb..1cf2c2e70d61f5 100644 --- a/common/op_params.py +++ b/common/op_params.py @@ -118,14 +118,14 @@ def __init__(self): #'use_virtual_middle_line': Param(False, bool, 'For roads over 4m wide, hug right. For roads under 2m wide, hug left.'), 'uniqueID': Param(None, [type(None), str], 'User\'s unique ID'), 'enable_indi_live': Param(False, bool, live=True), - 'indi_inner_gain_bp': Param([0, 255, 255], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_inner_gain_v': Param([6.0, 6.0, 6.0], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_outer_gain_bp': Param([0, 255, 255], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_outer_gain_v': Param([15, 15, 15], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_time_constant_bp': Param([0, 255, 255], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_time_constant_v': Param([5.5, 5.5, 5.5], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_actuator_effectiveness_bp': Param([0, 255, 255], [list, float, int], live=True, depends_on='enable_indi_live'), - 'indi_actuator_effectiveness_v': Param([6, 6, 6], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_inner_gain_bp': Param([18, 22, 26], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_inner_gain_v': Param([5, 10, 15], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_outer_gain_bp': Param([18, 22, 26], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_outer_gain_v': Param([4, 9, 14.99], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_time_constant_bp': Param([18, 22, 26], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_time_constant_v': Param([2, 4, 5.5], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_actuator_effectiveness_bp': Param([18, 22, 26], [list, float, int], live=True, depends_on='enable_indi_live'), + 'indi_actuator_effectiveness_v': Param([5, 10, 15], [list, float, int], live=True, depends_on='enable_indi_live'), 'steer_limit_timer': Param(0.4, VT.number, live=True, depends_on='enable_indi_live') } diff --git a/opendbc/toyota_nodsu_pt_generated_corolla_tss2.dbc b/opendbc/toyota_nodsu_pt_generated_corolla_tss2.dbc new file mode 100644 index 00000000000000..3dc5ffc24f67d2 --- /dev/null +++ b/opendbc/toyota_nodsu_pt_generated_corolla_tss2.dbc @@ -0,0 +1,434 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _toyota_nodsu_bsm.dbc starts here" +BO_ 1014 BSM: 8 XXX + SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX + SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _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 CGW + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" 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_ 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_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 353 DSU_SPEED: 7 XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX + +BO_ 452 ENGINE_RPM: 8 CGW + SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|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_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" 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_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 7 DSU + SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX + SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX + SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX + SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX + +BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 869 DSU_CRUISE : 7 DSU + SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX + SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX + SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX + SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX + SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" 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_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" 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_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1041 ACC_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1043 TIME : 8 CGW + SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX + SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX + SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX + SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX + SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX + SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX + SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX + SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX + SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX + +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|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 + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" 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_ 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_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +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_ 643 COUNTER "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was "SET_ME_1" and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; +CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +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"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +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_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +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 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_nodsu_pt.dbc starts here" + + + + +BO_ 401 STEERING_LTA: 8 XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX + SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX + SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX + SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX + SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" 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_ 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.50,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 + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 956 SPORT_ON 0 "off" 1 "on"; +VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/toyota_nodsu_pt_generated_corollah_tss2.dbc b/opendbc/toyota_nodsu_pt_generated_corollah_tss2.dbc new file mode 100644 index 00000000000000..0bce4844ac7ab1 --- /dev/null +++ b/opendbc/toyota_nodsu_pt_generated_corollah_tss2.dbc @@ -0,0 +1,420 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT" + + +CM_ "Imported file _toyota_nodsu_bsm.dbc starts here" +BO_ 1014 BSM: 8 XXX + SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX + SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; + + +CM_ "Imported file _comma.dbc starts here" +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + + BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + + BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + + +CM_ "Imported file _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 CGW + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" 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_ 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_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 353 DSU_SPEED: 7 XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX + +BO_ 452 ENGINE_RPM: 8 CGW + SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|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_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" 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_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 7 DSU + SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX + SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX + SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX + SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ SET_ME_X01 : 23|2@0+ (1,0) [0|3] "" HCU + SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X3 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX + +BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 869 DSU_CRUISE : 7 DSU + SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX + SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX + SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX + SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX + SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" 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_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" 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_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1041 ACC_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1043 TIME : 8 CGW + SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX + SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX + SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX + SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX + SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX + SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX + SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX + SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX + SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX + +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|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 + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" 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_ 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_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +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_ 643 COUNTER "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was "SET_ME_1" and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; +CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +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"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70" +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; + +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_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +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 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 129 "no entry"; +VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; + + +CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180"; + +CM_ "toyota_nodsu_hybrid_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.50,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 + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/release/files_common b/release/files_common index c37825849fc8bd..bec58aa5709fce 100644 --- a/release/files_common +++ b/release/files_common @@ -574,8 +574,10 @@ opendbc/toyota_corolla_2017_pt_generated.dbc opendbc/lexus_rx_350_2016_pt_generated.dbc opendbc/lexus_rx_hybrid_2017_pt_generated.dbc opendbc/toyota_nodsu_pt_generated.dbc +opendbc/toyota_nodsu_pt_generated_corolla_tss2.dbc opendbc/toyota_nodsu_pt_generated_rav4.dbc opendbc/toyota_nodsu_hybrid_pt_generated.dbc +opendbc/toyota_nodsu_pt_generated_corollah_tss2.dbc opendbc/toyota_camry_hybrid_2018_pt_generated.dbc opendbc/toyota_highlander_2017_pt_generated.dbc opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 2708cbecda55db..9acfca7147daea 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -262,12 +262,12 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2]: stop_and_go = True - ret.safetyParam = 53 - ret.wheelbase = 2.63906 + ret.safetyParam = 50 + ret.wheelbase = 2.63906 #testing 2.67 from master pending ret.steerRatio = 15.33 tire_stiffness_factor = 0.996 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG - ret.steerActuatorDelay = 0.6 + ret.steerActuatorDelay = 0.5 ret.steerLimitTimer = 5.0 ret.lateralTuning.init('indi') ret.lateralTuning.indi.innerLoopGainBP = [18, 22, 26] @@ -277,7 +277,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.lateralTuning.indi.timeConstantBP = [18, 22, 26] ret.lateralTuning.indi.timeConstantV = [2, 4, 5.5] ret.lateralTuning.indi.actuatorEffectivenessBP = [18, 22, 26] - ret.lateralTuning.indi.actuatorEffectivenessV = [5, 10, 15] + ret.lateralTuning.indi.actuatorEffectivenessV = [5, 10, 15] elif candidate in [CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2]: stop_and_go = True diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index c3bb4cf77c3f71..c1dde79d90ad58 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1395,8 +1395,8 @@ class CAR: CAR.HIGHLANDERH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), CAR.AVALON: dbc_dict('toyota_avalon_2017_pt_generated', 'toyota_adas'), CAR.RAV4_TSS2: dbc_dict('toyota_nodsu_pt_generated_rav4', 'toyota_tss2_adas'), - CAR.COROLLA_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.COROLLAH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.COROLLA_TSS2: dbc_dict('toyota_nodsu_pt_generated_corolla_tss2', 'toyota_tss2_adas'), + CAR.COROLLAH_TSS2: dbc_dict('toyota_nodsu_pt_generated_corollah_tss2', 'toyota_tss2_adas'), CAR.LEXUS_ES_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.LEXUS_ESH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), CAR.SIENNA: dbc_dict('toyota_sienna_xle_2018_pt_generated', 'toyota_adas'),