diff --git a/.gitignore b/.gitignore index 35691c34..f4932ed4 100644 --- a/.gitignore +++ b/.gitignore @@ -10,6 +10,7 @@ venv/ .vscode* model2.png a.out +.hypothesis *.dylib *.DSYM diff --git a/Pipfile b/Pipfile index cd9e0fa9..bef630b2 100644 --- a/Pipfile +++ b/Pipfile @@ -72,6 +72,7 @@ pre-commit = "*" mypy = "*" parameterized = "*" ft4222 = "*" +hypothesis = "*" [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index f309c3d8..079a220f 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "ab54a9e11a1f41563adab1dd3550400dc16c1d20eb019f0afc364bcbaed6e0b7" + "sha256": "49aa5075a4ce12ef245f293d727b87bcb668af87afe64609694d596859448fa1" }, "pipfile-spec": 6, "requires": { @@ -18,11 +18,11 @@ "default": { "astroid": { "hashes": [ - "sha256:ad63b8552c70939568966811a088ef0bc880f99a24a00834abd0e3681b514f91", - "sha256:bea3f32799fbb8581f58431c12591bc20ce11cbc90ad82e2ea5717d94f2080d5" + "sha256:4db03ab5fc3340cf619dbc25e42c2cc3755154ce6009469766d7143d1fc2ee4e", + "sha256:8a398dfce302c13f14bab13e2b14fe385d32b73f4e4853b9bdfb64598baa1975" ], - "markers": "python_version >= '3.6'", - "version": "==2.5.3" + "markers": "python_version ~= '3.6'", + "version": "==2.5.6" }, "atomicwrites": { "hashes": [ @@ -192,6 +192,7 @@ }, "gunicorn": { "hashes": [ + "sha256:9dcc4547dbb1cb284accfb15ab5667a0e5d1881cc443e0677b4882a4067a807e", "sha256:e0a968b5ba15f8a328fdfd7ab1fcb5af4470c28aaf7e55df02a99bc13138e6e8" ], "index": "pypi", @@ -624,19 +625,19 @@ }, "pyjwt": { "hashes": [ - "sha256:a5c70a06e1f33d81ef25eecd50d50bd30e34de1ca8b2b9fa3fe0daaabcf69bf7", - "sha256:b70b15f89dc69b993d8a8d32c299032d5355c82f9b5b7e851d1a6d706dffe847" + "sha256:934d73fbba91b0483d3857d1aff50e96b2a892384ee2c17417ed3203f173fca1", + "sha256:fba44e7898bbca160a2b2b501f492824fc8382485d3a6f11ba5d0c1937ce6130" ], "index": "pypi", - "version": "==2.0.1" + "version": "==2.1.0" }, "pylint": { "hashes": [ - "sha256:209d712ec870a0182df034ae19f347e725c1e615b2269519ab58a35b3fcbbe7a", - "sha256:bd38914c7731cdc518634a8d3c5585951302b6e2b6de60fbb3f7a0220e21eeee" + "sha256:586d8fa9b1891f4b725f587ef267abe2a1bad89d6b184520c7f07a253dd6e217", + "sha256:f7e2072654a6b6afdf5e2fb38147d3e2d2d43c89f648637baab63e026481279b" ], "index": "pypi", - "version": "==2.7.4" + "version": "==2.8.2" }, "pyserial": { "hashes": [ @@ -828,11 +829,11 @@ }, "typing-extensions": { "hashes": [ - "sha256:7cb407020f00f7bfc3cb3e7881628838e69d8f3fcab2f64742a5e76b2f841918", - "sha256:99d4073b617d30288f569d3f13d2bd7548c3a7e4c8de87db09a9d29bb3a4a60c", - "sha256:dafc7639cde7f1b6e1acc0f457842a83e722ccca8eef5270af2d74792619a89f" + "sha256:0ac0f89795dd19de6b97debb0c6af1c70987fd80a2d62d1958f7e56fcc31b497", + "sha256:50b6f157849174217d0656f99dc82fe932884fb250826c18350e159ec6cdf342", + "sha256:779383f6086d90c99ae41cf0ff39aac8a7937a9283ce0a414e5dd782f4c94a84" ], - "version": "==3.7.4.3" + "version": "==3.10.0.0" }, "urllib3": { "hashes": [ @@ -941,10 +942,10 @@ }, "applicationinsights": { "hashes": [ - "sha256:30a11aafacea34f8b160fbdc35254c9029c7e325267874e3c68f6bdbcd6ed2c3", - "sha256:b88bc5a41385d8e516489128d5e63f8c52efe597a3579b1718d1ab2f7cf150a2" + "sha256:0b761f3ef0680acf4731906dfc1807faa6f2a57168ae74592db0084a6099f7b3", + "sha256:e89a890db1c6906b6a7d0bcfd617dac83974773c64573147c8d6654f9cf2a6ea" ], - "version": "==0.11.9" + "version": "==0.11.10" }, "argcomplete": { "hashes": [ @@ -978,11 +979,11 @@ }, "astroid": { "hashes": [ - "sha256:ad63b8552c70939568966811a088ef0bc880f99a24a00834abd0e3681b514f91", - "sha256:bea3f32799fbb8581f58431c12591bc20ce11cbc90ad82e2ea5717d94f2080d5" + "sha256:4db03ab5fc3340cf619dbc25e42c2cc3755154ce6009469766d7143d1fc2ee4e", + "sha256:8a398dfce302c13f14bab13e2b14fe385d32b73f4e4853b9bdfb64598baa1975" ], - "markers": "python_version >= '3.6'", - "version": "==2.5.3" + "markers": "python_version ~= '3.6'", + "version": "==2.5.6" }, "async-generator": { "hashes": [ @@ -1132,19 +1133,19 @@ }, "boto3": { "hashes": [ - "sha256:5910c868c2cf0d30b6c9caed1d38a2b2c2c83e9713eadae0f43de4f42bfe863f", - "sha256:d0d1e8ca76a8e1b74f87a8324f97001d60bd8bbe6cca35a8e9e7b9abe5aa9ddb" + "sha256:ac10d832ad716281da6ca77cea824d723af479f8611087dee4b0489c48c32fd9", + "sha256:e2ef25afc36a301199bfbd662aef46dd11ed0db9baf96fce111db4043928065b" ], "index": "pypi", - "version": "==1.17.55" + "version": "==1.17.64" }, "botocore": { "hashes": [ - "sha256:5632c129e6c1c1a15e273fd3ec6f4431490e99ec61b6cff833538f456202e833", - "sha256:94a62f7f848b37757c3419193727e183bccdf5cb74167df30bafee5d8d649b7a" + "sha256:42dde7c699b3710e5c3a944cd8ce8b7a80b9f610d8857a0ad36bdc9743cc3375", + "sha256:ec418c273c37efd33d39bb4559f7df09de46df1f87fdbb064d8ebb281849a625" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4, 3.5'", - "version": "==1.20.55" + "version": "==1.20.64" }, "certifi": { "hashes": [ @@ -1358,11 +1359,11 @@ }, "elasticsearch": { "hashes": [ - "sha256:9a77172be02bc4855210d83f0f1346a1e7d421e3cb2ca47ba81ac0c5a717b3a0", - "sha256:c67b0f6541eda6de9f92eaea319c070aa2710c5d4d4ee5e3dfa3c21bd95aa378" + "sha256:1840fea8c305224b8c28acabc8697f739cdfb03618f2d2427b42838971a787f6", + "sha256:df35d8c638f946f098a74681b18611bdf27ba469fa2063e3dfc8bdc290b11419" ], "index": "pypi", - "version": "==7.12.0" + "version": "==7.12.1" }, "entrypoints": { "hashes": [ @@ -1517,6 +1518,7 @@ }, "gunicorn": { "hashes": [ + "sha256:9dcc4547dbb1cb284accfb15ab5667a0e5d1881cc443e0677b4882a4067a807e", "sha256:e0a968b5ba15f8a328fdfd7ab1fcb5af4470c28aaf7e55df02a99bc13138e6e8" ], "index": "pypi", @@ -1553,6 +1555,14 @@ "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", "version": "==9.1" }, + "hypothesis": { + "hashes": [ + "sha256:1d65f58d82d1cbd35b6441bda3bb11cb1adc879d6b2af191aea388fa412171b1", + "sha256:586b6c46e90878c2546743afbed348bca51e1f30e3461fa701fad58c2c47c650" + ], + "index": "pypi", + "version": "==6.10.1" + }, "identify": { "hashes": [ "sha256:9bcc312d4e2fa96c7abebcdfb1119563b511b5e3985ac52f60d9116277865b2e", @@ -1587,11 +1597,11 @@ }, "ipython": { "hashes": [ - "sha256:9c900332d4c5a6de534b4befeeb7de44ad0cc42e8327fa41b7685abde58cec74", - "sha256:c0ce02dfaa5f854809ab7413c601c4543846d9da81010258ecdab299b542d199" + "sha256:3455b020a895710c4366e8d1b326e5ee6aa684607907fc96895e7b8359569f49", + "sha256:69178f32bf9c6257430b6f592c3ae230c32861a1966d2facec454e09078e232d" ], "index": "pypi", - "version": "==7.22.0" + "version": "==7.23.0" }, "ipython-genutils": { "hashes": [ @@ -1895,6 +1905,14 @@ "index": "pypi", "version": "==3.4.1" }, + "matplotlib-inline": { + "hashes": [ + "sha256:5cf1176f554abb4fa98cb362aa2b55c500147e4bdbb07e3fda359143e1da0811", + "sha256:f41d5ff73c9f5385775d5c0bc13b424535c8402fe70ea8210f93e11f3683993e" + ], + "markers": "python_version >= '3.5'", + "version": "==0.1.2" + }, "mccabe": { "hashes": [ "sha256:ab8a6258860da4b6677da4bd2fe5dc2c659cff31b3ee4f7f5d64e79735b80d42", @@ -2433,27 +2451,27 @@ }, "pygments": { "hashes": [ - "sha256:2656e1a6edcdabf4275f9a3640db59fd5de107d88e8663c5d4e9a0fa62f77f94", - "sha256:534ef71d539ae97d4c3a4cf7d6f110f214b0e687e92f9cb9d2a3b0d3101289c8" + "sha256:a18f47b506a429f6f4b9df81bb02beab9ca21d0a5fee38ed15aef65f0545519f", + "sha256:d66e804411278594d764fc69ec36ec13d9ae9147193a1740cd34d272ca383b8e" ], "index": "pypi", - "version": "==2.8.1" + "version": "==2.9.0" }, "pyjwt": { "hashes": [ - "sha256:a5c70a06e1f33d81ef25eecd50d50bd30e34de1ca8b2b9fa3fe0daaabcf69bf7", - "sha256:b70b15f89dc69b993d8a8d32c299032d5355c82f9b5b7e851d1a6d706dffe847" + "sha256:934d73fbba91b0483d3857d1aff50e96b2a892384ee2c17417ed3203f173fca1", + "sha256:fba44e7898bbca160a2b2b501f492824fc8382485d3a6f11ba5d0c1937ce6130" ], "index": "pypi", - "version": "==2.0.1" + "version": "==2.1.0" }, "pylint": { "hashes": [ - "sha256:209d712ec870a0182df034ae19f347e725c1e615b2269519ab58a35b3fcbbe7a", - "sha256:bd38914c7731cdc518634a8d3c5585951302b6e2b6de60fbb3f7a0220e21eeee" + "sha256:586d8fa9b1891f4b725f587ef267abe2a1bad89d6b184520c7f07a253dd6e217", + "sha256:f7e2072654a6b6afdf5e2fb38147d3e2d2d43c89f648637baab63e026481279b" ], "index": "pypi", - "version": "==2.7.4" + "version": "==2.8.2" }, "pymongo": { "hashes": [ @@ -2773,11 +2791,11 @@ }, "qtconsole": { "hashes": [ - "sha256:4a38053993ca2da058f76f8d75b3d8906efbf9183de516f92f222ac8e37d9614", - "sha256:c091a35607d2a2432e004c4a112d241ce908086570cf68594176dd52ccaa212d" + "sha256:12c734494901658787339dea9bbd82f3dc0d5e394071377a1c77b4a0954d7d8b", + "sha256:3a2adecc43ff201a08972fb2179df22e7b3a08d71b9ed680f46ad1bfd4fb9132" ], "markers": "python_version >= '3.6'", - "version": "==5.0.3" + "version": "==5.1.0" }, "qtpy": { "hashes": [ @@ -2827,10 +2845,10 @@ }, "s3transfer": { "hashes": [ - "sha256:81b7b3516739b0cfbecaa9077a1baf783e7a790c0e49261fcc6ceda468765efa", - "sha256:b5130849df909773254099d085790456665f8d7e0032bbef6e3407f28adb1ad9" + "sha256:9b3752887a2880690ce628bc263d6d13a3864083aeacff4890c1c9839a5eb0bc", + "sha256:cb022f4b16551edebbb31a377d3f09600dbada7363d8c5db7976e7f47732e1b2" ], - "version": "==0.4.1" + "version": "==0.4.2" }, "scikit-image": { "hashes": [ @@ -2856,28 +2874,28 @@ }, "scipy": { "hashes": [ - "sha256:03f1fd3574d544456325dae502facdf5c9f81cbfe12808a5e67a737613b7ba8c", - "sha256:0c81ea1a95b4c9e0a8424cf9484b7b8fa7ef57169d7bcc0dfcfc23e3d7c81a12", - "sha256:1fba8a214c89b995e3721670e66f7053da82e7e5d0fe6b31d8e4b19922a9315e", - "sha256:37f4c2fb904c0ba54163e03993ce3544c9c5cde104bcf90614f17d85bdfbb431", - "sha256:50e5bcd9d45262725e652611bb104ac0919fd25ecb78c22f5282afabd0b2e189", - "sha256:6ca1058cb5bd45388041a7c3c11c4b2bd58867ac9db71db912501df77be2c4a4", - "sha256:77f7a057724545b7e097bfdca5c6006bed8580768cd6621bb1330aedf49afba5", - "sha256:816951e73d253a41fa2fd5f956f8e8d9ac94148a9a2039e7db56994520582bf2", - "sha256:96620240b393d155097618bcd6935d7578e85959e55e3105490bbbf2f594c7ad", - "sha256:993c86513272bc84c451349b10ee4376652ab21f312b0554fdee831d593b6c02", - "sha256:adf7cee8e5c92b05f2252af498f77c7214a2296d009fc5478fc432c2f8fb953b", - "sha256:bc52d4d70863141bb7e2f8fd4d98e41d77375606cde50af65f1243ce2d7853e8", - "sha256:c1d3f771c19af00e1a36f749bd0a0690cc64632783383bc68f77587358feb5a4", - "sha256:d744657c27c128e357de2f0fd532c09c84cd6e4933e8232895a872e67059ac37", - "sha256:e3e9742bad925c421d39e699daa8d396c57535582cba90017d17f926b61c1552", - "sha256:e547f84cd52343ac2d56df0ab08d3e9cc202338e7d09fafe286d6c069ddacb31", - "sha256:e89091e6a8e211269e23f049473b2fde0c0e5ae0dd5bd276c3fc91b97da83480", - "sha256:e9da33e21c9bc1b92c20b5328adb13e5f193b924c9b969cd700c8908f315aa59", - "sha256:ffdfb09315896c6e9ac739bb6e13a19255b698c24e6b28314426fd40a1180822" + "sha256:01b38dec7e9f897d4db04f8de4e20f0f5be3feac98468188a0f47a991b796055", + "sha256:10dbcc7de03b8d635a1031cb18fd3eaa997969b64fdf78f99f19ac163a825445", + "sha256:19aeac1ad3e57338723f4657ac8520f41714804568f2e30bd547d684d72c392e", + "sha256:1b21c6e0dc97b1762590b70dee0daddb291271be0580384d39f02c480b78290a", + "sha256:1caade0ede6967cc675e235c41451f9fb89ae34319ddf4740194094ab736b88d", + "sha256:23995dfcf269ec3735e5a8c80cfceaf384369a47699df111a6246b83a55da582", + "sha256:2a799714bf1f791fb2650d73222b248d18d53fd40d6af2df2c898db048189606", + "sha256:3274ce145b5dc416c49c0cf8b6119f787f0965cd35e22058fe1932c09fe15d77", + "sha256:33d1677d46111cfa1c84b87472a0274dde9ef4a7ef2e1f155f012f5f1e995d8f", + "sha256:44d452850f77e65e25b1eb1ac01e25770323a782bfe3a1a3e43847ad4266d93d", + "sha256:9e3302149a369697c6aaea18b430b216e3c88f9a61b62869f6104881e5f9ef85", + "sha256:a75b014d3294fce26852a9d04ea27b5671d86736beb34acdfc05859246260707", + "sha256:ad7269254de06743fb4768f658753de47d8b54e4672c5ebe8612a007a088bd48", + "sha256:b30280fbc1fd8082ac822994a98632111810311a9ece71a0e48f739df3c555a2", + "sha256:b79104878003487e2b4639a20b9092b02e1bad07fc4cf924b495cf413748a777", + "sha256:d449d40e830366b4c612692ad19fbebb722b6b847f78a7b701b1e0d6cda3cc13", + "sha256:d647757373985207af3343301d89fe738d5a294435a4f2aafb04c13b4388c896", + "sha256:f68eb46b86b2c246af99fcaa6f6e37c7a7a413e1084a794990b877f2ff71f7b6", + "sha256:fdf606341cd798530b05705c87779606fcdfaf768a8129c348ea94441da15b04" ], "index": "pypi", - "version": "==1.6.2" + "version": "==1.6.3" }, "seaborn": { "hashes": [ @@ -2982,45 +3000,52 @@ "index": "pypi", "version": "==1.15.0" }, + "sortedcontainers": { + "hashes": [ + "sha256:37257a32add0a3ee490bb170b599e93095eed89a55da91fa9f48753ea12fd73f", + "sha256:59cc937650cf60d677c16775597c89a960658a09cf7c1a668f86e1e4464b10a1" + ], + "version": "==2.3.0" + }, "sqlalchemy": { "hashes": [ - "sha256:0140f6dac2659fa6783e7029085ab0447d8eb23cf4d831fb907588d27ba158f7", - "sha256:034b42a6a59bf4ddc57e5a38a9dbac83ccd94c0b565ba91dba4ff58149706028", - "sha256:03a503ecff0cc2be3ad4dafd220eaff13721edb11c191670b7662932fb0a5c3a", - "sha256:069de3a701d33709236efe0d06f38846b738b19c63d45cc47f54590982ba7802", - "sha256:1735e06a3d5b0793d5ee2d952df8a5c63edaff6383c2210c9b5c93dc2ea4c315", - "sha256:19633df6be629200ff3c026f2837e1dd17908fb1bcea860290a5a45e6fa5148e", - "sha256:1e14fa32969badef9c309f55352e5c46f321bd29f7c600556caacdaa3eddfcf6", - "sha256:31e941d6db8b026bc63e46ef71e877913f128bd44260b90c645432626b7f9a47", - "sha256:452c4e002be727cb6f929dbd32bbc666a0921b86555b8af09709060ed3954bd3", - "sha256:45a720029756800628359192630fffdc9660ab6f27f0409bd24d9e09d75d6c18", - "sha256:4a2e7f037d3ca818d6d0490e3323fd451545f580df30d62b698da2f247015a34", - "sha256:4a7d4da2acf6d5d068fb41c48950827c49c3c68bfb46a1da45ea8fbf7ed4b471", - "sha256:4ad4044eb86fbcbdff2106e44f479fbdac703d77860b3e19988c8a8786e73061", - "sha256:4f631edf45a943738fa77612e85fc5c5d3fb637c4f5a530f7eedd1a7cd7a70a7", - "sha256:6389b10e23329dc8b5600c1a84e3da2628d0f437d8a5cd05aefd1470ec571dd1", - "sha256:6ebd58e73b7bd902688c0bb8dbabb0c36b756f02cc7b27ad5efa2f380c611f95", - "sha256:7180830ea1082b96b94884bc352b274e29b45151b6ee911bf1fd79cba2de659b", - "sha256:789be639501445d85fd4ca41d04f0f5c6cbb6deb0c6826aaa6f22774fe84ef94", - "sha256:7d89add44938ea4f52c7641d5805c9e154fed4381e874ef3221483eeb191a96d", - "sha256:842b0d4698381aac047f8ae57409c90b7e63ebabf5bc02814ddc8eaefd13499e", - "sha256:8f96d4b6a49d3f0f109365bb6303ae5d266d3f90280ca68cf8b2c46032491038", - "sha256:961b089e64c2ad29ad367487dd3ba1aa3eeba56bc82037ce91732baaa0f6ca90", - "sha256:96de1d4a2e05d4a017087cb29cd6a8ebfeecfd0e9f872880b1a589f011c1c02e", - "sha256:98214f04802a3fc740038744d8981a8f2fdca710f791ca125fc4792737d9f3a7", - "sha256:9cf94161cb55507cee147bf8abcfd3c076b353ad18743296764dd81108ea74f8", - "sha256:9fdf0713166f33e5e6ea98cf59deb305cb323131277f6880de6c509f468076f8", - "sha256:a41ab83ecfadf38a47bdfaf4e488f71579df47a711e1ab1dce30d34c7c25bd00", - "sha256:ac14fee167653ec6dee32d6aa4d501d90ae1bfbbc3eb5816940bccf227f0d617", - "sha256:b8b7d66ee8b8ac272adce0af1342a60854f0d89686e6d3318127a6a82a2f765c", - "sha256:bb1072fdf48ba870c0fe81bee8babe4ba2f096fb56bb4f3e0c2386a7626e405c", - "sha256:cd823071b97c1a6ac3af9e43b5d861126a1304033dcd18dfe354a02ec45642fe", - "sha256:d08173144aebdf30c21a331b532db16535cfa83deed12e8703fa6c67c0894ffc", - "sha256:e7d76312e904aa4ea221a92c0bc2e299ad46e4580e2d72ca1f7e6d31dce5bfab", - "sha256:f772e4428d413c0affe2a34836278fbe9df9a9c0940705860c2d3a4b50af1a66" + "sha256:08a00a955c5cb1d3a610f9735e0e9ca64f2fd2540c942ab84dc9a71433940f86", + "sha256:1b2b0199153a4ecbb57ec09ff8a3693dcb2c134fef217379e2761f27bccf3a14", + "sha256:1d8a71c2bf21437d6216ba1963507d4d1a37920429eafd09d85387d0d078fa5a", + "sha256:36bcf7530ca070e89f29e2f6e05c5566c9ab3a2e493608437a230253ecf112a7", + "sha256:375cde7038d3c4493e2e61273ed2a3be04b5845e9bea5c662543c22935fb439b", + "sha256:384c0ecc845b597eda2519de2f8dd66770e76f8f39e0d21f00dd5affaf293787", + "sha256:46737cd87a57e03ab20e79d29ad931b842e7b3226a169ae9b36babe69d92256f", + "sha256:49fc18facca9ecb29308e486de53e7d9ab7d7b02d6705158fa34af0c1a6c3b0b", + "sha256:4b9e7764638910c43eea6e6e367395dce3d1c6acc17f8550e66cd913725491d2", + "sha256:50dba4adb0f7cafb5c05e3e9734b7d84f0b009daf17ca5a3c1560be7dbcaaba7", + "sha256:586eb3698e616fe044472e7a249d24a5b05dc5c714dc0b9744417031988df3af", + "sha256:58bee8384a7e32846e560da0ad595cf0dd5046b286aafa8d000312c5db8899bf", + "sha256:5e7e9a7092aea03c68318d390f39dab75422143354543244b6e1b2b31848a494", + "sha256:6adf973e7e27bce34c6bb14f62368b99e53a55226836ac93ff1352fe467dc966", + "sha256:6d01d83d290db9e27ea02183e56ba548a48143b3b1b7977d07cedafc3606f91d", + "sha256:6f0bd9b2cf1c555c6bfbb71d58750d096f7462a582abf6994cff80fbfe0d8c94", + "sha256:74cd7afd1789eabe42c838747c5680d78317aee448a22de75638ac0735ae3284", + "sha256:79286d63e5f92340357bc2a0801637b2accc95d7e0044768c3eea5e8271cc300", + "sha256:8162f379edc3c1c0c4ac7436b3a8baa8ca7754913ed81002f631bc066486803e", + "sha256:85bd128ebb3c47615496778fedbe334094cf6133c6933804e237c741fce4f20c", + "sha256:8a00c3494a1553e171c77505653cca22f5fadf09a0af4a020243f1baaad412b3", + "sha256:8dd79b534516b9b792dbb319324962d02c69a50a390cb2387e360bebe5d7b280", + "sha256:938e819bc74c95466c7f6d5dc7e2d08142c116c380992aa36d60e64e7a62ffe7", + "sha256:98270f1c52dc4a62279aee7c0a134e84182372e4b3c7ee35cafd906c11f4e218", + "sha256:9c2afd9ad52387d32b2a856b19352d605213a06b4684a3b469ff8f39a27fb3a2", + "sha256:a35d909327a1c3bc407689179101af93de34bc6af8c6f07d5d29e4eaab54a9f4", + "sha256:a63848afe8f909d1dcea286c3856c1cc1de6e8908e9ce1bdb672c9f19b2d2aa7", + "sha256:b12b39ded8cee6c4fdd0b8aa5afdb8cb5641098f2625acc9175effdc064b5c9f", + "sha256:b53a0faf32cde49eb04ad81f8ff60cfa1dcc024aa6a6bb8b545621339395e640", + "sha256:c9937cb1061042fb09c4b622884407525a0a595e300ef199d80a7290ca2c71ea", + "sha256:e21ca6ecf2a48a53856562af3380f2a64a1ce08ae2d17c800095f4685ab499b1", + "sha256:e25d48233f5501b41c7d561cfd9ec9c89a891643aaf282750c129d627cc5a547", + "sha256:e288a3640c3c9311bb223c13e6ecb2ae4c5fb018756b5fbf82b9a1f13c6c6111", + "sha256:ed96e1f28708c5a00fb371971d6634210afdcabb439dd488d41e1cfc2c906459" ], "index": "pypi", - "version": "==1.4.11" + "version": "==1.4.13" }, "subprocess32": { "hashes": [ @@ -3169,11 +3194,11 @@ }, "typing-extensions": { "hashes": [ - "sha256:7cb407020f00f7bfc3cb3e7881628838e69d8f3fcab2f64742a5e76b2f841918", - "sha256:99d4073b617d30288f569d3f13d2bd7548c3a7e4c8de87db09a9d29bb3a4a60c", - "sha256:dafc7639cde7f1b6e1acc0f457842a83e722ccca8eef5270af2d74792619a89f" + "sha256:0ac0f89795dd19de6b97debb0c6af1c70987fd80a2d62d1958f7e56fcc31b497", + "sha256:50b6f157849174217d0656f99dc82fe932884fb250826c18350e159ec6cdf342", + "sha256:779383f6086d90c99ae41cf0ff39aac8a7937a9283ce0a414e5dd782f4c94a84" ], - "version": "==3.7.4.3" + "version": "==3.10.0.0" }, "urllib3": { "hashes": [ diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 183b9976..18733404 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -14,7 +14,7 @@ from cereal import car, log from cereal.services import service_list from common.params import Params from selfdrive.car.fingerprints import FW_VERSIONS -from selfdrive.car.car_helpers import get_car +from selfdrive.car.car_helpers import get_car, interfaces from selfdrive.manager.process import PythonProcess from selfdrive.manager.process_config import managed_processes @@ -148,7 +148,7 @@ class FakePubMaster(messaging.PubMaster): return dat -def fingerprint(msgs, fsm, can_sock): +def fingerprint(msgs, fsm, can_sock, fingerprint): print("start fingerprinting") fsm.wait_on_getitem = True @@ -172,14 +172,18 @@ def fingerprint(msgs, fsm, can_sock): print("finished fingerprinting") -def get_car_params(msgs, fsm, can_sock): - can = FakeSocket(wait=False) - sendcan = FakeSocket(wait=False) +def get_car_params(msgs, fsm, can_sock, fingerprint): + if fingerprint: + CarInterface, _, _ = interfaces[fingerprint] + CP = CarInterface.get_params(fingerprint) + else: + can = FakeSocket(wait=False) + sendcan = FakeSocket(wait=False) - canmsgs = [msg for msg in msgs if msg.which() == 'can'] - for m in canmsgs[:300]: - can.send(m.as_builder().to_bytes()) - _, CP = get_car(can, sendcan) + canmsgs = [msg for msg in msgs if msg.which() == 'can'] + for m in canmsgs[:300]: + can.send(m.as_builder().to_bytes()) + _, CP = get_car(can, sendcan) Params().put("CarParams", CP.to_bytes()) def controlsd_rcv_callback(msg, CP, cfg, fsm): @@ -328,14 +332,14 @@ CONFIGS = [ ] -def replay_process(cfg, lr): +def replay_process(cfg, lr, fingerprint=None): if cfg.fake_pubsubmaster: - return python_replay_process(cfg, lr) + return python_replay_process(cfg, lr, fingerprint) else: - return cpp_replay_process(cfg, lr) + return cpp_replay_process(cfg, lr, fingerprint) -def python_replay_process(cfg, lr): +def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] pub_sockets = [s for s in cfg.pub_sub.keys() if s != 'can'] @@ -356,8 +360,6 @@ def python_replay_process(cfg, lr): params.put_bool("CommunityFeaturesToggle", True) os.environ['NO_RADAR_SLEEP'] = "1" - os.environ['SKIP_FW_QUERY'] = "" - os.environ['FINGERPRINT'] = "" # TODO: remove after getting new route for civic & accord migration = { @@ -365,14 +367,20 @@ def python_replay_process(cfg, lr): "HONDA ACCORD 2018 SPORT 2T": "HONDA ACCORD 2018 2T", } - for msg in lr: - if msg.which() == 'carParams': - car_fingerprint = migration.get(msg.carParams.carFingerprint, msg.carParams.carFingerprint) - if len(msg.carParams.carFw) and (car_fingerprint in FW_VERSIONS): - params.put("CarParamsCache", msg.carParams.as_builder().to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = "1" - os.environ['FINGERPRINT'] = car_fingerprint + if fingerprint is not None: + os.environ['SKIP_FW_QUERY'] = "1" + os.environ['FINGERPRINT'] = fingerprint + else: + os.environ['SKIP_FW_QUERY'] = "" + os.environ['FINGERPRINT'] = "" + for msg in lr: + if msg.which() == 'carParams': + car_fingerprint = migration.get(msg.carParams.carFingerprint, msg.carParams.carFingerprint) + if len(msg.carParams.carFw) and (car_fingerprint in FW_VERSIONS): + params.put("CarParamsCache", msg.carParams.as_builder().to_bytes()) + else: + os.environ['SKIP_FW_QUERY'] = "1" + os.environ['FINGERPRINT'] = car_fingerprint assert(type(managed_processes[cfg.proc_name]) is PythonProcess) managed_processes[cfg.proc_name].prepare() @@ -385,7 +393,7 @@ def python_replay_process(cfg, lr): if cfg.init_callback is not None: if 'can' not in list(cfg.pub_sub.keys()): can_sock = None - cfg.init_callback(all_msgs, fsm, can_sock) + cfg.init_callback(all_msgs, fsm, can_sock, fingerprint) CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) @@ -421,7 +429,7 @@ def python_replay_process(cfg, lr): return log_msgs -def cpp_replay_process(cfg, lr): +def cpp_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] # We get responses here pm = messaging.PubMaster(cfg.pub_sub.keys()) sockets = {s: messaging.sub_sock(s, timeout=1000) for s in sub_sockets} diff --git a/selfdrive/test/process_replay/test_fuzzy.py b/selfdrive/test/process_replay/test_fuzzy.py new file mode 100755 index 00000000..3f9ac283 --- /dev/null +++ b/selfdrive/test/process_replay/test_fuzzy.py @@ -0,0 +1,180 @@ +#!/usr/bin/env python3 +import sys +import unittest +from collections import Counter + +import hypothesis.strategies as st +import numpy as np +from hypothesis import assume, given, settings + +from cereal import log +from selfdrive.car.toyota.values import CAR as TOYOTA +from selfdrive.test.process_replay.process_replay import (CONFIGS, + replay_process) + + +def get_process_config(process): + return [cfg for cfg in CONFIGS if cfg.proc_name == process][0] + + +def get_event_union_strategy(r, name): + return st.fixed_dictionaries({ + 'valid': st.booleans(), + 'logMonoTime': st.integers(min_value=0, max_value=2**64-1), + name: r[name[0].upper() + name[1:]], + }) + + +def get_strategy_for_events(event_types, finite=False): + # TODO: generate automatically based on capnp definitions + def floats(**kwargs): + allow_nan = False if finite else None + allow_infinity = False if finite else None + return st.floats(**kwargs, allow_nan=allow_nan, allow_infinity=allow_infinity) + + r = {} + r['liveLocationKalman.Measurement'] = st.fixed_dictionaries({ + 'value': st.lists(floats(), min_size=3, max_size=3), + 'std': st.lists(floats(), min_size=3, max_size=3), + 'valid': st.booleans(), + }) + r['LiveLocationKalman'] = st.fixed_dictionaries({ + 'angularVelocityCalibrated': r['liveLocationKalman.Measurement'], + 'inputsOK': st.booleans(), + 'posenetOK': st.booleans(), + }) + r['CarState'] = st.fixed_dictionaries({ + 'vEgo': floats(width=32), + 'vEgoRaw': floats(width=32), + 'steeringPressed': st.booleans(), + 'steeringAngleDeg': floats(width=32), + }) + r['CameraOdometry'] = st.fixed_dictionaries({ + 'frameId': st.integers(min_value=0, max_value=2**32-1), + 'timestampEof': st.integers(min_value=0, max_value=2**64-1), + 'trans': st.lists(floats(width=32), min_size=3, max_size=3), + 'rot': st.lists(floats(width=32), min_size=3, max_size=3), + 'transStd': st.lists(floats(width=32), min_size=3, max_size=3), + 'rotStd': st.lists(floats(width=32), min_size=3, max_size=3), + }) + r['SensorEventData.SensorVec'] = st.fixed_dictionaries({ + 'v': st.lists(floats(width=32), min_size=3, max_size=3), + 'status': st.integers(min_value=0, max_value=1), + }) + r['SensorEventData_gyro'] = st.fixed_dictionaries({ + 'version': st.just(1), + 'sensor': st.just(5), + 'type': st.just(16), # BMX055 + 'timestamp': st.integers(min_value=0, max_value=2**63-1), + 'source': st.just(8), + 'gyroUncalibrated': r['SensorEventData.SensorVec'], + }) + r['SensorEventData_accel'] = st.fixed_dictionaries({ + 'version': st.just(1), + 'sensor': st.just(1), + 'type': st.just(1), # BMX055 + 'timestamp': st.integers(min_value=0, max_value=2**63-1), + 'source': st.just(8), + 'acceleration': r['SensorEventData.SensorVec'], + }) + r['SensorEvents'] = st.lists(st.one_of(r['SensorEventData_gyro'], r['SensorEventData_accel']), min_size=1) + r['GpsLocationExternal'] = st.fixed_dictionaries({ + 'flags': st.integers(min_value=0, max_value=1), + 'latitude': floats(), + 'longitude': floats(), + 'altitude': floats(), + 'speed': floats(width=32), + 'bearingDeg': floats(width=32), + 'accuracy': floats(width=32), + 'timestamp': st.integers(min_value=0, max_value=2**63-1), + 'source': st.just(6), # Ublox + 'vNED': st.lists(floats(width=32), min_size=3, max_size=3), + 'verticalAccuracy': floats(width=32), + 'bearingAccuracyDeg': floats(width=32), + 'speedAccuracy': floats(width=32), + }) + r['LiveCalibration'] = st.fixed_dictionaries({ + 'calStatus': st.integers(min_value=0, max_value=1), + 'rpyCalib': st.lists(floats(width=32), min_size=3, max_size=3), + }) + + return st.lists(st.one_of(*[get_event_union_strategy(r, n) for n in event_types])) + + +def get_strategy_for_process(process, finite=False): + return get_strategy_for_events(get_process_config(process).pub_sub.keys(), finite) + + +def convert_to_lr(msgs): + return [log.Event.new_message(**m).as_reader() for m in msgs] + + +def assume_all_services_present(cfg, lr): + tps = Counter([m.which() for m in lr]) + for p in cfg.pub_sub: + assume(tps[p] > 0) + + +def is_finite(d, exclude=[], prefix=""): # pylint: disable=dangerous-default-value + ret = True + for k, v in d.items(): + name = prefix + f"{k}" + if name in exclude: + continue + + if isinstance(v, dict): + ret = ret and is_finite(v, exclude, name + ".") + else: + try: + ret = ret and np.isfinite(v).all() + except TypeError: + pass + + return ret + + +def test_process(dat, name): + cfg = get_process_config(name) + lr = convert_to_lr(dat) + assume_all_services_present(cfg, lr) + return replay_process(cfg, lr, TOYOTA.COROLLA_TSS2) + + +class TestFuzzy(unittest.TestCase): + @given(get_strategy_for_process('paramsd')) + @settings(deadline=1000) + def test_paramsd(self, dat): + for r in test_process(dat, 'paramsd'): + lp = r.liveParameters.to_dict() + assert is_finite(lp) + + @given(get_strategy_for_process('locationd', finite=True)) + @settings(deadline=10000) + def test_locationd(self, dat): + exclude = [ + 'positionGeodetic.std', + 'velocityNED.std', + 'orientationNED.std', + 'calibratedOrientationECEF.std', + ] + for r in test_process(dat, 'locationd'): + lp = r.liveLocationKalman.to_dict() + assert is_finite(lp, exclude) + + +if __name__ == "__main__": + procs = { + 'locationd': TestFuzzy().test_locationd, + 'paramsd': TestFuzzy().test_paramsd, + } + + if len(sys.argv) != 2: + print("Usage: ./test_fuzzy.py ") + sys.exit(0) + + proc = sys.argv[1] + if proc not in procs: + print(f"{proc} not available") + sys.exit(0) + else: + procs[proc]()