diff --git a/.gitignore b/.gitignore
index 5fc18bb07..3e87dcc43 100644
--- a/.gitignore
+++ b/.gitignore
@@ -58,6 +58,7 @@ one
openpilot
notebooks
xx
+yy
hyperthneed
panda_jungle
provisioning
diff --git a/Jenkinsfile b/Jenkinsfile
index a77613202..d12c8e494 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -1,7 +1,7 @@
def phone(String ip, String step_label, String cmd) {
withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) {
def ssh_cmd = """
-ssh -tt -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'EOF'
+ssh -tt -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END'
set -e
@@ -29,7 +29,7 @@ cd ${env.TEST_DIR} || true
${cmd}
exit 0
-EOF"""
+END"""
sh script: ssh_cmd, label: step_label
}
diff --git a/Pipfile b/Pipfile
index fdba04019..2cf24e9cc 100644
--- a/Pipfile
+++ b/Pipfile
@@ -50,7 +50,7 @@ libusb1 = "*"
nose = "*"
numpy = "*"
onnx = "*"
-onnxruntime = "*"
+onnxruntime-gpu = "*"
pillow = "*"
psutil = "*"
pycapnp = "==1.1.0"
diff --git a/Pipfile.lock b/Pipfile.lock
index 81dc794b5..67ea043bb 100644
--- a/Pipfile.lock
+++ b/Pipfile.lock
@@ -1,7 +1,7 @@
{
"_meta": {
"hash": {
- "sha256": "6b23dd7136502655f1c18c37d55db33d77f1b85e0572aed69869401df936003a"
+ "sha256": "3b697db3796ed6f0954ee08eda0b01913add0b5aa83f9f0e484182923fdbc3c2"
},
"pipfile-spec": 6,
"requires": {
@@ -148,11 +148,11 @@
},
"charset-normalizer": {
"hashes": [
- "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0",
- "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405"
+ "sha256:1eecaa09422db5be9e29d7fc65664e6c33bd06f9ced7838578ba40d58bdf3721",
+ "sha256:b0b883e8e874edfdece9c28f314e3dd5badf067342e42fb162203335ae61aa2c"
],
"markers": "python_version >= '3'",
- "version": "==2.0.8"
+ "version": "==2.0.9"
},
"click": {
"hashes": [
@@ -201,48 +201,45 @@
},
"cython": {
"hashes": [
- "sha256:09ac3087ac7a3d489ebcb3fb8402e00c13d1a3a1c6bc73fd3b0d756a3e341e79",
- "sha256:0a142c6b862e6ed6b02209d543062c038c110585b5e32d1ad7c9717af4f07e41",
- "sha256:0d414458cb22f8a90d64260da6dace5d5fcebde43f31be52ca51f818c46db8cb",
- "sha256:10cb3def9774fa99e4583617a5616874aed3255dc241fd1f4a3c2978c78e1c53",
- "sha256:112efa54a58293a4fb0acf0dd8e5b3736e95b595eee24dd88615648e445abe41",
- "sha256:166f9f29cd0058ce1a14a7b3a2458b849ed34b1ec5fd4108af3fdd2c24afcbb0",
- "sha256:2d9e61ed1056a3b6a4b9156b62297ad18b357a7948e57a2f49b061217696567e",
- "sha256:2f41ef7edd76dd23315925e003f0c58c8585f3ab24be6885c4b3f60e77c82746",
- "sha256:37bcfa5df2a3009f49624695d917c3804fccbdfcdc5eda6378754a879711a4d5",
- "sha256:416046a98255eff97ec02077d20ebeaae52682dfca1c35aadf31260442b92514",
- "sha256:4cf4452f0e4d50e11701bca38f3857fe6fa16593e7fd6a4d5f7be66f611b7da2",
- "sha256:55b0ee28c2c8118bfb3ad9b25cf7a6cbd724e442ea96956e32ccd908d5e3e043",
- "sha256:5dd56d0be50073f0e54825a8bc3393852de0eed126339ecbca0ae149dba55cfc",
- "sha256:5fa12ebafc2f688ea6d26ab6d1d2e634a9872509ba7135b902bb0d8b368fb04b",
- "sha256:5fb977945a2111f6b64501fdf7ed0ec162cc502b84457fd648d6a558ea8de0d6",
- "sha256:60c958bcab0ff315b4036a949bed1c65334e1f6a69e17e9966d742febb59043a",
- "sha256:661dbdea519d9cfb288867252b75fef73ffa8e8bb674cec27acf70646afb369b",
- "sha256:6a2cf2ccccc25413864928dfd730c29db6f63eaf98206c1e600003a445ca7f58",
- "sha256:6ade74eece909fd3a437d9a5084829180751d7ade118e281e9824dd75eafaff2",
- "sha256:73ac33a4379056a02031baa4def255717fadb9181b5ac2b244792d53eae1c925",
- "sha256:76cbca0188d278e93d12ebdaf5990678e6e436485fdfad49dbe9b07717d41a3c",
- "sha256:774cb8fd931ee1ba52c472bc1c19077cd6895c1b24014ae07bb27df59aed5ebe",
- "sha256:821c2d416ad7d006b069657ee1034c0e0cb45bdbe9ab6ab631e8c495dfcfa4ac",
- "sha256:84826ec1c11cda56261a252ddecac0c7d6b02e47e81b94f40b27b4c23c29c17c",
- "sha256:854fe2193d3ad4c8b61932ff54d6dbe10c5fa8749eb8958d72cc0ab28243f833",
- "sha256:88dc3c250dec280b0489a83950b15809762e27232f4799b1b8d0bad503f5ab84",
- "sha256:8cb87777e82d1996aef6c146560a19270684271c9c669ba62ac6803b3cd2ff82",
- "sha256:91339ee4b465924a3ea4b2a9cec7f7227bc4cadf673ce859d24c2b9ef60b1214",
- "sha256:9164aeef1af6f837e4fc20402a31d256188ba4d535e262c6cb78caf57ad744f8",
- "sha256:a102cfa795c6b3b81a29bdb9dbec545367cd7f353c03e6f30a056fdfefd92854",
- "sha256:ad43e684ade673565f6f9d6638015112f6c7f11aa2a632167b79014f613f0f5f",
- "sha256:afb521523cb46ddaa8d269b421f88ea2731fee05e65b952b96d4db760f5a2a1c",
- "sha256:b28f92e617f540d3f21f8fd479a9c6491be920ffff672a4c61b7fc4d7f749f39",
- "sha256:bc05de569f811be1fcfde6756c9048ae518f0c4b6d9f8f024752c5365d934cac",
- "sha256:cdf04d07c3600860e8c2ebaad4e8f52ac3feb212453c1764a49ac08c827e8443",
- "sha256:d8d1a087f35e39384303f5e6b75d465d6f29d746d7138eae9d3b6e8e6f769eae",
- "sha256:eb2843f8cc01c645725e6fc690a84e99cdb266ce8ebe427cf3a680ff09f876aa",
- "sha256:f2e9381497b12e8f622af620bde0d1d094035d79b899abb2ddd3a7891f535083",
- "sha256:f96411f0120b5cae483923aaacd2872af8709be4b46522daedc32f051d778385"
- ],
- "index": "pypi",
- "version": "==0.29.24"
+ "sha256:07d5b8ce032110822dad2eb09950a98b9e255d14c2daf094be32d663790b3365",
+ "sha256:08a502fe08756070276d841c830cfc37254a2383d0a5bea736ffb78eff613c88",
+ "sha256:0cf7c3033349d10c5eb33ded1a78974f680e95c245a585c18a2046c67f8ed461",
+ "sha256:0e9e28eb6bb19f5e25f4bf5c8f8ea7db3bc4910309fab2305e5c9c5a5223db77",
+ "sha256:1825d6f2160188dfe1faa0099d30ed0e5ae56826627bf0de6dcb8dcbcf64c9bd",
+ "sha256:191978e5839ca425eb78f0f60a84ad5db7a07b97e8076f9853d0d12c3ccec5d4",
+ "sha256:1c2f262f7d032ec0106534982609ae0148f86ba52fc747df64e645706af20926",
+ "sha256:3379e67113e92fef490a88eca685b07b711bb4db1ddce66af9e460673a5335cc",
+ "sha256:3497e366ffed67454162d31bf4bd2ac3aa183dfac089eb4124966c9f98bd9c05",
+ "sha256:3913f6a50409ab36a5b8edbb4c3e4d441027f43150d8335e5118d34ef04c745c",
+ "sha256:3e94eb973f99c1963973a46dbd9e3974a03b8fe0af3de02dc5d65b4c6a6f9b3f",
+ "sha256:44cc749f288423182504a8fc8734070a369bf576734b9f0fafff40cd6b6e1b3e",
+ "sha256:4dc3d230849d61844e6b5737ee624c896f51e98c8a5d13f965b02a7e735230be",
+ "sha256:4ee99fab5191f403f33774fc92123291c002947338c2628b1ed42ed0017149dd",
+ "sha256:4f7b135cba0d2509890e1dcff2005585bc3d51c9f17564b70d8bc82dc7ec3a5e",
+ "sha256:5d0d97a5f661dccf2f9e14cf27fe9027f772d089fb92fdd3dd8a584d9b8a2916",
+ "sha256:64394ec94d9a0e5002f77e67ee8ceed97f25b483b18ea6aab547f4d82ca32ef6",
+ "sha256:6759b73a9a1013cbdac71ebefa284aa50617b5b32957a54eedaa22ac2f6d48de",
+ "sha256:6efb798993260532879f683dc8ce9e30fd1ec86f02c926f1238a8e6a64576321",
+ "sha256:79d2f84a6d87d45ef580c0441b5394c4f29344e05126a8e2fb4ba4144425f3b0",
+ "sha256:7b3f6e4cfcc103bccdcbc666f613d669ac378c8918629296cdf8191c0c2ec418",
+ "sha256:800cbe944886320e4a4b623becb97960ae9d7d80f2d12980b83bcfb63ff47d5b",
+ "sha256:8726456c7e376410b3c631427da0a4affe1e481424436d1e3f1888cc3c0f8d2e",
+ "sha256:a206a1f8ea11314e02dc01bf24f397b8f1b413bbcc0e031396caa1a126b060c2",
+ "sha256:a87cbe3756e7c464acf3e9420d8741e62d3b2eace0846cb39f664ad378aab284",
+ "sha256:aa9e1fe5ee0a4f9d2430c1e0665f40b48f4b511150ca02f69e9bb49dc48d4e0e",
+ "sha256:b5b3e876e617fe2cf466d02198b76924dcda3cc162a1043226a9c181b9a662a6",
+ "sha256:b6f397256cfab2d0f0af42659fca3232c23f5a570b6c21ed66aaac22dd95da15",
+ "sha256:b8fc9c78262b140364ce1b28ac40ff505a47ac3fd4f86311d461df04a28b3f23",
+ "sha256:c204cb2d005a426c5c83309fd7edea335ff5c514ffa6dc72ddac92cfde170b69",
+ "sha256:d288f25e8abb43b1cfa2fe3d69b2d6236cca3ff6163d090e26c4b1e8ea80dfbf",
+ "sha256:decd641167e97a3c1f973bf0bbb560d251809f6db8168c10edf94c0a1e5dec65",
+ "sha256:e6fa0a7cec9461c5ca687f3c4bb59cf2565afb76c60303b2dc8b280c6e112810",
+ "sha256:e96857ab2dbd8a67852341001f1f2a1ef3f1939d82aea1337497a8f76a9d7f6c",
+ "sha256:eb64ec369eba2207fbe618650d78d9af0455e0c1abb301ec024fa9f3e17a15cc",
+ "sha256:f95433e6963164de372fc1ef01574d7419d96ce45274f296299267d874b90800"
+ ],
+ "index": "pypi",
+ "version": "==0.29.25"
},
"flake8": {
"hashes": [
@@ -303,7 +300,7 @@
"sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7",
"sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951"
],
- "markers": "python_version < '4' and python_full_version >= '3.6.1'",
+ "markers": "python_version < '4.0' and python_full_version >= '3.6.1'",
"version": "==5.10.1"
},
"itsdangerous": {
@@ -533,28 +530,16 @@
"index": "pypi",
"version": "==1.10.2"
},
- "onnxruntime": {
- "hashes": [
- "sha256:3bdb861822a63404cca7b46dce86d48bbc21c906a4b4ed13969bc89763ac7f96",
- "sha256:3fd1d6647245aa38e1099cfd355d84e807de5350d5216e84ceefd91c64ce243d",
- "sha256:48f0fcf3c9aa6836584e64abe63fa7395c02066d3259bbdeb489b4d172e0127a",
- "sha256:4aee9a893f93637341fd0e6b56fa3ab1c430d718d08d79a358603297a1575ad9",
- "sha256:5f00620fc0f51bc4d90ae6d96ceb4b6538e3bd1e328178104118ac672f37c40d",
- "sha256:7339cef9b918b88f1fec8109cfa0a8416f119c5968d00300a9186847d86e35de",
- "sha256:7f9d772a6330cb85e7723f84e357320a1603e3824a92aab4ef36fc3a41e64f16",
- "sha256:9002214af1b2317ab3a63a2f045f7d1363c207e661d475a877aa6499ca09d606",
- "sha256:9ccaf6a0365f2b86efe21681416b8cfe97f084a7d53bd1cf2bf889a0aef2b0d3",
- "sha256:9d03ff4a2717c4149acc7c649fd66a67e81ec44c9e6e2a00df1d6e9ca843f1b7",
- "sha256:a8a2315e2244ac371742f6e30da5367c680c3e84c31e291a35f8ddfab09c3c82",
- "sha256:ab62b29429e0e62c11478b2a8a3af2646531fba7800736e8b201d8baa50b43a8",
- "sha256:bdf1327932227383b04093a51266474b2703b3fcf9c0f6f11c652d9652b76a5c",
- "sha256:c8ff9c914b2b1c3b022dedc199e3f971e340d8923a1ef42d66530508fa367bf6",
- "sha256:cdec8538eb59e63a376d0677f7ec043ceb597d52ee88f1f7e250928893a0de7f",
- "sha256:cf3edbc54bfe99a119d73cd65398a2ec68ae3af2557ab7e645976314a8d11aa1",
- "sha256:d20ce3448babe89a77cc9d357730767deb3617e36439bddcd006f28abc72b416",
- "sha256:e1c1fe3f7d960eeffc02a5f196d85529254eefd59cbeecd8abee0a9467b5c2d8",
- "sha256:e3f8f7d5d4d66e3a4a2b731a000d3142a53a5403e8814e68bbd659514e815899",
- "sha256:fa927b1825f2851c0c8f3948515a56d76cb0686da9acd1d6f8fafe552c8d8fec"
+ "onnxruntime-gpu": {
+ "hashes": [
+ "sha256:064cd6ecbca26bac75299755240f6f6c47933598aa28a4b828fce6e58f49d7ae",
+ "sha256:123a0aa37026651d88c4f79dce0a104cd3bb7df2592a115f3a8e4b76d4cbda5f",
+ "sha256:206e04b34c92bfef432f7861a0deb42ca86b8ad9b0cae424ec1bd726bf38890a",
+ "sha256:b4924b4c7983ee981f76b0d2d9316edd0bf0386983a31c440771832fddbc72d0",
+ "sha256:cbca998cc4785dfc65f94bfb5af6ff45a1132e60e713e6c83ba755b55bd2b196",
+ "sha256:e17b5a33cdc209303a8b687c4f5ad06ef2f9bf2b32efe683b0e0c7de1858c97c",
+ "sha256:e23369b4b9367152f0f299a70543c9001e02667d7a202743f8351ab3a8b06c39",
+ "sha256:f3f37c105cd1c625069e7713a8627079e4691c0e61e9bec8d9e019be843d9783"
],
"index": "pypi",
"version": "==1.9.0"
@@ -715,39 +700,39 @@
},
"pycryptodome": {
"hashes": [
- "sha256:014c758af7fa38cab85b357a496b76f4fc9dda1f731eb28358d66fef7ad4a3e1",
- "sha256:06162fcfed2f9deee8383fd59eaeabc7b7ffc3af50d3fad4000032deb8f700b0",
- "sha256:0ca7a6b4fc1f9fafe990b95c8cda89099797e2cfbf40e55607f2f2f5a3355dcb",
- "sha256:2a4bcc8a9977fee0979079cd33a9e9f0d3ddba5660d35ffe874cf84f1dd399d2",
- "sha256:3c7ed5b07274535979c730daf5817db5e983ea80b04c22579eee8da4ca3ae4f8",
- "sha256:4169ed515742425ff21e4bd3fabbb6994ffb64434472fb72230019bdfa36b939",
- "sha256:428096bbf7a77e207f418dfd4d7c284df8ade81d2dc80f010e92753a3e406ad0",
- "sha256:4ce6b09547bf2c7cede3a017f79502eaed3e819c13cdb3cb357aea1b004e4cc6",
- "sha256:53989477044be41fa4a63da09d5038c2a34b2f4554cfea2e3933b17186ee9e19",
- "sha256:621a90147a5e255fdc2a0fec2d56626b76b5d72ea9e60164c9a5a8976d45b0c9",
- "sha256:6db1f9fa1f52226621905f004278ce7bd90c8f5363ffd5d7ab3755363d98549a",
- "sha256:6eda8a3157c91ba60b26a07bedd6c44ab8bda6cd79b6b5ea9744ba62c39b7b1e",
- "sha256:75e78360d1dd6d02eb288fd8275bb4d147d6e3f5337935c096d11dba1fa84748",
- "sha256:7ff701fc283412e651eaab4319b3cd4eaa0827e94569cd37ee9075d5c05fe655",
- "sha256:8f3a60926be78422e662b0d0b18351b426ce27657101c8a50bad80300de6a701",
- "sha256:a843350d08c3d22f6c09c2f17f020d8dcfa59496165d7425a3fba0045543dda7",
- "sha256:ae29fcd56152f417bfba50a36a56a7a5f9fb74ff80bab98704cac704de6568ab",
- "sha256:ae31cb874f6f0cedbed457c6374e7e54d7ed45c1a4e11a65a9c80968da90a650",
- "sha256:b33c9b3d1327d821e28e9cc3a6512c14f8b17570ddb4cfb9a52247ed0fcc5d8b",
- "sha256:b59bf823cfafde8ef1105d8984f26d1694dff165adb7198b12e3e068d7999b15",
- "sha256:bc3c61ff92efdcc14af4a7b81da71d849c9acee51d8fd8ac9841a7620140d6c6",
- "sha256:ce81b9c6aaa0f920e2ab05eb2b9f4ccd102e3016b2f37125593b16a83a4b0cc2",
- "sha256:d7e5f6f692421e5219aa3b545eb0cffd832cd589a4b9dcd4a5eb4260e2c0d68a",
- "sha256:da796e9221dda61a0019d01742337eb8a322de8598b678a4344ca0a436380315",
- "sha256:ead516e03dfe062aefeafe4a29445a6449b0fc43bc8cb30194b2754917a63798",
- "sha256:ed45ef92d21db33685b789de2c015e9d9a18a74760a8df1fc152faee88cdf741",
- "sha256:f19edd42368e9057c39492947bb99570dc927123e210008f2af7cf9b505c6892",
- "sha256:f9bad2220b80b4ed74f089db012ab5ab5419143a33fad6c8aedcc2a9341eac70",
- "sha256:fce7e22d96030b35345637c563246c24d4513bd3b413e1c40293114837ab8912",
- "sha256:ffd0cac13ff41f2d15ed39dc6ba1d2ad88dd2905d656c33d8235852f5d6151fd"
- ],
- "index": "pypi",
- "version": "==3.11.0"
+ "sha256:1181c90d1a6aee68a84826825548d0db1b58d8541101f908d779d601d1690586",
+ "sha256:12c7343aec5a3b3df5c47265281b12b611f26ec9367b6129199d67da54b768c1",
+ "sha256:212c7f7fe11cad9275fbcff50ca977f1c6643f13560d081e7b0f70596df447b8",
+ "sha256:32d15da81959faea6cbed95df2bb44f7f796211c110cf90b5ad3b2aeeb97fc8e",
+ "sha256:341c6bbf932c406b4f3ee2372e8589b67ac0cf4e99e7dc081440f43a3cde9f0f",
+ "sha256:3558616f45d8584aee3eba27559bc6fd0ba9be6c076610ed3cc62bd5229ffdc3",
+ "sha256:39da5807aa1ff820799c928f745f89432908bf6624b9e981d2d7f9e55d91b860",
+ "sha256:3f2f3dd596c6128d91314e60a6bcf4344610ef0e97f4ae4dd1770f86dd0748d8",
+ "sha256:4cded12e13785bbdf4ba1ff5fb9d261cd98162145f869e4fbc4a4b9083392f0b",
+ "sha256:5a8c24d39d4a237dbfe181ea6593792bf9b5582c7fcfa7b8e0e12fda5eec07af",
+ "sha256:5d4264039a2087977f50072aaff2346d1c1c101cb359f9444cf92e3d1f42b4cd",
+ "sha256:6bb0d340c93bcb674ea8899e2f6408ec64c6c21731a59481332b4b2a8143cc60",
+ "sha256:6f8f5b7b53516da7511951910ab458e799173722c91fea54e2ba2f56d102e4aa",
+ "sha256:90ad3381ccdc6a24cc2841e295706a168f32abefe64c679695712acac71fd5da",
+ "sha256:93acad54a72d81253242eb0a15064be559ec9d989e5173286dc21cad19f01765",
+ "sha256:9ea2f6674c803602a7c0437fccdc2ea036707e60456974fe26ca263bd501ec45",
+ "sha256:a6e1bcd9d5855f1a3c0f8d585f44c81b08f39a02754007f374fb8db9605ba29c",
+ "sha256:a78e4324e566b5fbc2b51e9240950d82fa9e1c7eb77acdf27f58712f65622c1d",
+ "sha256:aceb1d217c3a025fb963849071446cf3aca1353282fe1c3cb7bd7339a4d47947",
+ "sha256:aed7eb4b64c600fbc5e6d4238991ad1b4179a558401f203d1fcbd24883748982",
+ "sha256:b07a4238465eb8c65dd5df2ab8ba6df127e412293c0ed7656c003336f557a100",
+ "sha256:b91404611767a7485837a6f1fd20cf9a5ae0ad362040a022cd65827ecb1b0d00",
+ "sha256:d8083de50f6dec56c3c6f270fb193590999583a1b27c9c75bc0b5cac22d438cc",
+ "sha256:d845c587ceb82ac7cbac7d0bf8c62a1a0fe7190b028b322da5ca65f6e5a18b9e",
+ "sha256:db66ccda65d5d20c17b00768e462a86f6f540f9aea8419a7f76cc7d9effd82cd",
+ "sha256:dc88355c4b261ed259268e65705b28b44d99570337694d593f06e3b1698eaaf3",
+ "sha256:de0b711d673904dd6c65307ead36cb76622365a393569bf880895cba21195b7a",
+ "sha256:e05f994f30f1cda3cbe57441f41220d16731cf99d868bb02a8f6484c454c206b",
+ "sha256:e80f7469b0b3ea0f694230477d8501dc5a30a717e94fddd4821e6721f3053eae",
+ "sha256:f699360ae285fcae9c8f53ca6acf33796025a82bb0ccd7c1c551b04c1726def3"
+ ],
+ "index": "pypi",
+ "version": "==3.12.0"
},
"pyflakes": {
"hashes": [
@@ -767,23 +752,24 @@
},
"pylint": {
"hashes": [
- "sha256:4f4a52b132c05b49094b28e109febcec6bfb7bc6961c7485a5ad0a0f961df289",
- "sha256:b4b5a7b6d04e914a11c198c816042af1fb2d3cda29bb0c98a9c637010da2a5c5"
+ "sha256:9d945a73640e1fec07ee34b42f5669b770c759acd536ec7b16d7e4b87a9c9ff9",
+ "sha256:daabda3f7ed9d1c60f52d563b1b854632fd90035bcf01443e234d3dc794e3b74"
],
"index": "pypi",
- "version": "==2.12.1"
+ "version": "==2.12.2"
},
"pyopencl": {
"hashes": [
- "sha256:05ccbdc341f64f448bfdff173d1b1e79887129cb6c147605628bbd2e56bc3929",
- "sha256:0e705b47733d1055c4d8f7478907222e5881519a0dbadd1bf288baebfc024999",
- "sha256:51425e65ec49c738eefe21b1eeb1f39245b01cc0ddfd495fbe1f8df33dbc6c9e",
- "sha256:59f9824426d823b544717cc25dee221e1a5c5143143efb8d94034cf4ef562913",
- "sha256:662899ca2fb74f2d14c2d7ac0560d3cac07e6b0847a245694bb86a27a4d350ca",
- "sha256:99e26fde9e5c418878a5a4a685b8ebca118f423bb09f33e7e24cfd8ef94aee30"
+ "sha256:295213968ecffcc02ecbcf8b0ba18886c3d29312f66a64a6cdc04ee2efb09c66",
+ "sha256:6b2fc3ee18f154fff9a46d7a8d23ae5407ec0339282d57752fca55a23d6a3810",
+ "sha256:75a1f202741bace9606a8680bbbfac69bf8a73d4e7511fb1a6ce3e48185996ae",
+ "sha256:7b06f9612079195cfd14347712c52792d8f036d4c6f6831a194cc888ce3dd139",
+ "sha256:a10fbce5b10efa6fce4974958ad2adccee13a7ddf202cbcd5c3f23ef1b092f25",
+ "sha256:ba9f1a591f9770d656c9df3379c096e82867bbb10d1fb875ffb120e8926bd0ad",
+ "sha256:ea991b6e566c215dce0016c6765f2f9160a69d06c2f30ec92d99955b80701f2e"
],
"index": "pypi",
- "version": "==2021.2.9"
+ "version": "==2021.2.10"
},
"pyserial": {
"hashes": [
@@ -951,6 +937,14 @@
"index": "pypi",
"version": "==1.2.2"
},
+ "setuptools": {
+ "hashes": [
+ "sha256:6d10741ff20b89cd8c6a536ee9dc90d3002dec0226c78fb98605bfb9ef8a7adf",
+ "sha256:d144f85102f999444d06f9c0e8c737fd0194f10f2f7e5fdb77573f6e2fa4fad0"
+ ],
+ "markers": "python_version >= '3.6'",
+ "version": "==59.5.0"
+ },
"six": {
"hashes": [
"sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926",
@@ -1001,11 +995,11 @@
},
"typing-extensions": {
"hashes": [
- "sha256:2cdf80e4e04866a9b3689a51869016d36db0814d84b8d8a568d22781d45d27ed",
- "sha256:829704698b22e13ec9eaf959122315eabb370b0884400e9818334d8b677023d9"
+ "sha256:4ca091dea149f945ec56afb48dae714f21e8692ef22a395223bcd328961b6a0e",
+ "sha256:7f001e5ac290a0c0401508864c7ec868be4e701886d5b573a9528ed3973d9d3b"
],
- "markers": "python_version < '3.10'",
- "version": "==4.0.0"
+ "markers": "python_version >= '3.6'",
+ "version": "==4.0.1"
},
"urllib3": {
"hashes": [
@@ -1214,11 +1208,11 @@
},
"charset-normalizer": {
"hashes": [
- "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0",
- "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405"
+ "sha256:1eecaa09422db5be9e29d7fc65664e6c33bd06f9ced7838578ba40d58bdf3721",
+ "sha256:b0b883e8e874edfdece9c28f314e3dd5badf067342e42fb162203335ae61aa2c"
],
"markers": "python_version >= '3'",
- "version": "==2.0.8"
+ "version": "==2.0.9"
},
"control": {
"hashes": [
@@ -1229,56 +1223,56 @@
},
"coverage": {
"hashes": [
- "sha256:046647b96969fda1ae0605f61288635209dd69dcd27ba3ec0bf5148bc157f954",
- "sha256:06d009e8a29483cbc0520665bc46035ffe9ae0e7484a49f9782c2a716e37d0a0",
- "sha256:0cde7d9fe2fb55ff68ebe7fb319ef188e9b88e0a3d1c9c5db7dd829cd93d2193",
- "sha256:1de9c6f5039ee2b1860b7bad2c7bc3651fbeb9368e4c4d93e98a76358cdcb052",
- "sha256:24ed38ec86754c4d5a706fbd5b52b057c3df87901a8610d7e5642a08ec07087e",
- "sha256:27a3df08a855522dfef8b8635f58bab81341b2fb5f447819bc252da3aa4cf44c",
- "sha256:310c40bed6b626fd1f463e5a83dba19a61c4eb74e1ac0d07d454ebbdf9047e9d",
- "sha256:3348865798c077c695cae00da0924136bb5cc501f236cfd6b6d9f7a3c94e0ec4",
- "sha256:35b246ae3a2c042dc8f410c94bcb9754b18179cdb81ff9477a9089dbc9ecc186",
- "sha256:3f546f48d5d80a90a266769aa613bc0719cb3e9c2ef3529d53f463996dd15a9d",
- "sha256:586d38dfc7da4a87f5816b203ff06dd7c1bb5b16211ccaa0e9788a8da2b93696",
- "sha256:5d3855d5d26292539861f5ced2ed042fc2aa33a12f80e487053aed3bcb6ced13",
- "sha256:610c0ba11da8de3a753dc4b1f71894f9f9debfdde6559599f303286e70aeb0c2",
- "sha256:62646d98cf0381ffda301a816d6ac6c35fc97aa81b09c4c52d66a15c4bef9d7c",
- "sha256:66af99c7f7b64d050d37e795baadf515b4561124f25aae6e1baa482438ecc388",
- "sha256:675adb3b3380967806b3cbb9c5b00ceb29b1c472692100a338730c1d3e59c8b9",
- "sha256:6e5a8c947a2a89c56655ecbb789458a3a8e3b0cbf4c04250331df8f647b3de59",
- "sha256:7a39590d1e6acf6a3c435c5d233f72f5d43b585f5be834cff1f21fec4afda225",
- "sha256:80cb70264e9a1d04b519cdba3cd0dc42847bf8e982a4d55c769b9b0ee7cdce1e",
- "sha256:82fdcb64bf08aa5db881db061d96db102c77397a570fbc112e21c48a4d9cb31b",
- "sha256:8492d37acdc07a6eac6489f6c1954026f2260a85a4c2bb1e343fe3d35f5ee21a",
- "sha256:94f558f8555e79c48c422045f252ef41eb43becdd945e9c775b45ebfc0cbd78f",
- "sha256:958ac66272ff20e63d818627216e3d7412fdf68a2d25787b89a5c6f1eb7fdd93",
- "sha256:95a58336aa111af54baa451c33266a8774780242cab3704b7698d5e514840758",
- "sha256:96129e41405887a53a9cc564f960d7f853cc63d178f3a182fdd302e4cab2745b",
- "sha256:97ef6e9119bd39d60ef7b9cd5deea2b34869c9f0b9777450a7e3759c1ab09b9b",
- "sha256:98d44a8136eebbf544ad91fef5bd2b20ef0c9b459c65a833c923d9aa4546b204",
- "sha256:9d2c2e3ce7b8cc932a2f918186964bd44de8c84e2f9ef72dc616f5bb8be22e71",
- "sha256:a300b39c3d5905686c75a369d2a66e68fd01472ea42e16b38c948bd02b29e5bd",
- "sha256:a34fccb45f7b2d890183a263578d60a392a1a218fdc12f5bce1477a6a68d4373",
- "sha256:a4d48e42e17d3de212f9af44f81ab73b9378a4b2b8413fd708d0d9023f2bbde4",
- "sha256:af45eea024c0e3a25462fade161afab4f0d9d9e0d5a5d53e86149f74f0a35ecc",
- "sha256:ba6125d4e55c0b8e913dad27b22722eac7abdcb1f3eab1bd090eee9105660266",
- "sha256:bc1ee1318f703bc6c971da700d74466e9b86e0c443eb85983fb2a1bd20447263",
- "sha256:c18725f3cffe96732ef96f3de1939d81215fd6d7d64900dcc4acfe514ea4fcbf",
- "sha256:c8e9c4bcaaaa932be581b3d8b88b677489975f845f7714efc8cce77568b6711c",
- "sha256:cc799916b618ec9fd00135e576424165691fec4f70d7dc12cfaef09268a2478c",
- "sha256:cd2d11a59afa5001ff28073ceca24ae4c506da4355aba30d1e7dd2bd0d2206dc",
- "sha256:d0a595a781f8e186580ff8e3352dd4953b1944289bec7705377c80c7e36c4d6c",
- "sha256:d3c5f49ce6af61154060640ad3b3281dbc46e2e0ef2fe78414d7f8a324f0b649",
- "sha256:d9a635114b88c0ab462e0355472d00a180a5fbfd8511e7f18e4ac32652e7d972",
- "sha256:e5432d9c329b11c27be45ee5f62cf20a33065d482c8dec1941d6670622a6fb8f",
- "sha256:eab14fdd410500dae50fd14ccc332e65543e7b39f6fc076fe90603a0e5d2f929",
- "sha256:ebcc03e1acef4ff44f37f3c61df478d6e469a573aa688e5a162f85d7e4c3860d",
- "sha256:fae3fe111670e51f1ebbc475823899524e3459ea2db2cb88279bbfb2a0b8a3de",
- "sha256:fd92ece726055e80d4e3f01fff3b91f54b18c9c357c48fcf6119e87e2461a091",
- "sha256:ffa545230ca2ad921ad066bf8fd627e7be43716b6e0fcf8e32af1b8188ccb0ab"
- ],
- "index": "pypi",
- "version": "==6.1.2"
+ "sha256:01774a2c2c729619760320270e42cd9e797427ecfddd32c2a7b639cdc481f3c0",
+ "sha256:03b20e52b7d31be571c9c06b74746746d4eb82fc260e594dc662ed48145e9efd",
+ "sha256:0a7726f74ff63f41e95ed3a89fef002916c828bb5fcae83b505b49d81a066884",
+ "sha256:1219d760ccfafc03c0822ae2e06e3b1248a8e6d1a70928966bafc6838d3c9e48",
+ "sha256:13362889b2d46e8d9f97c421539c97c963e34031ab0cb89e8ca83a10cc71ac76",
+ "sha256:174cf9b4bef0db2e8244f82059a5a72bd47e1d40e71c68ab055425172b16b7d0",
+ "sha256:17e6c11038d4ed6e8af1407d9e89a2904d573be29d51515f14262d7f10ef0a64",
+ "sha256:215f8afcc02a24c2d9a10d3790b21054b58d71f4b3c6f055d4bb1b15cecce685",
+ "sha256:22e60a3ca5acba37d1d4a2ee66e051f5b0e1b9ac950b5b0cf4aa5366eda41d47",
+ "sha256:2641f803ee9f95b1f387f3e8f3bf28d83d9b69a39e9911e5bfee832bea75240d",
+ "sha256:276651978c94a8c5672ea60a2656e95a3cce2a3f31e9fb2d5ebd4c215d095840",
+ "sha256:3f7c17209eef285c86f819ff04a6d4cbee9b33ef05cbcaae4c0b4e8e06b3ec8f",
+ "sha256:3feac4084291642165c3a0d9eaebedf19ffa505016c4d3db15bfe235718d4971",
+ "sha256:49dbff64961bc9bdd2289a2bda6a3a5a331964ba5497f694e2cbd540d656dc1c",
+ "sha256:4e547122ca2d244f7c090fe3f4b5a5861255ff66b7ab6d98f44a0222aaf8671a",
+ "sha256:5829192582c0ec8ca4a2532407bc14c2f338d9878a10442f5d03804a95fac9de",
+ "sha256:5d6b09c972ce9200264c35a1d53d43ca55ef61836d9ec60f0d44273a31aa9f17",
+ "sha256:600617008aa82032ddeace2535626d1bc212dfff32b43989539deda63b3f36e4",
+ "sha256:619346d57c7126ae49ac95b11b0dc8e36c1dd49d148477461bb66c8cf13bb521",
+ "sha256:63c424e6f5b4ab1cf1e23a43b12f542b0ec2e54f99ec9f11b75382152981df57",
+ "sha256:6dbc1536e105adda7a6312c778f15aaabe583b0e9a0b0a324990334fd458c94b",
+ "sha256:6e1394d24d5938e561fbeaa0cd3d356207579c28bd1792f25a068743f2d5b282",
+ "sha256:86f2e78b1eff847609b1ca8050c9e1fa3bd44ce755b2ec30e70f2d3ba3844644",
+ "sha256:8bdfe9ff3a4ea37d17f172ac0dff1e1c383aec17a636b9b35906babc9f0f5475",
+ "sha256:8e2c35a4c1f269704e90888e56f794e2d9c0262fb0c1b1c8c4ee44d9b9e77b5d",
+ "sha256:92b8c845527eae547a2a6617d336adc56394050c3ed8a6918683646328fbb6da",
+ "sha256:9365ed5cce5d0cf2c10afc6add145c5037d3148585b8ae0e77cc1efdd6aa2953",
+ "sha256:9a29311bd6429be317c1f3fe4bc06c4c5ee45e2fa61b2a19d4d1d6111cb94af2",
+ "sha256:9a2b5b52be0a8626fcbffd7e689781bf8c2ac01613e77feda93d96184949a98e",
+ "sha256:a4bdeb0a52d1d04123b41d90a4390b096f3ef38eee35e11f0b22c2d031222c6c",
+ "sha256:a9c8c4283e17690ff1a7427123ffb428ad6a52ed720d550e299e8291e33184dc",
+ "sha256:b637c57fdb8be84e91fac60d9325a66a5981f8086c954ea2772efe28425eaf64",
+ "sha256:bf154ba7ee2fd613eb541c2bc03d3d9ac667080a737449d1a3fb342740eb1a74",
+ "sha256:c254b03032d5a06de049ce8bca8338a5185f07fb76600afff3c161e053d88617",
+ "sha256:c332d8f8d448ded473b97fefe4a0983265af21917d8b0cdcb8bb06b2afe632c3",
+ "sha256:c7912d1526299cb04c88288e148c6c87c0df600eca76efd99d84396cfe00ef1d",
+ "sha256:cfd9386c1d6f13b37e05a91a8583e802f8059bebfccde61a418c5808dea6bbfa",
+ "sha256:d5d2033d5db1d58ae2d62f095e1aefb6988af65b4b12cb8987af409587cc0739",
+ "sha256:dca38a21e4423f3edb821292e97cec7ad38086f84313462098568baedf4331f8",
+ "sha256:e2cad8093172b7d1595b4ad66f24270808658e11acf43a8f95b41276162eb5b8",
+ "sha256:e3db840a4dee542e37e09f30859f1612da90e1c5239a6a2498c473183a50e781",
+ "sha256:edcada2e24ed68f019175c2b2af2a8b481d3d084798b8c20d15d34f5c733fa58",
+ "sha256:f467bbb837691ab5a8ca359199d3429a11a01e6dfb3d9dcc676dc035ca93c0a9",
+ "sha256:f506af4f27def639ba45789fa6fde45f9a217da0be05f8910458e4557eed020c",
+ "sha256:f614fc9956d76d8a88a88bb41ddc12709caa755666f580af3a688899721efecd",
+ "sha256:f9afb5b746781fc2abce26193d1c817b7eb0e11459510fba65d2bd77fe161d9e",
+ "sha256:fb8b8ee99b3fffe4fd86f4c81b35a6bf7e4462cba019997af2fe679365db0c49"
+ ],
+ "index": "pypi",
+ "version": "==6.2"
},
"cryptography": {
"hashes": [
@@ -1371,11 +1365,11 @@
},
"fonttools": {
"hashes": [
- "sha256:dca694331af74c8ad47acc5171e57f6b78fac5692bf050f2ab572964577ac0dd",
- "sha256:eff1da7ea274c54cb8842853005a139f711646cbf6f1bcfb6c9b86a627f35ff0"
+ "sha256:ca6ecc67e5a5620d31754f92147f22f48fd5461fd3fafe6afe031aa9ee079b0f",
+ "sha256:edb48922873d3fda489ab400bd40888ac239ae8070b53f494b839bcdff0d01f6"
],
"markers": "python_version >= '3.7'",
- "version": "==4.28.2"
+ "version": "==4.28.3"
},
"hexdump": {
"hashes": [
@@ -1386,11 +1380,11 @@
},
"hypothesis": {
"hashes": [
- "sha256:92005826894782cc57c47b98debe1bc889b716f0774e60f83536f14360a9199e",
- "sha256:c4943d159f299a96b1c23277c4bcf0759a757888b67a6d73e9c70d853024aa15"
+ "sha256:25e0e581f999281ff765aba3c3f1e3ce289e82a1ff1b9de2c5082b37113aa448",
+ "sha256:adb42a52bc3c1300d0a0a221870ce5c264bee2e54b0473de6767c3ae02649b5f"
],
"index": "pypi",
- "version": "==6.27.2"
+ "version": "==6.30.1"
},
"identify": {
"hashes": [
@@ -1762,11 +1756,11 @@
},
"paramiko": {
"hashes": [
- "sha256:def3ec612399bab4e9f5eb66b0ae5983980db9dd9120d9e9c6ea3ff673865d1c",
- "sha256:e673b10ee0f1c80d46182d3af7751d033d9b573dd7054d2d0aa46be186c3c1d2"
+ "sha256:7b5910f5815a00405af55da7abcc8a9e0d9657f57fcdd9a89894fdbba1c6b8a8",
+ "sha256:85b1245054e5d7592b9088cc6d08da22445417912d3a3e48138675c7a8616438"
],
"index": "pypi",
- "version": "==2.8.0"
+ "version": "==2.8.1"
},
"pillow": {
"hashes": [
@@ -1832,11 +1826,11 @@
},
"pre-commit": {
"hashes": [
- "sha256:3c25add78dbdfb6a28a651780d5c311ac40dd17f160eb3954a0c59da40a505a7",
- "sha256:a4ed01000afcb484d9eb8d504272e642c4c4099bbad3a6b27e519bd6a3e928a6"
+ "sha256:758d1dc9b62c2ed8881585c254976d66eae0889919ab9b859064fc2fe3c7743e",
+ "sha256:fe9897cac830aa7164dbd02a4e7b90cae49630451ce88464bca73db486ba9f65"
],
"index": "pypi",
- "version": "==2.15.0"
+ "version": "==2.16.0"
},
"pycparser": {
"hashes": [
@@ -2052,6 +2046,9 @@
"sha256:93378f3d14fff07572392ce6a6a2ceb3a1f237733bd6dcb9eb6a2b29b0d19085",
"sha256:95c2d250074cfa76715d58830579c64dff7354484b284c2b8b87e5a38321672c",
"sha256:ab5875facfdef77e0a47d5fd39ea178b58e60e454a4c85aa1e52fcb80db7babf",
+ "sha256:b0e0aeb061a1d7dcd2ed59ea57ee56c9b23dd60100825f98238c06ee5cc4467e",
+ "sha256:b78a35c5c74d336f42f44106174b9851c783184a85a3fe3e68857259b37b9ffb",
+ "sha256:c9e04d7e9b03a8a6ac2045f7c5ef741be86727d8f49c45db45f244bdd2bcff17",
"sha256:ca36e7d9430f7481fc7d11e015ae16fbd5575615a8e9060538104778be84addf",
"sha256:ceebc3c4f6a109777c0053dfa0282fddb8893eddfb0d598574acfb734a926168",
"sha256:e2c036492e673aad1b7b0d0ccdc0cb30a968353d2c4bf92ac8e73509e1bf212c",
@@ -2065,6 +2062,14 @@
"index": "pypi",
"version": "==1.7.3"
},
+ "setuptools": {
+ "hashes": [
+ "sha256:6d10741ff20b89cd8c6a536ee9dc90d3002dec0226c78fb98605bfb9ef8a7adf",
+ "sha256:d144f85102f999444d06f9c0e8c737fd0194f10f2f7e5fdb77573f6e2fa4fad0"
+ ],
+ "markers": "python_version >= '3.6'",
+ "version": "==59.5.0"
+ },
"setuptools-scm": {
"hashes": [
"sha256:4c64444b1d49c4063ae60bfe1680f611c8b13833d556fd1d6050c0023162a119",
@@ -2097,11 +2102,11 @@
},
"sphinx": {
"hashes": [
- "sha256:6d051ab6e0d06cba786c4656b0fe67ba259fe058410f49e95bee6e49c4052cbf",
- "sha256:7e2b30da5f39170efcd95c6270f07669d623c276521fee27ad6c380f49d2bf5b"
+ "sha256:048dac56039a5713f47a554589dc98a442b39226a2b9ed7f82797fcb2fe9253f",
+ "sha256:32a5b3e9a1b176cc25ed048557d4d3d01af635e6b76c5bc7a43b0a34447fbd45"
],
"index": "pypi",
- "version": "==4.3.0"
+ "version": "==4.3.1"
},
"sphinx-rtd-theme": {
"hashes": [
@@ -2194,11 +2199,11 @@
},
"typing-extensions": {
"hashes": [
- "sha256:2cdf80e4e04866a9b3689a51869016d36db0814d84b8d8a568d22781d45d27ed",
- "sha256:829704698b22e13ec9eaf959122315eabb370b0884400e9818334d8b677023d9"
+ "sha256:4ca091dea149f945ec56afb48dae714f21e8692ef22a395223bcd328961b6a0e",
+ "sha256:7f001e5ac290a0c0401508864c7ec868be4e701886d5b573a9528ed3973d9d3b"
],
- "markers": "python_version < '3.10'",
- "version": "==4.0.0"
+ "markers": "python_version >= '3.6'",
+ "version": "==4.0.1"
},
"urllib3": {
"hashes": [
diff --git a/RELEASES.md b/RELEASES.md
index 3c73c6779..79ad237b5 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,6 +1,7 @@
Version 0.8.12 (2021-12-XX)
========================
* New alert sounds
+ * Audi Q3 2020-21 support thanks to jyoung8607!
* Honda Accord 2021 support thanks to csouers!
* Honda Accord Hybrid 2021 support thanks to csouers!
* Lexus RC 2020 support thanks to ErichMoraga!
diff --git a/SConstruct b/SConstruct
index a66290aab..14450cec9 100644
--- a/SConstruct
+++ b/SConstruct
@@ -90,7 +90,6 @@ if arch == "aarch64" or arch == "larch64":
"/usr/lib",
"/system/vendor/lib64",
"/system/comma/usr/lib",
- "#third_party/nanovg",
f"#third_party/acados/{arch}/lib",
]
@@ -209,7 +208,6 @@ env = Environment(
"#third_party/linux/include",
"#third_party/snpe/include",
"#third_party/mapbox-gl-native-qt/include",
- "#third_party/nanovg",
"#third_party/qrcode",
"#third_party",
"#cereal",
diff --git a/cereal b/cereal
index 486a09a2e..e5a04ab45 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit 486a09a2e9a8c4ae5bb2853a9bef2b64e875f883
+Subproject commit e5a04ab458afd52cf630cc9e35ccdc10efba6688
diff --git a/docs/CARS.md b/docs/CARS.md
index a4742603b..9c762ee7b 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -83,6 +83,7 @@
| Audi | A3 2014-19 | ACC + Lane Assist | Stock | 0mph | 0mph |
| Audi | A3 Sportback e-tron 2017-18 | ACC + Lane Assist | Stock | 0mph | 0mph |
| Audi | Q2 2018 | ACC + Lane Assist | Stock | 0mph | 0mph |
+| Audi | Q3 2020-21 | ACC + Lane Assist | Stock | 0mph | 0mph |
| Audi | S3 2015 | ACC + Lane Assist | Stock | 0mph | 0mph |
| Buick | Regal 20181 | Adaptive Cruise | openpilot | 0mph | 7mph |
| Cadillac | ATS 20181 | Adaptive Cruise | openpilot | 0mph | 7mph |
@@ -121,7 +122,7 @@
| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph |
| Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Forte 2018-21 | SCC + LKAS | Stock | 0mph | 0mph |
-| Kia | K5 2021 | SCC + LFA | Stock | 0mph | 0mph |
+| Kia | K5 2021-22 | SCC + LFA | Stock | 0mph | 0mph |
| Kia | Niro EV 2019-21 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Niro Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph |
diff --git a/release/files_common b/release/files_common
index 902242bcd..3fc354396 100644
--- a/release/files_common
+++ b/release/files_common
@@ -443,9 +443,6 @@ selfdrive/assets/training/*
third_party/SConscript
-third_party/nanovg/*.c
-third_party/nanovg/*.h
-
third_party/libgralloc/**
third_party/linux/**
third_party/opencl/**
diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc
index 75458974f..751f735ca 100644
--- a/selfdrive/boardd/panda.cc
+++ b/selfdrive/boardd/panda.cc
@@ -363,57 +363,49 @@ static uint8_t len_to_dlc(uint8_t len) {
}
}
-void Panda::pack_can_buffer(const capnp::List::Reader &can_data_list,
- std::function write_func) {
- if (send.size() < (can_data_list.size() * CANPACKET_MAX_SIZE)) {
- send.resize(can_data_list.size() * CANPACKET_MAX_SIZE);
+static void write_packet(uint8_t *dest, int *write_pos, const uint8_t *src, size_t size) {
+ for (int i = 0, &pos = *write_pos; i < size; ++i, ++pos) {
+ // Insert counter every 64 bytes (first byte of 64 bytes USB packet)
+ if (pos % USBPACKET_MAX_SIZE == 0) {
+ dest[pos] = pos / USBPACKET_MAX_SIZE;
+ pos++;
+ }
+ dest[pos] = src[i];
}
+}
- int msg_count = 0;
- while (msg_count < can_data_list.size()) {
- uint32_t pos = 0;
- while (pos < USB_TX_SOFT_LIMIT) {
- if (msg_count == can_data_list.size()) { break; }
- auto cmsg = can_data_list[msg_count];
-
- // check if the message is intended for this panda
- uint8_t bus = cmsg.getSrc();
- if (bus < bus_offset || bus >= (bus_offset + PANDA_BUS_CNT)) {
- msg_count++;
- continue;
- }
- auto can_data = cmsg.getDat();
- uint8_t data_len_code = len_to_dlc(can_data.size());
- assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8));
- assert(can_data.size() == dlc_to_len[data_len_code]);
-
- can_header header;
- header.addr = cmsg.getAddress();
- header.extended = (cmsg.getAddress() >= 0x800) ? 1 : 0;
- header.data_len_code = data_len_code;
- header.bus = bus - bus_offset;
- memcpy(&send[pos], &header, CANPACKET_HEAD_SIZE);
- memcpy(&send[pos+CANPACKET_HEAD_SIZE], can_data.begin(), can_data.size());
-
- pos += CANPACKET_HEAD_SIZE + dlc_to_len[data_len_code];
- msg_count++;
+void Panda::pack_can_buffer(const capnp::List::Reader &can_data_list,
+ std::function write_func) {
+ int32_t pos = 0;
+ uint8_t send_buf[2 * USB_TX_SOFT_LIMIT];
+
+ for (auto cmsg : can_data_list) {
+ // check if the message is intended for this panda
+ uint8_t bus = cmsg.getSrc();
+ if (bus < bus_offset || bus >= (bus_offset + PANDA_BUS_CNT)) {
+ continue;
}
+ auto can_data = cmsg.getDat();
+ uint8_t data_len_code = len_to_dlc(can_data.size());
+ assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8));
+ assert(can_data.size() == dlc_to_len[data_len_code]);
- if (pos > 0) { // Helps not to spam with ZLP
- // Counter needs to be inserted every 64 bytes (first byte of 64 bytes USB packet)
- uint8_t counter = 0;
- uint8_t to_write[USB_TX_SOFT_LIMIT+128];
- int ptr = 0;
- for (int i = 0; i < pos; i += 63) {
- to_write[ptr] = counter;
- int copy_size = ((pos - i) < 63) ? (pos - i) : 63;
- memcpy(&to_write[ptr+1], &(send.data()[i]) , copy_size);
- ptr += copy_size + 1;
- counter++;
- }
- write_func(to_write, ptr);
+ can_header header;
+ header.addr = cmsg.getAddress();
+ header.extended = (cmsg.getAddress() >= 0x800) ? 1 : 0;
+ header.data_len_code = data_len_code;
+ header.bus = bus - bus_offset;
+
+ write_packet(send_buf, &pos, (uint8_t *)&header, sizeof(can_header));
+ write_packet(send_buf, &pos, (uint8_t *)can_data.begin(), can_data.size());
+ if (pos >= USB_TX_SOFT_LIMIT) {
+ write_func(send_buf, pos);
+ pos = 0;
}
}
+
+ // send remaining packets
+ if (pos > 0) write_func(send_buf, pos);
}
void Panda::can_send(capnp::List::Reader can_data_list) {
diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h
index 79124a59b..fe6918948 100644
--- a/selfdrive/boardd/panda.h
+++ b/selfdrive/boardd/panda.h
@@ -69,7 +69,6 @@ class Panda {
libusb_context *ctx = NULL;
libusb_device_handle *dev_handle = NULL;
std::mutex usb_lock;
- std::vector send;
std::vector recv_buf;
void handle_usb_issue(int err, const char func[]);
void cleanup();
diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h
index f55bbd840..20c00c5b5 100644
--- a/selfdrive/camerad/cameras/camera_common.h
+++ b/selfdrive/camerad/cameras/camera_common.h
@@ -30,7 +30,6 @@
const int UI_BUF_COUNT = 4;
const int YUV_BUFFER_COUNT = Hardware::EON() ? 100 : 40;
-
enum CameraType {
RoadCam = 0,
DriverCam,
@@ -52,23 +51,6 @@ typedef struct CameraInfo {
bool hdr;
} CameraInfo;
-typedef struct LogCameraInfo {
- CameraType type;
- const char* filename;
- const char* frame_packet_name;
- const char* encode_idx_name;
- VisionStreamType stream_type;
- int frame_width, frame_height;
- int fps;
- int bitrate;
- bool is_h265;
- bool downscale;
- bool has_qcamera;
- bool trigger_rotate;
- bool enable;
- bool record;
-} LogCameraInfo;
-
typedef struct FrameMetadata {
uint32_t frame_id;
unsigned int frame_length;
diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py
index 315c398ab..7c6cc6d2d 100644
--- a/selfdrive/car/ford/values.py
+++ b/selfdrive/car/ford/values.py
@@ -9,12 +9,6 @@ MAX_ANGLE = 87. # make sure we never command the extremes (0xfff) which cause l
class CAR:
FUSION = "FORD FUSION 2018"
-FINGERPRINTS = {
- CAR.FUSION: [{
- 71: 8, 74: 8, 75: 8, 76: 8, 90: 8, 92: 8, 93: 8, 118: 8, 119: 8, 120: 8, 125: 8, 129: 8, 130: 8, 131: 8, 132: 8, 133: 8, 145: 8, 146: 8, 357: 8, 359: 8, 360: 8, 361: 8, 376: 8, 390: 8, 391: 8, 392: 8, 394: 8, 512: 8, 514: 8, 516: 8, 531: 8, 532: 8, 534: 8, 535: 8, 560: 8, 578: 8, 604: 8, 613: 8, 673: 8, 827: 8, 848: 8, 934: 8, 935: 8, 936: 8, 947: 8, 963: 8, 970: 8, 972: 8, 973: 8, 984: 8, 992: 8, 994: 8, 997: 8, 998: 8, 1003: 8, 1034: 8, 1045: 8, 1046: 8, 1053: 8, 1054: 8, 1058: 8, 1059: 8, 1068: 8, 1072: 8, 1073: 8, 1082: 8, 1107: 8, 1108: 8, 1109: 8, 1110: 8, 1200: 8, 1427: 8, 1430: 8, 1438: 8, 1459: 8
- }],
-}
-
DBC = {
CAR.FUSION: dbc_dict('ford_fusion_2018_pt', 'ford_fusion_2018_adas'),
}
diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py
index d75be7c71..e1488eda2 100644
--- a/selfdrive/car/honda/carcontroller.py
+++ b/selfdrive/car/honda/carcontroller.py
@@ -244,6 +244,6 @@ class CarController():
# Send dashboard UI commands.
if (frame % 10) == 0:
idx = (frame//10) % 4
- can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, CS.is_metric, idx, CS.CP.openpilotLongitudinalControl, CS.stock_hud))
+ can_sends.extend(hondacan.create_ui_commands(self.packer, CS.CP, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud))
return can_sends
diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py
index 5bcf59c25..7fcafe67f 100644
--- a/selfdrive/car/honda/hondacan.py
+++ b/selfdrive/car/honda/hondacan.py
@@ -1,4 +1,4 @@
-from selfdrive.car.honda.values import HONDA_BOSCH, CAR, CarControllerParams
+from selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, CAR, CarControllerParams
from selfdrive.config import Conversions as CV
# CAN bus layout with relay
@@ -98,14 +98,14 @@ def create_bosch_supplemental_1(packer, car_fingerprint, idx):
return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values, idx)
-def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, openpilot_longitudinal_control, stock_hud):
+def create_ui_commands(packer, CP, pcm_speed, hud, is_metric, idx, stock_hud):
commands = []
- bus_pt = get_pt_bus(car_fingerprint)
- radar_disabled = car_fingerprint in HONDA_BOSCH and openpilot_longitudinal_control
- bus_lkas = get_lkas_cmd_bus(car_fingerprint, radar_disabled)
+ bus_pt = get_pt_bus(CP.carFingerprint)
+ radar_disabled = CP.carFingerprint in HONDA_BOSCH and CP.openpilotLongitudinalControl
+ bus_lkas = get_lkas_cmd_bus(CP.carFingerprint, radar_disabled)
- if openpilot_longitudinal_control:
- if car_fingerprint in HONDA_BOSCH:
+ if CP.openpilotLongitudinalControl:
+ if CP.carFingerprint in HONDA_BOSCH:
acc_hud_values = {
'CRUISE_SPEED': hud.v_cruise,
'ENABLE_MINI_CAR': 1,
@@ -142,16 +142,24 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx,
'SOLID_LANES': hud.lanes,
'BEEP': 0,
}
- commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values, idx))
- if radar_disabled and car_fingerprint in HONDA_BOSCH:
+ if not (CP.flags & HondaFlags.BOSCH_EXT_HUD):
+ lkas_hud_values['SET_ME_X48'] = 0x48
+
+ if CP.flags & HondaFlags.BOSCH_EXT_HUD and not CP.openpilotLongitudinalControl:
+ commands.append(packer.make_can_msg('LKAS_HUD_A', bus_lkas, lkas_hud_values, idx))
+ commands.append(packer.make_can_msg('LKAS_HUD_B', bus_lkas, lkas_hud_values, idx))
+ else:
+ commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values, idx))
+
+ if radar_disabled and CP.carFingerprint in HONDA_BOSCH:
radar_hud_values = {
'CMBS_OFF': 0x01,
'SET_TO_1': 0x01,
}
commands.append(packer.make_can_msg('RADAR_HUD', bus_pt, radar_hud_values, idx))
- if car_fingerprint == CAR.CIVIC_BOSCH:
+ if CP.carFingerprint == CAR.CIVIC_BOSCH:
commands.append(packer.make_can_msg("LEGACY_BRAKE_COMMAND", bus_pt, {}, idx))
return commands
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index 5a5aea9f9..09804c3eb 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -3,7 +3,7 @@ from cereal import car
from panda import Panda
from common.numpy_fast import interp
from common.params import Params
-from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL
+from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL
from selfdrive.car import STD_CARGO_KG, CivicParams, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config
from selfdrive.car.interfaces import CarInterfaceBase
from selfdrive.car.disable_ecu import disable_ecu
@@ -52,6 +52,10 @@ class CarInterface(CarInterfaceBase):
if candidate == CAR.CRV_5G:
ret.enableBsm = 0x12f8bfa7 in fingerprint[0]
+ # Detect Bosch cars with new HUD msgs
+ if any(0x33DA in f for f in fingerprint.values()):
+ ret.flags |= HondaFlags.BOSCH_EXT_HUD.value
+
# Accord 1.5T CVT has different gearbox message
if candidate == CAR.ACCORD and 0x191 in fingerprint[1]:
ret.transmissionType = TransmissionType.cvt
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index b6ed1b261..9f248de65 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -1,3 +1,5 @@
+from enum import IntFlag
+
from cereal import car
from selfdrive.car import dbc_dict
@@ -37,6 +39,11 @@ class CarControllerParams():
self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV)
+class HondaFlags(IntFlag):
+ # Bosch models with alternate set of LKAS_HUD messages
+ BOSCH_EXT_HUD = 1
+
+
# Car button codes
class CruiseButtons:
RES_ACCEL = 4
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index ddcd00ba0..67516809a 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -696,28 +696,34 @@ FW_VERSIONS = {
b'\xf1\000DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ',
b'\xf1\x8799110L2000\xf1\000DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ',
b'\xf1\x8799110L2100\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ',
+ b'\xf1\x8799110L2100\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ',
],
(Ecu.eps, 0x7D4, None): [
b'\xf1\x8756310-L3110\xf1\000DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101',
b'\xf1\x8756310-L3220\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101',
+ b'\xf1\x8757700-L3000\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102',
],
(Ecu.fwdCamera, 0x7C4, None): [
b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915',
+ b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208',
],
(Ecu.esp, 0x7D1, None): [
b'\xf1\000DL ESC \006 101 \004\002 58910-L3200',
b'\xf1\x8758910-L3200\xf1\000DL ESC \006 101 \004\002 58910-L3200',
b'\xf1\x8758910-L3800\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800',
+ b'\xf1\x8758910-L3600\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600',
],
(Ecu.engine, 0x7E0, None): [
b'\xf1\x87391212MKT0',
b'\xf1\x87391212MKV0',
+ b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DLDWN5TMDCXXXJ1B',
],
(Ecu.transmission, 0x7E1, None): [
b'\xf1\000bcsh8p54 U913\000\000\000\000\000\000TDL2T16NB1ia\v\xb8',
b'\xf1\x87SALFEA5652514GK2UUeV\x88\x87\x88xxwg\x87ww\x87wwfwvd/\xfb\xffvU_\xff\x93\xd3\xf1\x81U913\000\000\000\000\000\000\xf1\000bcsh8p54 U913\000\000\000\000\000\000TDL2T16NB1ia\v\xb8',
b'\xf1\x87SALFEA6046104GK2wvwgeTeFg\x88\x96xwwwwffvfe?\xfd\xff\x86fo\xff\x97A\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB1ia\x0b\xb8',
b'\xf1\x87SCMSAA8572454GK1\x87x\x87\x88Vf\x86hgwvwvwwgvwwgT?\xfb\xff\x97fo\xffH\xb8\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18',
+ b'\xf1\x87954A02N300\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 WDL3T25XXX730NS2b\x1f\xb8%',
],
},
CAR.KONA_EV: {
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 943b030e8..100c7cb44 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -545,6 +545,7 @@ FW_VERSIONS = {
b'\x018966312W9000\x00\x00\x00\x00',
],
(Ecu.engine, 0x7e0, None): [
+ b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
@@ -571,6 +572,7 @@ FW_VERSIONS = {
b'\x01F152602560\x00\x00\x00\x00\x00\x00',
b'\x01F152602590\x00\x00\x00\x00\x00\x00',
b'\x01F152602650\x00\x00\x00\x00\x00\x00',
+ b"\x01F15260A010\x00\x00\x00\x00\x00\x00",
b'\x01F15260A050\x00\x00\x00\x00\x00\x00',
b'\x01F152612641\x00\x00\x00\x00\x00\x00',
b'\x01F152612651\x00\x00\x00\x00\x00\x00',
@@ -669,6 +671,7 @@ FW_VERSIONS = {
b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00',
+ b"\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00",
b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py
index 115b9f1a4..2179bf950 100644
--- a/selfdrive/car/volkswagen/interface.py
+++ b/selfdrive/car/volkswagen/interface.py
@@ -134,6 +134,10 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1205 + STD_CARGO_KG
ret.wheelbase = 2.61
+ elif candidate == CAR.AUDI_Q3_MK2:
+ ret.mass = 1623 + STD_CARGO_KG
+ ret.wheelbase = 2.68
+
elif candidate == CAR.SEAT_ATECA_MK1:
ret.mass = 1900 + STD_CARGO_KG
ret.wheelbase = 2.64
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index 5dcdad3b5..27effb4ac 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -84,6 +84,7 @@ class CAR:
TROC_MK1 = "VOLKSWAGEN T-ROC 1ST GEN" # Chassis A1, Mk1 VW VW T-Roc and variants
AUDI_A3_MK3 = "AUDI A3 3RD GEN" # Chassis 8V/FF, Mk3 Audi A3 and variants
AUDI_Q2_MK1 = "AUDI Q2 1ST GEN" # Chassis GA, Mk1 Audi Q2 (RoW) and Q2L (China only)
+ AUDI_Q3_MK2 = "AUDI Q3 2ND GEN" # Chassis 8U/F3/FS, Mk2 Audi Q3 and variants
SEAT_ATECA_MK1 = "SEAT ATECA 1ST GEN" # Chassis 5F, Mk1 SEAT Ateca and CUPRA Ateca
SEAT_LEON_MK3 = "SEAT LEON 3RD GEN" # Chassis 5F, Mk3 SEAT Leon and variants
SKODA_KAMIQ_MK1 = "SKODA KAMIQ 1ST GEN" # Chassis NW, Mk1 Skoda Kamiq
@@ -560,6 +561,28 @@ FW_VERSIONS = {
b'\xf1\x872Q0907572M \xf1\x890233',
],
},
+ CAR.AUDI_Q3_MK2: {
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8705E906018N \xf1\x899970',
+ b'\xf1\x8783A906259 \xf1\x890001',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x8709G927158CN\xf1\x893608',
+ b'\xf1\x870GC300046F \xf1\x892701',
+ ],
+ (Ecu.srs, 0x715, None): [
+ b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111',
+ b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111',
+ ],
+ (Ecu.eps, 0x712, None): [
+ b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300',
+ b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800',
+ ],
+ (Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x872Q0907572R \xf1\x890372',
+ b'\xf1\x872Q0907572T \xf1\x890383',
+ ],
+ },
CAR.SEAT_ATECA_MK1: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704E906027KA\xf1\x893749',
diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc
index ea09ee070..a405d2160 100644
--- a/selfdrive/common/params.cc
+++ b/selfdrive/common/params.cc
@@ -153,7 +153,6 @@ std::unordered_map keys = {
{"TrainingVersion", PERSISTENT},
{"UpdateAvailable", CLEAR_ON_MANAGER_START},
{"UpdateFailedCount", CLEAR_ON_MANAGER_START},
- {"UploadRaw", PERSISTENT},
{"Version", PERSISTENT},
{"VisionRadarToggle", PERSISTENT},
{"ApiCache_Device", PERSISTENT},
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
index f895f6b16..e75e84da1 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
@@ -242,7 +242,7 @@ class LongitudinalMpc():
self.solver.cost_set(i, 'Zl', Zl)
def set_weights_for_xva_policy(self):
- W = np.asfortranarray(np.diag([0., 10., 1., 10., 1.]))
+ W = np.asfortranarray(np.diag([0., 10., 1., 10., 0.0, 1.]))
for i in range(N):
self.solver.cost_set(i, 'W', W)
# Setting the slice without the copy make the array not contiguous,
@@ -255,7 +255,7 @@ class LongitudinalMpc():
self.solver.cost_set(i, 'Zl', Zl)
def set_cur_state(self, v, a):
- if abs(self.x0[1] - v) > 1.:
+ if abs(self.x0[1] - v) > 2.:
self.x0[1] = v
self.x0[2] = a
for i in range(0, N+1):
diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py
index 1c1ab0e17..41bae4c47 100755
--- a/selfdrive/controls/lib/longitudinal_planner.py
+++ b/selfdrive/controls/lib/longitudinal_planner.py
@@ -68,8 +68,7 @@ class Planner:
force_slow_decel = sm['controlsState'].forceDecel
prev_accel_constraint = True
- enabled = (long_control_state == LongCtrlState.pid) or (long_control_state == LongCtrlState.stopping)
- if not enabled or sm['carState'].gasPressed:
+ if long_control_state == LongCtrlState.off or sm['carState'].gasPressed:
self.v_desired = v_ego
self.a_desired = a_ego
# Smoothly changing between accel trajectory is only relevant when OP is driving
diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py
index 5b7596df2..f482cd6cf 100644
--- a/selfdrive/hardware/tici/hardware.py
+++ b/selfdrive/hardware/tici/hardware.py
@@ -303,6 +303,10 @@ class Tici(HardwareBase):
val = "0" if powersave_enabled else "1"
os.system(f"sudo su -c 'echo {val} > /sys/devices/system/cpu/cpu{i}/online'")
+ for n in ('0', '4'):
+ gov = 'powersave' if powersave_enabled else 'performance'
+ os.system(f"sudo su -c 'echo {gov} > /sys/devices/system/cpu/cpufreq/policy{n}/scaling_governor'")
+
def get_gpu_usage_percent(self):
try:
used, total = open('/sys/class/kgsl/kgsl-3d0/gpubusy').read().strip().split()
diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc
index e3444f331..c1bb3b182 100644
--- a/selfdrive/loggerd/loggerd.cc
+++ b/selfdrive/loggerd/loggerd.cc
@@ -180,6 +180,7 @@ void rotate_if_needed(LoggerdState *s) {
void loggerd_thread() {
// setup messaging
typedef struct QlogState {
+ std::string name;
int counter, freq;
} QlogState;
std::unordered_map qlog_states;
@@ -195,7 +196,11 @@ void loggerd_thread() {
SubSocket * sock = SubSocket::create(s.ctx, it.name);
assert(sock != NULL);
poller->registerSocket(sock);
- qlog_states[sock] = {.counter = 0, .freq = it.decimation};
+ qlog_states[sock] = {
+ .name = it.name,
+ .counter = 0,
+ .freq = it.decimation,
+ };
}
// init logger
@@ -219,6 +224,7 @@ void loggerd_thread() {
// poll for new messages on all sockets
for (auto sock : poller->poll(1000)) {
// drain socket
+ int count = 0;
QlogState &qs = qlog_states[sock];
Message *msg = nullptr;
while (!do_exit && (msg = sock->receive(true))) {
@@ -233,6 +239,12 @@ void loggerd_thread() {
double seconds = (millis_since_boot() - start_ts) / 1000.0;
LOGD("%lu messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count / seconds, bytes_count * 0.001 / seconds);
}
+
+ count++;
+ if (count >= 200) {
+ LOGE("large volume of '%s' messages", qs.name.c_str());
+ break;
+ }
}
}
}
diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h
index 977e03b8d..0101a91a5 100644
--- a/selfdrive/loggerd/loggerd.h
+++ b/selfdrive/loggerd/loggerd.h
@@ -41,12 +41,26 @@ const int DCAM_BITRATE = Hardware::TICI() ? MAIN_BITRATE : 2500000;
const bool LOGGERD_TEST = getenv("LOGGERD_TEST");
const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) : 60;
+struct LogCameraInfo {
+ CameraType type;
+ const char *filename;
+ VisionStreamType stream_type;
+ int frame_width, frame_height;
+ int fps;
+ int bitrate;
+ bool is_h265;
+ bool downscale;
+ bool has_qcamera;
+ bool trigger_rotate;
+ bool enable;
+ bool record;
+};
+
const LogCameraInfo cameras_logged[] = {
{
.type = RoadCam,
.stream_type = VISION_STREAM_ROAD,
.filename = "fcamera.hevc",
- .frame_packet_name = "roadCameraState",
.fps = MAIN_FPS,
.bitrate = MAIN_BITRATE,
.is_h265 = true,
@@ -60,7 +74,6 @@ const LogCameraInfo cameras_logged[] = {
.type = DriverCam,
.stream_type = VISION_STREAM_DRIVER,
.filename = "dcamera.hevc",
- .frame_packet_name = "driverCameraState",
.fps = MAIN_FPS, // on EONs, more compressed this way
.bitrate = DCAM_BITRATE,
.is_h265 = true,
@@ -74,7 +87,6 @@ const LogCameraInfo cameras_logged[] = {
.type = WideRoadCam,
.stream_type = VISION_STREAM_WIDE_ROAD,
.filename = "ecamera.hevc",
- .frame_packet_name = "wideRoadCameraState",
.fps = MAIN_FPS,
.bitrate = MAIN_BITRATE,
.is_h265 = true,
diff --git a/selfdrive/loggerd/tests/loggerd_tests_common.py b/selfdrive/loggerd/tests/loggerd_tests_common.py
index 579aaf604..1a16e343e 100644
--- a/selfdrive/loggerd/tests/loggerd_tests_common.py
+++ b/selfdrive/loggerd/tests/loggerd_tests_common.py
@@ -56,7 +56,6 @@ class MockParams():
def __init__(self):
self.params = {
"DongleId": b"0000000000000000",
- "UploadRaw": b"1",
"IsOffroad": b"1",
}
diff --git a/selfdrive/loggerd/tests/test_uploader.py b/selfdrive/loggerd/tests/test_uploader.py
old mode 100644
new mode 100755
index 8ebb001c7..8562f5f21
--- a/selfdrive/loggerd/tests/test_uploader.py
+++ b/selfdrive/loggerd/tests/test_uploader.py
@@ -1,3 +1,5 @@
+#!/usr/bin/env python3
+import os
import time
import threading
import unittest
@@ -50,66 +52,72 @@ class TestUploader(UploaderTestCase):
self.end_event.set()
self.up_thread.join()
- def gen_files(self, lock=False):
+ def gen_files(self, lock=False, boot=True):
f_paths = list()
- for t in ["bootlog.bz2", "qlog.bz2", "rlog.bz2", "dcamera.hevc", "fcamera.hevc"]:
+ for t in ["qlog.bz2", "rlog.bz2", "dcamera.hevc", "fcamera.hevc"]:
f_paths.append(self.make_file_with_data(self.seg_dir, t, 1, lock=lock))
+
+ if boot:
+ f_paths.append(self.make_file_with_data("boot", f"{self.seg_dir}.bz2", 1, lock=lock))
return f_paths
- def gen_order(self, seg1, seg2):
- keys = [f"{self.seg_format.format(i)}/qlog.bz2" for i in seg1]
+ def gen_order(self, seg1, seg2, boot=True):
+ keys = []
+ if boot:
+ keys += [f"boot/{self.seg_format.format(i)}.bz2" for i in seg1]
+ keys += [f"boot/{self.seg_format2.format(i)}.bz2" for i in seg2]
+ keys += [f"{self.seg_format.format(i)}/qlog.bz2" for i in seg1]
keys += [f"{self.seg_format2.format(i)}/qlog.bz2" for i in seg2]
- for i in seg1:
- keys += [f"{self.seg_format.format(i)}/{f}" for f in ['rlog.bz2', 'fcamera.hevc', 'dcamera.hevc']]
- for i in seg2:
- keys += [f"{self.seg_format2.format(i)}/{f}" for f in ['rlog.bz2', 'fcamera.hevc', 'dcamera.hevc']]
- keys += [f"{self.seg_format.format(i)}/bootlog.bz2" for i in seg1]
- keys += [f"{self.seg_format2.format(i)}/bootlog.bz2" for i in seg2]
return keys
def test_upload(self):
- f_paths = self.gen_files(lock=False)
+ self.gen_files(lock=False)
self.start_thread()
# allow enough time that files could upload twice if there is a bug in the logic
time.sleep(5)
self.join_thread()
- self.assertTrue(len(log_handler.upload_ignored) == 0, "Some files were ignored")
- self.assertFalse(len(log_handler.upload_order) < len(f_paths), "Some files failed to upload")
- self.assertFalse(len(log_handler.upload_order) > len(f_paths), "Some files were uploaded twice")
- for f_path in f_paths:
- self.assertTrue(getxattr(f_path, uploader.UPLOAD_ATTR_NAME), "All files not uploaded")
exp_order = self.gen_order([self.seg_num], [])
+
+ self.assertTrue(len(log_handler.upload_ignored) == 0, "Some files were ignored")
+ self.assertFalse(len(log_handler.upload_order) < len(exp_order), "Some files failed to upload")
+ self.assertFalse(len(log_handler.upload_order) > len(exp_order), "Some files were uploaded twice")
+ for f_path in exp_order:
+ self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not uploaded")
+
self.assertTrue(log_handler.upload_order == exp_order, "Files uploaded in wrong order")
def test_upload_ignored(self):
self.set_ignore()
- f_paths = self.gen_files(lock=False)
+ self.gen_files(lock=False)
self.start_thread()
# allow enough time that files could upload twice if there is a bug in the logic
time.sleep(5)
self.join_thread()
- self.assertTrue(len(log_handler.upload_order) == 0, "Some files were not ignored")
- self.assertFalse(len(log_handler.upload_ignored) < len(f_paths), "Some files failed to ignore")
- self.assertFalse(len(log_handler.upload_ignored) > len(f_paths), "Some files were ignored twice")
- for f_path in f_paths:
- self.assertTrue(getxattr(f_path, uploader.UPLOAD_ATTR_NAME), "All files not ignored")
exp_order = self.gen_order([self.seg_num], [])
+
+ self.assertTrue(len(log_handler.upload_order) == 0, "Some files were not ignored")
+ self.assertFalse(len(log_handler.upload_ignored) < len(exp_order), "Some files failed to ignore")
+ self.assertFalse(len(log_handler.upload_ignored) > len(exp_order), "Some files were ignored twice")
+ for f_path in exp_order:
+ self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not ignored")
+
self.assertTrue(log_handler.upload_ignored == exp_order, "Files ignored in wrong order")
def test_upload_files_in_create_order(self):
- f_paths = list()
seg1_nums = [0, 1, 2, 10, 20]
for i in seg1_nums:
self.seg_dir = self.seg_format.format(i)
- f_paths += self.gen_files()
+ self.gen_files(boot=False)
seg2_nums = [5, 50, 51]
for i in seg2_nums:
self.seg_dir = self.seg_format2.format(i)
- f_paths += self.gen_files()
+ self.gen_files(boot=False)
+
+ exp_order = self.gen_order(seg1_nums, seg2_nums, boot=False)
self.start_thread()
# allow enough time that files could upload twice if there is a bug in the logic
@@ -117,15 +125,15 @@ class TestUploader(UploaderTestCase):
self.join_thread()
self.assertTrue(len(log_handler.upload_ignored) == 0, "Some files were ignored")
- self.assertFalse(len(log_handler.upload_order) < len(f_paths), "Some files failed to upload")
- self.assertFalse(len(log_handler.upload_order) > len(f_paths), "Some files were uploaded twice")
- for f_path in f_paths:
- self.assertTrue(getxattr(f_path, uploader.UPLOAD_ATTR_NAME), "All files not uploaded")
- exp_order = self.gen_order(seg1_nums, seg2_nums)
+ self.assertFalse(len(log_handler.upload_order) < len(exp_order), "Some files failed to upload")
+ self.assertFalse(len(log_handler.upload_order) > len(exp_order), "Some files were uploaded twice")
+ for f_path in exp_order:
+ self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not uploaded")
+
self.assertTrue(log_handler.upload_order == exp_order, "Files uploaded in wrong order")
def test_no_upload_with_lock_file(self):
- f_paths = self.gen_files(lock=True)
+ f_paths = self.gen_files(lock=True, boot=False)
self.start_thread()
# allow enough time that files should have been uploaded if they would be uploaded
@@ -137,4 +145,4 @@ class TestUploader(UploaderTestCase):
if __name__ == "__main__":
- unittest.main()
+ unittest.main(failfast=True)
diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py
index e99725f0c..10bf218b0 100644
--- a/selfdrive/loggerd/uploader.py
+++ b/selfdrive/loggerd/uploader.py
@@ -60,8 +60,6 @@ class Uploader():
self.last_resp = None
self.last_exc = None
- self.raw_size = 0
- self.raw_count = 0
self.immediate_size = 0
self.immediate_count = 0
@@ -72,21 +70,16 @@ class Uploader():
self.immediate_folders = ["crash/", "boot/"]
self.immediate_priority = {"qlog.bz2": 0, "qcamera.ts": 1}
- self.high_priority = {"rlog.bz2": 0, "fcamera.hevc": 1, "dcamera.hevc": 2, "ecamera.hevc": 3}
def get_upload_sort(self, name):
if name in self.immediate_priority:
return self.immediate_priority[name]
- if name in self.high_priority:
- return self.high_priority[name] + 100
return 1000
def list_upload_files(self):
if not os.path.isdir(self.root):
return
- self.raw_size = 0
- self.raw_count = 0
self.immediate_size = 0
self.immediate_count = 0
@@ -116,38 +109,27 @@ class Uploader():
if name in self.immediate_priority:
self.immediate_count += 1
self.immediate_size += os.path.getsize(fn)
- else:
- self.raw_count += 1
- self.raw_size += os.path.getsize(fn)
except OSError:
pass
yield (name, key, fn)
- def next_file_to_upload(self, with_raw):
+ def next_file_to_upload(self):
upload_files = list(self.list_upload_files())
- # try to upload qlog files first
for name, key, fn in upload_files:
- if name in self.immediate_priority or any(f in fn for f in self.immediate_folders):
+ if any(f in fn for f in self.immediate_folders):
return (key, fn)
- if with_raw:
- # then upload the full log files, rear and front camera files
- for name, key, fn in upload_files:
- if name in self.high_priority:
- return (key, fn)
-
- # then upload other files
- for name, key, fn in upload_files:
- if not name.endswith('.lock') and not name.endswith(".tmp"):
- return (key, fn)
+ for name, key, fn in upload_files:
+ if name in self.immediate_priority:
+ return (key, fn)
return None
def do_upload(self, key, fn):
try:
- url_resp = self.api.get("v1.4/"+self.dongle_id+"/upload_url/", timeout=10, path=key, access_token=self.api.get_token())
+ url_resp = self.api.get("v1.4/" + self.dongle_id + "/upload_url/", timeout=10, path=key, access_token=self.api.get_token())
if url_resp.status_code == 412:
self.last_resp = url_resp
return
@@ -226,8 +208,6 @@ class Uploader():
def get_msg(self):
msg = messaging.new_message("uploaderState")
us = msg.uploaderState
- us.rawQueueSize = int(self.raw_size / 1e6)
- us.rawQueueCount = self.raw_count
us.immediateQueueSize = int(self.immediate_size / 1e6)
us.immediateQueueCount = self.immediate_count
us.lastTime = self.last_time
@@ -260,10 +240,7 @@ def uploader_fn(exit_event):
time.sleep(60 if offroad else 5)
continue
- good_internet = network_type in [NetworkType.wifi, NetworkType.ethernet]
- allow_raw_upload = params.get_bool("UploadRaw")
-
- d = uploader.next_file_to_upload(with_raw=allow_raw_upload and good_internet and offroad)
+ d = uploader.next_file_to_upload()
if d is None: # Nothing to upload
if allow_sleep:
time.sleep(60 if offroad else 5)
diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py
index 6acda36a2..d16a14503 100755
--- a/selfdrive/manager/test/test_manager.py
+++ b/selfdrive/manager/test/test_manager.py
@@ -19,6 +19,7 @@ ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not D
class TestManager(unittest.TestCase):
def setUp(self):
os.environ['PASSIVE'] = '0'
+ HARDWARE.set_power_save(False)
def tearDown(self):
manager.manager_cleanup()
diff --git a/selfdrive/modeld/runners/onnx_runner.py b/selfdrive/modeld/runners/onnx_runner.py
index 811ea91ab..3b19550e8 100755
--- a/selfdrive/modeld/runners/onnx_runner.py
+++ b/selfdrive/modeld/runners/onnx_runner.py
@@ -5,8 +5,9 @@ import sys
import numpy as np
os.environ["OMP_NUM_THREADS"] = "4"
+os.environ["OMP_WAIT_POLICY"] = "PASSIVE"
-import onnxruntime as ort
+import onnxruntime as ort # pylint: disable=import-error
def read(sz):
dd = []
@@ -38,22 +39,22 @@ def run_loop(m):
if __name__ == "__main__":
- print(ort.get_available_providers(), file=sys.stderr)
+ print("Onnx available providers: ", ort.get_available_providers(), file=sys.stderr)
+ options = ort.SessionOptions()
+ options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL
if 'OpenVINOExecutionProvider' in ort.get_available_providers() and 'ONNXCPU' not in os.environ:
- print("OnnxJit is using openvino", file=sys.stderr)
- options = ort.SessionOptions()
- options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL
provider = 'OpenVINOExecutionProvider'
+ elif 'CUDAExecutionProvider' in ort.get_available_providers() and 'ONNXCPU' not in os.environ:
+ options.intra_op_num_threads = 2
+ provider = 'CUDAExecutionProvider'
else:
- print("OnnxJit is using CPU", file=sys.stderr)
- options = ort.SessionOptions()
- options.intra_op_num_threads = 4
+ options.intra_op_num_threads = 2
options.inter_op_num_threads = 8
options.execution_mode = ort.ExecutionMode.ORT_SEQUENTIAL
options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_ENABLE_ALL
-
provider = 'CPUExecutionProvider'
- ort_session = ort.InferenceSession(sys.argv[1], options)
- ort_session.set_providers([provider], None)
+ print("Onnx selected provider: ", [provider], file=sys.stderr)
+ ort_session = ort.InferenceSession(sys.argv[1], options, providers=[provider])
+ print("Onnx using ", ort_session.get_providers(), file=sys.stderr)
run_loop(ort_session)
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 38d586039..debd3800c 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-7bcb9e414784d5ca8a4338680421023d07ef9e53
\ No newline at end of file
+a64f5f3d44b2d96c5b555dd91172e5e8d760edb2
\ No newline at end of file
diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh
index 53c7b3909..260a1b448 100755
--- a/selfdrive/test/setup_device_ci.sh
+++ b/selfdrive/test/setup_device_ci.sh
@@ -1,4 +1,6 @@
-#!/usr/bin/bash -e
+#!/usr/bin/bash
+
+set -e
if [ -z "$SOURCE_DIR" ]; then
echo "SOURCE_DIR must be set"
@@ -24,8 +26,35 @@ if [ -f "/EON" ]; then
rm -rf /data/safe_staging
fi
+export KEYS_PATH="/usr/comma/setup_keys"
+export CONTINUE_PATH="/data/continue.sh"
+if [ -f "/EON" ]; then
+ export KEYS_PATH="/data/data/com.termux/files/home/setup_keys"
+ export CONTINUE_PATH="/data/data/com.termux/files/continue.sh"
+fi
+tee $CONTINUE_PATH << EOF
+#!/usr/bin/bash
+
+PARAMS_ROOT="/data/params/d"
+
+while true; do
+ mkdir -p \$PARAMS_ROOT
+ cp $KEYS_PATH \$PARAMS_ROOT/GithubSshKeys
+ echo -n 1 > \$PARAMS_ROOT/SshEnabled
+ sleep 1m
+done
+
+sleep infinity
+EOF
+chmod +x $CONTINUE_PATH
+
# set up environment
+if [ ! -d "$SOURCE_DIR" ]; then
+ git clone https://github.com/commaai/openpilot.git $SOURCE_DIR
+fi
cd $SOURCE_DIR
+
+rm -f .git/index.lock
git reset --hard
git fetch
find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \;
diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py
index a7d8daf14..d342919ee 100755
--- a/selfdrive/test/test_onroad.py
+++ b/selfdrive/test/test_onroad.py
@@ -138,21 +138,18 @@ class TestOnroad(unittest.TestCase):
cls.lr = list(LogReader(os.path.join(segs[-1], "rlog.bz2")))
return
+ # setup env
os.environ['REPLAY'] = "1"
os.environ['SKIP_FW_QUERY'] = "1"
os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019"
+
+ params = Params()
+ params.clear_all()
set_params_enabled()
# Make sure athena isn't running
- Params().delete("DongleId")
- Params().delete("AthenadPid")
os.system("pkill -9 -f athena")
- logger_root = Path(ROOT)
- initial_segments = set()
- if logger_root.exists():
- initial_segments = set(Path(ROOT).iterdir())
-
# start manager and run openpilot for a minute
try:
manager_path = os.path.join(BASEDIR, "selfdrive/manager/manager.py")
@@ -164,15 +161,19 @@ class TestOnroad(unittest.TestCase):
sm.update(1000)
# make sure we get at least two full segments
+ route = None
cls.segments = []
with Timeout(300, "timed out waiting for logs"):
+ while route is None:
+ route = params.get("CurrentRoute", encoding="utf-8")
+ time.sleep(0.1)
+
while len(cls.segments) < 3:
- new_paths = set()
- if logger_root.exists():
- new_paths = set(logger_root.iterdir()) - initial_segments
- segs = [p for p in new_paths if "--" in str(p)]
+ segs = set()
+ if Path(ROOT).exists():
+ segs = set(Path(ROOT).glob(f"{route}--*"))
cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1]))
- time.sleep(5)
+ time.sleep(2)
finally:
proc.terminate()
diff --git a/selfdrive/test/test_routes.py b/selfdrive/test/test_routes.py
index 696fe0de0..dc6b926db 100755
--- a/selfdrive/test/test_routes.py
+++ b/selfdrive/test/test_routes.py
@@ -158,6 +158,7 @@ routes = [
TestRoute("0cd0b7f7e31a3853|2021-11-18--00-38-32", VOLKSWAGEN.TROC_MK1),
TestRoute("07667b885add75fd|2021-01-23--19-48-42", VOLKSWAGEN.AUDI_A3_MK3),
TestRoute("6c6b466346192818|2021-06-06--14-17-47", VOLKSWAGEN.AUDI_Q2_MK1),
+ TestRoute("0cd0b7f7e31a3853|2021-12-03--03-12-05", VOLKSWAGEN.AUDI_Q3_MK2),
TestRoute("8f205bdd11bcbb65|2021-03-26--01-00-17", VOLKSWAGEN.SEAT_ATECA_MK1),
TestRoute("fc6b6c9a3471c846|2021-05-27--13-39-56", VOLKSWAGEN.SEAT_LEON_MK3),
TestRoute("12d6ae3057c04b0d|2021-09-15--00-04-07", VOLKSWAGEN.SKODA_KAMIQ_MK1),
diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py
index eb3e59426..c5bf955e7 100755
--- a/selfdrive/thermald/thermald.py
+++ b/selfdrive/thermald/thermald.py
@@ -22,15 +22,13 @@ from selfdrive.hardware import EON, TICI, PC, HARDWARE
from selfdrive.loggerd.config import get_available_percent
from selfdrive.swaglog import cloudlog
from selfdrive.thermald.power_monitoring import PowerMonitoring
-from selfdrive.version import get_tested_branch, terms_version, training_version
+from selfdrive.version import terms_version, training_version
ThermalStatus = log.DeviceState.ThermalStatus
NetworkType = log.DeviceState.NetworkType
NetworkStrength = log.DeviceState.NetworkStrength
CURRENT_TAU = 15. # 15s time constant
TEMP_TAU = 5. # 5s time constant
-DAYS_NO_CONNECTIVITY_MAX = 14 # do not allow to engage after this many days
-DAYS_NO_CONNECTIVITY_PROMPT = 10 # send an offroad prompt after this many days
DISCONNECT_TIMEOUT = 5. # wait 5 seconds before going offroad after disconnect so you get an alert
ThermalBand = namedtuple("ThermalBand", ['min_temp', 'max_temp'])
@@ -165,10 +163,11 @@ def thermald_thread():
fan_speed = 0
count = 0
- startup_conditions = {
+ onroad_conditions = {
"ignition": False,
}
- startup_conditions_prev = startup_conditions.copy()
+ startup_conditions = {}
+ startup_conditions_prev = {}
off_ts = None
started_ts = None
@@ -222,12 +221,12 @@ def thermald_thread():
if pandaState.pandaType == log.PandaState.PandaType.unknown:
no_panda_cnt += 1
if no_panda_cnt > DISCONNECT_TIMEOUT / DT_TRML:
- if startup_conditions["ignition"]:
+ if onroad_conditions["ignition"]:
cloudlog.error("Lost panda connection while onroad")
- startup_conditions["ignition"] = False
+ onroad_conditions["ignition"] = False
else:
no_panda_cnt = 0
- startup_conditions["ignition"] = pandaState.ignitionLine or pandaState.ignitionCan
+ onroad_conditions["ignition"] = pandaState.ignitionLine or pandaState.ignitionCan
in_car = pandaState.harnessStatus != log.PandaState.HarnessStatus.notConnected
usb_power = peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client
@@ -306,7 +305,7 @@ def thermald_thread():
)
if handle_fan is not None:
- fan_speed = handle_fan(controller, max_comp_temp, fan_speed, startup_conditions["ignition"])
+ fan_speed = handle_fan(controller, max_comp_temp, fan_speed, onroad_conditions["ignition"])
msg.deviceState.fanSpeedPercentDesired = fan_speed
is_offroad_for_5_min = (started_ts is None) and ((not started_seen) or (off_ts is None) or (sec_since_boot() - off_ts > 60 * 5))
@@ -324,47 +323,11 @@ def thermald_thread():
# **** starting logic ****
- # Check for last update time and display alerts if needed
+ # Ensure date/time are valid
now = datetime.datetime.utcnow()
-
- # show invalid date/time alert
startup_conditions["time_valid"] = (now.year > 2020) or (now.year == 2020 and now.month >= 10)
set_offroad_alert_if_changed("Offroad_InvalidTime", (not startup_conditions["time_valid"]))
- # Show update prompt
- try:
- last_update = datetime.datetime.fromisoformat(params.get("LastUpdateTime", encoding='utf8'))
- except (TypeError, ValueError):
- last_update = now
- dt = now - last_update
-
- update_failed_count = params.get("UpdateFailedCount")
- update_failed_count = 0 if update_failed_count is None else int(update_failed_count)
- last_update_exception = params.get("LastUpdateException", encoding='utf8')
-
- if update_failed_count > 15 and last_update_exception is not None:
- if get_tested_branch():
- extra_text = "Ensure the software is correctly installed"
- else:
- extra_text = last_update_exception
-
- set_offroad_alert_if_changed("Offroad_ConnectivityNeeded", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeededPrompt", False)
- set_offroad_alert_if_changed("Offroad_UpdateFailed", True, extra_text=extra_text)
- elif dt.days > DAYS_NO_CONNECTIVITY_MAX and update_failed_count > 1:
- set_offroad_alert_if_changed("Offroad_UpdateFailed", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeededPrompt", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeeded", True)
- elif dt.days > DAYS_NO_CONNECTIVITY_PROMPT:
- remaining = max(DAYS_NO_CONNECTIVITY_MAX - dt.days, 1)
- set_offroad_alert_if_changed("Offroad_UpdateFailed", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeeded", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeededPrompt", True, extra_text=f"{remaining} day{'' if remaining == 1 else 's'}.")
- else:
- set_offroad_alert_if_changed("Offroad_UpdateFailed", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeeded", False)
- set_offroad_alert_if_changed("Offroad_ConnectivityNeededPrompt", False)
-
startup_conditions["up_to_date"] = params.get("Offroad_ConnectivityNeeded") is None or params.get_bool("DisableUpdates") or params.get_bool("SnoozeUpdate")
startup_conditions["not_uninstalling"] = not params.get_bool("DoUninstall")
startup_conditions["accepted_terms"] = params.get("HasAcceptedTerms") == terms_version
@@ -377,14 +340,17 @@ def thermald_thread():
startup_conditions["not_taking_snapshot"] = not params.get_bool("IsTakingSnapshot")
# if any CPU gets above 107 or the battery gets above 63, kill all processes
# controls will warn with CPU above 95 or battery above 60
- startup_conditions["device_temp_good"] = thermal_status < ThermalStatus.danger
- set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", (not startup_conditions["device_temp_good"]))
+ onroad_conditions["device_temp_good"] = thermal_status < ThermalStatus.danger
+ set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", (not onroad_conditions["device_temp_good"]))
if TICI:
set_offroad_alert_if_changed("Offroad_StorageMissing", (not Path("/data/media").is_mount()))
# Handle offroad/onroad transition
- should_start = all(startup_conditions.values())
+ should_start = all(onroad_conditions.values())
+ if started_ts is None:
+ should_start = should_start and all(startup_conditions.values())
+
if should_start != should_start_prev or (count == 0):
params.put_bool("IsOnroad", should_start)
params.put_bool("IsOffroad", not should_start)
@@ -396,25 +362,25 @@ def thermald_thread():
started_ts = sec_since_boot()
started_seen = True
else:
- if startup_conditions["ignition"] and (startup_conditions != startup_conditions_prev):
- cloudlog.event("Startup blocked", startup_conditions=startup_conditions)
+ if onroad_conditions["ignition"] and (startup_conditions != startup_conditions_prev):
+ cloudlog.event("Startup blocked", startup_conditions=startup_conditions, onroad_conditions=onroad_conditions)
started_ts = None
if off_ts is None:
off_ts = sec_since_boot()
# Offroad power monitoring
- power_monitor.calculate(peripheralState, startup_conditions["ignition"])
+ power_monitor.calculate(peripheralState, onroad_conditions["ignition"])
msg.deviceState.offroadPowerUsageUwh = power_monitor.get_power_used()
msg.deviceState.carBatteryCapacityUwh = max(0, power_monitor.get_car_battery_capacity())
current_power_draw = HARDWARE.get_current_power_draw() # pylint: disable=assignment-from-none
msg.deviceState.powerDrawW = current_power_draw if current_power_draw is not None else 0
# Check if we need to disable charging (handled by boardd)
- msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(startup_conditions["ignition"], in_car, off_ts)
+ msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(onroad_conditions["ignition"], in_car, off_ts)
# Check if we need to shut down
- if power_monitor.should_shutdown(peripheralState, startup_conditions["ignition"], in_car, off_ts, started_seen):
+ if power_monitor.should_shutdown(peripheralState, onroad_conditions["ignition"], in_car, off_ts, started_seen):
cloudlog.info(f"shutting device down, offroad since {off_ts}")
# TODO: add function for blocking cloudlog instead of sleep
time.sleep(10)
diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript
index da16c12d1..52e4e0c42 100644
--- a/selfdrive/ui/SConscript
+++ b/selfdrive/ui/SConscript
@@ -56,10 +56,9 @@ qt_env.Program("qt/text", ["qt/text.cc"], LIBS=qt_libs)
qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=qt_libs)
# build main UI
-qt_src = ["main.cc", "ui.cc", "paint.cc", "qt/sidebar.cc", "qt/onroad.cc",
+qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/onroad.cc",
"qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc",
- "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc",
- "#third_party/nanovg/nanovg.c"]
+ "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc"]
qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs)
diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc
deleted file mode 100644
index 612b924f3..000000000
--- a/selfdrive/ui/paint.cc
+++ /dev/null
@@ -1,311 +0,0 @@
-#include "selfdrive/ui/paint.h"
-
-#include
-
-#ifdef __APPLE__
-#include
-#define NANOVG_GL3_IMPLEMENTATION
-#define nvgCreate nvgCreateGL3
-#else
-#include
-#define NANOVG_GLES3_IMPLEMENTATION
-#define nvgCreate nvgCreateGLES3
-#endif
-
-#define NANOVG_GLES3_IMPLEMENTATION
-#include
-#include
-
-#include "selfdrive/common/util.h"
-#include "selfdrive/hardware/hw.h"
-#include "selfdrive/ui/ui.h"
-
-static void ui_draw_text(const UIState *s, float x, float y, const char *string, float size, NVGcolor color, const char *font_name) {
- nvgFontFace(s->vg, font_name);
- nvgFontSize(s->vg, size);
- nvgFillColor(s->vg, color);
- nvgText(s->vg, x, y, string, NULL);
-}
-
-static void draw_chevron(UIState *s, float x, float y, float sz, NVGcolor fillColor, NVGcolor glowColor) {
- // glow
- float g_xo = sz/5;
- float g_yo = sz/10;
- nvgBeginPath(s->vg);
- nvgMoveTo(s->vg, x+(sz*1.35)+g_xo, y+sz+g_yo);
- nvgLineTo(s->vg, x, y-g_xo);
- nvgLineTo(s->vg, x-(sz*1.35)-g_xo, y+sz+g_yo);
- nvgClosePath(s->vg);
- nvgFillColor(s->vg, glowColor);
- nvgFill(s->vg);
-
- // chevron
- nvgBeginPath(s->vg);
- nvgMoveTo(s->vg, x+(sz*1.25), y+sz);
- nvgLineTo(s->vg, x, y);
- nvgLineTo(s->vg, x-(sz*1.25), y+sz);
- nvgClosePath(s->vg);
- nvgFillColor(s->vg, fillColor);
- nvgFill(s->vg);
-}
-
-static void ui_draw_circle_image(const UIState *s, int center_x, int center_y, int radius, const char *image, NVGcolor color, float img_alpha) {
- nvgBeginPath(s->vg);
- nvgCircle(s->vg, center_x, center_y, radius);
- nvgFillColor(s->vg, color);
- nvgFill(s->vg);
- const int img_size = radius * 1.5;
- ui_draw_image(s, {center_x - (img_size / 2), center_y - (img_size / 2), img_size, img_size}, image, img_alpha);
-}
-
-static void ui_draw_circle_image(const UIState *s, int center_x, int center_y, int radius, const char *image, bool active) {
- float bg_alpha = active ? 0.3f : 0.1f;
- float img_alpha = active ? 1.0f : 0.15f;
- ui_draw_circle_image(s, center_x, center_y, radius, image, nvgRGBA(0, 0, 0, (255 * bg_alpha)), img_alpha);
-}
-
-static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) {
- // Draw lead car indicator
- auto [x, y] = vd;
-
- float fillAlpha = 0;
- float speedBuff = 10.;
- float leadBuff = 40.;
- float d_rel = lead_data.getDRel();
- float v_rel = lead_data.getVRel();
- if (d_rel < leadBuff) {
- fillAlpha = 255*(1.0-(d_rel/leadBuff));
- if (v_rel < 0) {
- fillAlpha += 255*(-1*(v_rel/speedBuff));
- }
- fillAlpha = (int)(fmin(fillAlpha, 255));
- }
-
- float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35;
- x = std::clamp(x, 0.f, s->fb_w - sz / 2);
- y = std::fmin(s->fb_h - sz * .6, y);
- draw_chevron(s, x, y, sz, nvgRGBA(201, 34, 49, fillAlpha), COLOR_YELLOW);
-}
-
-static void ui_draw_line(UIState *s, const line_vertices_data &vd, NVGcolor *color, NVGpaint *paint) {
- if (vd.cnt == 0) return;
-
- const vertex_data *v = &vd.v[0];
- nvgBeginPath(s->vg);
- nvgMoveTo(s->vg, v[0].x, v[0].y);
- for (int i = 1; i < vd.cnt; i++) {
- nvgLineTo(s->vg, v[i].x, v[i].y);
- }
- nvgClosePath(s->vg);
- if (color) {
- nvgFillColor(s->vg, *color);
- } else if (paint) {
- nvgFillPaint(s->vg, *paint);
- }
- nvgFill(s->vg);
-}
-
-static void ui_draw_vision_lane_lines(UIState *s) {
- const UIScene &scene = s->scene;
- NVGpaint track_bg;
- if (!scene.end_to_end) {
- // paint lanelines
- for (int i = 0; i < std::size(scene.lane_line_vertices); i++) {
- NVGcolor color = nvgRGBAf(1.0, 1.0, 1.0, scene.lane_line_probs[i]);
- ui_draw_line(s, scene.lane_line_vertices[i], &color, nullptr);
- }
-
- // paint road edges
- for (int i = 0; i < std::size(scene.road_edge_vertices); i++) {
- NVGcolor color = nvgRGBAf(1.0, 0.0, 0.0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0));
- ui_draw_line(s, scene.road_edge_vertices[i], &color, nullptr);
- }
- track_bg = nvgLinearGradient(s->vg, s->fb_w, s->fb_h, s->fb_w, s->fb_h * .4,
- COLOR_WHITE, COLOR_WHITE_ALPHA(0));
- } else {
- track_bg = nvgLinearGradient(s->vg, s->fb_w, s->fb_h, s->fb_w, s->fb_h * .4,
- COLOR_RED, COLOR_RED_ALPHA(0));
- }
- // paint path
- ui_draw_line(s, scene.track_vertices, nullptr, &track_bg);
-}
-
-// Draw all world space objects.
-static void ui_draw_world(UIState *s) {
- nvgScissor(s->vg, 0, 0, s->fb_w, s->fb_h);
-
- // Draw lane edges and vision/mpc tracks
- ui_draw_vision_lane_lines(s);
-
- // Draw lead indicators if openpilot is handling longitudinal
- if (s->scene.longitudinal_control) {
- auto lead_one = (*s->sm)["radarState"].getRadarState().getLeadOne();
- auto lead_two = (*s->sm)["radarState"].getRadarState().getLeadTwo();
- if (lead_one.getStatus()) {
- draw_lead(s, lead_one, s->scene.lead_vertices[0]);
- }
- if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) {
- draw_lead(s, lead_two, s->scene.lead_vertices[1]);
- }
- }
- nvgResetScissor(s->vg);
-}
-
-static void ui_draw_vision_maxspeed(UIState *s) {
- const int SET_SPEED_NA = 255;
- float maxspeed = (*s->sm)["controlsState"].getControlsState().getVCruise();
- const bool is_cruise_set = maxspeed != 0 && maxspeed != SET_SPEED_NA;
- if (is_cruise_set && !s->scene.is_metric) { maxspeed *= KM_TO_MILE; }
-
- const Rect rect = {bdr_s * 2, int(bdr_s * 1.5), 184, 202};
- ui_fill_rect(s->vg, rect, COLOR_BLACK_ALPHA(100), 30.);
- ui_draw_rect(s->vg, rect, COLOR_WHITE_ALPHA(100), 10, 20.);
-
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- ui_draw_text(s, rect.centerX(), 118, "MAX", 26 * 2.5, COLOR_WHITE_ALPHA(is_cruise_set ? 200 : 100), "sans-regular");
- if (is_cruise_set) {
- const std::string maxspeed_str = std::to_string((int)std::nearbyint(maxspeed));
- ui_draw_text(s, rect.centerX(), 212, maxspeed_str.c_str(), 48 * 2.5, COLOR_WHITE, "sans-bold");
- } else {
- ui_draw_text(s, rect.centerX(), 212, "N/A", 42 * 2.5, COLOR_WHITE_ALPHA(100), "sans-semibold");
- }
-}
-
-static void ui_draw_vision_speed(UIState *s) {
- const float speed = std::max(0.0, (*s->sm)["carState"].getCarState().getVEgo() * (s->scene.is_metric ? MS_TO_KPH : MS_TO_MPH));
- const std::string speed_str = std::to_string((int)std::nearbyint(speed));
- nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE);
- ui_draw_text(s, s->fb_w/2, 210, speed_str.c_str(), 96 * 2.5, COLOR_WHITE, "sans-bold");
- ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular");
-}
-
-static void ui_draw_vision_event(UIState *s) {
- if (s->scene.engageable) {
- // draw steering wheel
- const int radius = 96;
- const int center_x = s->fb_w - radius - bdr_s * 2;
- const int center_y = radius + (bdr_s * 1.5);
- const QColor &color = bg_colors[s->status];
- NVGcolor nvg_color = nvgRGBA(color.red(), color.green(), color.blue(), color.alpha());
- ui_draw_circle_image(s, center_x, center_y, radius, "wheel", nvg_color, 1.0f);
- }
-}
-
-static void ui_draw_vision_face(UIState *s) {
- const int radius = 96;
- const int center_x = radius + (bdr_s * 2);
- const int center_y = s->fb_h - footer_h / 2;
- ui_draw_circle_image(s, center_x, center_y, radius, "driver_face", s->scene.dm_active);
-}
-
-static void ui_draw_vision_header(UIState *s) {
- NVGpaint gradient = nvgLinearGradient(s->vg, 0, header_h - (header_h / 2.5), 0, header_h,
- nvgRGBAf(0, 0, 0, 0.45), nvgRGBAf(0, 0, 0, 0));
- ui_fill_rect(s->vg, {0, 0, s->fb_w , header_h}, gradient);
- ui_draw_vision_maxspeed(s);
- ui_draw_vision_speed(s);
- ui_draw_vision_event(s);
-}
-
-static void ui_draw_vision(UIState *s) {
- const UIScene *scene = &s->scene;
- // Draw augmented elements
- if (scene->world_objects_visible) {
- ui_draw_world(s);
- }
- // Set Speed, Current Speed, Status/Events
- ui_draw_vision_header(s);
- if ((*s->sm)["controlsState"].getControlsState().getAlertSize() == cereal::ControlsState::AlertSize::NONE) {
- ui_draw_vision_face(s);
- }
-}
-
-void ui_draw(UIState *s, int w, int h) {
- // Update intrinsics matrix after possible wide camera toggle change
- if (s->fb_w != w || s->fb_h != h) {
- ui_resize(s, w, h);
- }
- glEnable(GL_BLEND);
- glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
- nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f);
- ui_draw_vision(s);
- nvgEndFrame(s->vg);
- glDisable(GL_BLEND);
-}
-
-void ui_draw_image(const UIState *s, const Rect &r, const char *name, float alpha) {
- nvgBeginPath(s->vg);
- NVGpaint imgPaint = nvgImagePattern(s->vg, r.x, r.y, r.w, r.h, 0, s->images.at(name), alpha);
- nvgRect(s->vg, r.x, r.y, r.w, r.h);
- nvgFillPaint(s->vg, imgPaint);
- nvgFill(s->vg);
-}
-
-void ui_draw_rect(NVGcontext *vg, const Rect &r, NVGcolor color, int width, float radius) {
- nvgBeginPath(vg);
- radius > 0 ? nvgRoundedRect(vg, r.x, r.y, r.w, r.h, radius) : nvgRect(vg, r.x, r.y, r.w, r.h);
- nvgStrokeColor(vg, color);
- nvgStrokeWidth(vg, width);
- nvgStroke(vg);
-}
-
-static inline void fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor *color, const NVGpaint *paint, float radius) {
- nvgBeginPath(vg);
- radius > 0 ? nvgRoundedRect(vg, r.x, r.y, r.w, r.h, radius) : nvgRect(vg, r.x, r.y, r.w, r.h);
- if (color) nvgFillColor(vg, *color);
- if (paint) nvgFillPaint(vg, *paint);
- nvgFill(vg);
-}
-void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor &color, float radius) {
- fill_rect(vg, r, &color, nullptr, radius);
-}
-void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGpaint &paint, float radius) {
- fill_rect(vg, r, nullptr, &paint, radius);
-}
-
-void ui_nvg_init(UIState *s) {
- // on EON, we enable MSAA
- s->vg = Hardware::EON() ? nvgCreate(0) : nvgCreate(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG);
- assert(s->vg);
-
- // init fonts
- std::pair fonts[] = {
- {"sans-regular", "../assets/fonts/opensans_regular.ttf"},
- {"sans-semibold", "../assets/fonts/opensans_semibold.ttf"},
- {"sans-bold", "../assets/fonts/opensans_bold.ttf"},
- };
- for (auto [name, file] : fonts) {
- int font_id = nvgCreateFont(s->vg, name, file);
- assert(font_id >= 0);
- }
-
- // init images
- std::vector> images = {
- {"wheel", "../assets/img_chffr_wheel.png"},
- {"driver_face", "../assets/img_driver_face.png"},
- };
- for (auto [name, file] : images) {
- s->images[name] = nvgCreateImage(s->vg, file, 1);
- assert(s->images[name] != 0);
- }
-}
-
-void ui_resize(UIState *s, int width, int height) {
- s->fb_w = width;
- s->fb_h = height;
-
- auto intrinsic_matrix = s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix;
- float zoom = ZOOM / intrinsic_matrix.v[0];
- if (s->wide_camera) {
- zoom *= 0.5;
- }
-
- // Apply transformation such that video pixel coordinates match video
- // 1) Put (0, 0) in the middle of the video
- // 2) Apply same scaling as video
- // 3) Put (0, 0) in top left corner of video
- s->car_space_transform.reset();
- s->car_space_transform.translate(width / 2, height / 2 + y_offset)
- .scale(zoom, zoom)
- .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]);
-}
diff --git a/selfdrive/ui/paint.h b/selfdrive/ui/paint.h
deleted file mode 100644
index 4ce7cbd13..000000000
--- a/selfdrive/ui/paint.h
+++ /dev/null
@@ -1,12 +0,0 @@
-#pragma once
-
-#include "selfdrive/ui/ui.h"
-
-void ui_draw(UIState *s, int w, int h);
-void ui_draw_image(const UIState *s, const Rect &r, const char *name, float alpha);
-void ui_draw_rect(NVGcontext *vg, const Rect &r, NVGcolor color, int width, float radius = 0);
-void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGpaint &paint, float radius = 0);
-void ui_fill_rect(NVGcontext *vg, const Rect &r, const NVGcolor &color, float radius = 0);
-void ui_nvg_init(UIState *s);
-void ui_resize(UIState *s, int width, int height);
-void ui_update_params(UIState *s);
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index 7bee7f7ca..e1bfe96c8 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -112,10 +112,6 @@ void MapWindow::timerUpdate() {
update();
- if (m_map.isNull()) {
- return;
- }
-
sm->update(0);
if (sm->updated("liveLocationKalman")) {
auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman();
@@ -134,6 +130,21 @@ void MapWindow::timerUpdate() {
velocity_filter.update(velocity);
}
}
+
+ if (sm->updated("navRoute")) {
+ qWarning() << "Got new navRoute from navd. Opening map:" << allow_open;
+
+ // Only open the map on setting destination the first time
+ if (allow_open) {
+ setVisible(true); // Show map on destination set/change
+ allow_open = false;
+ }
+ }
+
+ if (m_map.isNull()) {
+ return;
+ }
+
loaded_once = loaded_once || m_map->isFullyLoaded();
if (!loaded_once) {
map_instructions->showError("Map Loading");
@@ -186,7 +197,7 @@ void MapWindow::timerUpdate() {
}
if (sm->rcv_frame("navRoute") != route_rcv_frame) {
- qWarning() << "Got new navRoute from navd";
+ qWarning() << "Updating navLayer with new route";
auto route = (*sm)["navRoute"].getNavRoute();
auto route_points = capnp_coordinate_list_to_collection(route.getCoordinates());
QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {});
@@ -196,11 +207,6 @@ void MapWindow::timerUpdate() {
m_map->updateSource("navSource", navSource);
m_map->setLayoutProperty("navLayer", "visibility", "visible");
- // Only open the map on setting destination the first time
- if (allow_open) {
- setVisible(true); // Show map on destination set/change
- allow_open = false;
- }
route_rcv_frame = sm->rcv_frame("navRoute");
}
}
diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc
index e5438f7c8..487ba5624 100644
--- a/selfdrive/ui/qt/offroad/settings.cc
+++ b/selfdrive/ui/qt/offroad/settings.cc
@@ -1,6 +1,7 @@
#include "selfdrive/ui/qt/offroad/settings.h"
#include
+#include
#include
#include
@@ -58,12 +59,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
"Use features, such as community supported hardware, from the open source community that are not maintained or supported by comma.ai and have not been confirmed to meet the standard safety model. Be extra cautious when using these features",
"../assets/offroad/icon_shell.png",
},
- {
- "UploadRaw",
- "Upload Raw Logs",
- "Upload full logs and full resolution video by default while on Wi-Fi. If not enabled, individual logs can be marked for upload at useradmin.comma.ai.",
- "../assets/offroad/icon_network.png",
- },
{
"RecordFront",
"Record and Upload Driver Camera",
diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc
index 5abcf6104..53cc96367 100644
--- a/selfdrive/ui/qt/onroad.cc
+++ b/selfdrive/ui/qt/onroad.cc
@@ -1,9 +1,10 @@
#include "selfdrive/ui/qt/onroad.h"
+#include
+
#include
#include "selfdrive/common/timing.h"
-#include "selfdrive/ui/paint.h"
#include "selfdrive/ui/qt/util.h"
#ifdef ENABLE_MAPS
#include "selfdrive/ui/qt/maps/map.h"
@@ -17,13 +18,18 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) {
stacked_layout->setStackingMode(QStackedLayout::StackAll);
main_layout->addLayout(stacked_layout);
+ QStackedLayout *road_view_layout = new QStackedLayout;
+ road_view_layout->setStackingMode(QStackedLayout::StackAll);
nvg = new NvgWindow(VISION_STREAM_RGB_BACK, this);
+ road_view_layout->addWidget(nvg);
+ hud = new OnroadHud(this);
+ road_view_layout->addWidget(hud);
QWidget * split_wrapper = new QWidget;
split = new QHBoxLayout(split_wrapper);
split->setContentsMargins(0, 0, 0, 0);
split->setSpacing(0);
- split->addWidget(nvg);
+ split->addLayout(road_view_layout);
stacked_layout->addWidget(split_wrapper);
@@ -48,6 +54,9 @@ void OnroadWindow::updateState(const UIState &s) {
}
alerts->updateAlert(alert, bgColor);
}
+
+ hud->updateState(s);
+
if (bg != bgColor) {
// repaint border
bg = bgColor;
@@ -91,6 +100,7 @@ void OnroadWindow::paintEvent(QPaintEvent *event) {
// ***** onroad widgets *****
+// OnroadAlerts
void OnroadAlerts::updateAlert(const Alert &a, const QColor &color) {
if (!alert.equal(a) || color != bg) {
alert = a;
@@ -150,6 +160,106 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) {
}
}
+// OnroadHud
+OnroadHud::OnroadHud(QWidget *parent) : QWidget(parent) {
+ engage_img = QPixmap("../assets/img_chffr_wheel.png").scaled(img_size, img_size, Qt::KeepAspectRatio, Qt::SmoothTransformation);
+ dm_img = QPixmap("../assets/img_driver_face.png").scaled(img_size, img_size, Qt::KeepAspectRatio, Qt::SmoothTransformation);
+
+ connect(this, &OnroadHud::valueChanged, [=] { update(); });
+}
+
+void OnroadHud::updateState(const UIState &s) {
+ const int SET_SPEED_NA = 255;
+ const SubMaster &sm = *(s.sm);
+ const auto cs = sm["controlsState"].getControlsState();
+
+ float maxspeed = cs.getVCruise();
+ bool cruise_set = maxspeed > 0 && (int)maxspeed != SET_SPEED_NA;
+ if (cruise_set && !s.scene.is_metric) {
+ maxspeed *= KM_TO_MILE;
+ }
+ QString maxspeed_str = cruise_set ? QString::number(std::nearbyint(maxspeed)) : "N/A";
+ float cur_speed = std::max(0.0, sm["carState"].getCarState().getVEgo() * (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH));
+
+ setProperty("is_cruise_set", cruise_set);
+ setProperty("speed", QString::number(std::nearbyint(cur_speed)));
+ setProperty("maxSpeed", maxspeed_str);
+ setProperty("speedUnit", s.scene.is_metric ? "km/h" : "mph");
+ setProperty("hideDM", cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE);
+ setProperty("status", s.status);
+
+ // update engageability and DM icons at 2Hz
+ if (sm.frame % (UI_FREQ / 2) == 0) {
+ setProperty("engageable", cs.getEngageable() || cs.getEnabled());
+ setProperty("dmActive", sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode());
+ }
+}
+
+void OnroadHud::paintEvent(QPaintEvent *event) {
+ QPainter p(this);
+ p.setRenderHint(QPainter::Antialiasing);
+
+ // Header gradient
+ QLinearGradient bg(0, header_h - (header_h / 2.5), 0, header_h);
+ bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45));
+ bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0));
+ p.fillRect(0, 0, width(), header_h, bg);
+
+ // max speed
+ QRect rc(bdr_s * 2, bdr_s * 1.5, 184, 202);
+ p.setPen(QPen(QColor(0xff, 0xff, 0xff, 100), 10));
+ p.setBrush(QColor(0, 0, 0, 100));
+ p.drawRoundedRect(rc, 20, 20);
+ p.setPen(Qt::NoPen);
+
+ configFont(p, "Open Sans", 48, "Regular");
+ drawText(p, rc.center().x(), 118, "MAX", is_cruise_set ? 200 : 100);
+ if (is_cruise_set) {
+ configFont(p, "Open Sans", 88, is_cruise_set ? "Bold" : "SemiBold");
+ drawText(p, rc.center().x(), 212, maxSpeed, 255);
+ } else {
+ configFont(p, "Open Sans", 80, "SemiBold");
+ drawText(p, rc.center().x(), 212, maxSpeed, 100);
+ }
+
+ // current speed
+ configFont(p, "Open Sans", 176, "Bold");
+ drawText(p, rect().center().x(), 210, speed);
+ configFont(p, "Open Sans", 66, "Regular");
+ drawText(p, rect().center().x(), 290, speedUnit, 200);
+
+ // engage-ability icon
+ if (engageable) {
+ drawIcon(p, rect().right() - radius / 2 - bdr_s * 2, radius / 2 + int(bdr_s * 1.5),
+ engage_img, bg_colors[status], 1.0);
+ }
+
+ // dm icon
+ if (!hideDM) {
+ drawIcon(p, radius / 2 + (bdr_s * 2), rect().bottom() - footer_h / 2,
+ dm_img, QColor(0, 0, 0, 70), dmActive ? 1.0 : 0.2);
+ }
+}
+
+void OnroadHud::drawText(QPainter &p, int x, int y, const QString &text, int alpha) {
+ QFontMetrics fm(p.font());
+ QRect init_rect = fm.boundingRect(text);
+ QRect real_rect = fm.boundingRect(init_rect, 0, text);
+ real_rect.moveCenter({x, y - real_rect.height() / 2});
+
+ p.setPen(QColor(0xff, 0xff, 0xff, alpha));
+ p.drawText(real_rect.x(), real_rect.bottom(), text);
+}
+
+void OnroadHud::drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity) {
+ p.setPen(Qt::NoPen);
+ p.setBrush(bg);
+ p.drawEllipse(x - radius / 2, y - radius / 2, radius, radius);
+ p.setOpacity(opacity);
+ p.drawPixmap(x - img_size / 2, y - img_size / 2, img);
+}
+
+// NvgWindow
void NvgWindow::initializeGL() {
CameraViewWidget::initializeGL();
qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION));
@@ -157,14 +267,105 @@ void NvgWindow::initializeGL() {
qInfo() << "OpenGL renderer:" << QString((const char*)glGetString(GL_RENDERER));
qInfo() << "OpenGL language version:" << QString((const char*)glGetString(GL_SHADING_LANGUAGE_VERSION));
- ui_nvg_init(&QUIState::ui_state);
prev_draw_t = millis_since_boot();
setBackgroundColor(bg_colors[STATUS_DISENGAGED]);
}
+void NvgWindow::updateFrameMat(int w, int h) {
+ CameraViewWidget::updateFrameMat(w, h);
+
+ UIState *s = &QUIState::ui_state;
+ s->fb_w = w;
+ s->fb_h = h;
+ auto intrinsic_matrix = s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix;
+ float zoom = ZOOM / intrinsic_matrix.v[0];
+ if (s->wide_camera) {
+ zoom *= 0.5;
+ }
+ // Apply transformation such that video pixel coordinates match video
+ // 1) Put (0, 0) in the middle of the video
+ // 2) Apply same scaling as video
+ // 3) Put (0, 0) in top left corner of video
+ s->car_space_transform.reset();
+ s->car_space_transform.translate(w / 2, h / 2 + y_offset)
+ .scale(zoom, zoom)
+ .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]);
+}
+
+void NvgWindow::drawLaneLines(QPainter &painter, const UIScene &scene) {
+ if (!scene.end_to_end) {
+ // lanelines
+ for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) {
+ painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, scene.lane_line_probs[i]));
+ painter.drawPolygon(scene.lane_line_vertices[i].v, scene.lane_line_vertices[i].cnt);
+ }
+ // road edges
+ for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) {
+ painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0)));
+ painter.drawPolygon(scene.road_edge_vertices[i].v, scene.road_edge_vertices[i].cnt);
+ }
+ }
+ // paint path
+ QLinearGradient bg(0, height(), 0, height() / 4);
+ bg.setColorAt(0, scene.end_to_end ? redColor() : QColor(255, 255, 255));
+ bg.setColorAt(1, scene.end_to_end ? redColor(0) : QColor(255, 255, 255, 0));
+ painter.setBrush(bg);
+ painter.drawPolygon(scene.track_vertices.v, scene.track_vertices.cnt);
+}
+
+void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) {
+ const float speedBuff = 10.;
+ const float leadBuff = 40.;
+ const float d_rel = lead_data.getX()[0];
+ const float v_rel = lead_data.getV()[0];
+
+ float fillAlpha = 0;
+ if (d_rel < leadBuff) {
+ fillAlpha = 255 * (1.0 - (d_rel / leadBuff));
+ if (v_rel < 0) {
+ fillAlpha += 255 * (-1 * (v_rel / speedBuff));
+ }
+ fillAlpha = (int)(fmin(fillAlpha, 255));
+ }
+
+ float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35;
+ float x = std::clamp((float)vd.x(), 0.f, width() - sz / 2);
+ float y = std::fmin(height() - sz * .6, (float)vd.y());
+
+ float g_xo = sz / 5;
+ float g_yo = sz / 10;
+
+ QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_xo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}};
+ painter.setBrush(QColor(218, 202, 37, 255));
+ painter.drawPolygon(glow, std::size(glow));
+
+ // chevron
+ QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}};
+ painter.setBrush(redColor(fillAlpha));
+ painter.drawPolygon(chevron, std::size(chevron));
+}
+
void NvgWindow::paintGL() {
CameraViewWidget::paintGL();
- ui_draw(&QUIState::ui_state, width(), height());
+
+ UIState *s = &QUIState::ui_state;
+ if (s->scene.world_objects_visible) {
+ QPainter painter(this);
+ painter.setRenderHint(QPainter::Antialiasing);
+ painter.setPen(Qt::NoPen);
+
+ drawLaneLines(painter, s->scene);
+
+ if (s->scene.longitudinal_control) {
+ auto leads = (*s->sm)["modelV2"].getModelV2().getLeadsV3();
+ if (leads[0].getProb() > .5) {
+ drawLead(painter, leads[0], s->scene.lead_vertices[0]);
+ }
+ if (leads[1].getProb() > .5 && (std::abs(leads[1].getX()[0] - leads[0].getX()[0]) > 3.0)) {
+ drawLead(painter, leads[1], s->scene.lead_vertices[1]);
+ }
+ }
+ }
double cur_draw_t = millis_since_boot();
double dt = cur_draw_t - prev_draw_t;
@@ -177,6 +378,7 @@ void NvgWindow::paintGL() {
void NvgWindow::showEvent(QShowEvent *event) {
CameraViewWidget::showEvent(event);
+
ui_update_params(&QUIState::ui_state);
prev_draw_t = millis_since_boot();
}
diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h
index 1076ed01e..37460c8ba 100644
--- a/selfdrive/ui/qt/onroad.h
+++ b/selfdrive/ui/qt/onroad.h
@@ -9,6 +9,43 @@
// ***** onroad widgets *****
+class OnroadHud : public QWidget {
+ Q_OBJECT
+ Q_PROPERTY(QString speed MEMBER speed NOTIFY valueChanged);
+ Q_PROPERTY(QString speedUnit MEMBER speedUnit NOTIFY valueChanged);
+ Q_PROPERTY(QString maxSpeed MEMBER maxSpeed NOTIFY valueChanged);
+ Q_PROPERTY(bool is_cruise_set MEMBER is_cruise_set NOTIFY valueChanged);
+ Q_PROPERTY(bool engageable MEMBER engageable NOTIFY valueChanged);
+ Q_PROPERTY(bool dmActive MEMBER dmActive NOTIFY valueChanged);
+ Q_PROPERTY(bool hideDM MEMBER hideDM NOTIFY valueChanged);
+ Q_PROPERTY(int status MEMBER status NOTIFY valueChanged);
+
+public:
+ explicit OnroadHud(QWidget *parent);
+ void updateState(const UIState &s);
+
+private:
+ void drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity);
+ void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255);
+ void paintEvent(QPaintEvent *event) override;
+
+ QPixmap engage_img;
+ QPixmap dm_img;
+ const int radius = 192;
+ const int img_size = (radius / 2) * 1.5;
+ QString speed;
+ QString speedUnit;
+ QString maxSpeed;
+ bool is_cruise_set = false;
+ bool engageable = false;
+ bool dmActive = false;
+ bool hideDM = false;
+ int status = STATUS_DISENGAGED;
+
+signals:
+ void valueChanged();
+};
+
class OnroadAlerts : public QWidget {
Q_OBJECT
@@ -35,6 +72,10 @@ protected:
void paintGL() override;
void initializeGL() override;
void showEvent(QShowEvent *event) override;
+ void updateFrameMat(int w, int h) override;
+ void drawLaneLines(QPainter &painter, const UIScene &scene);
+ void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd);
+ inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); }
double prev_draw_t = 0;
};
@@ -49,6 +90,7 @@ public:
private:
void paintEvent(QPaintEvent *event);
void mousePressEvent(QMouseEvent* e) override;
+ OnroadHud *hud;
OnroadAlerts *alerts;
NvgWindow *nvg;
QColor bg = bg_colors[STATUS_DISENGAGED];
diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc
index 1661c6c5d..b1defb008 100644
--- a/selfdrive/ui/qt/util.cc
+++ b/selfdrive/ui/qt/util.cc
@@ -85,6 +85,7 @@ void setQtSurfaceFormat() {
#else
fmt.setRenderableType(QSurfaceFormat::OpenGLES);
#endif
+ fmt.setSamples(16);
QSurfaceFormat::setDefaultFormat(fmt);
}
diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc
index f09b1b179..4203d146e 100644
--- a/selfdrive/ui/qt/widgets/cameraview.cc
+++ b/selfdrive/ui/qt/widgets/cameraview.cc
@@ -1,12 +1,18 @@
#include "selfdrive/ui/qt/widgets/cameraview.h"
+#ifdef __APPLE__
+#include
+#else
+#include
+#endif
+
#include
#include
namespace {
const char frame_vertex_shader[] =
-#ifdef NANOVG_GL3_IMPLEMENTATION
+#ifdef __APPLE__
"#version 150 core\n"
#else
"#version 300 es\n"
@@ -21,7 +27,7 @@ const char frame_vertex_shader[] =
"}\n";
const char frame_fragment_shader[] =
-#ifdef NANOVG_GL3_IMPLEMENTATION
+#ifdef __APPLE__
"#version 150 core\n"
#else
"#version 300 es\n"
diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h
index 146528cd2..4cfba3c6f 100644
--- a/selfdrive/ui/qt/widgets/cameraview.h
+++ b/selfdrive/ui/qt/widgets/cameraview.h
@@ -7,6 +7,7 @@
#include
#include
#include "cereal/visionipc/visionipc_client.h"
+#include "selfdrive/camerad/cameras/camera_common.h"
#include "selfdrive/common/visionimg.h"
#include "selfdrive/ui/ui.h"
@@ -32,7 +33,7 @@ protected:
void showEvent(QShowEvent *event) override;
void hideEvent(QHideEvent *event) override;
void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); }
- void updateFrameMat(int w, int h);
+ virtual void updateFrameMat(int w, int h);
void vipcThread();
bool zoomed_view;
diff --git a/selfdrive/ui/soundd/sound.cc b/selfdrive/ui/soundd/sound.cc
index 766c37a51..4e88f41b1 100644
--- a/selfdrive/ui/soundd/sound.cc
+++ b/selfdrive/ui/soundd/sound.cc
@@ -1,5 +1,7 @@
#include "selfdrive/ui/soundd/sound.h"
+#include
+
#include
#include
#include
diff --git a/selfdrive/ui/tests/test_soundd.py b/selfdrive/ui/tests/test_soundd.py
index 363dda657..5414c5e38 100755
--- a/selfdrive/ui/tests/test_soundd.py
+++ b/selfdrive/ui/tests/test_soundd.py
@@ -19,7 +19,7 @@ SOUNDS = {
AudibleAlert.disengage: 230,
AudibleAlert.refuse: 189,
AudibleAlert.prompt: 230,
- AudibleAlert.promptRepeat: 468,
+ AudibleAlert.promptRepeat: 520,
AudibleAlert.promptDistracted: 187,
AudibleAlert.warningSoft: 499,
AudibleAlert.warningImmediate: 496,
@@ -66,9 +66,9 @@ class TestSoundd(unittest.TestCase):
pm.send('controlsState', msg)
time.sleep(DT_CTRL)
- tolerance = expected_writes / 10
+ tolerance = expected_writes / 8
actual_writes = get_total_writes() - start_writes
- #print(f" expected {expected_writes} writes, got {actual_writes}")
+ print(f" expected {expected_writes} writes, got {actual_writes}")
assert abs(expected_writes - actual_writes) <= tolerance, f"{alert_sounds[sound]}: expected {expected_writes} writes, got {actual_writes}"
if __name__ == "__main__":
diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc
index 7a4de0658..53d73c104 100644
--- a/selfdrive/ui/ui.cc
+++ b/selfdrive/ui/ui.cc
@@ -1,11 +1,11 @@
#include "selfdrive/ui/ui.h"
-#include
-
#include
#include
-#include
+#include "common/transformations/orientation.hpp"
+#include "selfdrive/common/params.h"
+#include "selfdrive/common/swaglog.h"
#include "selfdrive/common/util.h"
#include "selfdrive/common/watchdog.h"
#include "selfdrive/hardware/hw.h"
@@ -14,10 +14,9 @@
#define BACKLIGHT_TS 10.00
#define BACKLIGHT_OFFROAD 50
-
// Projects a point in car to space to the corresponding point in full frame
// image space.
-static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, vertex_data *out) {
+static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, QPointF *out) {
const float margin = 500.0f;
const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin};
@@ -28,8 +27,7 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y,
// Project.
QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]});
if (clip_region.contains(point)) {
- out->x = point.x();
- out->y = point.y();
+ *out = point;
return true;
}
return false;
@@ -57,7 +55,7 @@ static void update_leads(UIState *s, const cereal::RadarState::Reader &radar_sta
static void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTData::Reader &line,
float y_off, float z_off, line_vertices_data *pvd, int max_idx) {
const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ();
- vertex_data *v = &pvd->v[0];
+ QPointF *v = &pvd->v[0];
for (int i = 0; i <= max_idx; i++) {
v += calib_frame_to_full_frame(s, line_x[i], line_y[i] - y_off, line_z[i] + z_off, v);
}
@@ -110,16 +108,10 @@ static void update_state(UIState *s) {
UIScene &scene = s->scene;
s->running_time = 1e-9 * (nanos_since_boot() - sm["deviceState"].getDeviceState().getStartedMonoTime());
- // update engageability and DM icons at 2Hz
- if (sm.frame % (UI_FREQ / 2) == 0) {
- auto cs = sm["controlsState"].getControlsState();
- scene.engageable = cs.getEngageable() || cs.getEnabled();
- scene.dm_active = sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode();
- }
- if (sm.updated("modelV2") && s->vg) {
+ if (sm.updated("modelV2")) {
update_model(s, sm["modelV2"].getModelV2());
}
- if (sm.updated("radarState") && s->vg) {
+ if (sm.updated("radarState")) {
std::optional line;
if (sm.rcv_frame("modelV2") > 0) {
line = sm["modelV2"].getModelV2().getPosition();
diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h
index 4c94a8303..3b3d11b67 100644
--- a/selfdrive/ui/ui.h
+++ b/selfdrive/ui/ui.h
@@ -1,31 +1,17 @@
#pragma once
-#include