diff --git a/Pipfile b/Pipfile index 3fc26b363b..fdba040198 100644 --- a/Pipfile +++ b/Pipfile @@ -57,6 +57,7 @@ pycapnp = "==1.1.0" pycryptodome = "*" PyJWT = "*" pylint = "*" +pyopencl = "*" pyserial = "*" python-dateutil = "*" PyYAML = "*" diff --git a/Pipfile.lock b/Pipfile.lock index a1aaeb8766..81dc794b53 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "c0f1a46ca2ccdc208a392c5ce78d9d928f82d40afd46a33da7b99b895798fce2" + "sha256": "6b23dd7136502655f1c18c37d55db33d77f1b85e0572aed69869401df936003a" }, "pipfile-spec": 6, "requires": { @@ -16,13 +16,20 @@ ] }, "default": { + "appdirs": { + "hashes": [ + "sha256:7d5d0167b2b1ba821647616af46a749d1c653740dd0d2415100fe26e27afdf41", + "sha256:a841dacd6b99318a741b166adb07e19ee71a274450e68237b4650ca1055ab128" + ], + "version": "==1.4.4" + }, "astroid": { "hashes": [ - "sha256:11f7356737b624c42e21e71fe85eea6875cb94c03c82ac76bd535a0ff10b0f25", - "sha256:abc423a1e85bc1553954a14f2053473d2b7f8baf32eae62a328be24f436b5107" + "sha256:5939cf55de24b92bda00345d4d0659d01b3c7dafb5055165c330bc7c568ba273", + "sha256:776ca0b748b4ad69c00bfe0fff38fa2d21c338e12c84aa9715ee0d473c422778" ], "markers": "python_version ~= '3.6'", - "version": "==2.8.5" + "version": "==2.9.0" }, "atomicwrites": { "hashes": [ @@ -141,11 +148,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:e019de665e2bcf9c2b64e2e5aa025fa991da8720daa3c1138cadd2fd1856aed0", - "sha256:f7af805c321bfa1ce6714c51f254e0d5bb5e5834039bc17db7ebe3a4cec9492b" + "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0", + "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405" ], "markers": "python_version >= '3'", - "version": "==2.0.7" + "version": "==2.0.8" }, "click": { "hashes": [ @@ -167,29 +174,30 @@ }, "cryptography": { "hashes": [ - "sha256:07bb7fbfb5de0980590ddfc7f13081520def06dc9ed214000ad4372fb4e3c7f6", - "sha256:18d90f4711bf63e2fb21e8c8e51ed8189438e6b35a6d996201ebd98a26abbbe6", - "sha256:1ed82abf16df40a60942a8c211251ae72858b25b7421ce2497c2eb7a1cee817c", - "sha256:22a38e96118a4ce3b97509443feace1d1011d0571fae81fc3ad35f25ba3ea999", - "sha256:2d69645f535f4b2c722cfb07a8eab916265545b3475fdb34e0be2f4ee8b0b15e", - "sha256:4a2d0e0acc20ede0f06ef7aa58546eee96d2592c00f450c9acb89c5879b61992", - "sha256:54b2605e5475944e2213258e0ab8696f4f357a31371e538ef21e8d61c843c28d", - "sha256:7075b304cd567694dc692ffc9747f3e9cb393cc4aa4fb7b9f3abd6f5c4e43588", - "sha256:7b7ceeff114c31f285528ba8b390d3e9cfa2da17b56f11d366769a807f17cbaa", - "sha256:7eba2cebca600a7806b893cb1d541a6e910afa87e97acf2021a22b32da1df52d", - "sha256:928185a6d1ccdb816e883f56ebe92e975a262d31cc536429041921f8cb5a62fd", - "sha256:9933f28f70d0517686bd7de36166dda42094eac49415459d9bdf5e7df3e0086d", - "sha256:a688ebcd08250eab5bb5bca318cc05a8c66de5e4171a65ca51db6bd753ff8953", - "sha256:abb5a361d2585bb95012a19ed9b2c8f412c5d723a9836418fab7aaa0243e67d2", - "sha256:c10c797ac89c746e488d2ee92bd4abd593615694ee17b2500578b63cad6b93a8", - "sha256:ced40344e811d6abba00295ced98c01aecf0c2de39481792d87af4fa58b7b4d6", - "sha256:d57e0cdc1b44b6cdf8af1d01807db06886f10177469312fbde8f44ccbb284bc9", - "sha256:d99915d6ab265c22873f1b4d6ea5ef462ef797b4140be4c9d8b179915e0985c6", - "sha256:eb80e8a1f91e4b7ef8b33041591e6d89b2b8e122d787e87eeb2b08da71bb16ad", - "sha256:ebeddd119f526bcf323a89f853afb12e225902a24d29b55fe18dd6fcb2838a76" - ], - "index": "pypi", - "version": "==35.0.0" + "sha256:2049f8b87f449fc6190350de443ee0c1dd631f2ce4fa99efad2984de81031681", + "sha256:231c4a69b11f6af79c1495a0e5a85909686ea8db946935224b7825cfb53827ed", + "sha256:24469d9d33217ffd0ce4582dfcf2a76671af115663a95328f63c99ec7ece61a4", + "sha256:2deab5ec05d83ddcf9b0916319674d3dae88b0e7ee18f8962642d3cde0496568", + "sha256:494106e9cd945c2cadfce5374fa44c94cfadf01d4566a3b13bb487d2e6c7959e", + "sha256:4c702855cd3174666ef0d2d13dcc879090aa9c6c38f5578896407a7028f75b9f", + "sha256:52f769ecb4ef39865719aedc67b4b7eae167bafa48dbc2a26dd36fa56460507f", + "sha256:5c49c9e8fb26a567a2b3fa0343c89f5d325447956cc2fc7231c943b29a973712", + "sha256:684993ff6f67000a56454b41bdc7e015429732d65a52d06385b6e9de6181c71e", + "sha256:6fbbbb8aab4053fa018984bb0e95a16faeb051dd8cca15add2a27e267ba02b58", + "sha256:8982c19bb90a4fa2aad3d635c6d71814e38b643649b4000a8419f8691f20ac44", + "sha256:9511416e85e449fe1de73f7f99b21b3aa04fba4c4d335d30c486ba3756e3a2a6", + "sha256:97199a13b772e74cdcdb03760c32109c808aff7cd49c29e9cf4b7754bb725d1d", + "sha256:a776bae1629c8d7198396fd93ec0265f8dd2341c553dc32b976168aaf0e6a636", + "sha256:aa94d617a4cd4cdf4af9b5af65100c036bce22280ebb15d8b5262e8273ebc6ba", + "sha256:b17d83b3d1610e571fedac21b2eb36b816654d6f7496004d6a0d32f99d1d8120", + "sha256:d73e3a96c38173e0aa5646c31bf8473bc3564837977dd480f5cbeacf1d7ef3a3", + "sha256:d91bc9f535599bed58f6d2e21a2724cb0c3895bf41c6403fe881391d29096f1d", + "sha256:ef216d13ac8d24d9cd851776662f75f8d29c9f2d05cdcc2d34a18d32463a9b0b", + "sha256:f6a5a85beb33e57998dc605b9dbe7deaa806385fdf5c4810fb849fcd04640c81", + "sha256:f92556f94e476c1b616e6daec5f7ddded2c082efa7cee7f31c7aeda615906ed8" + ], + "index": "pypi", + "version": "==36.0.0" }, "cython": { "hashes": [ @@ -759,11 +767,23 @@ }, "pylint": { "hashes": [ - "sha256:0f358e221c45cbd4dad2a1e4b883e75d28acdcccd29d40c76eb72b307269b126", - "sha256:2c9843fff1a88ca0ad98a256806c82c5a8f86086e7ccbdb93297d86c3f90c436" + "sha256:4f4a52b132c05b49094b28e109febcec6bfb7bc6961c7485a5ad0a0f961df289", + "sha256:b4b5a7b6d04e914a11c198c816042af1fb2d3cda29bb0c98a9c637010da2a5c5" + ], + "index": "pypi", + "version": "==2.12.1" + }, + "pyopencl": { + "hashes": [ + "sha256:05ccbdc341f64f448bfdff173d1b1e79887129cb6c147605628bbd2e56bc3929", + "sha256:0e705b47733d1055c4d8f7478907222e5881519a0dbadd1bf288baebfc024999", + "sha256:51425e65ec49c738eefe21b1eeb1f39245b01cc0ddfd495fbe1f8df33dbc6c9e", + "sha256:59f9824426d823b544717cc25dee221e1a5c5143143efb8d94034cf4ef562913", + "sha256:662899ca2fb74f2d14c2d7ac0560d3cac07e6b0847a245694bb86a27a4d350ca", + "sha256:99e26fde9e5c418878a5a4a685b8ebca118f423bb09f33e7e24cfd8ef94aee30" ], "index": "pypi", - "version": "==2.11.1" + "version": "==2021.2.9" }, "pyserial": { "hashes": [ @@ -781,6 +801,13 @@ "index": "pypi", "version": "==2.8.2" }, + "pytools": { + "hashes": [ + "sha256:db6cf83c9ba0a165d545029e2301621486d1e9ef295684072e5cd75316a13755" + ], + "markers": "python_version ~= '3.6'", + "version": "==2021.2.9" + }, "pyyaml": { "hashes": [ "sha256:0283c35a6a9fbf047493e3a0ce8d79ef5030852c51e9d911a27badfde0605293", @@ -883,19 +910,19 @@ }, "scons": { "hashes": [ - "sha256:663f819e744ddadcdf4f46b03289a7210313b86041efe1b9c8dde81dba437b72", - "sha256:691893b63f38ad14295f5104661d55cb738ec6514421c6261323351c25432b0a" + "sha256:8c13911a2aa40552553488f7d625af4c0768fc8cdedab4a858d8ce42c8c3664d", + "sha256:d47081587e3675cc168f1f54f0d74a69b328a2fc90ec4feb85f728677419b879" ], "index": "pypi", - "version": "==4.2.0" + "version": "==4.3.0" }, "sentry-sdk": { "hashes": [ - "sha256:b9844751e40710e84a457c5bc29b21c383ccb2b63d76eeaad72f7f1c808c8828", - "sha256:c091cc7115ff25fe3a0e410dbecd7a996f81a3f6137d2272daef32d6c3cfa6dc" + "sha256:0db297ab32e095705c20f742c3a5dac62fe15c4318681884053d0898e5abb2f6", + "sha256:789a11a87ca02491896e121efdd64e8fd93327b69e8f2f7d42f03e2569648e88" ], "index": "pypi", - "version": "==1.4.3" + "version": "==1.5.0" }, "setproctitle": { "hashes": [ @@ -1187,11 +1214,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:e019de665e2bcf9c2b64e2e5aa025fa991da8720daa3c1138cadd2fd1856aed0", - "sha256:f7af805c321bfa1ce6714c51f254e0d5bb5e5834039bc17db7ebe3a4cec9492b" + "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0", + "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405" ], "markers": "python_version >= '3'", - "version": "==2.0.7" + "version": "==2.0.8" }, "control": { "hashes": [ @@ -1255,29 +1282,30 @@ }, "cryptography": { "hashes": [ - "sha256:07bb7fbfb5de0980590ddfc7f13081520def06dc9ed214000ad4372fb4e3c7f6", - "sha256:18d90f4711bf63e2fb21e8c8e51ed8189438e6b35a6d996201ebd98a26abbbe6", - "sha256:1ed82abf16df40a60942a8c211251ae72858b25b7421ce2497c2eb7a1cee817c", - "sha256:22a38e96118a4ce3b97509443feace1d1011d0571fae81fc3ad35f25ba3ea999", - "sha256:2d69645f535f4b2c722cfb07a8eab916265545b3475fdb34e0be2f4ee8b0b15e", - "sha256:4a2d0e0acc20ede0f06ef7aa58546eee96d2592c00f450c9acb89c5879b61992", - "sha256:54b2605e5475944e2213258e0ab8696f4f357a31371e538ef21e8d61c843c28d", - "sha256:7075b304cd567694dc692ffc9747f3e9cb393cc4aa4fb7b9f3abd6f5c4e43588", - "sha256:7b7ceeff114c31f285528ba8b390d3e9cfa2da17b56f11d366769a807f17cbaa", - "sha256:7eba2cebca600a7806b893cb1d541a6e910afa87e97acf2021a22b32da1df52d", - "sha256:928185a6d1ccdb816e883f56ebe92e975a262d31cc536429041921f8cb5a62fd", - "sha256:9933f28f70d0517686bd7de36166dda42094eac49415459d9bdf5e7df3e0086d", - "sha256:a688ebcd08250eab5bb5bca318cc05a8c66de5e4171a65ca51db6bd753ff8953", - "sha256:abb5a361d2585bb95012a19ed9b2c8f412c5d723a9836418fab7aaa0243e67d2", - "sha256:c10c797ac89c746e488d2ee92bd4abd593615694ee17b2500578b63cad6b93a8", - "sha256:ced40344e811d6abba00295ced98c01aecf0c2de39481792d87af4fa58b7b4d6", - "sha256:d57e0cdc1b44b6cdf8af1d01807db06886f10177469312fbde8f44ccbb284bc9", - "sha256:d99915d6ab265c22873f1b4d6ea5ef462ef797b4140be4c9d8b179915e0985c6", - "sha256:eb80e8a1f91e4b7ef8b33041591e6d89b2b8e122d787e87eeb2b08da71bb16ad", - "sha256:ebeddd119f526bcf323a89f853afb12e225902a24d29b55fe18dd6fcb2838a76" - ], - "index": "pypi", - "version": "==35.0.0" + "sha256:2049f8b87f449fc6190350de443ee0c1dd631f2ce4fa99efad2984de81031681", + "sha256:231c4a69b11f6af79c1495a0e5a85909686ea8db946935224b7825cfb53827ed", + "sha256:24469d9d33217ffd0ce4582dfcf2a76671af115663a95328f63c99ec7ece61a4", + "sha256:2deab5ec05d83ddcf9b0916319674d3dae88b0e7ee18f8962642d3cde0496568", + "sha256:494106e9cd945c2cadfce5374fa44c94cfadf01d4566a3b13bb487d2e6c7959e", + "sha256:4c702855cd3174666ef0d2d13dcc879090aa9c6c38f5578896407a7028f75b9f", + "sha256:52f769ecb4ef39865719aedc67b4b7eae167bafa48dbc2a26dd36fa56460507f", + "sha256:5c49c9e8fb26a567a2b3fa0343c89f5d325447956cc2fc7231c943b29a973712", + "sha256:684993ff6f67000a56454b41bdc7e015429732d65a52d06385b6e9de6181c71e", + "sha256:6fbbbb8aab4053fa018984bb0e95a16faeb051dd8cca15add2a27e267ba02b58", + "sha256:8982c19bb90a4fa2aad3d635c6d71814e38b643649b4000a8419f8691f20ac44", + "sha256:9511416e85e449fe1de73f7f99b21b3aa04fba4c4d335d30c486ba3756e3a2a6", + "sha256:97199a13b772e74cdcdb03760c32109c808aff7cd49c29e9cf4b7754bb725d1d", + "sha256:a776bae1629c8d7198396fd93ec0265f8dd2341c553dc32b976168aaf0e6a636", + "sha256:aa94d617a4cd4cdf4af9b5af65100c036bce22280ebb15d8b5262e8273ebc6ba", + "sha256:b17d83b3d1610e571fedac21b2eb36b816654d6f7496004d6a0d32f99d1d8120", + "sha256:d73e3a96c38173e0aa5646c31bf8473bc3564837977dd480f5cbeacf1d7ef3a3", + "sha256:d91bc9f535599bed58f6d2e21a2724cb0c3895bf41c6403fe881391d29096f1d", + "sha256:ef216d13ac8d24d9cd851776662f75f8d29c9f2d05cdcc2d34a18d32463a9b0b", + "sha256:f6a5a85beb33e57998dc605b9dbe7deaa806385fdf5c4810fb849fcd04640c81", + "sha256:f92556f94e476c1b616e6daec5f7ddded2c082efa7cee7f31c7aeda615906ed8" + ], + "index": "pypi", + "version": "==36.0.0" }, "cycler": { "hashes": [ @@ -1343,11 +1371,11 @@ }, "fonttools": { "hashes": [ - "sha256:68071406009e7ef6a5fdcd85d95975cd6963867bb226f2b786bfffe15d1959ef", - "sha256:8c8f84131bf04f3b1dcf99b9763cec35c347164ab6ad006e18d2f99fcab05529" + "sha256:dca694331af74c8ad47acc5171e57f6b78fac5692bf050f2ab572964577ac0dd", + "sha256:eff1da7ea274c54cb8842853005a139f711646cbf6f1bcfb6c9b86a627f35ff0" ], "markers": "python_version >= '3.7'", - "version": "==4.28.1" + "version": "==4.28.2" }, "hexdump": { "hashes": [ @@ -1358,19 +1386,19 @@ }, "hypothesis": { "hashes": [ - "sha256:8f7318839b64bae1410704933fe01f3db5f80f20f2ba8d4ea3520443ae3a001d", - "sha256:f1627022f75306c653115fbd169ba6a4322804f60533a7b46625fd0eecba43d5" + "sha256:92005826894782cc57c47b98debe1bc889b716f0774e60f83536f14360a9199e", + "sha256:c4943d159f299a96b1c23277c4bcf0759a757888b67a6d73e9c70d853024aa15" ], "index": "pypi", - "version": "==6.24.5" + "version": "==6.27.2" }, "identify": { "hashes": [ - "sha256:4f85f9bd8e6e5e2d61b2f8de5ff5313d8a1cfac4c88822d74406de45ad10bd82", - "sha256:8cb609a671d2f861ae7fe583711a43fd2faab0c892f39cbc4568b0c51b354238" + "sha256:a33ae873287e81651c7800ca309dc1f84679b763c9c8b30680e16fbfa82f0107", + "sha256:eba31ca80258de6bb51453084bff4a923187cd2193b9c13710f2516ab30732cc" ], "markers": "python_full_version >= '3.6.1'", - "version": "==2.3.6" + "version": "==2.4.0" }, "idna": { "hashes": [ @@ -1682,47 +1710,47 @@ }, "opencv-python-headless": { "hashes": [ - "sha256:014e4a892f67043610521e673883da5ad98a6e61356a609c6502b9d22144f2f1", - "sha256:01a6411eb9eecf58db3a50fa761f0527bdd2b23b884b3bea44eb57e6d06e4767", - "sha256:067e4736cdc70712f43c064bfe53ba80492c20479ad3290849337f948572c392", - "sha256:09b21c48144a9dd82e435d66ccd834f3a391a2cd2b69f787aabbc7cd3576f2f1", - "sha256:113b8ce88f337ab3a1ee670b8c5afc3fbf0d8aafec7b2ee897ad5efd9926ce90", - "sha256:1162de92301d0d13642afe8e163593982d3159ef21eba95a56ba3f5ca8024861", - "sha256:1799ae397677bd3a68aff4eb4f5c122baf3ee73a26fe67391e0d618bd2b7d046", - "sha256:1e0498bc4a39d887e84801b82df5cc943a5ae4b596511da7e69df64b263f293b", - "sha256:27b9118b342dc464590ed233c7f468c8cb68ee0e5d9734d9b67fb0bc1b10abd6", - "sha256:32e1f478457adeea4e1a3d6baf33310331740cceffd83a2f34e00a7e5bae6407", - "sha256:37e20b1a0c623c7e01381668b83342387798d0f32ff8a7d7f3dd0ef127eb10fa", - "sha256:3e32018e65eabc9aab10c7a109be5f735cf2c3934a47025b6903dcec034d460b", - "sha256:4b9fa45f1b364e7585fd4a2781565667efed49124748fb3ec2a66e40b7398338", - "sha256:526417214a1cad27e3d2d064e535868ae05f5a07a0e344d54fe81078bbacfa57", - "sha256:540fa340b29dd86670e1f91bbcd2675df032b774f77d08909faf818696524617", - "sha256:64bfc55fe60ed9ad778ec73161f0cea58e425a3f2f06293756f82880319bffa9", - "sha256:685c41fce11c83a238ab40bd57d5b39c3fc4f87a898565cd27e4a521b5902a62", - "sha256:69c55e055e81a2eead40e6f2521ad27bdd11523dc0c1de5e5aea23041a0a49f0", - "sha256:6e0757762096158b803b366c386f25f24715662465c448ed70ce65ecd93e41a2", - "sha256:79ca8b8feab911a80692fa3871c02526844f112e0f8bf4749f78383696cfaa4c", - "sha256:807ac9d48c11b3f734d9de5eda69e1c4197204bac1e6db3d3d51859832df6fc1", - "sha256:84f037ba74482548c066ad5e341f77ebcd3d08d06a540a4a1182300045b8bde8", - "sha256:989d4817a2f22a601707ea36a3664a6c26cee155ed441363d5f29d73d9aec610", - "sha256:a148f8bdb54e03b1d899acb95aa6d870d6f10eed037d9b4700912068f3952c32", - "sha256:bb29a911c4a67f9710b53b94766be1bb22926b98460790091d4620a534329736", - "sha256:c8b595731b5c519daf2bf3c074ec2080eb51e8efef198a4493f930b5e4439bb0", - "sha256:d1735296d88e16379d001c4946c1a196b87e3c3ff4da0c10762918dded02f670", - "sha256:d73972a62d3e48ee01783d4eee01152c93348c70305c91f85fb668ddcc8907ad", - "sha256:dabf703efe12ec4341efd71c1dd384542e28fc49b7d2ea02f185ef22bb75a1c8", - "sha256:fdd80034749b8b2f211c2549293b34af691e4f90bf17b320a84b09b784275cc2" - ], - "index": "pypi", - "version": "==4.5.4.58" + "sha256:01f76ca55fdb7e94c3e7eab5035376d06518155e3d88a08096e4670e57a0cee4", + "sha256:03349d9fb28703b2eaa8b1f333a6139b9849596ae4445cb1d76e2a7f5e4a2cf8", + "sha256:29f5372dabdcd571074f0539bd294a2f5a245a00b871827af6d75a971b3f657e", + "sha256:30261b87477a718993fa7cd8a44b7de986b81f8005e23110978c58fd53eb5e43", + "sha256:33e534fbc7a417a05ef6b14812fe8ff6b6b7152c22d502b61536c50ad63f80cb", + "sha256:3a8457918ecbca57669f141e7dba92e56af370876d022d75d58b94174d11e26b", + "sha256:4ef93f338b16e95418b69293924745a36f23e3d05da5ee10dde76af72b0889e3", + "sha256:5009a183be7a6817ff216dcb63ef95022c74e360011fa52aa33bc833256693b5", + "sha256:5331ce17a094bea4f8132ee23b2eaade85904199c0d04501102c9bb889302c67", + "sha256:659107ea6059b5cc953e1a32136a54998540cefea47b01dd62f1e806d10cbe39", + "sha256:6d949ec3e10cffa915ab1853e490674b8c420ba29eb0aeea72785f3e254dc7a1", + "sha256:6e7710aff3a0717f39c9ade77fdd9111203b09589539655044e73cc5d9960666", + "sha256:7b4bd3c6a0d2601b2619ae406eb85a41dff538a7c9cb2a54fb1e90631bf33887", + "sha256:7da49405e163b7a2cf891bf54a877ff3e198bc0bfe55009c1d19eb5a0153921d", + "sha256:7f8dd594ea0b0049d1614d7bfba984ebd926b2f12670edf6ae3d9d5d6ff8f8f0", + "sha256:8f8a06f75dc69631404e0846038d30ff43c9a9d60fcffe07c7a88f8b8c8c776c", + "sha256:99e678db353102119cbfe9d17aef520bacf585a3a287c4278dd1ce6fcd3be8f7", + "sha256:a1f9d41c6afe86fdbe85ac31ff9a6ce893af2d0fce68fbd1581dbbc0e4dfcb25", + "sha256:a1fd5bbf5db00432fb368c73e7d70ead13f69619b33e01dabf2906426a1a9277", + "sha256:a5461ad9789c784e75713d6c213c0e34b709073c71ec8ed94129419ea0ce7c01", + "sha256:a6ba305364df31b8ac8471a719371d0c05e1e5f7cc5b8a2295e7e958f9bc39bb", + "sha256:bbf37d5de98b09e7513e61fca6ebf6466fd82c3c2f0475e51d2a3c80e0bc1a92", + "sha256:bc9502064e8c3ff6f40b74c8a68fb31d0c9eae18c1d3f52d4e3f0ccda986f7cb", + "sha256:cdea7ab1698b69274eb69b16efdd7b16944c5019c06f0ace9530f91862496cf4", + "sha256:cdfec5dedd44617d94725170446cbe77c0b45044188bdc97cd251e698aeee822", + "sha256:db112fe9ffde7af96df09befcefdd33c4338f3a34fbfe894e04e66e14f584d9e", + "sha256:db461f2f0bfac155d56be7688ab6b43c140ce8b944aa5e6cfcb754bfeeeca750", + "sha256:dc303a5e09089001fd4fd51bd18a6d519e81ad5cbc36bb4b5fc3388d22a64be1", + "sha256:eb9e571427b7f44b8d8f9a3b6b7b25e45bc8e8895ed3cf3ecd917c0125cf3477", + "sha256:f4fbd431b2b0014b7d99e870f428eebf50a0149e4be1a72b905569aaadf4b540" + ], + "index": "pypi", + "version": "==4.5.4.60" }, "packaging": { "hashes": [ - "sha256:096d689d78ca690e4cd8a89568ba06d07ca097e3306a4381635073ca91479966", - "sha256:14317396d1e8cdb122989b916fa2c7e9ca8e2be9e8060a6eff75b6b7b4d8a7e0" + "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb", + "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522" ], "markers": "python_version >= '3.6'", - "version": "==21.2" + "version": "==21.3" }, "parameterized": { "hashes": [ @@ -1923,11 +1951,11 @@ }, "pyparsing": { "hashes": [ - "sha256:c203ec8783bf771a155b207279b9bccb8dea02d8f0c9e5f8ead507bc3246ecc1", - "sha256:ef9d7589ef3c200abe66653d3f1ab1033c3c419ae9b9bdb1240a85b024efc88b" + "sha256:04ff808a5b90911829c55c4e26f75fa5ca8a2f5f36aa3a51f68e27033341d3e4", + "sha256:d9bdec0013ef1eb5a84ab39a3b3868911598afa494f5faa038647101504e2b81" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.4.7" + "markers": "python_version >= '3.6'", + "version": "==3.0.6" }, "pyprof2calltree": { "hashes": [ @@ -2007,33 +2035,35 @@ }, "scipy": { "hashes": [ - "sha256:1437073f1d4664990879aa8f9547524764372e0fef84a077be4b19e82bba7a8d", - "sha256:17fd991a275e4283453f89d404209aa92059ac68d76d804b4bc1716a3742e1b5", - "sha256:1ea6233f5a365cb7945b4304bd06323ece3ece85d6a3fa8598d2f53e513467c9", - "sha256:2d25272c03ee3c0fe5e0dff1bb7889280bb6c9e1766fa9c7bde81ad8a5f78694", - "sha256:30bdda199667e74b50208a793eb1ba47a04e5e3fa16f5ff06c6f7969ae78e4da", - "sha256:359b60a0cccd17723b9d5e329a5212a710e771a3ddde800e472fb93732756c46", - "sha256:39f838ea5ce8da868785193d88d05cf5a6d5c390804ec99de29a28e1dcdd53e6", - "sha256:4d175ba93e00d8eef8f7cd70d4d88a9106a86800c82ea03cf2268c36d6545483", - "sha256:5273d832fb9cd5724ee0d335c16a903b923441107dd973d27fc4293075a9f4e3", - "sha256:54951f51d731c832b1b8885e0a92e89f33d087de7e40d02078bf0d49c7cbdbb5", - "sha256:74f518ce542533054695f743e4271cb8986b63f95bb51d70fcee4f3929cbff7d", - "sha256:7b1d0f5f524518f1a86f288443528e4ff4a739c0966db663af4129b7ac7849f8", - "sha256:82c5befebf54d799d77e5f0205c03030f57f69ba2541baa44d2e6ad138c28cd3", - "sha256:8482c8e45857ab0a5446eb7460d2307a27cbbe659d6d2257820c6d6eb950fd0f", - "sha256:87cf3964db0f1cce17aeed5bfc1b89a6b4b07dbfc48e50d21fa3549e00456803", - "sha256:8b5726a0fedeaa6beb1095e4466998bdd1d1e960b28db9b5a16c89cbd7b2ebf1", - "sha256:97eb573e361a73a553b915dc195c6f72a08249964b1a33f157f9659f3b6210d1", - "sha256:a80eb01c43fd98257ec7a49ff5cec0edba32031b5f86503f55399a48cb2c5379", - "sha256:cac71d5476a6f56b50459da21f6221707e0051ebd428b2137db32ef4a43bb15e", - "sha256:d86abd1ddf421dea5e9cebfeb4de0d205b3dc04e78249afedba9c6c3b2227ff2", - "sha256:dc2d1bf41294e63c7302bf499973ac0c7f73c93c01763db43055f6525234bf11", - "sha256:e08b81fcd9bf98740b58dc6fdd7879e33a64dcb682201c1135f7d4a75216bb05", - "sha256:e3efe7ef75dfe627b354ab0af0dbc918eadee97cc80ff1aabea6d3e01114ebdd", - "sha256:fa2dbabaaecdb502641b0b3c00dec05fb475ae48655c66da16c9ed24eda1e711" - ], - "index": "pypi", - "version": "==1.7.2" + "sha256:033ce76ed4e9f62923e1f8124f7e2b0800db533828c853b402c7eec6e9465d80", + "sha256:173308efba2270dcd61cd45a30dfded6ec0085b4b6eb33b5eb11ab443005e088", + "sha256:21b66200cf44b1c3e86495e3a436fc7a26608f92b8d43d344457c54f1c024cbc", + "sha256:2c56b820d304dffcadbbb6cbfbc2e2c79ee46ea291db17e288e73cd3c64fefa9", + "sha256:304dfaa7146cffdb75fbf6bb7c190fd7688795389ad060b970269c8576d038e9", + "sha256:3f78181a153fa21c018d346f595edd648344751d7f03ab94b398be2ad083ed3e", + "sha256:4d242d13206ca4302d83d8a6388c9dfce49fc48fdd3c20efad89ba12f785bf9e", + "sha256:5d1cc2c19afe3b5a546ede7e6a44ce1ff52e443d12b231823268019f608b9b12", + "sha256:5f2cfc359379c56b3a41b17ebd024109b2049f878badc1e454f31418c3a18436", + "sha256:65bd52bf55f9a1071398557394203d881384d27b9c2cad7df9a027170aeaef93", + "sha256:7edd9a311299a61e9919ea4192dd477395b50c014cdc1a1ac572d7c27e2207fa", + "sha256:8499d9dd1459dc0d0fe68db0832c3d5fc1361ae8e13d05e6849b358dc3f2c279", + "sha256:866ada14a95b083dd727a845a764cf95dd13ba3dc69a16b99038001b05439709", + "sha256:87069cf875f0262a6e3187ab0f419f5b4280d3dcf4811ef9613c605f6e4dca95", + "sha256:93378f3d14fff07572392ce6a6a2ceb3a1f237733bd6dcb9eb6a2b29b0d19085", + "sha256:95c2d250074cfa76715d58830579c64dff7354484b284c2b8b87e5a38321672c", + "sha256:ab5875facfdef77e0a47d5fd39ea178b58e60e454a4c85aa1e52fcb80db7babf", + "sha256:ca36e7d9430f7481fc7d11e015ae16fbd5575615a8e9060538104778be84addf", + "sha256:ceebc3c4f6a109777c0053dfa0282fddb8893eddfb0d598574acfb734a926168", + "sha256:e2c036492e673aad1b7b0d0ccdc0cb30a968353d2c4bf92ac8e73509e1bf212c", + "sha256:eb326658f9b73c07081300daba90a8746543b5ea177184daed26528273157294", + "sha256:eb7ae2c4dbdb3c9247e07acc532f91077ae6dbc40ad5bd5dca0bb5a176ee9bda", + "sha256:edad1cf5b2ce1912c4d8ddad20e11d333165552aba262c882e28c78bbc09dbf6", + "sha256:eef93a446114ac0193a7b714ce67659db80caf940f3232bad63f4c7a81bc18df", + "sha256:f7eaea089345a35130bc9a39b89ec1ff69c208efa97b3f8b25ea5d4c41d88094", + "sha256:f99d206db1f1ae735a8192ab93bd6028f3a42f6fa08467d37a14eb96c9dd34a3" + ], + "index": "pypi", + "version": "==1.7.3" }, "setuptools-scm": { "hashes": [ diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 2873aa7223..ed129db6ee 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -1,19 +1,25 @@ #!/usr/bin/env python3 import argparse -import carla # pylint: disable=import-error import math -import numpy as np -import time import threading -from cereal import log +import time +import os from multiprocessing import Process, Queue from typing import Any +import carla # pylint: disable=import-error +import numpy as np +import pyopencl as cl +import pyopencl.array as cl_array +from lib.can import can_function + import cereal.messaging as messaging -from common.params import Params +from cereal import log +from cereal.visionipc.visionipc_pyx import VisionIpcServer, VisionStreamType # pylint: disable=no-name-in-module, import-error +from common.basedir import BASEDIR from common.numpy_fast import clip -from common.realtime import Ratekeeper, DT_DMON -from lib.can import can_function +from common.params import Params +from common.realtime import DT_DMON, Ratekeeper from selfdrive.car.honda.values import CruiseButtons from selfdrive.test.helpers import set_params_enabled @@ -21,18 +27,18 @@ parser = argparse.ArgumentParser(description='Bridge between CARLA and openpilot parser.add_argument('--joystick', action='store_true') parser.add_argument('--low_quality', action='store_true') parser.add_argument('--town', type=str, default='Town04_Opt') -parser.add_argument('--spawn_point', dest='num_selected_spawn_point', - type=int, default=16) +parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16) args = parser.parse_args() -W, H = 1164, 874 +W, H = 1928, 1208 REPEAT_COUNTER = 5 PRINT_DECIMATION = 100 STEER_RATIO = 15. pm = messaging.PubMaster(['roadCameraState', 'sensorEvents', 'can', "gpsLocationExternal"]) -sm = messaging.SubMaster(['carControl','controlsState']) +sm = messaging.SubMaster(['carControl', 'controlsState']) + class VehicleState: def __init__(self): @@ -40,8 +46,9 @@ class VehicleState: self.angle = 0 self.bearing_deg = 0.0 self.vel = carla.Vector3D() - self.cruise_button= 0 - self.is_engaged=False + self.cruise_button = 0 + self.is_engaged = False + def steer_rate_limit(old, new): # Rate limiting to 0.5 degrees per step @@ -53,21 +60,56 @@ def steer_rate_limit(old, new): else: return new -frame_id = 0 -def cam_callback(image): - global frame_id - img = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) - img = np.reshape(img, (H, W, 4)) - img = img[:, :, [0, 1, 2]].copy() - - dat = messaging.new_message('roadCameraState') - dat.roadCameraState = { - "frameId": image.frame, - "image": img.tobytes(), - "transform": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] - } - pm.send('roadCameraState', dat) - frame_id += 1 + +class Camerad: + def __init__(self): + self.frame_id = 0 + self.vipc_server = VisionIpcServer("camerad") + + # TODO: remove RGB buffers once the last RGB vipc subscriber is removed + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_RGB_BACK, 4, True, W, H) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, W, H) + self.vipc_server.start_listener() + + # set up for pyopencl rgb to yuv conversion + self.ctx = cl.create_some_context() + self.queue = cl.CommandQueue(self.ctx) + cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W*3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " + + # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed + kernel_fn = os.path.join(BASEDIR, "selfdrive", "camerad", "transforms", "rgb_to_yuv.cl") + prg = cl.Program(self.ctx, open(kernel_fn).read()).build(cl_arg) + self.krnl = prg.rgb_to_yuv + self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 + self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 + + def cam_callback(self, image): + img = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) + img = np.reshape(img, (H, W, 4)) + img = img[:, :, [0, 1, 2]].copy() + + # convert RGB frame to YUV + rgb = np.reshape(img, (H, W * 3)) + rgb_cl = cl_array.to_device(self.queue, rgb) + yuv_cl = cl_array.empty_like(rgb_cl) + self.krnl(self.queue, (np.int32(self.Wdiv4), np.int32(self.Hdiv4)), None, rgb_cl.data, yuv_cl.data).wait() + yuv = np.resize(yuv_cl.get(), np.int32((rgb.size / 2))) + eof = self.frame_id * 0.05 + + # TODO: remove RGB send once the last RGB vipc subscriber is removed + self.vipc_server.send(VisionStreamType.VISION_STREAM_RGB_BACK, img.tobytes(), self.frame_id, eof, eof) + self.vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, yuv.data.tobytes(), self.frame_id, eof, eof) + + dat = messaging.new_message('roadCameraState') + dat.roadCameraState = { + "frameId": image.frame, + "transform": [1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0] + } + pm.send('roadCameraState', dat) + self.frame_id += 1 + def imu_callback(imu, vehicle_state): vehicle_state.bearing_deg = math.degrees(imu.compass) @@ -83,6 +125,7 @@ def imu_callback(imu, vehicle_state): dat.sensorEvents[1].gyroUncalibrated.v = [imu.gyroscope.x, imu.gyroscope.y, imu.gyroscope.z] pm.send('sensorEvents', dat) + def panda_state_function(exit_event: threading.Event): pm = messaging.PubMaster(['pandaStates']) while not exit_event.is_set(): @@ -97,6 +140,7 @@ def panda_state_function(exit_event: threading.Event): pm.send('pandaStates', dat) time.sleep(0.5) + def peripheral_state_function(exit_event: threading.Event): pm = messaging.PubMaster(['peripheralState']) while not exit_event.is_set(): @@ -112,20 +156,21 @@ def peripheral_state_function(exit_event: threading.Event): pm.send('peripheralState', dat) time.sleep(0.5) + def gps_callback(gps, vehicle_state): dat = messaging.new_message('gpsLocationExternal') # transform vel from carla to NED # north is -Y in CARLA velNED = [ - -vehicle_state.vel.y, # north/south component of NED is negative when moving south - vehicle_state.vel.x, # positive when moving east, which is x in carla + -vehicle_state.vel.y, # north/south component of NED is negative when moving south + vehicle_state.vel.x, # positive when moving east, which is x in carla vehicle_state.vel.z, ] dat.gpsLocationExternal = { "timestamp": int(time.time() * 1000), - "flags": 1, # valid fix + "flags": 1, # valid fix "accuracy": 1.0, "verticalAccuracy": 1.0, "speedAccuracy": 0.1, @@ -141,8 +186,9 @@ def gps_callback(gps, vehicle_state): pm.send('gpsLocationExternal', dat) + def fake_driver_monitoring(exit_event: threading.Event): - pm = messaging.PubMaster(['driverState','driverMonitoringState']) + pm = messaging.PubMaster(['driverState', 'driverMonitoringState']) while not exit_event.is_set(): # dmonitoringmodeld output dat = messaging.new_message('driverState') @@ -160,16 +206,16 @@ def fake_driver_monitoring(exit_event: threading.Event): time.sleep(DT_DMON) + def can_function_runner(vs: VehicleState, exit_event: threading.Event): i = 0 while not exit_event.is_set(): can_function(pm, vs.speed, vs.angle, i, vs.cruise_button, vs.is_engaged) time.sleep(0.01) - i+=1 + i += 1 def bridge(q): - # setup CARLA client = carla.Client("127.0.0.1", 2000) client.set_timeout(10.0) @@ -209,11 +255,12 @@ def bridge(q): blueprint = blueprint_library.find('sensor.camera.rgb') blueprint.set_attribute('image_size_x', str(W)) blueprint.set_attribute('image_size_y', str(H)) - blueprint.set_attribute('fov', '70') + blueprint.set_attribute('fov', '40') blueprint.set_attribute('sensor_tick', '0.05') transform = carla.Transform(carla.Location(x=0.8, z=1.13)) camera = world.spawn_actor(blueprint, transform, attach_to=vehicle) - camera.listen(cam_callback) + camerad = Camerad() + camera.listen(camerad.cam_callback) vehicle_state = VehicleState() @@ -244,7 +291,6 @@ def bridge(q): brake_ease_out_counter = REPEAT_COUNTER steer_ease_out_counter = REPEAT_COUNTER - vc = carla.VehicleControl(throttle=0, steer=0, brake=0, reverse=False) is_openpilot_engaged = False @@ -253,12 +299,11 @@ def bridge(q): throttle_manual = steer_manual = brake_manual = 0 old_steer = old_brake = old_throttle = 0 - throttle_manual_multiplier = 0.7 #keyboard signal is always 1 - brake_manual_multiplier = 0.7 #keyboard signal is always 1 - steer_manual_multiplier = 45 * STEER_RATIO #keyboard signal is always 1 - + throttle_manual_multiplier = 0.7 # keyboard signal is always 1 + brake_manual_multiplier = 0.7 # keyboard signal is always 1 + steer_manual_multiplier = 45 * STEER_RATIO # keyboard signal is always 1 - while 1: + while True: # 1. Read the throttle, steer and brake from op or manual controls # 2. Set instructions in Carla # 3. Send current carstate to op via can @@ -282,7 +327,6 @@ def bridge(q): brake_manual = float(m[1]) is_openpilot_engaged = False elif m[0] == "reverse": - #in_reverse = not in_reverse cruise_button = CruiseButtons.CANCEL is_openpilot_engaged = False elif m[0] == "cruise": @@ -302,19 +346,16 @@ def bridge(q): steer_out = steer_manual * steer_manual_multiplier brake_out = brake_manual * brake_manual_multiplier - #steer_out = steer_out - # steer_out = steer_rate_limit(old_steer, steer_out) old_steer = steer_out old_throttle = throttle_out old_brake = brake_out - # print('message',old_throttle, old_steer, old_brake) - if is_openpilot_engaged: sm.update(0) + # TODO gas and brake is deprecated - throttle_op = clip(sm['carControl'].actuators.accel/1.6, 0.0, 1.0) - brake_op = clip(-sm['carControl'].actuators.accel/4.0, 0.0, 1.0) + throttle_op = clip(sm['carControl'].actuators.accel / 1.6, 0.0, 1.0) + brake_op = clip(-sm['carControl'].actuators.accel / 4.0, 0.0, 1.0) steer_op = sm['carControl'].actuators.steeringAngleDeg throttle_out = throttle_op @@ -325,24 +366,24 @@ def bridge(q): old_steer = steer_out else: - if throttle_out==0 and old_throttle>0: - if throttle_ease_out_counter>0: + if throttle_out == 0 and old_throttle > 0: + if throttle_ease_out_counter > 0: throttle_out = old_throttle throttle_ease_out_counter += -1 else: throttle_ease_out_counter = REPEAT_COUNTER old_throttle = 0 - if brake_out==0 and old_brake>0: - if brake_ease_out_counter>0: + if brake_out == 0 and old_brake > 0: + if brake_ease_out_counter > 0: brake_out = old_brake brake_ease_out_counter += -1 else: brake_ease_out_counter = REPEAT_COUNTER old_brake = 0 - if steer_out==0 and old_steer!=0: - if steer_ease_out_counter>0: + if steer_out == 0 and old_steer != 0: + if steer_ease_out_counter > 0: steer_out = old_steer steer_ease_out_counter += -1 else: @@ -350,28 +391,27 @@ def bridge(q): old_steer = 0 # --------------Step 2------------------------------- - steer_carla = steer_out / (max_steer_angle * STEER_RATIO * -1) - steer_carla = np.clip(steer_carla, -1,1) + steer_carla = np.clip(steer_carla, -1, 1) steer_out = steer_carla * (max_steer_angle * STEER_RATIO * -1) old_steer = steer_carla * (max_steer_angle * STEER_RATIO * -1) - vc.throttle = throttle_out/0.6 + vc.throttle = throttle_out / 0.6 vc.steer = steer_carla vc.brake = brake_out vehicle.apply_control(vc) # --------------Step 3------------------------------- vel = vehicle.get_velocity() - speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) # in m/s + speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) # in m/s vehicle_state.speed = speed vehicle_state.vel = vel vehicle_state.angle = steer_out vehicle_state.cruise_button = cruise_button vehicle_state.is_engaged = is_openpilot_engaged - if rk.frame%PRINT_DECIMATION == 0: + if rk.frame % PRINT_DECIMATION == 0: print("frame: ", "engaged:", is_openpilot_engaged, "; throttle: ", round(vc.throttle, 3), "; steer(c/deg): ", round(vc.steer, 3), round(steer_out, 3), "; brake: ", round(vc.brake, 3)) rk.keep_time() @@ -385,6 +425,7 @@ def bridge(q): camera.destroy() vehicle.destroy() + def bridge_keep_alive(q: Any): while 1: try: @@ -393,6 +434,7 @@ def bridge_keep_alive(q: Any): except RuntimeError: print("Restarting bridge...") + if __name__ == "__main__": # make sure params are in a good state set_params_enabled() diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh index e10d688c2f..b94a453b7b 100755 --- a/tools/sim/launch_openpilot.sh +++ b/tools/sim/launch_openpilot.sh @@ -5,8 +5,7 @@ export NOBOARD="1" export SIMULATION="1" export FINGERPRINT="HONDA CIVIC 2016" -# TODO: remove this once the bridge uses visionipc -export BLOCK="loggerd" +export BLOCK="camerad,loggerd" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd ../../selfdrive/manager && ./manager.py diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 97754ab0b8..4873947d4b 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -62,7 +62,7 @@ def can_function(pm, speed, angle, idx, cruise_button, is_engaged): msg.append(packer.make_can_msg("CRUISE", 0, {}, idx)) msg.append(packer.make_can_msg("SCM_FEEDBACK", 0, {"MAIN_ON": 1}, idx)) msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {"ACC_STATUS": int(is_engaged)}, idx)) - msg.append(packer.make_can_msg("HUD_SETTING", 0, {}, idx)) + msg.append(packer.make_can_msg("HUD_SETTING", 0, {})) # *** cam bus *** msg.append(packer.make_can_msg("STEERING_CONTROL", 2, {}, idx))