src: implement simulation data sources
This commit is contained in:
@@ -1,5 +1,5 @@
|
||||
[target.xtensa-esp32s3-none-elf]
|
||||
runner = "espflash flash --monitor --chip esp32s3"
|
||||
runner = "espflash flash --monitor --chip esp32s3 --partition-table ./partitions.csv"
|
||||
|
||||
[env]
|
||||
ESP_LOG="info"
|
||||
|
||||
343
Cargo.lock
generated
343
Cargo.lock
generated
@@ -44,6 +44,12 @@ dependencies = [
|
||||
"serde",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "bitfield"
|
||||
version = "0.14.0"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "2d7e60934ceec538daadb9d8432424ed043a904d8e0243f3c6446bce549a46ac"
|
||||
|
||||
[[package]]
|
||||
name = "bitfield"
|
||||
version = "0.19.2"
|
||||
@@ -61,7 +67,7 @@ checksum = "52511b09931f7d5fe3a14f23adefbc23e5725b184013e96c8419febb61f14734"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -76,6 +82,65 @@ version = "2.9.4"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "2261d10cca569e4643e526d8dc2e62e433cc8aba21ab764233731f8d369bf394"
|
||||
|
||||
[[package]]
|
||||
name = "bleps"
|
||||
version = "0.1.0"
|
||||
source = "git+https://github.com/bjoernQ/bleps?rev=a5148d8ae679e021b78f53fd33afb8bb35d0b62e#a5148d8ae679e021b78f53fd33afb8bb35d0b62e"
|
||||
dependencies = [
|
||||
"bitfield 0.14.0",
|
||||
"bleps-dedup",
|
||||
"bleps-macros",
|
||||
"critical-section",
|
||||
"embedded-io",
|
||||
"embedded-io-async",
|
||||
"futures",
|
||||
"log",
|
||||
"rand_core 0.6.4",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "bleps-dedup"
|
||||
version = "0.1.0"
|
||||
source = "git+https://github.com/bjoernQ/bleps?rev=a5148d8ae679e021b78f53fd33afb8bb35d0b62e#a5148d8ae679e021b78f53fd33afb8bb35d0b62e"
|
||||
dependencies = [
|
||||
"darling 0.20.11",
|
||||
"proc-macro-error",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "bleps-macros"
|
||||
version = "0.1.0"
|
||||
source = "git+https://github.com/bjoernQ/bleps?rev=a5148d8ae679e021b78f53fd33afb8bb35d0b62e#a5148d8ae679e021b78f53fd33afb8bb35d0b62e"
|
||||
dependencies = [
|
||||
"litrs 0.2.3",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn 1.0.109",
|
||||
"uuid",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "bt-hci"
|
||||
version = "0.3.2"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "fa7f7c19df9648c1da4f5356c4256533e38bd65633b6a41654922475a1c6d777"
|
||||
dependencies = [
|
||||
"embassy-sync 0.7.2",
|
||||
"embedded-io",
|
||||
"embedded-io-async",
|
||||
"futures-intrusive",
|
||||
"heapless",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "bumpalo"
|
||||
version = "3.19.0"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "46c5e41b57b8bba42a04676d81cb89e9ee8e859a1a66f80a5a72e1cb76b34d43"
|
||||
|
||||
[[package]]
|
||||
name = "bytemuck"
|
||||
version = "1.23.2"
|
||||
@@ -125,6 +190,15 @@ dependencies = [
|
||||
"typenum",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "csv-core"
|
||||
version = "0.1.12"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "7d02f3b0da4c6504f86e9cd789d8dbafab48c2321be74e9987593de5a894d93d"
|
||||
dependencies = [
|
||||
"memchr",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "darling"
|
||||
version = "0.20.11"
|
||||
@@ -156,7 +230,7 @@ dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"strsim",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -169,7 +243,7 @@ dependencies = [
|
||||
"ident_case",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -180,7 +254,7 @@ checksum = "fc34b93ccb385b40dc71c6fceac4b2ad23662c7eeb248cf10d529b7e055b6ead"
|
||||
dependencies = [
|
||||
"darling_core 0.20.11",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -191,7 +265,7 @@ checksum = "d38308df82d1080de0afee5d069fa14b0326a88c14f15c5ccda35b4a6c414c81"
|
||||
dependencies = [
|
||||
"darling_core 0.21.3",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -202,7 +276,7 @@ checksum = "6178a82cf56c836a3ba61a7935cdb1c49bfaa6fa4327cd5bf554a503087de26b"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -220,7 +294,7 @@ version = "0.2.11"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "95249b50c6c185bee49034bcb378a49dc2b5dff0be90ff6616d31d64febab05d"
|
||||
dependencies = [
|
||||
"litrs",
|
||||
"litrs 0.4.2",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -296,7 +370,7 @@ dependencies = [
|
||||
"darling 0.20.11",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -539,7 +613,7 @@ dependencies = [
|
||||
"darling 0.21.3",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -609,7 +683,7 @@ version = "1.0.0-rc.0"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "f3887eda2917deef3d99e7a5c324f9190714e99055361ad36890dffd0a995b49"
|
||||
dependencies = [
|
||||
"bitfield",
|
||||
"bitfield 0.19.2",
|
||||
"bitflags 2.9.4",
|
||||
"bytemuck",
|
||||
"cfg-if",
|
||||
@@ -687,12 +761,12 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "fbece384edaf0d1eabfa45afa96d910634d4158638ef983b2d419a8dec832246"
|
||||
dependencies = [
|
||||
"document-features",
|
||||
"litrs",
|
||||
"litrs 0.4.2",
|
||||
"object",
|
||||
"proc-macro-crate",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
"termcolor",
|
||||
]
|
||||
|
||||
@@ -797,6 +871,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "84908f2e95cb99a200cf448abafc416576338be590778a15d9224eee237f3210"
|
||||
dependencies = [
|
||||
"allocator-api2",
|
||||
"bt-hci",
|
||||
"cfg-if",
|
||||
"critical-section",
|
||||
"document-features",
|
||||
@@ -930,12 +1005,52 @@ dependencies = [
|
||||
"gcd",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "futures"
|
||||
version = "0.3.31"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "65bc07b1a8bc7c85c5f2e110c476c7389b4554ba72af57d8445ea63a576b0876"
|
||||
dependencies = [
|
||||
"futures-channel",
|
||||
"futures-core",
|
||||
"futures-io",
|
||||
"futures-sink",
|
||||
"futures-task",
|
||||
"futures-util",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "futures-channel"
|
||||
version = "0.3.31"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "2dff15bf788c671c1934e366d07e30c1814a8ef514e1af724a602e8a2fbe1b10"
|
||||
dependencies = [
|
||||
"futures-core",
|
||||
"futures-sink",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "futures-core"
|
||||
version = "0.3.31"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "05f29059c0c2090612e8d742178b0580d2dc940c837851ad723096f87af6663e"
|
||||
|
||||
[[package]]
|
||||
name = "futures-intrusive"
|
||||
version = "0.5.0"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "1d930c203dd0b6ff06e0201a4a2fe9149b43c684fd4420555b26d21b1a02956f"
|
||||
dependencies = [
|
||||
"futures-core",
|
||||
"lock_api",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "futures-io"
|
||||
version = "0.3.31"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "9e5c1b78ca4aae1ac06c48a526a655760685149f0d465d21f37abfe57ce075c6"
|
||||
|
||||
[[package]]
|
||||
name = "futures-sink"
|
||||
version = "0.3.31"
|
||||
@@ -955,6 +1070,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "9fa08315bb612088cc391249efdc3bc77536f16c91f6cf495e6fbe85b20a4a81"
|
||||
dependencies = [
|
||||
"futures-core",
|
||||
"futures-sink",
|
||||
"futures-task",
|
||||
"pin-project-lite",
|
||||
"pin-utils",
|
||||
@@ -1040,7 +1156,7 @@ dependencies = [
|
||||
"indoc",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1070,7 +1186,17 @@ checksum = "03343451ff899767262ec32146f6d559dd759fdadf42ff0e227c7c48f72594b4"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "js-sys"
|
||||
version = "0.3.80"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "852f13bec5eba4ba9afbeb93fd7c13fe56147f055939ae21c43a29a0ecb2702e"
|
||||
dependencies = [
|
||||
"once_cell",
|
||||
"wasm-bindgen",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1094,6 +1220,15 @@ version = "0.10.5"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286"
|
||||
|
||||
[[package]]
|
||||
name = "litrs"
|
||||
version = "0.2.3"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "f9275e0933cf8bb20f008924c0cb07a0692fe54d8064996520bf998de9eb79aa"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "litrs"
|
||||
version = "0.4.2"
|
||||
@@ -1103,6 +1238,16 @@ dependencies = [
|
||||
"proc-macro2",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "lock_api"
|
||||
version = "0.4.13"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "96936507f153605bddfcda068dd804796c84324ed2510809e5b2a624c81da765"
|
||||
dependencies = [
|
||||
"autocfg",
|
||||
"scopeguard",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "log"
|
||||
version = "0.4.28"
|
||||
@@ -1214,7 +1359,7 @@ checksum = "ed3955f1a9c7c0c15e092f9c887db08b1fc683305fdf6eb6684f22555355e202"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1255,6 +1400,12 @@ dependencies = [
|
||||
"memchr",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "once_cell"
|
||||
version = "1.21.3"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "42f5e15c9953c5e4ccceeb2e7382a716482c34515315f7b03532b8b4e8393d2d"
|
||||
|
||||
[[package]]
|
||||
name = "paste"
|
||||
version = "1.0.15"
|
||||
@@ -1306,7 +1457,7 @@ checksum = "a33fa6ec7f2047f572d49317cca19c87195de99c6e5b6ee492da701cfe02b053"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1318,6 +1469,30 @@ dependencies = [
|
||||
"toml_edit",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "proc-macro-error"
|
||||
version = "1.0.4"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c"
|
||||
dependencies = [
|
||||
"proc-macro-error-attr",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn 1.0.109",
|
||||
"version_check",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "proc-macro-error-attr"
|
||||
version = "1.0.4"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"version_check",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "proc-macro2"
|
||||
version = "1.0.101"
|
||||
@@ -1365,7 +1540,9 @@ name = "renderbug-embassy"
|
||||
version = "0.1.0"
|
||||
dependencies = [
|
||||
"anyhow",
|
||||
"bleps",
|
||||
"critical-section",
|
||||
"csv-core",
|
||||
"embassy-embedded-hal 0.5.0",
|
||||
"embassy-executor",
|
||||
"embassy-net",
|
||||
@@ -1390,6 +1567,7 @@ dependencies = [
|
||||
"nalgebra",
|
||||
"nmea",
|
||||
"rgb",
|
||||
"serde_json",
|
||||
"smart-leds",
|
||||
"smart-leds-trait",
|
||||
"smoltcp",
|
||||
@@ -1436,7 +1614,7 @@ checksum = "f265be5d634272320a7de94cea15c22a3bfdd4eb42eb43edc528415f066a1f25"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1453,15 +1631,27 @@ checksum = "fc71814687c45ba4cd1e47a54e03a2dbc62ca3667098fbae9cc6b423956758fa"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "rustversion"
|
||||
version = "1.0.22"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "b39cdef0fa800fc44525c84ccb54a029961a8215f9619753635a9c0d2538d46d"
|
||||
|
||||
[[package]]
|
||||
name = "ryu"
|
||||
version = "1.0.20"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "28d3b2b1366ec20994f1fd18c3c594f05c5dd4bc44d8bb0c1c632c8d6829481f"
|
||||
|
||||
[[package]]
|
||||
name = "scopeguard"
|
||||
version = "1.2.0"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49"
|
||||
|
||||
[[package]]
|
||||
name = "semihosting"
|
||||
version = "0.1.20"
|
||||
@@ -1470,22 +1660,45 @@ checksum = "c3e1c7d2b77d80283c750a39c52f1ab4d17234e8f30bca43550f5b2375f41d5f"
|
||||
|
||||
[[package]]
|
||||
name = "serde"
|
||||
version = "1.0.219"
|
||||
version = "1.0.226"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "5f0e2c6ed6606019b4e29e69dbaba95b11854410e5347d525002456dbbb786b6"
|
||||
checksum = "0dca6411025b24b60bfa7ec1fe1f8e710ac09782dca409ee8237ba74b51295fd"
|
||||
dependencies = [
|
||||
"serde_core",
|
||||
"serde_derive",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "serde_core"
|
||||
version = "1.0.226"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "ba2ba63999edb9dac981fb34b3e5c0d111a69b0924e253ed29d83f7c99e966a4"
|
||||
dependencies = [
|
||||
"serde_derive",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "serde_derive"
|
||||
version = "1.0.219"
|
||||
version = "1.0.226"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "5b0276cf7f2c73365f7157c8123c21cd9a50fbbd844757af28ca1f5925fc2a00"
|
||||
checksum = "8db53ae22f34573731bafa1db20f04027b2d25e02d8205921b569171699cdb33"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "serde_json"
|
||||
version = "1.0.145"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "402a6f66d8c709116cf22f558eab210f5a50187f702eb4d7e5ef38d9a7f1c79c"
|
||||
dependencies = [
|
||||
"itoa",
|
||||
"memchr",
|
||||
"ryu",
|
||||
"serde",
|
||||
"serde_core",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1584,7 +1797,18 @@ dependencies = [
|
||||
"heck",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "syn"
|
||||
version = "1.0.109"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"unicode-ident",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
@@ -1658,6 +1882,16 @@ dependencies = [
|
||||
"portable-atomic",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "uuid"
|
||||
version = "1.18.1"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "2f87b8aa10b915a06587d0dec516c282ff295b475d94abf425d62b57710070a2"
|
||||
dependencies = [
|
||||
"js-sys",
|
||||
"wasm-bindgen",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "vcell"
|
||||
version = "0.1.3"
|
||||
@@ -1676,6 +1910,65 @@ version = "1.0.2"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d"
|
||||
|
||||
[[package]]
|
||||
name = "wasm-bindgen"
|
||||
version = "0.2.103"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "ab10a69fbd0a177f5f649ad4d8d3305499c42bab9aef2f7ff592d0ec8f833819"
|
||||
dependencies = [
|
||||
"cfg-if",
|
||||
"once_cell",
|
||||
"rustversion",
|
||||
"wasm-bindgen-macro",
|
||||
"wasm-bindgen-shared",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "wasm-bindgen-backend"
|
||||
version = "0.2.103"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "0bb702423545a6007bbc368fde243ba47ca275e549c8a28617f56f6ba53b1d1c"
|
||||
dependencies = [
|
||||
"bumpalo",
|
||||
"log",
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn 2.0.106",
|
||||
"wasm-bindgen-shared",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "wasm-bindgen-macro"
|
||||
version = "0.2.103"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "fc65f4f411d91494355917b605e1480033152658d71f722a90647f56a70c88a0"
|
||||
dependencies = [
|
||||
"quote",
|
||||
"wasm-bindgen-macro-support",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "wasm-bindgen-macro-support"
|
||||
version = "0.2.103"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "ffc003a991398a8ee604a401e194b6b3a39677b3173d6e74495eb51b82e99a32"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn 2.0.106",
|
||||
"wasm-bindgen-backend",
|
||||
"wasm-bindgen-shared",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "wasm-bindgen-shared"
|
||||
version = "0.2.103"
|
||||
source = "registry+https://github.com/rust-lang/crates.io-index"
|
||||
checksum = "293c37f4efa430ca14db3721dfbe48d8c33308096bd44d80ebaa775ab71ba1cf"
|
||||
dependencies = [
|
||||
"unicode-ident",
|
||||
]
|
||||
|
||||
[[package]]
|
||||
name = "winapi-util"
|
||||
version = "0.1.11"
|
||||
@@ -1738,5 +2031,5 @@ checksum = "c5a56a616147f5947ceb673790dd618d77b30e26e677f4a896df049d73059438"
|
||||
dependencies = [
|
||||
"proc-macro2",
|
||||
"quote",
|
||||
"syn",
|
||||
"syn 2.0.106",
|
||||
]
|
||||
|
||||
@@ -54,6 +54,7 @@ esp-wifi = { version = "0.15.0", features = [
|
||||
"log-04",
|
||||
"smoltcp",
|
||||
"wifi",
|
||||
"ble"
|
||||
] }
|
||||
smoltcp = { version = "0.12.0", default-features = false, features = [
|
||||
"log",
|
||||
@@ -89,9 +90,12 @@ embassy-embedded-hal = "0.5.0"
|
||||
embedded-hal-async = "1.0.0"
|
||||
smart-leds-trait = "0.3.1"
|
||||
anyhow = { version = "1.0.99", default-features = false }
|
||||
kfilter = "0.4.0"
|
||||
nalgebra = { version = "0.33.2", default-features = false }
|
||||
esp-storage = { version = "0.7.0", features = ["esp32s3"] }
|
||||
bleps = { git = "https://github.com/bjoernQ/bleps", package = "bleps", rev = "a5148d8ae679e021b78f53fd33afb8bb35d0b62e", features = [ "macros", "async"] }
|
||||
serde_json = {version = "1.0.145", default-features = false, features = ["alloc"] }
|
||||
csv-core = "0.1.12"
|
||||
kfilter = "0.4.0"
|
||||
|
||||
[profile.dev]
|
||||
# Rust debug is too slow.
|
||||
|
||||
5
partitions.csv
Normal file
5
partitions.csv
Normal file
@@ -0,0 +1,5 @@
|
||||
# Name, Type, SubType, Offset, Size, Flags
|
||||
# Note: if you have increased the bootloader size, make sure to update the offsets to avoid overlap
|
||||
nvs, data, nvs, , 0x6000,
|
||||
phy_init, data, phy, , 0x1000,
|
||||
factory, app, factory, , 3M,
|
||||
|
@@ -56,14 +56,14 @@ impl Backoff {
|
||||
'outer: loop {
|
||||
for attempt in self.attempts {
|
||||
match &latest {
|
||||
Err(_) => {
|
||||
Err(err) => {
|
||||
match attempt {
|
||||
Attempts::Finite(1) => {
|
||||
warn!("Operation failed on final attempt.");
|
||||
warn!("Operation failed on final attempt: {err:?}");
|
||||
break 'outer
|
||||
}
|
||||
attempt => {
|
||||
warn!("Operation failed. Retrying attempt {attempt:?} after {delay}");
|
||||
warn!("Operation failed: {err:?} Retrying attempt {attempt:?} after {delay}");
|
||||
Timer::after(delay).await;
|
||||
delay *= 2;
|
||||
latest = f().await
|
||||
|
||||
212
src/bin/main.rs
212
src/bin/main.rs
@@ -7,32 +7,44 @@
|
||||
)]
|
||||
#![feature(future_join)]
|
||||
|
||||
use core::ptr::addr_of_mut;
|
||||
|
||||
use bleps::ad_structure::{create_advertising_data, AdStructure, BR_EDR_NOT_SUPPORTED, LE_GENERAL_DISCOVERABLE};
|
||||
use bleps::attribute_server::{AttributeServer, NotificationData};
|
||||
use bleps::{gatt, Ble, HciConnector};
|
||||
use embassy_embedded_hal::shared_bus::asynch::i2c::I2cDevice;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::channel::DynamicReceiver;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use embassy_time::{Instant, Timer};
|
||||
use esp_backtrace as _;
|
||||
use esp_hal::i2c::master::{Config, I2c};
|
||||
use esp_hal::gpio::Pin;
|
||||
use esp_hal::i2c::master::{Config, I2c};
|
||||
use esp_hal::interrupt::software::SoftwareInterruptControl;
|
||||
use esp_hal::system::{AppCoreGuard, CpuControl, Stack};
|
||||
use esp_hal::timer::AnyTimer;
|
||||
use esp_hal::Async;
|
||||
use esp_hal::clock::CpuClock;
|
||||
use esp_hal::rmt::Rmt;
|
||||
use esp_hal::time::Rate;
|
||||
use esp_hal::timer::systimer::SystemTimer;
|
||||
use esp_hal::timer::timg::TimerGroup;
|
||||
use esp_hal_embassy::{Executor, InterruptExecutor};
|
||||
use esp_wifi::ble::controller::BleConnector;
|
||||
use figments::surface::BufferedSurfacePool;
|
||||
use log::info;
|
||||
use renderbug_embassy::events::BusGarage;
|
||||
use renderbug_embassy::events::{BusGarage, Measurement, Telemetry};
|
||||
use renderbug_embassy::tasks::simulation::{motion_simulation_task, location_simulation_task};
|
||||
use renderbug_embassy::tasks::ui::{Ui, ui_main};
|
||||
use renderbug_embassy::tasks::gps::gps_task;
|
||||
use renderbug_embassy::tasks::motion::motion_task;
|
||||
use serde_json::json;
|
||||
use static_cell::StaticCell;
|
||||
|
||||
use renderbug_embassy::{
|
||||
tasks::mpu::*,
|
||||
tasks::render::render
|
||||
};
|
||||
|
||||
extern crate alloc;
|
||||
|
||||
// This creates a default app-descriptor required by the esp-idf bootloader.
|
||||
@@ -41,6 +53,8 @@ esp_bootloader_esp_idf::esp_app_desc!();
|
||||
|
||||
static I2C_BUS: StaticCell<Mutex<CriticalSectionRawMutex, I2c<'static, Async>>> = StaticCell::new();
|
||||
static BUS_GARAGE: StaticCell<BusGarage> = StaticCell::new();
|
||||
static mut CORE2_STACK: Stack<8192> = Stack::new();
|
||||
static CORE_HANDLE: StaticCell<AppCoreGuard> = StaticCell::new();
|
||||
|
||||
#[esp_hal_embassy::main]
|
||||
async fn main(spawner: Spawner) {
|
||||
@@ -49,7 +63,7 @@ async fn main(spawner: Spawner) {
|
||||
let config = esp_hal::Config::default().with_cpu_clock(CpuClock::max());
|
||||
let peripherals = esp_hal::init(config);
|
||||
|
||||
esp_alloc::heap_allocator!(size: 64 * 1024);
|
||||
esp_alloc::heap_allocator!(size: 128 * 1024);
|
||||
|
||||
let timer0 = SystemTimer::new(peripherals.SYSTIMER);
|
||||
esp_hal_embassy::init([timer0.alarm0, timer0.alarm1, timer0.alarm2]);
|
||||
@@ -57,31 +71,181 @@ async fn main(spawner: Spawner) {
|
||||
|
||||
let garage = BUS_GARAGE.init(Default::default());
|
||||
|
||||
info!("Setting up wifi");
|
||||
let rng = esp_hal::rng::Rng::new(peripherals.RNG);
|
||||
let timer1 = TimerGroup::new(peripherals.TIMG0);
|
||||
let wifi_init =
|
||||
esp_wifi::init(timer1.timer0, rng).expect("Failed to initialize WIFI/BLE controller");
|
||||
let (mut _wifi_controller, _interfaces) = esp_wifi::wifi::new(&wifi_init, peripherals.WIFI)
|
||||
.expect("Failed to initialize WIFI controller");
|
||||
info!("Setting up rendering pipeline");
|
||||
let mut surfaces = BufferedSurfacePool::default();
|
||||
let ui = Ui::new(&mut surfaces, &garage.display);
|
||||
|
||||
let swi = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);
|
||||
static STATIC_HI_EXEC: StaticCell<InterruptExecutor<0>> = StaticCell::new();
|
||||
let hi_exec = STATIC_HI_EXEC.init(InterruptExecutor::new(swi.software_interrupt0));
|
||||
let hi_spawn = hi_exec.start(esp_hal::interrupt::Priority::Priority1);
|
||||
hi_spawn.must_spawn(render(peripherals.RMT, peripherals.GPIO5.degrade(), surfaces, &garage.display));
|
||||
|
||||
info!("Launching i2c sensor tasks");
|
||||
let i2c = I2c::new(peripherals.I2C1, Config::default().with_frequency(Rate::from_khz(400)).with_timeout(esp_hal::i2c::master::BusTimeout::Maximum)).unwrap().with_scl(peripherals.GPIO4).with_sda(peripherals.GPIO3).into_async();
|
||||
let i2c_bus = I2C_BUS.init(Mutex::new(i2c));
|
||||
|
||||
spawner.must_spawn(mpu_task(garage.motion.sender(), garage.scenes.dyn_sender(), I2cDevice::new(i2c_bus)));
|
||||
spawner.must_spawn(gps_task(garage.motion.sender(), garage.scenes.dyn_sender(), I2cDevice::new(i2c_bus)));
|
||||
spawner.must_spawn(mpu_task(garage.motion.dyn_sender(), I2cDevice::new(i2c_bus)));
|
||||
spawner.must_spawn(gps_task(garage.motion.dyn_sender(), I2cDevice::new(i2c_bus)));
|
||||
|
||||
// TODO: Only run the motion sim sources with cfg(simulation)
|
||||
spawner.must_spawn(motion_simulation_task(garage.motion.dyn_sender()));
|
||||
spawner.must_spawn(location_simulation_task(garage.motion.dyn_sender()));
|
||||
|
||||
info!("Launching motion engine");
|
||||
spawner.must_spawn(motion_task(garage.motion.receiver(), garage.scenes.dyn_sender()));
|
||||
spawner.must_spawn(motion_task(garage.motion.dyn_receiver(), garage.scenes.dyn_sender(), garage.telemetry.dyn_sender()));
|
||||
|
||||
info!("Setting up rendering pipeline");
|
||||
let mut surfaces = BufferedSurfacePool::default();
|
||||
let ui = Ui::new(&mut surfaces, &garage.display);
|
||||
let frequency: Rate = Rate::from_mhz(80);
|
||||
let rmt = Rmt::new(peripherals.RMT, frequency)
|
||||
.expect("Failed to initialize RMT").into_async();
|
||||
let rmt_channel = rmt.channel0;
|
||||
spawner.must_spawn(render(rmt_channel, peripherals.GPIO5.degrade(), surfaces, &garage.display));
|
||||
spawner.must_spawn(ui_main(garage.scenes.dyn_receiver(), ui));
|
||||
info!("Starting communications and UI on core 2");
|
||||
let mut cpu_control = CpuControl::new(peripherals.CPU_CTRL);
|
||||
CORE_HANDLE.init(cpu_control.start_app_core(unsafe { &mut *addr_of_mut!(CORE2_STACK) }, || {
|
||||
static STATIC_EXEC: StaticCell<Executor> = StaticCell::new();
|
||||
let exec = STATIC_EXEC.init(Executor::new());
|
||||
exec.run(|spawner| {
|
||||
let timer1 = TimerGroup::new(peripherals.TIMG0);
|
||||
spawner.must_spawn(wifi_task(garage.telemetry.dyn_receiver(), timer1.timer0.into(), peripherals.RNG, peripherals.WIFI, peripherals.BT));
|
||||
spawner.must_spawn(ui_main(garage.scenes.dyn_receiver(), ui));
|
||||
});
|
||||
}).unwrap());
|
||||
|
||||
info!("System is ready in {}ms", Instant::now().as_millis());
|
||||
}
|
||||
|
||||
// TODO: Wifi task needs to know when there is data to upload, so it only connects when needed.
|
||||
#[embassy_executor::task]
|
||||
async fn wifi_task(telemetry: DynamicReceiver<'static, Telemetry>, timer: AnyTimer<'static>, rng: esp_hal::peripherals::RNG<'static>, _wifi_device: esp_hal::peripherals::WIFI<'static>, bluetooth_device: esp_hal::peripherals::BT<'static>) {
|
||||
let rng = esp_hal::rng::Rng::new(rng);
|
||||
let wifi_init =
|
||||
esp_wifi::init(timer, rng).expect("Failed to initialize WIFI/BLE controller");
|
||||
|
||||
info!("Setting up BLE stack");
|
||||
let connector = BleConnector::new(&wifi_init, bluetooth_device);
|
||||
let get_millis = || esp_hal::time::Instant::now().duration_since_epoch().as_millis();
|
||||
let hci = HciConnector::new(connector, get_millis);
|
||||
let mut ble = Ble::new(&hci);
|
||||
ble.init().unwrap();
|
||||
ble.cmd_set_le_advertising_parameters().unwrap();
|
||||
ble.cmd_set_le_advertising_data(
|
||||
create_advertising_data(&[
|
||||
AdStructure::Flags(LE_GENERAL_DISCOVERABLE | BR_EDR_NOT_SUPPORTED),
|
||||
AdStructure::ServiceUuids16(&[Uuid::Uuid16(0x0001)]),
|
||||
AdStructure::CompleteLocalName("Renderbug!")
|
||||
])
|
||||
.unwrap()
|
||||
).unwrap();
|
||||
ble.cmd_set_le_advertise_enable(true).unwrap();
|
||||
|
||||
let mut wf1 = |_offset: usize, data: &[u8]| {
|
||||
info!("Read serial data! {data:?}");
|
||||
};
|
||||
|
||||
let s = &b""[..];
|
||||
// Other useful characteristics:
|
||||
// 0x2A67 - Location and speed
|
||||
// 0x2A00 - Device name
|
||||
// 0x2B90 - Device time
|
||||
// Permitted characteristics:
|
||||
// Acceleration
|
||||
// Force
|
||||
// Length
|
||||
// Linear position
|
||||
// Rotational speed
|
||||
// Temperature
|
||||
// Torque
|
||||
// Useful app that logs data: https://github.com/a2ruan/ArduNetApp?tab=readme-ov-file
|
||||
// Requires service 4fafc201-1fb5-459e-8fcc-c5c9c331914b, characteristic beb5483e-36e1-4688-b7f5-ea07361b26a8
|
||||
gatt!([service {
|
||||
uuid: "6E400001-B5A3-F393-E0A9-E50E24DCCA9E", // Nordic UART
|
||||
characteristics: [
|
||||
characteristic {
|
||||
uuid: "6E400003-B5A3-F393-E0A9-E50E24DCCA9E", // TX from device, everything is sent as notifications
|
||||
notify: true,
|
||||
name: "tx",
|
||||
value: s
|
||||
},
|
||||
characteristic {
|
||||
uuid: "6E400002-B5A3-F393-E0A9-E50E24DCCA9E", // RX from phone
|
||||
write: wf1
|
||||
},
|
||||
]
|
||||
}]);
|
||||
let mut rng = bleps::no_rng::NoRng;
|
||||
let mut srv = AttributeServer::new(&mut ble, &mut gatt_attributes, &mut rng);
|
||||
|
||||
info!("BLE running!");
|
||||
// TODO: Somehow need to recreate the attributeserver after disconnecting?
|
||||
loop {
|
||||
let notification = match telemetry.try_receive() {
|
||||
Err(_) => None,
|
||||
//TODO: Should make Telemetry values serde-encodable
|
||||
Ok(Telemetry::Measurement(Measurement::IMU { accel, gyro })) => {
|
||||
let json_data = json!({
|
||||
"x": accel.x,
|
||||
"y": accel.y,
|
||||
"z": accel.z,
|
||||
"gx": gyro.x,
|
||||
"gy": gyro.y,
|
||||
"gz": gyro.z
|
||||
});
|
||||
let json_buf = serde_json::to_string(&json_data).unwrap();
|
||||
Some(json_buf)
|
||||
},
|
||||
Ok(Telemetry::Measurement(Measurement::GPS(Some(measurement)))) => {
|
||||
info!("gps telemetry");
|
||||
let json_data = json!({
|
||||
"lat": measurement.x,
|
||||
"lng": measurement.y
|
||||
});
|
||||
let json_buf = serde_json::to_string(&json_data).unwrap();
|
||||
Some(json_buf)
|
||||
},
|
||||
_ => None
|
||||
/*Ok(Measurement::Prediction(prediction)) => {
|
||||
let json_data = json!({
|
||||
"predict_lat": prediction.x,
|
||||
"predict_lng": prediction.y
|
||||
});
|
||||
let json_buf = serde_json::to_string(&json_data).unwrap();
|
||||
Some(json_buf)
|
||||
}*/
|
||||
};
|
||||
|
||||
match notification {
|
||||
None => {
|
||||
srv.do_work().unwrap();
|
||||
Timer::after_millis(5).await;
|
||||
},
|
||||
Some(serial_data) => {
|
||||
for chunk in serial_data.as_bytes().chunks(20) {
|
||||
srv.do_work_with_notification(Some(NotificationData::new(tx_handle, chunk))).unwrap();
|
||||
}
|
||||
srv.do_work_with_notification(Some(NotificationData::new(tx_handle, &b"\n"[..]))).unwrap();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
let (mut wifi, _interfaces) = esp_wifi::wifi::new(&wifi_init, wifi_device)
|
||||
.expect("Failed to initialize WIFI controller"); }
|
||||
|
||||
loop {
|
||||
//let results = wifi.scan_n_async(16).await.unwrap();
|
||||
wifi.set_configuration(&esp_wifi::wifi::Configuration::Client(
|
||||
ClientConfiguration {
|
||||
ssid: "The Frequency".to_string(),
|
||||
auth_method: esp_wifi::wifi::AuthMethod::WPA2Personal,
|
||||
password: "thepasswordkenneth".to_string(),
|
||||
..Default::default()
|
||||
}
|
||||
)).unwrap();
|
||||
|
||||
if wifi.connect_async().await.is_ok() {
|
||||
info!("Connected to wifi!");
|
||||
while wifi.is_connected().unwrap() {
|
||||
Timer::after_secs(60).await;
|
||||
}
|
||||
info!("Disconnected.");
|
||||
}
|
||||
Timer::after_secs(30).await;
|
||||
}
|
||||
*/
|
||||
}
|
||||
}
|
||||
@@ -1,26 +1,26 @@
|
||||
use figments::{hardware::{Brightness, Gamma}, mappings::linear::LinearSpace, power::AsMilliwatts, prelude::*, smart_leds::BrightnessWriter};
|
||||
use figments::{hardware::{Brightness, Gamma, OutputAsync}, mappings::linear::LinearSpace, power::AsMilliwatts, prelude::*, smart_leds::{BrightnessWriter, BrightnessWriterAsync}};
|
||||
use core::{fmt::Debug, ops::IndexMut};
|
||||
//use std::io::Write;
|
||||
|
||||
//use super::{Output};
|
||||
use figments::hardware::Output;
|
||||
use smart_leds::SmartLedsWriteAsync;
|
||||
use smart_leds::{SmartLedsWrite, SmartLedsWriteAsync};
|
||||
|
||||
pub trait LinearPixbuf: Pixbuf + Sample<'static, LinearSpace, Output = Self::Format> + IndexMut<usize, Output = Self::Format> + AsRef<[Self::Format]> {}
|
||||
impl<T> LinearPixbuf for T where T: Pixbuf + Sample<'static, LinearSpace, Output = Self::Format> + IndexMut<usize, Output = Self::Format> + AsRef<[Self::Format]> {}
|
||||
|
||||
pub struct BikeOutput<T: SmartLedsWriteAsync> {
|
||||
pub struct BikeOutput<T: SmartLedsWrite> {
|
||||
pixbuf: [T::Color; 178],
|
||||
writer: BrightnessWriter<T>
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> Debug for BikeOutput<T> {
|
||||
impl<T: SmartLedsWrite> Debug for BikeOutput<T> {
|
||||
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
|
||||
f.debug_struct("BikeOutput").field("pixbuf", &core::any::type_name_of_val(&self.pixbuf)).field("writer", &core::any::type_name_of_val(&self.writer)).finish()
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
impl<T: SmartLedsWrite> BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
pub fn new(target: T, max_mw: u32) -> Self {
|
||||
Self {
|
||||
pixbuf: [Default::default(); 178],
|
||||
@@ -29,7 +29,7 @@ impl<T: SmartLedsWriteAsync> BikeOutput<T> where T::Color: HardwarePixel + Gamma
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> Brightness for BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
impl<T: SmartLedsWrite> Brightness for BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
fn set_brightness(&mut self, brightness: u8) {
|
||||
self.writer.set_brightness(brightness);
|
||||
}
|
||||
@@ -43,13 +43,78 @@ impl<T: SmartLedsWriteAsync> Brightness for BikeOutput<T> where T::Color: Hardwa
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T: SmartLedsWriteAsync + 'a> Output<'a, BikeSpace> for BikeOutput<T> where T::Color: 'static + HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + Gamma + Copy, T::Error: core::fmt::Debug {
|
||||
async fn blank(&mut self) -> Result<(), Self::Error> {
|
||||
impl<'a, T: SmartLedsWrite + 'a> Output<'a, BikeSpace> for BikeOutput<T> where T::Color: 'static + HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + Gamma + Copy, T::Error: core::fmt::Debug {
|
||||
fn blank(&mut self) -> Result<(), Self::Error> {
|
||||
self.pixbuf.blank();
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn commit(&mut self) -> Result<(), Self::Error> {
|
||||
fn commit(&mut self) -> Result<(), Self::Error> {
|
||||
self.writer.write(&self.pixbuf)
|
||||
}
|
||||
|
||||
type HardwarePixel = T::Color;
|
||||
type Error = T::Error;
|
||||
}
|
||||
|
||||
impl<'a, T: SmartLedsWrite> Sample<'a, BikeSpace> for BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + 'static {
|
||||
type Output = T::Color;
|
||||
|
||||
fn sample(&mut self, rect: &Rectangle<BikeSpace>) -> impl Iterator<Item = (Coordinates<BikeSpace>, &'a mut Self::Output)> {
|
||||
let bufref = unsafe {
|
||||
&mut *(&mut self.pixbuf as *mut [T::Color; 178])
|
||||
};
|
||||
BikeIter {
|
||||
pixbuf: bufref,
|
||||
cur: rect.top_left,
|
||||
end: rect.bottom_right
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// ASYNC
|
||||
|
||||
pub struct BikeOutputAsync<T: SmartLedsWriteAsync> {
|
||||
pixbuf: [T::Color; 178],
|
||||
writer: BrightnessWriterAsync<T>
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> Debug for BikeOutputAsync<T> {
|
||||
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
|
||||
f.debug_struct("BikeOutput").field("pixbuf", &core::any::type_name_of_val(&self.pixbuf)).field("writer", &core::any::type_name_of_val(&self.writer)).finish()
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> BikeOutputAsync<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
pub fn new(target: T, max_mw: u32) -> Self {
|
||||
Self {
|
||||
pixbuf: [Default::default(); 178],
|
||||
writer: BrightnessWriterAsync::new(target, max_mw)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: SmartLedsWriteAsync> Brightness for BikeOutputAsync<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, T::Error: core::fmt::Debug {
|
||||
fn set_brightness(&mut self, brightness: u8) {
|
||||
self.writer.set_brightness(brightness);
|
||||
}
|
||||
|
||||
fn set_on(&mut self, is_on: bool) {
|
||||
self.writer.set_on(is_on);
|
||||
}
|
||||
|
||||
fn set_gamma(&mut self, gamma: f32) {
|
||||
self.writer.set_gamma(gamma);
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T: SmartLedsWriteAsync + 'a> OutputAsync<'a, BikeSpace> for BikeOutputAsync<T> where T::Color: 'static + HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + Gamma + Copy, T::Error: core::fmt::Debug {
|
||||
async fn blank_async(&mut self) -> Result<(), Self::Error> {
|
||||
self.pixbuf.blank();
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn commit_async(&mut self) -> Result<(), Self::Error> {
|
||||
self.writer.write(&self.pixbuf).await
|
||||
}
|
||||
|
||||
@@ -57,7 +122,7 @@ impl<'a, T: SmartLedsWriteAsync + 'a> Output<'a, BikeSpace> for BikeOutput<T> wh
|
||||
type Error = T::Error;
|
||||
}
|
||||
|
||||
impl<'a, T: SmartLedsWriteAsync> Sample<'a, BikeSpace> for BikeOutput<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + 'static {
|
||||
impl<'a, T: SmartLedsWriteAsync> Sample<'a, BikeSpace> for BikeOutputAsync<T> where T::Color: HardwarePixel + Gamma + Fract8Ops, [T::Color; 178]: AsMilliwatts + 'static {
|
||||
type Output = T::Color;
|
||||
|
||||
fn sample(&mut self, rect: &Rectangle<BikeSpace>) -> impl Iterator<Item = (Coordinates<BikeSpace>, &'a mut Self::Output)> {
|
||||
|
||||
@@ -1,56 +1,95 @@
|
||||
use log::*;
|
||||
use nalgebra::{Matrix3, Rotation3, Unit, Vector3};
|
||||
|
||||
use nalgebra::{Rotation3, Unit, Vector3, ComplexField};
|
||||
|
||||
use crate::CircularBuffer;
|
||||
|
||||
type Sample = Vector3<f32>; // [ax, ay, az] in m/s^2
|
||||
|
||||
#[derive(Debug, Clone, Copy)]
|
||||
#[derive(Debug, Clone, Copy, Default)]
|
||||
pub struct SensorAlignment {
|
||||
/// 3x3 transform matrix: raw -> body
|
||||
/// includes permutation, sign, and bias subtraction.
|
||||
pub transform: Rotation3<f32>,
|
||||
/// bias vector in body frame
|
||||
pub accel_bias: Vector3<f32>,
|
||||
/// bias vector in sensor frame
|
||||
pub bias: Vector3<f32>
|
||||
}
|
||||
|
||||
pub gyro_bias: Vector3<f32>,
|
||||
#[derive(Debug, Clone, Copy)]
|
||||
pub enum Direction {
|
||||
UpZ,
|
||||
DnZ,
|
||||
UpX,
|
||||
DnX,
|
||||
UpY,
|
||||
DnY
|
||||
}
|
||||
|
||||
impl From<Direction> for Unit<Vector3<f32>> {
|
||||
fn from(value: Direction) -> Self {
|
||||
Unit::new_normalize(match value {
|
||||
Direction::UpZ => Vector3::z(),
|
||||
Direction::DnZ => -Vector3::z(),
|
||||
Direction::UpX => Vector3::x(),
|
||||
Direction::DnX => -Vector3::x(),
|
||||
Direction::UpY => Vector3::y(),
|
||||
Direction::DnY => -Vector3::y(),
|
||||
})
|
||||
}
|
||||
}
|
||||
|
||||
impl SensorAlignment {
|
||||
pub fn apply(&self, raw: &Sample) -> Vector3<f32> {
|
||||
self.transform * raw - self.accel_bias
|
||||
self.transform * (raw - self.bias)
|
||||
}
|
||||
|
||||
pub fn apply_gyro(&self, raw: &Sample) -> Vector3<f32> {
|
||||
self.transform * raw - self.gyro_bias
|
||||
}
|
||||
|
||||
pub fn new(accel_samples: &[Sample], gyro_samples: &[Sample]) -> SensorAlignment {
|
||||
let avg: Vector3<f32> = accel_samples.iter().sum::<Vector3<f32>>() / (accel_samples.len() as f32);
|
||||
let down_body = Unit::new_normalize(avg);
|
||||
let down_world = Unit::new_normalize(Vector3::new(0.0, 0.0, -1.0));
|
||||
let rot_down = Rotation3::rotation_between(&down_world, &down_body).unwrap_or_else(Rotation3::identity);
|
||||
let forward_world = Vector3::x();
|
||||
|
||||
let forward_projected = (forward_world - forward_world.dot(&down_world) * down_world.into_inner()).normalize();
|
||||
|
||||
// Transform forward into the body frame
|
||||
let forward_body = rot_down * forward_projected;
|
||||
|
||||
// Construct a proper body frame basis
|
||||
let right_body = down_body.cross(&forward_body).normalize();
|
||||
let forward_body = right_body.cross(&down_body).normalize();
|
||||
|
||||
// Construct rotation matrix from basis vectors
|
||||
let rot = Matrix3::from_columns(&[forward_body, right_body, down_body.into_inner()]);
|
||||
let transform = Rotation3::from_matrix_unchecked(rot);
|
||||
|
||||
let gyro_avg: Vector3<f32> = gyro_samples.iter().sum::<Vector3<f32>>() / (gyro_samples.len() as f32);
|
||||
|
||||
info!("down_body={down_body:?} down_world={down_world:?}");
|
||||
pub fn from_samples(accel_samples: &[Sample], down_direction: Direction) -> SensorAlignment {
|
||||
let bias: Vector3<f32> = accel_samples.iter().sum::<Vector3<f32>>() / (accel_samples.len() as f32);
|
||||
// Figure out the unit vector pointing 'down' at rest
|
||||
let down_body = Unit::new_normalize(bias);
|
||||
// Create our 'true' down vector
|
||||
let down_world: Unit<Vector3<f32>> = down_direction.into();//Unit::new_normalize(Vector3::new(0.0, 0.0, -1.0));
|
||||
// Determine how the axes are rotated between the two
|
||||
let axis = down_body.cross(&down_world);
|
||||
let axis_unit = Unit::new_normalize(axis);
|
||||
let angle = down_body.dot(&down_world).clamp(-1.0, 1.0).acos();
|
||||
// Create a rotation matrix from the angles
|
||||
let transform = Rotation3::from_axis_angle(&axis_unit, angle);
|
||||
|
||||
Self {
|
||||
transform,
|
||||
accel_bias: transform * avg,
|
||||
gyro_bias: transform * gyro_avg
|
||||
bias,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct DirectionEstimator {
|
||||
buf: CircularBuffer<Vector3<f32>>,
|
||||
direction: Direction,
|
||||
pub alignment: SensorAlignment
|
||||
}
|
||||
|
||||
impl DirectionEstimator {
|
||||
pub fn new(direction: Direction) -> Self {
|
||||
Self {
|
||||
buf: Default::default(),
|
||||
alignment: Default::default(),
|
||||
direction,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl DirectionEstimator {
|
||||
pub fn update(&mut self, accel: Vector3<f32>) {
|
||||
self.buf.insert(accel);
|
||||
|
||||
if self.buf.next_index == 0 {
|
||||
self.alignment = SensorAlignment::from_samples(&self.buf.data, self.direction);
|
||||
}
|
||||
}
|
||||
|
||||
pub fn apply(&self, vec: &Vector3<f32>) -> Vector3<f32> {
|
||||
self.alignment.apply(vec)
|
||||
}
|
||||
}
|
||||
87
src/ego/kalman.rs
Normal file
87
src/ego/kalman.rs
Normal file
@@ -0,0 +1,87 @@
|
||||
#![allow(non_snake_case)] // TODO, because most of this code came from chatgpt and I'm still not sure if it actually works or is completely wrong
|
||||
use nalgebra::{SMatrix, SVector};
|
||||
|
||||
/// State: [px, py, vx, vy]
|
||||
pub type State = SVector<f32, 6>;
|
||||
pub type Control = SVector<f32, 3>; // dx, dx, yaw
|
||||
pub type GpsMeasurement = SVector<f32, 2>; // gps x, gps y
|
||||
|
||||
pub struct Kalman {
|
||||
x: State, // state estimate
|
||||
P: SMatrix<f32, 6, 6>, // covariance
|
||||
F: SMatrix<f32, 6, 6>, // state transition
|
||||
B: SMatrix<f32, 6, 3>, // control matrix
|
||||
H: SMatrix<f32, 2, 6>, // measurement matrix
|
||||
Q: SMatrix<f32, 6, 6>, // process noise
|
||||
R: SMatrix<f32, 2, 2>, // measurement noise
|
||||
}
|
||||
|
||||
impl Kalman {
|
||||
pub fn new(dt: f32) -> Self {
|
||||
let mut kf = Kalman {
|
||||
x: State::zeros(),
|
||||
P: SMatrix::identity(),
|
||||
F: SMatrix::identity(),
|
||||
B: SMatrix::zeros(),
|
||||
H: SMatrix::zeros(),
|
||||
Q: SMatrix::identity() * 0.1,
|
||||
R: SMatrix::identity() * 3.0, // GPS noise
|
||||
};
|
||||
|
||||
// F (state transition)
|
||||
kf.F[(0,2)] = dt;
|
||||
kf.F[(1,3)] = dt;
|
||||
kf.F[(4,5)] = dt;
|
||||
|
||||
// B (control matrix)
|
||||
kf.B[(0,0)] = 0.5 * dt * dt;
|
||||
kf.B[(1,1)] = 0.5 * dt * dt;
|
||||
kf.B[(2,0)] = dt;
|
||||
kf.B[(3,1)] = dt;
|
||||
kf.B[(5,2)] = dt;
|
||||
|
||||
// H (GPS: positions only)
|
||||
kf.H[(0,0)] = 1.0;
|
||||
kf.H[(1,1)] = 1.0;
|
||||
|
||||
kf
|
||||
}
|
||||
|
||||
pub fn predict(&mut self, u: &Control) {
|
||||
self.x = self.F * self.x + self.B * u;
|
||||
self.P = self.F * self.P * self.F.transpose() + self.Q;
|
||||
}
|
||||
|
||||
pub fn update(&mut self, z: &GpsMeasurement) {
|
||||
let y = z - self.H * self.x; // innovation
|
||||
let S = self.H * self.P * self.H.transpose() + self.R;
|
||||
if let Some(s_inv) = S.try_inverse() {
|
||||
let K = self.P * self.H.transpose() * s_inv;
|
||||
self.x += K * y;
|
||||
self.P = (SMatrix::<f32,6,6>::identity() - K * self.H) * self.P;
|
||||
}
|
||||
}
|
||||
|
||||
// Used to indicate stationary behavior and therefore velocities should be zero
|
||||
pub fn update_zupt(&mut self) {
|
||||
let z = SVector::<f32, 2>::zeros(); // velocity = 0
|
||||
let mut H = SMatrix::<f32, 2, 6>::zeros();
|
||||
H[(0,2)] = 1.0; // vx
|
||||
H[(1,3)] = 1.0; // vy
|
||||
|
||||
let R = SMatrix::<f32, 2, 2>::identity() * 0.01; // very confident
|
||||
|
||||
let y = z - H * self.x;
|
||||
let S = H * self.P * H.transpose() + R;
|
||||
|
||||
if let Some(s_inv) = S.try_inverse() {
|
||||
let k = self.P * H.transpose() * s_inv;
|
||||
self.x += k * y;
|
||||
self.P = (SMatrix::<f32,6,6>::identity() - k * H) * self.P;
|
||||
}
|
||||
}
|
||||
|
||||
pub fn state(&self) -> &State {
|
||||
&self.x
|
||||
}
|
||||
}
|
||||
@@ -1,3 +1,4 @@
|
||||
pub mod alignment;
|
||||
pub mod tilt;
|
||||
pub mod heading;
|
||||
pub mod heading;
|
||||
pub mod kalman;
|
||||
@@ -1,7 +1,8 @@
|
||||
|
||||
use core::sync::atomic::{AtomicBool, AtomicU8};
|
||||
|
||||
use embassy_sync::{blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}, channel::Channel};
|
||||
use embassy_sync::{blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}, channel::Channel, signal::Signal};
|
||||
use figments::hardware::Brightness;
|
||||
use nalgebra::{Vector2, Vector3};
|
||||
|
||||
#[derive(Clone, Copy, Default, Debug)]
|
||||
@@ -18,9 +19,22 @@ pub enum Scene {
|
||||
#[derive(Clone, Copy, Debug)]
|
||||
pub enum Measurement {
|
||||
// GPS coordinates
|
||||
GPS(Vector2<f64>),
|
||||
GPS(Option<Vector2<f64>>),
|
||||
// Accelerometer values in body frame where x=forwards
|
||||
IMU(Vector3<f32>)
|
||||
IMU { accel: Vector3<f32>, gyro: Vector3<f32> },
|
||||
}
|
||||
|
||||
#[derive(Clone, Copy, Debug)]
|
||||
pub enum Prediction {
|
||||
Location(Vector2<f32>),
|
||||
Velocity(Vector2<f32>)
|
||||
}
|
||||
|
||||
#[derive(Clone, Copy, Debug)]
|
||||
pub enum Telemetry {
|
||||
Prediction(Prediction),
|
||||
Measurement(Measurement),
|
||||
Notification(Notification)
|
||||
}
|
||||
|
||||
#[derive(Clone, Copy, Debug)]
|
||||
@@ -35,25 +49,53 @@ pub enum Notification {
|
||||
SetBrakelight(bool)
|
||||
}
|
||||
|
||||
#[derive(Debug)]
|
||||
// TODO: Make this clone() able, so multiple threads can point to the same underlying atomics for the hardware controls
|
||||
pub struct DisplayControls {
|
||||
pub on: AtomicBool,
|
||||
pub brightness: AtomicU8
|
||||
pub brightness: AtomicU8,
|
||||
pub render_is_running: Signal<CriticalSectionRawMutex, bool>
|
||||
}
|
||||
|
||||
impl Brightness for DisplayControls {
|
||||
fn set_brightness(&mut self, brightness: u8) {
|
||||
self.brightness.store(brightness, core::sync::atomic::Ordering::Relaxed);
|
||||
}
|
||||
|
||||
fn set_on(&mut self, is_on: bool) {
|
||||
self.on.store(is_on, core::sync::atomic::Ordering::Relaxed);
|
||||
}
|
||||
|
||||
// TODO: Split gamma out from brightness controls
|
||||
fn set_gamma(&mut self, _gamma: f32) {
|
||||
unimplemented!()
|
||||
}
|
||||
}
|
||||
|
||||
impl core::fmt::Debug for DisplayControls {
|
||||
fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> Result<(), core::fmt::Error> {
|
||||
f.debug_struct("DisplayControls")
|
||||
.field("on", &self.on)
|
||||
.field("brightness", &self.brightness)
|
||||
.field("render_is_running", &self.render_is_running.signaled())
|
||||
.finish()
|
||||
}
|
||||
}
|
||||
|
||||
impl Default for DisplayControls {
|
||||
fn default() -> Self {
|
||||
Self {
|
||||
on: AtomicBool::new(true),
|
||||
brightness: AtomicU8::new(255)
|
||||
brightness: AtomicU8::new(255),
|
||||
render_is_running: Signal::new()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct BusGarage {
|
||||
pub motion: Channel<NoopRawMutex, Measurement, 4>,
|
||||
pub scenes: Channel<CriticalSectionRawMutex, Notification, 4>,
|
||||
pub motion: Channel<NoopRawMutex, Measurement, 5>,
|
||||
pub scenes: Channel<CriticalSectionRawMutex, Notification, 5>,
|
||||
pub telemetry: Channel<CriticalSectionRawMutex, Telemetry, 15>,
|
||||
pub display: DisplayControls
|
||||
}
|
||||
|
||||
@@ -62,6 +104,7 @@ impl Default for BusGarage {
|
||||
Self {
|
||||
motion: Channel::new(),
|
||||
scenes: Channel::new(),
|
||||
telemetry: Channel::new(),
|
||||
display: Default::default()
|
||||
}
|
||||
}
|
||||
|
||||
26
src/lib.rs
26
src/lib.rs
@@ -35,4 +35,30 @@ pub fn as_milliwatts(pixel: &Rgb<u8>) -> u32 {
|
||||
let blue = (pixel.b as u32 * BLUE_MW).wrapping_shr(8);
|
||||
|
||||
red + green + blue + DARK_MW
|
||||
}
|
||||
|
||||
|
||||
#[derive(Debug)]
|
||||
pub struct CircularBuffer<T, const SIZE: usize = 20> {
|
||||
pub data: [T; SIZE],
|
||||
next_index: usize
|
||||
}
|
||||
|
||||
impl<T: Default + Copy, const SIZE: usize> Default for CircularBuffer<T, SIZE> {
|
||||
fn default() -> Self {
|
||||
Self {
|
||||
data: [Default::default(); SIZE],
|
||||
next_index: 0
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<T, const SIZE: usize> CircularBuffer<T, SIZE> {
|
||||
pub fn insert(&mut self, value: T) {
|
||||
self.data[self.next_index] = value;
|
||||
self.next_index += 1;
|
||||
if self.next_index == self.data.len() {
|
||||
self.next_index = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -37,9 +37,9 @@ impl Shader<Uniforms, BikeSpace, Rgba<u8>> for Background {
|
||||
pub struct Tail {}
|
||||
impl Shader<Uniforms, BikeSpace, Rgba<u8>> for Tail {
|
||||
fn draw(&self, coords: &Coordinates<BikeSpace>, uniforms: &Uniforms) -> Rgba<u8> {
|
||||
let hue_offset = 0u8.lerp8by8(16, sin8(uniforms.frame.wrapping_sub(coords.x))) as i8 - 8;
|
||||
let hue_offset: u8 = 32.scale8(sin8(uniforms.frame.wrapping_sub(coords.x)));
|
||||
let value = max(30, inoise8(coords.x.wrapping_add(uniforms.frame) as i16, coords.y.wrapping_add(uniforms.frame) as i16));
|
||||
Hsv::new(hue_offset.wrapping_sub(uniforms.primary_color.hue as i8) as u8, max(210, sin8(uniforms.frame.wrapping_add(coords.x))), value).into()
|
||||
Hsv::new(uniforms.primary_color.hue.wrapping_sub(hue_offset), max(210, sin8(uniforms.frame.wrapping_add(coords.x))), value).into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -122,4 +122,3 @@ impl Shader<Uniforms, BikeSpace, Rgba<u8>> for Thinking {
|
||||
).into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
use alloc::string::String;
|
||||
use embassy_embedded_hal::shared_bus::asynch::i2c::I2cDevice;
|
||||
use embassy_sync::{blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}, channel::{DynamicSender, Sender}};
|
||||
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, channel::DynamicSender};
|
||||
use embassy_time::Timer;
|
||||
use embedded_hal_async::i2c::I2c as _;
|
||||
use esp_hal::{i2c::master::I2c, Async};
|
||||
@@ -8,13 +8,13 @@ use log::*;
|
||||
use nalgebra::Vector2;
|
||||
use nmea::Nmea;
|
||||
|
||||
use crate::{backoff::Backoff, events::{Measurement, Notification}};
|
||||
use crate::{backoff::Backoff, events::Measurement};
|
||||
|
||||
#[allow(dead_code)] //FIXME: Allow switching to this via configure option
|
||||
const GPS_TEST_DATA: &str = include_str!("../test.nmea");
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn gps_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sink: DynamicSender<'static, Notification>, mut i2c_bus: I2cDevice<'static, CriticalSectionRawMutex, I2c<'static, Async>>) {
|
||||
pub async fn gps_task(events: DynamicSender<'static, Measurement>, mut i2c_bus: I2cDevice<'static, CriticalSectionRawMutex, I2c<'static, Async>>) {
|
||||
Backoff::from_secs(5).forever().attempt::<_, (), ()>(async || {
|
||||
Backoff::from_secs(5).forever().attempt(async || {
|
||||
info!("Initializing GPS");
|
||||
@@ -50,20 +50,19 @@ pub async fn gps_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sin
|
||||
if let Ok(result) = parser.parse(&strbuf) {
|
||||
match parser.fix_type {
|
||||
None if has_lock => {
|
||||
sink.send(Notification::GPSLost).await;
|
||||
events.send(Measurement::GPS(None)).await;
|
||||
has_lock = false
|
||||
},
|
||||
None => (),
|
||||
Some(_) => {
|
||||
if !has_lock {
|
||||
sink.send(Notification::GPSAcquired).await;
|
||||
has_lock = true;
|
||||
}
|
||||
|
||||
//TODO: 4 satellites seems to be "Some" fix, 6 is a perfect fix
|
||||
//TODO: Only send updates when we get the correct nmea sentence
|
||||
if let (Some(lat), Some(lng)) = (parser.latitude, parser.longitude) {
|
||||
events.send(Measurement::GPS(Vector2::new(lat, lng))).await;
|
||||
events.send(Measurement::GPS(Some(Vector2::new(lat, lng)))).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -2,4 +2,5 @@ pub mod mpu;
|
||||
pub mod render;
|
||||
pub mod motion;
|
||||
pub mod gps;
|
||||
pub mod ui;
|
||||
pub mod ui;
|
||||
pub mod simulation;
|
||||
@@ -1,98 +1,111 @@
|
||||
#![allow(non_snake_case)] // WIP, because most of this code came from chatgpt and I'm still not sure if it actually works or is completely wrong
|
||||
use embassy_sync::{blocking_mutex::raw::NoopRawMutex, channel::{DynamicSender, Receiver}};
|
||||
use nalgebra::{SMatrix, SVector};
|
||||
use embassy_sync::channel::{DynamicReceiver, DynamicSender};
|
||||
use nalgebra::{Rotation3, Vector2, Vector3, ComplexField};
|
||||
|
||||
use crate::{ego::heading::HeadingEstimator, events::{Measurement, Notification}};
|
||||
use crate::{ego::{alignment::{Direction, DirectionEstimator, SensorAlignment}, heading::HeadingEstimator, kalman::{GpsMeasurement, Kalman}}, events::{Measurement, Notification, Prediction, Telemetry}, CircularBuffer};
|
||||
use log::*;
|
||||
use nalgebra::ComplexField;
|
||||
|
||||
/// State: [px, py, vx, vy]
|
||||
type State = SVector<f32, 6>;
|
||||
type Control = SVector<f32, 3>; // dx, dx, yaw
|
||||
type GpsMeasurement = SVector<f32, 2>; // gps x, gps y
|
||||
|
||||
pub struct Kalman {
|
||||
x: State, // state estimate
|
||||
P: SMatrix<f32, 6, 6>, // covariance
|
||||
F: SMatrix<f32, 6, 6>, // state transition
|
||||
B: SMatrix<f32, 6, 3>, // control matrix
|
||||
H: SMatrix<f32, 2, 6>, // measurement matrix
|
||||
Q: SMatrix<f32, 6, 6>, // process noise
|
||||
R: SMatrix<f32, 2, 2>, // measurement noise
|
||||
}
|
||||
|
||||
impl Kalman {
|
||||
pub fn new(dt: f32) -> Self {
|
||||
let mut kf = Kalman {
|
||||
x: State::zeros(),
|
||||
P: SMatrix::identity(),
|
||||
F: SMatrix::identity(),
|
||||
B: SMatrix::zeros(),
|
||||
H: SMatrix::zeros(),
|
||||
Q: SMatrix::identity() * 5.0,
|
||||
R: SMatrix::identity() * 5.0, // GPS noise
|
||||
};
|
||||
|
||||
// F (state transition)
|
||||
kf.F[(0,2)] = dt;
|
||||
kf.F[(1,3)] = dt;
|
||||
kf.F[(4,5)] = dt;
|
||||
|
||||
// B (control matrix)
|
||||
kf.B[(0,0)] = 0.5 * dt * dt;
|
||||
kf.B[(1,1)] = 0.5 * dt * dt;
|
||||
kf.B[(2,0)] = dt;
|
||||
kf.B[(3,1)] = dt;
|
||||
kf.B[(5,2)] = dt;
|
||||
|
||||
// H (GPS: positions only)
|
||||
kf.H[(0,0)] = 1.0;
|
||||
kf.H[(1,1)] = 1.0;
|
||||
|
||||
kf
|
||||
}
|
||||
|
||||
pub fn predict(&mut self, u: &Control) {
|
||||
self.x = self.F * self.x + self.B * u;
|
||||
self.P = self.F * self.P * self.F.transpose() + self.Q;
|
||||
}
|
||||
|
||||
pub fn update(&mut self, z: &GpsMeasurement) {
|
||||
let y = z - self.H * self.x; // innovation
|
||||
let S = self.H * self.P * self.H.transpose() + self.R;
|
||||
if let Some(s_inv) = S.try_inverse() {
|
||||
let K = self.P * self.H.transpose() * s_inv;
|
||||
self.x += K * y;
|
||||
self.P = (SMatrix::<f32,6,6>::identity() - K * self.H) * self.P;
|
||||
}
|
||||
}
|
||||
|
||||
// Used to indicate stationary behavior and therefore velocities should be zero
|
||||
pub fn update_zupt(&mut self) {
|
||||
let z = SVector::<f32, 2>::zeros(); // velocity = 0
|
||||
let mut H = SMatrix::<f32, 2, 6>::zeros();
|
||||
H[(0,2)] = 1.0; // vx
|
||||
H[(1,3)] = 1.0; // vy
|
||||
|
||||
let R = SMatrix::<f32, 2, 2>::identity() * 0.01; // very confident
|
||||
|
||||
let y = z - H * self.x;
|
||||
let S = H * self.P * H.transpose() + R;
|
||||
|
||||
if let Some(s_inv) = S.try_inverse() {
|
||||
let k = self.P * H.transpose() * s_inv;
|
||||
self.x += k * y;
|
||||
self.P = (SMatrix::<f32,6,6>::identity() - k * H) * self.P;
|
||||
}
|
||||
}
|
||||
|
||||
pub fn state(&self) -> &State {
|
||||
&self.x
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn motion_task(src: Receiver<'static, NoopRawMutex, Measurement, 4>, sink: DynamicSender<'static, Notification>) {
|
||||
pub async fn motion_task(src: DynamicReceiver<'static, Measurement>, ui_sink: DynamicSender<'static, Notification>, telemetry_sink: DynamicSender<'static, Telemetry>) {
|
||||
//TODO: is this the right value? how do update frequencies work?
|
||||
let dt = 0.01; // 10 Hz
|
||||
let mut kf = Kalman::new(dt);
|
||||
|
||||
let mut recent_accel: CircularBuffer<Vector3<f32>, 100> = CircularBuffer::default();
|
||||
let mut gravity_align = None;
|
||||
let mut forwards_align = DirectionEstimator::new(Direction::UpX);
|
||||
let mut last_fix = Vector2::default();
|
||||
let mut reference_fix = None;
|
||||
let mut heading = HeadingEstimator::new(0.0);
|
||||
|
||||
loop {
|
||||
let next_measurement = src.receive().await;
|
||||
let _ = telemetry_sink.try_send(Telemetry::Measurement(next_measurement));
|
||||
match next_measurement {
|
||||
Measurement::IMU { accel, gyro } => {
|
||||
recent_accel.insert(accel);
|
||||
// Require a gravity alignment first
|
||||
if gravity_align.is_none() {
|
||||
gravity_align = {
|
||||
let align = SensorAlignment::from_samples(&recent_accel.data, crate::ego::alignment::Direction::DnZ);
|
||||
if align.bias.norm() < 9.764 || align.bias.norm() > 9.834 {
|
||||
None
|
||||
} else {
|
||||
ui_sink.send(Notification::CalibrationComplete).await;
|
||||
Some(align)
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// Minimum motion threshold
|
||||
if accel.xy().magnitude() >= 0.8 {
|
||||
// Try to build a new 'forwards' alignment
|
||||
forwards_align.update(accel);
|
||||
|
||||
// Rotate the measurement into the gravity-down frame
|
||||
let (body_accel, body_gyro) = if let Some(ref adj) = gravity_align {
|
||||
(adj.apply(&accel), adj.apply(&gyro))
|
||||
} else {
|
||||
(accel, gyro)
|
||||
};
|
||||
|
||||
// Then rotate the other two axes to produce the final body frame
|
||||
let forwards_adjusted = forwards_align.apply(&body_accel);
|
||||
heading.update(body_gyro.z, 0.1); // TODO: need to correctly use time values for dt
|
||||
let heading_rotation = Rotation3::from_axis_angle(&Vector3::z_axis(), heading.heading());
|
||||
|
||||
let enu_rotated = heading_rotation * forwards_adjusted;
|
||||
|
||||
// FIXME: the last thing to add here is rotating the acceleration measurements into the ENU frame.
|
||||
let m = Vector3::new(enu_rotated.x, enu_rotated.y, body_gyro.z);
|
||||
kf.predict(&m);
|
||||
} else {
|
||||
// Otherwise, we are standing stationary and should insert accel=0 data into the model
|
||||
kf.update_zupt();
|
||||
}
|
||||
}
|
||||
},
|
||||
Measurement::GPS(Some(gps_pos)) => {
|
||||
match reference_fix {
|
||||
None => {
|
||||
reference_fix = Some(gps_pos);
|
||||
last_fix = gps_pos;
|
||||
ui_sink.send(Notification::GPSAcquired).await;
|
||||
},
|
||||
Some(coords) => {
|
||||
|
||||
let est = kf.state();
|
||||
info!("pos=\t({},\t{})\tvel=({},\t{})\theading={}\t({})\tforwards={:?}", est[0], est[1], est[2], est[3], est[4], heading.heading(), forwards_align.apply(&Vector3::new(1.0, 0.0, 0.0)));
|
||||
if last_fix != coords {
|
||||
let gps_heading = last_fix.angle(&coords);
|
||||
heading.correct(gps_heading as f32, 0.9);
|
||||
}
|
||||
|
||||
// Convert GPS coordinates into a meter distance away from the known fix location
|
||||
let dx = (gps_pos.x - coords.x) * coords.x.cos() * 6371000.0;
|
||||
let dy = (gps_pos.y - coords.y) * 6371000.0;
|
||||
kf.update(&GpsMeasurement::new(dx as f32, dy as f32));
|
||||
info!("GPS={gps_pos:?} d=({dx}, {dy}) heading={}", heading.heading().to_degrees());
|
||||
|
||||
last_fix = coords;
|
||||
}
|
||||
}
|
||||
},
|
||||
Measurement::GPS(None) => {
|
||||
reference_fix = None;
|
||||
ui_sink.send(Notification::GPSLost).await;
|
||||
}
|
||||
}
|
||||
|
||||
let est = kf.state();
|
||||
if est[2].abs() + est[3].abs() >= 5.0 {
|
||||
//info!("pos=\t({},\t{})\tvel=({},\t{})\theading={}\tforwards={:?}", est[0], est[1], est[2], est[3], est[4], forwards_align.apply(&Vector3::new(1.0, 0.0, 0.0)));
|
||||
}
|
||||
|
||||
let _ = telemetry_sink.try_send(Telemetry::Prediction(Prediction::Location(est.xy())));
|
||||
}
|
||||
}
|
||||
|
||||
/*#[embassy_executor::task]
|
||||
pub async fn _motion_task(src: DynamicReceiver<'static, Measurement>, sink: DynamicSender<'static, Notification>, telemetry_sink: DynamicSender<'static, Measurement>) {
|
||||
//TODO: is this the right value? how do update frequencies work?
|
||||
let dt = 0.01; // 10 Hz
|
||||
let mut kf = Kalman::new(dt);
|
||||
@@ -102,58 +115,89 @@ pub async fn motion_task(src: Receiver<'static, NoopRawMutex, Measurement, 4>, s
|
||||
//TODO: Accelerating/decelerating events need thresholds, maybe a PID to detect? PID setpoint can be a running average speed, and if the calculated error is above/below a threshold, it means we are accelerating/decelerating
|
||||
|
||||
let mut last_fix = None;
|
||||
let mut last_idle = Instant::now();
|
||||
let mut is_maybe_idling = false;
|
||||
let mut is_idle = false;
|
||||
let mut is_parked = false;
|
||||
|
||||
loop {
|
||||
match src.receive().await {
|
||||
Measurement::IMU(imu_accel) => {
|
||||
Measurement::IMU{ accel, gyro } => {
|
||||
//info!("IMU update {imu_accel:?}");
|
||||
//info!("m=\t({:?}, {:?})\tyaw={:?}", imu_accel.x, imu_accel.y, imu_accel.z);
|
||||
//kf.predict(&Control::new(imu_accel.x, imu_accel.y, imu_accel.z));
|
||||
// TODO: Also needs corrected using GPS headings via rotation from body frame into world frame
|
||||
//heading.heading();
|
||||
heading.update(imu_accel.z, 0.01);
|
||||
heading.update(accel.z, 0.01);
|
||||
|
||||
//info!("{}", imu_accel.xy().magnitude());
|
||||
if imu_accel.xy().magnitude() >= 0.2 {
|
||||
kf.predict(&imu_accel);
|
||||
if accel.xy().magnitude() >= 0.8 {
|
||||
//info!("magnitude {imu_accel:?} {}", imu_accel.xy().magnitude());
|
||||
kf.predict(&accel);
|
||||
if is_parked {
|
||||
info!("Wake up!");
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::ParkedIdle)).await;
|
||||
is_maybe_idling = false;
|
||||
is_parked = false;
|
||||
is_idle = false;
|
||||
}
|
||||
} else {
|
||||
//info!("Stationary!!");
|
||||
kf.update_zupt();
|
||||
|
||||
if !is_maybe_idling {
|
||||
is_maybe_idling = true;
|
||||
last_idle = Instant::now();
|
||||
} else if !is_idle && Instant::now() - last_idle >= Duration::from_secs(15) {
|
||||
info!("Parked idle");
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::ParkedIdle)).await;
|
||||
is_idle = true;
|
||||
} else if !is_parked && Instant::now() - last_idle >= Duration::from_secs(60 * 3) {
|
||||
info!("Parked long term!");
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::ParkedLongTerm)).await;
|
||||
is_parked = true;
|
||||
}
|
||||
}
|
||||
// TODO: Rotate the acceleration values into the World frame using GPS heading values
|
||||
|
||||
// X means forwards, Y is left/right slide, Z is vertical movement
|
||||
if imu_accel.x > 1.0 {
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::Accelerating)).await;
|
||||
} else if imu_accel.x < -1.0 {
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::Decelerating)).await;
|
||||
if accel.x > 1.0 {
|
||||
//sink.send(Notification::SceneChange(crate::events::Scene::Accelerating)).await;
|
||||
} else if accel.x < -1.0 {
|
||||
//sink.send(Notification::SceneChange(crate::events::Scene::Decelerating)).await;
|
||||
}
|
||||
|
||||
let _ = telemetry_sink.try_send(Measurement::IMU { accel, gyro });
|
||||
}
|
||||
Measurement::GPS(gps_pos) => {
|
||||
info!("GPS update! {gps_pos:?}");
|
||||
//info!("GPS update! {gps_pos:?}");
|
||||
match last_fix {
|
||||
None => last_fix = Some(gps_pos),
|
||||
Some(coords) => {
|
||||
let dx = (gps_pos.x - coords.x) * coords.x.cos() * 6371000.0;
|
||||
let dy = (gps_pos.y - coords.y) * 6371000.0;
|
||||
kf.update(&GpsMeasurement::new(dx as f32, dy as f32));
|
||||
//last_fix = Some(gps_pos);
|
||||
}
|
||||
}
|
||||
|
||||
let _ = telemetry_sink.try_send(Measurement::GPS(gps_pos));
|
||||
}
|
||||
}
|
||||
|
||||
let est = kf.state();
|
||||
//let _ = telemetry_sink.try_send(Measurement::Prediction(*est));
|
||||
if est[2].abs() + est[3].abs() >= 0.2 {
|
||||
info!("pos=\t({},\t{})\tvel=({},\t{})\theading=({},\t{})", est[0], est[1], est[2], est[3], est[4], est[5]);
|
||||
}
|
||||
|
||||
if est[2].abs() + est[3].abs() > 0f32 {
|
||||
if est[2].abs() > 1.0 {
|
||||
if !is_moving {
|
||||
is_moving = true;
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::Accelerating)).await;
|
||||
}
|
||||
} else if is_moving {
|
||||
is_moving = false;
|
||||
sink.send(Notification::SceneChange(crate::events::Scene::StoplightIdle)).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
}*/
|
||||
@@ -1,16 +1,15 @@
|
||||
use core::cell::RefCell;
|
||||
|
||||
use embassy_embedded_hal::shared_bus::asynch::i2c::I2cDevice;
|
||||
use embassy_sync::{blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}, channel::{DynamicSender, Sender}};
|
||||
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, channel::DynamicSender};
|
||||
use embassy_time::{Delay, Timer};
|
||||
use esp_hal::{i2c::master::I2c, Async};
|
||||
use log::{info, warn};
|
||||
use mpu6050_dmp::{address::Address, calibration::CalibrationParameters, error_async::Error, sensor_async::Mpu6050};
|
||||
use nalgebra::Vector3;
|
||||
use core::f32::consts::PI;
|
||||
use nalgebra::ComplexField;
|
||||
|
||||
use crate::{backoff::Backoff, ego::{alignment::SensorAlignment, tilt::TiltEstimator}, events::{Measurement, Notification}};
|
||||
use crate::{backoff::Backoff, ego::tilt::TiltEstimator, events::Measurement};
|
||||
|
||||
const G: f32 = 9.80665;
|
||||
const SENS_2G: f32 = 16384.0;
|
||||
@@ -28,7 +27,7 @@ fn gyro_raw_to_rads(raw: i16) -> f32 {
|
||||
(raw as f32 / 16.4) * (DEG2RAD)
|
||||
}
|
||||
|
||||
/// Rotate body accel into ENU and remove gravity; returns (east, north, up) linear accel in m/s^2
|
||||
/*/// Rotate body accel into ENU and remove gravity; returns (east, north, up) linear accel in m/s^2
|
||||
pub fn accel_body_to_enu_lin(body_acc: (f32,f32,f32), roll: f32, pitch: f32, yaw: f32) -> (f32,f32,f32) {
|
||||
let (ax, ay, az) = body_acc;
|
||||
|
||||
@@ -63,10 +62,10 @@ pub fn accel_body_to_enu_lin(body_acc: (f32,f32,f32), roll: f32, pitch: f32, yaw
|
||||
let az_lin = az_nav - G; // linear acceleration in up axis
|
||||
|
||||
(ax_lin, ay_lin, az_lin)
|
||||
}
|
||||
}*/
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn mpu_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sink: DynamicSender<'static, Notification>, bus: I2cDevice<'static, CriticalSectionRawMutex, I2c<'static, Async>>) {
|
||||
pub async fn mpu_task(events: DynamicSender<'static, Measurement>, bus: I2cDevice<'static, CriticalSectionRawMutex, I2c<'static, Async>>) {
|
||||
let backoff = Backoff::from_millis(5);
|
||||
let busref = RefCell::new(Some(bus));
|
||||
|
||||
@@ -92,24 +91,8 @@ pub async fn mpu_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sin
|
||||
|
||||
let sensor_ref = &mut sensor;
|
||||
|
||||
let alignment = {
|
||||
info!("Locating earth...");
|
||||
let mut accel_samples = [Vector3::default(); 100];
|
||||
let mut gyro_samples = [Vector3::default(); 100];
|
||||
for (idx, (accel_sample, gyro_sample)) in accel_samples.iter_mut().zip(gyro_samples.iter_mut()).enumerate() {
|
||||
let (accel, gyro) = backoff.attempt(async || { sensor_ref.motion6().await }).await.unwrap();
|
||||
*accel_sample = Vector3::new(accel_raw_to_ms2(accel.x()), accel_raw_to_ms2(accel.y()), accel_raw_to_ms2(accel.z()));
|
||||
*gyro_sample = Vector3::new(gyro_raw_to_rads(gyro.x()), gyro_raw_to_rads(gyro.y()), gyro_raw_to_rads(gyro.z()));
|
||||
info!("{idx}/200 {accel_sample:?} {gyro_sample:?}");
|
||||
Timer::after_millis(5).await;
|
||||
}
|
||||
|
||||
SensorAlignment::new(accel_samples.as_slice(), gyro_samples.as_slice())
|
||||
};
|
||||
|
||||
info!("MPU is ready! earth={alignment:?}");
|
||||
sink.send(Notification::CalibrationComplete).await;
|
||||
let mut tilt = TiltEstimator::new(0.3);
|
||||
info!("MPU is ready!");
|
||||
let _tilt = TiltEstimator::new(0.3);
|
||||
//TODO: Need to read in a constant buffer of accelerometer measurements, which we can then use to determine where "forward" points in the body frame when converting from the sensor frame.
|
||||
// From there, we can rotate the body frame into the world frame using gps headings to generate a compass north
|
||||
fn lowpass(prev: f32, current: f32, alpha: f32) -> f32 {
|
||||
@@ -121,16 +104,16 @@ pub async fn mpu_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sin
|
||||
Ok((accel_data, gyro_data)) => {
|
||||
|
||||
// Apply the initial alignment correction to put it into the body frame where X is forward
|
||||
let adjusted = alignment.apply(&Vector3::new(
|
||||
let adjusted = Vector3::new(
|
||||
accel_raw_to_ms2(accel_data.x()),
|
||||
accel_raw_to_ms2(accel_data.y()),
|
||||
accel_raw_to_ms2(accel_data.z())
|
||||
));
|
||||
let adjusted_gyro = alignment.apply_gyro(&Vector3::new(
|
||||
);
|
||||
let adjusted_gyro = Vector3::new(
|
||||
gyro_raw_to_rads(gyro_data.x()),
|
||||
gyro_raw_to_rads(gyro_data.y()),
|
||||
gyro_raw_to_rads(gyro_data.z())
|
||||
));
|
||||
);
|
||||
|
||||
let filtered = Vector3::new(
|
||||
lowpass(prev_accel.x, adjusted.x, 0.3),
|
||||
@@ -140,15 +123,16 @@ pub async fn mpu_task(events: Sender<'static, NoopRawMutex, Measurement, 4>, sin
|
||||
prev_accel = adjusted;
|
||||
|
||||
// Apply current rotation and accel values to rotate our values back into the ENU frame
|
||||
tilt.update(0.01, (filtered.x, filtered.y, filtered.z), (adjusted_gyro.x, adjusted_gyro.y, adjusted_gyro.z));
|
||||
/*tilt.update(0.01, (filtered.x, filtered.y, filtered.z), (adjusted_gyro.x, adjusted_gyro.y, adjusted_gyro.z));
|
||||
let (roll, pitch, yaw) = tilt.angles();
|
||||
let (ax_e, ay_n, _az_up) = accel_body_to_enu_lin((filtered.x,filtered.y,filtered.z), roll, pitch, yaw);
|
||||
let (ax_e, ay_n, az_up) = accel_body_to_enu_lin((filtered.x,filtered.y,filtered.z), roll, pitch, yaw);
|
||||
|
||||
let measured = Vector3::new(ax_e, ay_n, adjusted_gyro.z);
|
||||
let measured = Vector3::new(ax_e, ay_n, az_up);*/
|
||||
events.send(
|
||||
Measurement::IMU(
|
||||
measured
|
||||
)
|
||||
Measurement::IMU {
|
||||
accel: filtered,
|
||||
gyro: adjusted_gyro
|
||||
}
|
||||
).await;
|
||||
Timer::after_millis(10).await;
|
||||
},
|
||||
|
||||
@@ -1,11 +1,12 @@
|
||||
use embassy_time::{Duration, Instant, Timer};
|
||||
use esp_hal::{gpio::AnyPin, rmt::ChannelCreator, Async};
|
||||
use esp_hal::{gpio::AnyPin, rmt::Rmt, time::Rate};
|
||||
use esp_hal_smartled::{buffer_size_async, SmartLedsAdapterAsync};
|
||||
use figments::{hardware::{Brightness, Output}, prelude::Hsv, surface::{BufferedSurfacePool, Surfaces}};
|
||||
use figments::{hardware::{Brightness, OutputAsync}, prelude::Hsv, surface::{BufferedSurfacePool, Surfaces}};
|
||||
use log::{info, warn};
|
||||
use rgb::Rgba;
|
||||
use nalgebra::ComplexField;
|
||||
|
||||
use crate::{display::{BikeOutput, BikeSpace}, events::DisplayControls};
|
||||
use crate::{display::{BikeOutputAsync, BikeSpace}, events::DisplayControls};
|
||||
|
||||
#[derive(Default)]
|
||||
pub struct Uniforms {
|
||||
@@ -16,9 +17,15 @@ pub struct Uniforms {
|
||||
//TODO: Import the bike surfaces from renderbug-prime, somehow make those surfaces into tasks
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn render(rmt_channel: ChannelCreator<Async, 0>, gpio: AnyPin<'static>, surfaces: BufferedSurfacePool<Uniforms, BikeSpace, Rgba<u8>>, controls: &'static DisplayControls) {
|
||||
pub async fn render(rmt: esp_hal::peripherals::RMT<'static>, gpio: AnyPin<'static>, surfaces: BufferedSurfacePool<Uniforms, BikeSpace, Rgba<u8>>, controls: &'static DisplayControls) {
|
||||
let frequency: Rate = Rate::from_mhz(80);
|
||||
let rmt = Rmt::new(rmt, frequency)
|
||||
.expect("Failed to initialize RMT").into_async();
|
||||
let rmt_channel = rmt.channel0;
|
||||
|
||||
let rmt_buffer = [0u32; buffer_size_async(178)];
|
||||
|
||||
//let target = SmartLedsAdapterAsync::new(rmt_channel, gpio, rmt_buffer);
|
||||
let target = SmartLedsAdapterAsync::new(rmt_channel, gpio, rmt_buffer);
|
||||
|
||||
// Change this to adjust the power available; the USB spec says 500ma is the standard limit, but sometimes you can draw more from a power brick
|
||||
@@ -29,16 +36,22 @@ pub async fn render(rmt_channel: ChannelCreator<Async, 0>, gpio: AnyPin<'static>
|
||||
const MAX_POWER_MW : u32 = POWER_VOLTS * POWER_MA;
|
||||
|
||||
// This value is used as the 'seed' for rendering each frame, allowing us to do things like run the animation backwards, frames for double FPS, or even use system uptime for more human-paced animations
|
||||
let mut uniforms = Uniforms::default();
|
||||
let mut uniforms = Uniforms {
|
||||
primary_color: Hsv::new(210, 255, 255),
|
||||
..Uniforms::default()
|
||||
};
|
||||
|
||||
let mut output = BikeOutput::new(target, MAX_POWER_MW);
|
||||
let mut output = BikeOutputAsync::new(target, MAX_POWER_MW);
|
||||
|
||||
info!("Rendering started!");
|
||||
info!("Rendering started! {}ms since boot", Instant::now().as_millis());
|
||||
controls.render_is_running.signal(true);
|
||||
|
||||
const FPS: u64 = 60;
|
||||
const RENDER_BUDGET: Duration = Duration::from_millis(1000 / FPS);
|
||||
|
||||
loop {
|
||||
let start = Instant::now();
|
||||
//pixbuf.blank();
|
||||
output.blank().await.expect("Failed to blank framebuf");
|
||||
output.blank_async().await.expect("Failed to blank framebuf");
|
||||
|
||||
surfaces.render_to(&mut output, &uniforms);
|
||||
|
||||
@@ -47,19 +60,19 @@ pub async fn render(rmt_channel: ChannelCreator<Async, 0>, gpio: AnyPin<'static>
|
||||
output.set_brightness(controls.brightness.load(core::sync::atomic::Ordering::Relaxed));
|
||||
|
||||
// Finally, write out the rendered frame
|
||||
output.commit().await.expect("Failed to commit frame");
|
||||
output.commit_async().await.expect("Failed to commit frame");
|
||||
|
||||
let render_duration = Instant::now() - start;
|
||||
let render_budget = Duration::from_millis(16);
|
||||
|
||||
if render_duration < render_budget {
|
||||
let remaining_budget = render_budget - render_duration;
|
||||
if render_duration < RENDER_BUDGET {
|
||||
let remaining_budget = RENDER_BUDGET - render_duration;
|
||||
uniforms.frame += 1;
|
||||
Timer::after(remaining_budget).await;
|
||||
} else {
|
||||
warn!("Render stall! Frame took {}ms", render_duration.as_millis());
|
||||
let dropped_count = (render_duration.as_ticks() as f32 / RENDER_BUDGET.as_ticks() as f32).ceil() as usize;
|
||||
warn!("Render stall! Frame took {}ms, dropping {dropped_count} frame(s)", render_duration.as_millis());
|
||||
// If we took longer than the budget, we need to drop some frames to catch up
|
||||
uniforms.frame += dropped_count;
|
||||
}
|
||||
|
||||
// Increment the frame counter
|
||||
uniforms.frame += 1;
|
||||
}
|
||||
}
|
||||
161
src/tasks/simulation.rs
Normal file
161
src/tasks/simulation.rs
Normal file
@@ -0,0 +1,161 @@
|
||||
|
||||
use embassy_sync::channel::DynamicSender;
|
||||
use csv_core::{ReadFieldResult, Reader};
|
||||
use embassy_time::{Duration, Timer};
|
||||
use nalgebra::{Vector2, Vector3};
|
||||
|
||||
use crate::events::Measurement;
|
||||
|
||||
const ACCELEROMETER_DATA: &str = include_str!("../../test-data/accelerometer.csv");
|
||||
//const GYRO_DATA: &str = include_str!("../../test-data/gyro.csv");
|
||||
const GPS_DATA: &str = include_str!("../../test-data/gps.csv");
|
||||
|
||||
struct SimDataReader<'a> {
|
||||
reader: Reader,
|
||||
buf: &'a str,
|
||||
read_offset: usize
|
||||
}
|
||||
|
||||
impl<'a> SimDataReader<'a> {
|
||||
pub fn new(buf: &'a str) -> Self {
|
||||
Self {
|
||||
buf,
|
||||
read_offset: 0,
|
||||
reader: Reader::new()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a> Iterator for SimDataReader<'a> {
|
||||
type Item = &'a str;
|
||||
|
||||
fn next(&mut self) -> Option<Self::Item> {
|
||||
let mut out_buf = [0u8; 128];
|
||||
match self.reader.read_field(&self.buf.as_bytes()[self.read_offset..(self.read_offset + 128).min(self.buf.len())], &mut out_buf) {
|
||||
(ReadFieldResult::Field { record_end: _ }, read_size, write_size) => {
|
||||
let start = self.read_offset;
|
||||
self.read_offset += read_size;
|
||||
Some(&self.buf[start..(start + write_size)])
|
||||
},
|
||||
(ReadFieldResult::End, _, _) => None,
|
||||
err => panic!("{:?}", err)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[derive(Default, Debug, Clone, Copy)]
|
||||
enum MotionFields {
|
||||
#[default]
|
||||
Time,
|
||||
SecondsElapsed,
|
||||
Z,
|
||||
Y,
|
||||
X,
|
||||
End
|
||||
}
|
||||
|
||||
impl MotionFields {
|
||||
pub fn next(self) -> Self {
|
||||
match self {
|
||||
Self::Time => Self::SecondsElapsed,
|
||||
Self::SecondsElapsed => Self::Z,
|
||||
Self::Z => Self::Y,
|
||||
Self::Y => Self::X,
|
||||
Self::X => Self::End,
|
||||
Self::End => panic!("No more fields")
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#[derive(Default, Debug, Clone, Copy)]
|
||||
enum GpsFields {
|
||||
#[default]
|
||||
Time,
|
||||
SecondsElapsed,
|
||||
BearingAcc,
|
||||
SpeedAcc,
|
||||
VertAcc,
|
||||
HorizAcc,
|
||||
Speed,
|
||||
Bearing,
|
||||
Altitude,
|
||||
Longitude,
|
||||
Latitude,
|
||||
End
|
||||
}
|
||||
|
||||
impl GpsFields {
|
||||
pub fn next(self) -> Self {
|
||||
match self {
|
||||
Self::Time => Self::SecondsElapsed,
|
||||
Self::SecondsElapsed => Self::BearingAcc,
|
||||
Self::BearingAcc => Self::SpeedAcc,
|
||||
Self::SpeedAcc => Self::VertAcc,
|
||||
Self::VertAcc => Self::HorizAcc,
|
||||
Self::HorizAcc => Self::Speed,
|
||||
Self::Speed => Self::Bearing,
|
||||
Self::Bearing => Self::Altitude,
|
||||
Self::Altitude => Self::Longitude,
|
||||
Self::Longitude => Self::Latitude,
|
||||
Self::Latitude => Self::End,
|
||||
Self::End => panic!("No more fields")
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn motion_simulation_task(events: DynamicSender<'static, Measurement>) {
|
||||
let mut accel = Vector3::default();
|
||||
let mut cur_field = MotionFields::default();
|
||||
let mut last_stamp = 0.0;
|
||||
let mut cur_delta = Duration::from_ticks(0);
|
||||
let reader = SimDataReader::new(ACCELEROMETER_DATA);
|
||||
for field in reader {
|
||||
match cur_field {
|
||||
MotionFields::SecondsElapsed => {
|
||||
let secs = field.parse::<f64>().unwrap();
|
||||
cur_delta = Duration::from_millis(((secs - last_stamp) * 1000.0) as u64);
|
||||
last_stamp = secs;
|
||||
}
|
||||
MotionFields::X => accel.x = field.parse::<f32>().unwrap(),
|
||||
MotionFields::Y => accel.y = field.parse().unwrap(),
|
||||
MotionFields::Z => accel.z = field.parse().unwrap(),
|
||||
_ => ()
|
||||
}
|
||||
cur_field = cur_field.next();
|
||||
if let MotionFields::End = cur_field {
|
||||
cur_field = MotionFields::default();
|
||||
events.send(Measurement::IMU{ accel, gyro: Vector3::default() }).await;
|
||||
Timer::after(cur_delta).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn location_simulation_task(events: DynamicSender<'static, Measurement>) {
|
||||
let mut coords = Vector2::default();
|
||||
let mut cur_field = GpsFields::default();
|
||||
let mut last_stamp = 0.0;
|
||||
let mut cur_delta = Duration::from_ticks(0);
|
||||
let reader = SimDataReader::new(GPS_DATA);
|
||||
for field in reader {
|
||||
match cur_field {
|
||||
GpsFields::SecondsElapsed => {
|
||||
let secs = field.parse::<f64>().unwrap();
|
||||
cur_delta = Duration::from_millis(((secs - last_stamp) * 1000.0) as u64);
|
||||
last_stamp = secs;
|
||||
}
|
||||
GpsFields::Latitude => coords.x = field.parse::<f64>().unwrap(),
|
||||
GpsFields::Longitude => coords.y = field.parse().unwrap(),
|
||||
_ => ()
|
||||
}
|
||||
|
||||
cur_field = cur_field.next();
|
||||
if let GpsFields::End = cur_field {
|
||||
cur_field = GpsFields::default();
|
||||
Timer::after(cur_delta).await;
|
||||
events.send(Measurement::GPS(Some(coords))).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,8 +1,9 @@
|
||||
use embassy_sync::channel::DynamicReceiver;
|
||||
use embassy_time::{Duration, Instant, Timer};
|
||||
use figments::{liber8tion::interpolate::{ease_in_out_quad, Fract8}, prelude::*};
|
||||
use figments::{liber8tion::interpolate::Fract8, prelude::*};
|
||||
use rgb::{Rgb, Rgba};
|
||||
use log::*;
|
||||
use nalgebra::ComplexField;
|
||||
|
||||
use crate::{display::BikeSpace, events::{DisplayControls, Notification, Scene}, shaders::*, tasks::render::Uniforms};
|
||||
|
||||
@@ -79,10 +80,29 @@ impl<S: Surface<Uniforms = Uniforms, CoordinateSpace = BikeSpace, Pixel = Rgba<u
|
||||
|
||||
pub async fn flash_notification_color(&mut self, color: Rgb<u8>) {
|
||||
self.notification.set_shader(Background::from_color(color));
|
||||
self.notification.set_opacity(255);
|
||||
self.notification.set_opacity(0);
|
||||
self.notification.set_visible(true);
|
||||
// Fade in to full on over 1s
|
||||
Self::animate_duration(Duration::from_secs(1), |pct| {
|
||||
self.notification.set_opacity(pct);
|
||||
}).await;
|
||||
|
||||
// Pulse quickly 3 times
|
||||
for _ in 0..3 {
|
||||
// Brief dimming back to half brightness for half a sec
|
||||
Self::animate_duration(Duration::from_millis(100), |pct| {
|
||||
self.notification.set_opacity(100 + pct/2);
|
||||
}).await;
|
||||
|
||||
// Back to full
|
||||
Self::animate_duration(Duration::from_millis(100), |pct| {
|
||||
self.notification.set_opacity(100 + (255 - pct) / 2);
|
||||
}).await;
|
||||
}
|
||||
|
||||
// Back to off
|
||||
Self::animate_duration(Duration::from_secs(3), |pct| {
|
||||
self.notification.set_opacity(255 * pct);
|
||||
self.notification.set_opacity(255 - pct);
|
||||
}).await;
|
||||
self.notification.set_visible(false);
|
||||
}
|
||||
@@ -104,19 +124,36 @@ impl<S: Surface<Uniforms = Uniforms, CoordinateSpace = BikeSpace, Pixel = Rgba<u
|
||||
}
|
||||
}
|
||||
|
||||
pub fn expo_in(t: f32) -> f32 {
|
||||
if t <= 0.0 {
|
||||
0.0
|
||||
} else {
|
||||
2f32.powf(10.0 * t - 10.0)
|
||||
}
|
||||
}
|
||||
|
||||
pub fn expo_out(t: f32) -> f32 {
|
||||
if 1.0 <= t {
|
||||
1.0
|
||||
} else {
|
||||
1.0 - 2f32.powf(-10.0 * t)
|
||||
}
|
||||
}
|
||||
|
||||
pub async fn startup_fade_sequence(&mut self) {
|
||||
info!("Running startup fade sequence");
|
||||
// Start with a completely transparent overlay, which then fades in over 1 second
|
||||
self.overlay.set_opacity(0);
|
||||
self.overlay.set_visible(true);
|
||||
Self::animate_duration(Duration::from_secs(1), |pct| {
|
||||
self.overlay.set_opacity(ease_in_out_quad(pct));
|
||||
Self::animate_duration(Duration::from_secs(2), |pct| {
|
||||
self.overlay.set_opacity((Self::expo_in(pct as f32 / 255.0) * 255.0) as u8);
|
||||
}).await;
|
||||
// When the overlay is fully opaque and all lower layers will be hidden, turn them on
|
||||
self.apply_scene(Scene::Startup).await;
|
||||
Timer::after_secs(1).await;
|
||||
// Then fade out the overlay over 3 seconds, allowing the base animations to be shown
|
||||
Self::animate_duration(Duration::from_secs(3), |pct| {
|
||||
self.overlay.set_opacity(ease_in_out_quad(255 - pct));
|
||||
Self::animate_duration(Duration::from_secs(1), |pct| {
|
||||
self.overlay.set_opacity((Self::expo_in((255 - pct) as f32 / 255.0) * 255.0) as u8);
|
||||
}).await;
|
||||
self.overlay.set_visible(false);
|
||||
info!("Fade sequence completed");
|
||||
@@ -178,13 +215,13 @@ impl<S: Surface<Uniforms = Uniforms, CoordinateSpace = BikeSpace, Pixel = Rgba<u
|
||||
Scene::ParkedIdle => {
|
||||
// Ensure the display is on
|
||||
self.display.on.store(true, core::sync::atomic::Ordering::Relaxed);
|
||||
Self::animate_duration(Duration::from_secs(1), |pct| {
|
||||
self.display.brightness.store(128.scale8(255 - pct), core::sync::atomic::Ordering::Relaxed);
|
||||
}).await;
|
||||
// Hide the content; only notifications will remain
|
||||
self.background.set_visible(true);
|
||||
self.tail.set_visible(false);
|
||||
self.panels.set_visible(false);
|
||||
Self::animate_duration(Duration::from_secs(1), |pct| {
|
||||
self.display.brightness.store(128.scale8(255 - pct), core::sync::atomic::Ordering::Relaxed);
|
||||
}).await;
|
||||
},
|
||||
Scene::ParkedLongTerm => {
|
||||
// For long-term parking, we turn off the safety lights
|
||||
@@ -195,12 +232,27 @@ impl<S: Surface<Uniforms = Uniforms, CoordinateSpace = BikeSpace, Pixel = Rgba<u
|
||||
self.display.brightness.store(255 - pct, core::sync::atomic::Ordering::Relaxed);
|
||||
}).await;
|
||||
self.display.on.store(false, core::sync::atomic::Ordering::Relaxed);
|
||||
},
|
||||
Scene::Accelerating => {
|
||||
self.display.on.store(true, core::sync::atomic::Ordering::Relaxed);
|
||||
self.display.brightness.store(255, core::sync::atomic::Ordering::Relaxed);
|
||||
self.tail.set_shader(Thinking::default());
|
||||
self.panels.set_shader(Panel::default());
|
||||
},
|
||||
Scene::Decelerating => {
|
||||
self.display.on.store(true, core::sync::atomic::Ordering::Relaxed);
|
||||
self.display.brightness.store(255, core::sync::atomic::Ordering::Relaxed);
|
||||
self.panels.set_shader(Thinking::default());
|
||||
self.tail.set_shader(Tail::default());
|
||||
}
|
||||
_ => {
|
||||
warn!("Unimplemented scene {next_scene:?}!");
|
||||
}
|
||||
_ => unimplemented!()
|
||||
}
|
||||
}
|
||||
|
||||
pub async fn on_event(&mut self, event: Notification) {
|
||||
info!("UI Event: {event:?}");
|
||||
match event {
|
||||
// Apply the scene when it is changed
|
||||
Notification::SceneChange(scene) => self.apply_scene(scene).await,
|
||||
@@ -231,6 +283,9 @@ impl<S: Surface<Uniforms = Uniforms, CoordinateSpace = BikeSpace, Pixel = Rgba<u
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn ui_main(events: DynamicReceiver<'static, Notification>, mut ui: Ui<BufferedSurface<Uniforms, BikeSpace, Rgba<u8>>>) {
|
||||
// Wait for the renderer to start running
|
||||
ui.display.render_is_running.wait().await;
|
||||
|
||||
// Run the fade sequence
|
||||
ui.startup_fade_sequence().await;
|
||||
|
||||
@@ -240,6 +295,9 @@ pub async fn ui_main(events: DynamicReceiver<'static, Notification>, mut ui: Ui<
|
||||
ui.set_headlight_on(true).await;
|
||||
// Turn off the brakelight
|
||||
ui.set_brakelight_on(false).await;
|
||||
|
||||
// Flash white to indicate we are ready
|
||||
ui.flash_notification_color(Rgb::new(255, 255, 255)).await;
|
||||
loop {
|
||||
ui.on_event(events.receive().await).await;
|
||||
}
|
||||
|
||||
52046
test-data/Accelerometer.csv
Normal file
52046
test-data/Accelerometer.csv
Normal file
File diff suppressed because it is too large
Load Diff
52125
test-data/AccelerometerUncalibrated.csv
Normal file
52125
test-data/AccelerometerUncalibrated.csv
Normal file
File diff suppressed because it is too large
Load Diff
51205
test-data/Compass.csv
Normal file
51205
test-data/Compass.csv
Normal file
File diff suppressed because it is too large
Load Diff
52349
test-data/Gyroscope.csv
Normal file
52349
test-data/Gyroscope.csv
Normal file
File diff suppressed because it is too large
Load Diff
52278
test-data/GyroscopeUncalibrated.csv
Normal file
52278
test-data/GyroscopeUncalibrated.csv
Normal file
File diff suppressed because it is too large
Load Diff
4067
test-data/Location.csv
Normal file
4067
test-data/Location.csv
Normal file
File diff suppressed because it is too large
Load Diff
51848
test-data/Orientation.csv
Normal file
51848
test-data/Orientation.csv
Normal file
File diff suppressed because it is too large
Load Diff
52215
test-data/TotalAcceleration.csv
Normal file
52215
test-data/TotalAcceleration.csv
Normal file
File diff suppressed because it is too large
Load Diff
190
test-data/WiFi.csv
Normal file
190
test-data/WiFi.csv
Normal file
@@ -0,0 +1,190 @@
|
||||
time,seconds_elapsed,level,frequency,capabilities,BSSID,SSID
|
||||
1758611323985000000,40.023,-76,2462,[WPA2-PSK+FT/PSK-CCMP-128][RSN-PSK+FT/PSK-CCMP-128][ESS],24:5a:4c:ae:aa:14,The Frequency
|
||||
1758611323985000000,40.023,-87,5280,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],2c:91:ab:57:75:2b,WhereTheFudgeIsTheMyWiFiCable
|
||||
1758611323985000000,40.023,-79,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],26:5a:4c:9e:aa:14,The Out Of Band
|
||||
1758611323985000000,40.023,-77,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],2c:91:ab:57:75:2a,WhereTheFudgeIsTheMyWiFiCable
|
||||
1758611363985000000,80.023,-54,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],98:d8:63:db:3f:38,Lackus KS08
|
||||
1758611363985000000,80.023,-54,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],98:d8:63:47:0f:54,PHLED HH Gerhofstr. 2
|
||||
1758611403986000000,120.02399975585938,-58,5560,[ESS],36:56:ee:c8:7d:c8,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-80,5600,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],92:78:48:14:8a:ba,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-84,2437,[ESS],ee:a8:1f:3d:b9:f4,Vodafone Hotspot
|
||||
1758611403986000000,120.02399975585938,-74,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],2e:d1:c6:31:d7:b2,My SEAT 1449
|
||||
1758611403986000000,120.02399975585938,-60,5700,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:c8:79:4a,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-80,5580,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:c8:79:8d,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-85,2412,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],54:1f:8d:92:f9:e7,gigacube-92F9E7
|
||||
1758611403986000000,120.02399975585938,-82,5580,[ESS],36:56:ee:c8:79:8d,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-83,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],48:2f:6b:9b:e0:02,SAP-IOT
|
||||
1758611403986000000,120.02399975585938,-85,5600,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][MFPC],84:78:48:14:8a:ba,Unifi Privat FS
|
||||
1758611403986000000,120.02399975585938,-64,5700,[ESS],36:56:ee:c8:79:4a,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-60,2462,[ESS],34:56:fe:c8:79:4a,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-83,2462,[WPA2-EAP/SHA1+FT/EAP-CCMP-128][RSN-EAP/SHA1+FT/EAP-CCMP-128][ESS][MFPC],48:2f:6b:9b:e0:00,SAP
|
||||
1758611403986000000,120.02399975585938,-90,5240,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],ec:aa:a0:2d:88:8b,LSPXPT1_888B
|
||||
1758611403986000000,120.02399975585938,-81,2462,[ESS],48:2f:6b:9b:e0:01,SAP-Guest
|
||||
1758611403986000000,120.02399975585938,-85,5785,[ESS],48:2f:6b:9b:e7:11,SAP-Guest
|
||||
1758611403986000000,120.02399975585938,-85,5785,[WPA2-EAP/SHA1+FT/EAP-CCMP-128][RSN-EAP/SHA1+FT/EAP-CCMP-128][ESS][MFPC],48:2f:6b:9b:e7:10,SAP
|
||||
1758611403986000000,120.02399975585938,-85,5785,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],48:2f:6b:9b:e7:12,SAP-IOT
|
||||
1758611403986000000,120.02399975585938,-72,5700,[ESS],e2:cb:ac:35:26:15,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-72,5700,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:35:26:15,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-83,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0c:71:8c:a8:6d:51,gigacube-B6E2
|
||||
1758611403986000000,120.02399975585938,-75,5560,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:35:2b:58,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-81,5660,[ESS],36:56:ee:c8:85:f2,#Quartier_Heidestrasse
|
||||
1758611403986000000,120.02399975585938,-84,5600,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][MFPC],8a:78:48:14:8a:ba,FRITZ!Box 5590 ANN
|
||||
1758611403986000000,120.02399975585938,-79,5600,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],8e:78:48:14:8a:ba,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-84,5600,[ESS],48:2f:6b:9b:e0:11,SAP-Guest
|
||||
1758611403986000000,120.02399975585938,-83,5600,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],48:2f:6b:9b:e0:12,SAP-IOT
|
||||
1758611403986000000,120.02399975585938,-80,2412,[WPA2-EAP/SHA1+FT/EAP-CCMP-128][RSN-EAP/SHA1+FT/EAP-CCMP-128][ESS][MFPC],48:2f:6b:9b:e7:00,SAP
|
||||
1758611403986000000,120.02399975585938,-83,5600,[WPA2-EAP/SHA1+FT/EAP-CCMP-128][RSN-EAP/SHA1+FT/EAP-CCMP-128][ESS][MFPC],48:2f:6b:9b:e0:10,SAP
|
||||
1758611403986000000,120.02399975585938,-81,5660,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:c8:85:f2,(hidden SSID)
|
||||
1758611403986000000,120.02399975585938,-81,2412,[ESS],48:2f:6b:9b:e7:01,SAP-Guest
|
||||
1758611403986000000,120.02399975585938,-57,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],10:2d:41:cc:65:2b,FocSign_K75549263
|
||||
1758611443987000000,160.025,-75,5560,[ESS],36:56:ee:c8:7d:c8,#Quartier_Heidestrasse
|
||||
1758611443987000000,160.025,-66,5700,[ESS],e2:cb:ac:35:26:15,#Quartier_Heidestrasse
|
||||
1758611443987000000,160.025,-72,2462,[ESS],e0:cb:bc:35:26:15,#Quartier_Heidestrasse
|
||||
1758611443987000000,160.025,-84,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],c2:4d:a7:cb:d9:8b,B535_D9CB
|
||||
1758611443987000000,160.025,-83,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],c2:4d:a7:cb:d9:8f,B535_D9CB
|
||||
1758611443987000000,160.025,-82,5700,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:c8:79:4a,(hidden SSID)
|
||||
1758611443987000000,160.025,-59,2412,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][ESS],c0:49:ef:92:c1:cd,PIX-G-9
|
||||
1758611443987000000,160.025,-71,5700,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:35:26:15,(hidden SSID)
|
||||
1758611443987000000,160.025,-83,5320,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],54:1f:8d:94:f7:04,BCGP-Berlin
|
||||
1758611443987000000,160.025,-69,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:bc:35:26:15,(hidden SSID)
|
||||
1758611443987000000,160.025,-84,5680,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:2c:6e:bf:4b:51,H7
|
||||
1758611443987000000,160.025,-74,5560,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:c8:7d:c8,(hidden SSID)
|
||||
1758611443987000000,160.025,-87,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],e0:08:55:8f:da:6d,FRITZ!Box 6850 VD
|
||||
1758611443987000000,160.025,-84,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],c2:4d:a7:cb:d9:93,B535_D9CB_5G
|
||||
1758611443987000000,160.025,-75,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],04:c4:61:f4:e1:66,NetConnect-11694-5-126
|
||||
1758611443987000000,160.025,-83,5320,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],5a:1f:8d:94:f7:04,(hidden SSID)
|
||||
1758611443987000000,160.025,-83,5700,[ESS],36:56:ee:c8:79:4a,#Quartier_Heidestrasse
|
||||
1758611443987000000,160.025,-83,2462,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],54:1f:8d:92:f7:04,BCGP-Berlin
|
||||
1758611483987000000,200.025,-89,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],2e:d1:c6:f2:95:6d,My VW 2420
|
||||
1758611483987000000,200.025,-81,5580,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],c2:cb:ac:bf:1c:28,ADLER WiFi - Apt 39
|
||||
1758611483987000000,200.025,-89,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],00:a0:57:81:33:83,Casalot-Intern
|
||||
1758611483987000000,200.025,-80,5680,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:2c:6e:bf:4b:51,H7
|
||||
1758611483987000000,200.025,-78,2462,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],44:4e:6d:fb:12:61,FRITZ!Box 6820 AP
|
||||
1758611483987000000,200.025,-88,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],50:e6:36:a5:17:45,S5gZ4n
|
||||
1758611483987000000,200.025,-77,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],04:c4:61:f4:e1:66,NetConnect-11694-5-126
|
||||
1758611483987000000,200.025,-80,2462,[WPA2-EAP/SHA1-CCMP-128][RSN-EAP/SHA1-CCMP-128][WPA-EAP/SHA1-CCMP-128][ESS],06:fa:c4:53:25:da,Koester-Notebook
|
||||
1758611483987000000,200.025,-85,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],3c:52:a1:a8:d4:e0,ADLER WiFi - Apt 39_EXT
|
||||
1758611483987000000,200.025,-86,2442,[WPA-PSK-CCMP-128][WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],24:2f:d0:a0:be:86,ChaOs
|
||||
1758611483987000000,200.025,-77,5280,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],ca:cb:ac:96:f2:8e,ADLER WiFi - Apt 41
|
||||
1758611483987000000,200.025,-85,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:bf:f3:41,(hidden SSID)
|
||||
1758611483987000000,200.025,-84,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:a0:00:42,(hidden SSID)
|
||||
1758611483987000000,200.025,-87,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:97:6c:7c,(hidden SSID)
|
||||
1758611483987000000,200.025,-85,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],c2:4d:a7:cb:d9:8f,B535_D9CB
|
||||
1758611483987000000,200.025,-69,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],32:da:4b:e7:70:eb,WBRE-Berlin
|
||||
1758611483987000000,200.025,-82,5580,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:bf:1c:28,(hidden SSID)
|
||||
1758611483987000000,200.025,-69,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],32:dc:4b:e7:70:eb,BCGP-Berlin_Guest
|
||||
1758611483987000000,200.025,-85,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],7e:4d:8f:42:14:26,DIRECT-26-HP OfficeJet Pro 7740
|
||||
1758611483987000000,200.025,-88,5785,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][WPA-PSK-CCMP-128][ESS][MFPC],48:da:35:9b:fd:fb,HotspotU6YU
|
||||
1758611483987000000,200.025,-78,5280,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:96:f2:8e,(hidden SSID)
|
||||
1758611483987000000,200.025,-85,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],c2:4d:a7:cb:d9:93,B535_D9CB_5G
|
||||
1758611483987000000,200.025,-87,5560,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:bf:f4:81,(hidden SSID)
|
||||
1758611483987000000,200.025,-80,2442,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],32:ce:4b:e7:70:ea,BCGP-Berlin_Guest
|
||||
1758611483987000000,200.025,-84,5805,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][WPA-PSK-CCMP-128][ESS][MFPC],f8:55:cd:67:1c:09,HotspotcYj7
|
||||
1758611483987000000,200.025,-87,5220,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:15:c8:f2:6c:85,FRITZ!Box 6591 Cable MD
|
||||
1758611523988000000,240.026,-86,5785,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],80:5f:8e:26:50:a0,BYD
|
||||
1758611523988000000,240.026,-87,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],78:6a:1f:3f:38:c5,Vodafone-90D5
|
||||
1758611523988000000,240.026,-82,2462,[WPA2-EAP/SHA1-CCMP-128][RSN-EAP/SHA1-CCMP-128][WPA-EAP/SHA1-CCMP-128][ESS],e4:fa:c4:53:25:da,Koester-Smartphone
|
||||
1758611523988000000,240.026,-77,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],32:da:4b:e7:70:eb,WBRE-Berlin
|
||||
1758611523988000000,240.026,-79,5580,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],c2:cb:ac:bf:1c:28,ADLER WiFi - Apt 39
|
||||
1758611523988000000,240.026,-86,5320,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],54:1f:8d:94:f7:04,BCGP-Berlin
|
||||
1758611523988000000,240.026,-88,5200,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:a0:04:1b,(hidden SSID)
|
||||
1758611523988000000,240.026,-79,5580,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:bf:1c:28,(hidden SSID)
|
||||
1758611523988000000,240.026,-77,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],32:dc:4b:e7:70:eb,BCGP-Berlin_Guest
|
||||
1758611523988000000,240.026,-85,5745,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],70:74:14:36:40:6f,Porsche_WLAN_4741 5GHz
|
||||
1758611523988000000,240.026,-82,5680,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:2c:6e:bf:4b:51,H7
|
||||
1758611523988000000,240.026,-84,5280,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:96:f2:8e,(hidden SSID)
|
||||
1758611523988000000,240.026,-79,2462,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],44:4e:6d:fb:12:61,FRITZ!Box 6820 AP
|
||||
1758611523988000000,240.026,-78,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],72:3a:14:36:40:6f,Porsche_WLAN_4741
|
||||
1758611523988000000,240.026,-83,5240,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:a0:04:36,(hidden SSID)
|
||||
1758611523988000000,240.026,-83,5240,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],3a:56:ee:a0:04:36,ADLER WiFi - Apt 34
|
||||
1758611523988000000,240.026,-71,2442,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],32:ce:4b:e7:70:ea,BCGP-Berlin_Guest
|
||||
1758611523988000000,240.026,-73,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],04:c4:61:f4:e1:66,NetConnect-11694-5-126
|
||||
1758611523988000000,240.026,-86,5320,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],5a:1f:8d:94:f7:04,(hidden SSID)
|
||||
1758611523988000000,240.026,-83,5280,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],ca:cb:ac:96:f2:8e,ADLER WiFi - Apt 41
|
||||
1758611523988000000,240.026,-83,2412,[WPA2-EAP/SHA1-CCMP-128][RSN-EAP/SHA1-CCMP-128][WPA-EAP/SHA1-CCMP-128][ESS],9c:53:22:ac:98:05,Koester-Smartphone
|
||||
1758611523988000000,240.026,-86,5240,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],de:cb:ac:96:4a:29,(hidden SSID)
|
||||
1758611523988000000,240.026,-81,2412,[WPA2-EAP/SHA1-CCMP-128][RSN-EAP/SHA1-CCMP-128][WPA-EAP/SHA1-CCMP-128][ESS],0e:53:22:ac:98:05,Koester-Notebook
|
||||
1758611523988000000,240.026,-88,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0a:56:ee:a0:00:42,(hidden SSID)
|
||||
1758611563989000000,280.027,-87,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],78:6a:1f:3f:38:c5,Vodafone-90D5
|
||||
1758611563989000000,280.027,-84,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],48:a9:d2:df:55:af,Audi_MMI_0663
|
||||
1758611563989000000,280.027,-86,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],04:c4:61:f4:e1:66,NetConnect-11694-5-126
|
||||
1758611563989000000,280.027,-89,5200,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][WPA-PSK-CCMP-128+TKIP][ESS][WPS],00:0f:94:09:90:05,CBB GmbH
|
||||
1758611563989000000,280.027,-75,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][MFPC],fa:6d:cc:9a:40:ee,Audi_MMI_9728
|
||||
1758611563989000000,280.027,-79,5765,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][MFPC],76:85:2a:e2:f5:bb,BYD-fe639
|
||||
1758611563989000000,280.027,-87,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],80:2a:a8:a8:a9:2e,ubnt
|
||||
1758611563989000000,280.027,-74,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],ee:65:cc:73:3f:23,PROJ733f23
|
||||
1758611563989000000,280.027,-71,5785,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][WPA-PSK-CCMP-128][ESS][MFPC],48:da:35:9b:fd:fb,HotspotU6YU
|
||||
1758611603990000000,320.0280002441406,-86,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],98:9d:5d:8e:c5:d8,Vodafone-C5CC
|
||||
1758611603990000000,320.0280002441406,-82,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],78:6a:1f:3f:38:c5,Vodafone-90D5
|
||||
1758611603990000000,320.0280002441406,-82,5200,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],9e:50:d1:04:4a:23,My VW 1539
|
||||
1758611603990000000,320.0280002441406,-85,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],a0:e7:ae:12:cc:e0,Vodafone-6285
|
||||
1758611603990000000,320.0280002441406,-83,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],1c:9e:cc:77:19:80,Vodafone-1974
|
||||
1758611603990000000,320.0280002441406,-86,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:15:c8:bb:51:72,FRITZ!Box 7590 WM
|
||||
1758611603990000000,320.0280002441406,-79,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],10:4e:89:5f:df:44,ConnectedCAM2919
|
||||
1758611603990000000,320.0280002441406,-83,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],36:60:f9:27:8f:25,(hidden SSID)
|
||||
1758611603990000000,320.0280002441406,-86,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],80:2a:a8:a8:a9:2e,ubnt
|
||||
1758611603990000000,320.0280002441406,-80,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS][MFPC],9e:50:d1:64:4a:23,My VW 1539
|
||||
1758611603990000000,320.0280002441406,-81,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],34:60:f9:17:8f:25,TP-Link_8F25
|
||||
1758611603990000000,320.0280002441406,-88,5200,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][WPA-PSK-CCMP-128+TKIP][ESS][WPS],00:0f:94:09:90:05,CBB GmbH
|
||||
1758611603990000000,320.0280002441406,-78,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],da:fe:f2:64:a9:73,(hidden SSID)
|
||||
1758611603990000000,320.0280002441406,-86,2417,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],98:25:4a:84:c4:0c,TP-Link_C4FZ
|
||||
1758611603990000000,320.0280002441406,-84,2462,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][ESS],00:1e:42:2f:2d:d5,LivEye#L-O-222
|
||||
1758611603990000000,320.0280002441406,-84,2417,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],f2:09:0d:d9:79:11,(hidden SSID)
|
||||
1758611603990000000,320.0280002441406,-78,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],4a:75:62:15:bf:af,Audi_MMI_2520
|
||||
1758611643990000000,360.0280002441406,-85,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],c8:d3:ff:85:5e:d1,DIRECT-D0-HP OfficeJet Pro 8710
|
||||
1758611643990000000,360.0280002441406,-83,5260,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],98:9d:5d:8e:c5:d8,Vodafone-C5CC
|
||||
1758611643990000000,360.0280002441406,-83,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],a0:e7:ae:12:cc:e0,Vodafone-6285
|
||||
1758611643990000000,360.0280002441406,-85,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],f8:5e:42:72:63:38,Vodafone-6334
|
||||
1758611643990000000,360.0280002441406,-86,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],1c:9e:cc:77:19:80,Vodafone-1974
|
||||
1758611643990000000,360.0280002441406,-82,2412,[ESS],fa:5e:42:72:63:3a,Vodafone Homespot
|
||||
1758611643990000000,360.0280002441406,-87,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],f0:af:85:b8:39:61,Vodafone-07DF
|
||||
1758611643990000000,360.0280002441406,-85,2412,[ESS],fa:5e:42:72:63:3c,Vodafone Hotspot
|
||||
1758611643990000000,360.0280002441406,-91,5240,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],a0:e4:cb:3d:a9:c3,o2-WLAN12
|
||||
1758611643990000000,360.0280002441406,-61,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],10:4e:89:5f:df:44,ConnectedCAM2919
|
||||
1758611643990000000,360.0280002441406,-86,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],a0:e4:cb:3d:a9:c2,o2-WLAN12
|
||||
1758611643990000000,360.0280002441406,-87,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],80:2a:a8:a8:a9:2e,ubnt
|
||||
1758611643990000000,360.0280002441406,-90,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],34:e1:a9:4e:de:a3,FRITZ!Box 7530 AA
|
||||
1758611643990000000,360.0280002441406,-87,5300,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],b0:f2:08:78:6f:7b,FRITZ!Box 6850 YG
|
||||
1758611643990000000,360.0280002441406,-77,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],34:60:f9:17:8f:25,TP-Link_8F25
|
||||
1758611643990000000,360.0280002441406,-87,5200,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][WPA-PSK-CCMP-128+TKIP][ESS][WPS],00:0f:94:09:90:05,CBB GmbH
|
||||
1758611643990000000,360.0280002441406,-79,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],00:00:00:00:01:78,DIRECT-F2-HP OfficeJet 7510
|
||||
1758611643990000000,360.0280002441406,-72,2412,[ESS],04:f0:21:a6:7c:2f,BVG Wi-Fi
|
||||
1758611643990000000,360.0280002441406,-84,5200,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],34:60:f9:17:8f:24,TP-Link_8F25_5G
|
||||
1758611643990000000,360.0280002441406,-77,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],da:fe:f2:64:a9:73,(hidden SSID)
|
||||
1758611643990000000,360.0280002441406,-81,2462,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][ESS],00:1e:42:2f:2d:d5,LivEye#L-O-222
|
||||
1758611643990000000,360.0280002441406,-82,5785,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],8e:53:e6:1e:bf:2a,DIRECT-BMW 37515
|
||||
1758611643990000000,360.0280002441406,-82,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],8e:53:e6:0e:bf:2a,DIRECT-BMW 37515
|
||||
1758611683991000000,400.029,-82,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],62:e6:36:0c:49:79,Mount Zion 0361
|
||||
1758611683991000000,400.029,-85,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],dc:15:c8:ad:87:50,SuperspeedU
|
||||
1758611683991000000,400.029,-86,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],de:cd:2f:a2:5e:ad,DIRECT-2FA2DEAD
|
||||
1758611683991000000,400.029,-81,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],50:e6:36:0c:49:78,FRITZ!Box 7530 TL
|
||||
1758611683991000000,400.029,-88,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],64:7b:1e:7f:c5:8f,WLAN-913349
|
||||
1758611683991000000,400.029,-81,5500,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],8c:6a:8d:e3:78:70,Vodafone-7864
|
||||
1758611683991000000,400.029,-84,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],98:9d:5d:8f:f7:40,Vodafone-F73C
|
||||
1758611683991000000,400.029,-87,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],de:cd:2f:a2:5e:aa,DIRECT-2FA2DEAA
|
||||
1758611723994000000,440.0319997558594,-90,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],9c:c8:fc:31:62:2e,Vodafone-2 4
|
||||
1758611723994000000,440.0319997558594,-81,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],9c:c8:fc:31:62:2d,Vodafone-2 4
|
||||
1758611723994000000,440.0319997558594,-85,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],3e:87:c0:22:40:fc,Redmi Note 14 Pro
|
||||
1758611723994000000,440.0319997558594,-78,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],62:8d:26:77:93:4b,(hidden SSID)
|
||||
1758611723994000000,440.0319997558594,-85,5500,[ESS],24:a4:3c:86:46:e7,freifunk-bbb-bht-s
|
||||
1758611723994000000,440.0319997558594,-79,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],62:8d:26:77:93:4c,(hidden SSID)
|
||||
1758611723994000000,440.0319997558594,-86,2412,[WPA2-PSK-CCMP-128+TKIP][RSN-PSK-CCMP-128+TKIP][WPA-PSK-CCMP-128+TKIP][ESS],c0:ee:40:48:43:4c,mcx1-03540
|
||||
1758611723994000000,440.0319997558594,-83,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],60:8d:26:77:93:4d,WLAN-981710
|
||||
1758611723994000000,440.0319997558594,-91,5320,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],ce:d4:2e:30:8b:ef,(hidden SSID)
|
||||
1758611723994000000,440.0319997558594,-86,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],f2:c4:75:a6:f3:c8,Galaxy A51EE10
|
||||
1758611723994000000,440.0319997558594,-87,5260,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][WPS][MFPC],98:9b:cb:37:b9:1f,Kentucky
|
||||
1758611723994000000,440.0319997558594,-84,5680,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],f0:4b:8a:62:ee:60,Vodafone-0AA1
|
||||
1758611723994000000,440.0319997558594,-86,2427,[ESS],88:12:ac:ac:31:5d,SENA WA-AC315C
|
||||
1758611723994000000,440.0319997558594,-72,5540,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],2c:00:ab:85:37:b1,Vodafone-E42B
|
||||
1758611723994000000,440.0319997558594,-80,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],60:b5:8d:7b:56:8f,FRITZ!Box 7530 ZB
|
||||
1758611723994000000,440.0319997558594,-89,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],4e:1b:86:fa:54:2d,(hidden SSID)
|
||||
1758611723994000000,440.0319997558594,-89,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],4e:1b:86:fa:54:2e,(hidden SSID)
|
||||
1758611723994000000,440.0319997558594,-89,5200,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],4c:1b:86:d5:97:a9,WLAN-283443
|
||||
1758611723994000000,440.0319997558594,-79,5180,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],60:8d:26:77:93:49,WLAN-981710
|
||||
1758611763994000000,480.0319997558594,-88,5220,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],ac:6f:bb:c7:7f:dd,N14WL
|
||||
1758611763994000000,480.0319997558594,-88,5220,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],a6:6f:bb:c7:7f:dc,(hidden SSID)
|
||||
1758611763994000000,480.0319997558594,-81,2442,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],88:03:55:ef:72:ac,o2-WLAN24
|
||||
1758611763994000000,480.0319997558594,-86,2412,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],b8:69:f4:73:cf:77,urbanizers
|
||||
1758611763994000000,480.0319997558594,-86,2462,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS][WPS],50:6f:0c:c4:d4:5e,FriedoLAN
|
||||
1758611763994000000,480.0319997558594,-75,2437,[WPA2-PSK-CCMP-128][RSN-PSK-CCMP-128][ESS],0c:ea:14:7c:02:32,ServiceConceptFM
|
||||
1758611803994000000,520.0319997558594,-87,5240,[WPA2-PSK-CCMP-128][RSN-PSK+SAE-CCMP-128][ESS][MFPC],c2:c4:f9:72:47:1e,MBUX 77988
|
||||
|
9969
test-data/accelerometer.csv
Normal file
9969
test-data/accelerometer.csv
Normal file
File diff suppressed because it is too large
Load Diff
223
test-data/gps.csv
Normal file
223
test-data/gps.csv
Normal file
@@ -0,0 +1,223 @@
|
||||
1758611288739000000,4.777,0,0,1,80.72899627685547,0,0,87.80000305175781,13.3650032,52.5325205
|
||||
1758611288795000000,4.833,0,0,1,13.442000389099121,0,0,87.80000305175781,13.3649933,52.5325162
|
||||
1758611299389000000,15.427,0,0,1,77.00499725341797,0,0,87.80000305175781,13.3649933,52.5325162
|
||||
1758611305230579500,21.268579345703124,63.735355377197266,1.5448625087738037,1.164355754852295,30.66900062561035,0.36000001430511475,12,87.80000305175781,13.3645272,52.5328863
|
||||
1758611305330214000,21.3682138671875,49.04451370239258,1.5784169435501099,3.866894245147705,26.0939998626709,1.059999942779541,0,87.69999694824219,13.3644028,52.532623
|
||||
1758611305430148000,21.468148193359376,51.483497619628906,1.6253306865692139,3.8678934574127197,24.614999771118164,1.059999942779541,0,87.69999694824219,13.3644028,52.5326241
|
||||
1758611305529933600,21.56793359375,53.557315826416016,1.6724233627319336,3.8688912391662598,23.905000686645508,1.059999942779541,0,87.69999694824219,13.3644028,52.532625
|
||||
1758611305630380500,21.668380615234376,55.61048126220703,1.7140594720840454,3.8698959350585938,23.5049991607666,1.059999942779541,0,87.69999694824219,13.3644029,52.5326259
|
||||
1758611305729792000,21.7677919921875,57.638675689697266,1.7531685829162598,3.870889902114868,23.259000778198242,1.059999942779541,0,87.69999694824219,13.3644029,52.5326268
|
||||
1758611305830181400,21.868181396484374,59.96837615966797,1.8006943464279175,3.871893882751465,23.10700035095215,1.059999942779541,0,87.69999694824219,13.3644029,52.5326279
|
||||
1758611305930525000,21.96852490234375,61.930301666259766,1.8425254821777344,3.872897148132324,23.010000228881836,1.059999942779541,0,87.69999694824219,13.3644029,52.5326288
|
||||
1758611306030584800,22.068584716796874,63.85710525512695,1.882153034210205,3.8738977909088135,22.950000762939453,1.059999942779541,0,87.69999694824219,13.364403,52.5326297
|
||||
1758611306129976800,22.167976806640624,65.74655151367188,1.924084186553955,3.874891757965088,22.917999267578125,1.059999942779541,0,87.69999694824219,13.364403,52.5326307
|
||||
1758611306230689300,22.268689208984377,67.90131378173828,1.9780040979385376,3.875898838043213,22.908000946044922,1.059999942779541,0,87.69999694824219,13.364403,52.5326317
|
||||
1758611306330606600,22.368606689453124,38.896793365478516,0.9840731620788574,3.8768980503082275,21.809999465942383,0.9900000095367432,354,87.69999694824219,13.3648203,52.5325672
|
||||
1758611306430305000,22.468304931640624,41.55168151855469,1.03232741355896,3.8778951168060303,20.888999938964844,0.9900000095367432,354,87.69999694824219,13.3648202,52.5325682
|
||||
1758611306529823500,22.567823486328123,43.8006477355957,1.0807404518127441,3.8788902759552,20.104999542236328,0.9900000095367432,354,87.69999694824219,13.36482,52.5325691
|
||||
1758611306630458600,22.668458740234374,46.01896667480469,1.1216059923171997,3.879896640777588,19.43199920654297,0.9900000095367432,354,87.69999694824219,13.3648199,52.5325699
|
||||
1758611306730393600,22.7683935546875,48.20179748535156,1.1638728380203247,3.8808958530426025,18.849000930786133,0.9900000095367432,354,87.69999694824219,13.3648198,52.5325708
|
||||
1758611306829840600,22.867840576171876,50.698204040527344,1.212641716003418,3.8818905353546143,18.341999053955078,0.9900000095367432,354,87.69999694824219,13.3648196,52.5325718
|
||||
1758611306930260200,22.96826025390625,52.791141510009766,1.2615070343017578,3.882894515991211,17.895999908447266,0.9900000095367432,354,87.69999694824219,13.3648195,52.5325726
|
||||
1758611307029761000,23.067760986328125,54.83805847167969,1.3029965162277222,3.883889675140381,17.503999710083008,0.9900000095367432,354,87.69999694824219,13.3648194,52.5325735
|
||||
1758611307130241500,23.168241455078125,56.83687973022461,1.3453624248504639,3.884894371032715,17.1560001373291,0.9900000095367432,354,87.69999694824219,13.3648192,52.5325743
|
||||
1758611307230104600,23.2681044921875,59.10601806640625,1.3944532871246338,3.8858931064605713,16.849000930786133,0.9900000095367432,354,87.69999694824219,13.3648191,52.5325753
|
||||
1758611307330447600,23.368447509765623,39.80328369140625,1.7681912183761597,3.8868963718414307,16.597000122070312,1.7599999904632568,244,87.69999694824219,13.3647645,52.5325694
|
||||
1758611307430458400,23.468458251953123,41.101436614990234,1.8104419708251953,3.8878965377807617,16.37299919128418,1.7599999904632568,244,87.69999694824219,13.3647623,52.5325687
|
||||
1758611307530368800,23.56836865234375,42.61482238769531,1.8656097650527954,3.8888957500457764,16.173999786376953,1.7599999904632568,244,87.69999694824219,13.3647597,52.532568
|
||||
1758611307629849000,23.66784912109375,43.90934371948242,1.900315761566162,3.889890432357788,15.998000144958496,1.7599999904632568,244,87.69999694824219,13.3647574,52.5325673
|
||||
1758611307730620400,23.768620361328125,45.19991683959961,1.9491792917251587,3.8908982276916504,15.840999603271484,1.7599999904632568,244,87.69999694824219,13.3647552,52.5325667
|
||||
1758611307830648300,23.8686484375,46.48525619506836,1.9839859008789062,3.8918983936309814,15.70199966430664,1.7599999904632568,244,87.69999694824219,13.3647529,52.532566
|
||||
1758611307930066700,23.968066650390625,47.976585388183594,2.0329535007476807,3.892892599105835,15.579999923706055,1.7599999904632568,244,87.69999694824219,13.3647503,52.5325652
|
||||
1758611308030475800,24.068475830078125,49.24654006958008,2.08197021484375,3.8938968181610107,15.472000122070312,1.7599999904632568,244,87.69999694824219,13.364748,52.5325646
|
||||
1758611308130260200,24.16826025390625,50.5077018737793,2.131032705307007,3.894894599914551,15.376999855041504,1.7599999904632568,244,87.69999694824219,13.3647458,52.5325639
|
||||
1758611308230107600,24.268107666015624,51.759159088134766,2.1660101413726807,3.895893096923828,15.293999671936035,1.7599999904632568,244,87.69999694824219,13.3647435,52.5325633
|
||||
1758611308330159400,24.368159423828125,34.79586410522461,0.7424957752227783,3.8968935012817383,15.20300006866455,0.9599999785423279,53,87.69999694824219,13.3646153,52.5325326
|
||||
1758611308430406400,24.468406494140623,37.164207458496094,0.7778174877166748,3.8978960514068604,15.119999885559082,0.9599999785423279,53,87.69999694824219,13.3646164,52.5325331
|
||||
1758611308530300000,24.5682998046875,39.5001220703125,0.8273451328277588,3.898895025253296,15.043000221252441,0.9599999785423279,53,87.69999694824219,13.3646175,52.5325336
|
||||
1758611308630436000,24.66843603515625,42.176944732666016,0.8769264221191406,3.8998963832855225,14.973999977111816,0.9599999785423279,53,87.69999694824219,13.3646187,52.5325342
|
||||
1758611308730304800,24.7683046875,44.42461013793945,0.9196738600730896,3.900895118713379,14.91100025177002,0.9599999785423279,53,87.69999694824219,13.3646198,52.5325347
|
||||
1758611308830144800,24.868144775390626,46.625152587890625,0.9620810747146606,3.901893377304077,14.852999687194824,0.9599999785423279,53,87.69999694824219,13.3646209,52.5325352
|
||||
1758611308930557400,24.968557373046874,48.775596618652344,1.0049875974655151,3.902897596359253,14.800999641418457,0.9599999785423279,53,87.69999694824219,13.364622,52.5325357
|
||||
1758611309030018600,25.0680185546875,50.873626708984375,1.0547511577606201,3.9038922786712646,14.753999710083008,0.9599999785423279,53,87.69999694824219,13.3646231,52.5325362
|
||||
1758611309129869000,25.167869140625,53.25279235839844,1.1045360565185547,3.904890775680542,14.711999893188477,0.9599999785423279,53,87.69999694824219,13.3646244,52.5325368
|
||||
1758611309230215700,25.268215576171876,55.23197937011719,1.1543396711349487,3.9058942794799805,14.673999786376953,0.9599999785423279,53,87.69999694824219,13.3646255,52.5325373
|
||||
1758611309330085400,25.36808544921875,25.05569839477539,0.9604686498641968,3.906892776489258,14.687000274658203,0.6499999761581421,53,87.69999694824219,13.3647293,52.5325922
|
||||
1758611309430174200,25.46817431640625,25.88075828552246,0.9948869347572327,3.907893657684326,14.701000213623047,0.6499999761581421,53,87.69999694824219,13.3647301,52.5325925
|
||||
1758611309529871400,25.567871337890626,26.70581817626953,1.043503761291504,3.908890724182129,14.715999603271484,0.6499999761581421,53,87.69999694824219,13.3647309,52.5325929
|
||||
1758611309630589400,25.66858935546875,27.668386459350586,1.09224534034729,3.909897804260254,14.732999801635742,0.6499999761581421,53,87.69999694824219,13.3647318,52.5325932
|
||||
1758611309730477000,25.76847705078125,28.493446350097656,1.1335784196853638,3.9108967781066895,14.75100040435791,0.6499999761581421,53,87.69999694824219,13.3647325,52.5325935
|
||||
1758611309830320400,25.8683203125,29.318504333496094,1.1759251356124878,3.911895275115967,14.770999908447266,0.6499999761581421,53,87.69999694824219,13.3647333,52.5325939
|
||||
1758611309930166500,25.96816650390625,30.143564224243164,1.2249490022659302,3.912893772125244,14.791999816894531,0.6499999761581421,53,87.69999694824219,13.364734,52.5325942
|
||||
1758611310030584300,26.068584228515626,31.10613250732422,1.2740486860275269,3.913897752761841,14.814000129699707,0.6499999761581421,53,87.69999694824219,13.364735,52.5325945
|
||||
1758611310130026800,26.16802685546875,31.93119239807129,1.3159027099609375,3.9148921966552734,14.838000297546387,0.6499999761581421,53,87.69999694824219,13.3647357,52.5325949
|
||||
1758611310229841000,26.2678408203125,32.75625228881836,1.3651739358901978,3.9158904552459717,14.86299991607666,0.6499999761581421,53,87.69999694824219,13.3647365,52.5325952
|
||||
1758611310330264000,26.36826416015625,24.918188095092773,0.9571833610534668,3.9168946743011475,14.416999816894531,0.3799999952316284,53,87.69999694824219,13.3646178,52.5325994
|
||||
1758611310429973500,26.467973388671876,25.88075828552246,1.009554386138916,3.91789174079895,14.430000305175781,0.3799999952316284,53,87.69999694824219,13.3646181,52.5325997
|
||||
1758611310530670800,26.5686708984375,26.70581817626953,1.0511897802352905,3.918898820877075,14.154000282287598,0.3799999952316284,53,87.69999694824219,13.3646185,52.5326
|
||||
1758611310630457900,26.668457763671874,27.5308780670166,1.0904127359390259,3.9198966026306152,14.020999908447266,0.3799999952316284,53,87.69999694824219,13.3646188,52.5326002
|
||||
1758611310730201300,26.768201416015625,28.35593605041504,1.1322543621063232,3.920894145965576,13.887999534606934,0.3799999952316284,53,87.69999694824219,13.3646191,52.5326005
|
||||
1758611310830531300,26.86853125,29.318504333496094,1.1860016584396362,3.9218974113464355,13.753000259399414,0.3799999952316284,53,87.69999694824219,13.3646195,52.5326008
|
||||
1758611310930310100,26.96831005859375,30.143564224243164,1.220041036605835,3.9228951930999756,13.788999557495117,0.3799999952316284,53,87.69999694824219,13.3646198,52.532601
|
||||
1758611311029996500,27.06799658203125,30.968624114990234,1.2682271003723145,3.923892021179199,13.657999992370605,0.3799999952316284,53,87.69999694824219,13.3646202,52.5326013
|
||||
1758611311130709800,27.168709716796876,31.793684005737305,1.316548466682434,3.924899101257324,13.345000267028809,0.3799999952316284,53,87.69999694824219,13.3646205,52.5326016
|
||||
1758611311230474800,27.268474853515624,25.05569839477539,0.9295697808265686,3.925896644592285,13.413999557495117,0.30000001192092896,53,87.69999694824219,13.3645663,52.5325966
|
||||
1758611311321207800,27.359207763671876,25.88075828552246,0.9642613530158997,3.9268040657043457,13.298999786376953,0.30000001192092896,53,87.69999694824219,13.3645665,52.5325968
|
||||
1758611311420878300,27.45887841796875,26.70581817626953,1.0131633281707764,3.9278008937835693,13.440999984741211,0.30000001192092896,53,87.69999694824219,13.3645667,52.5325971
|
||||
1758611311521585400,27.55958544921875,27.668386459350586,1.0621676445007324,3.9288079738616943,13.583999633789062,0.30000001192092896,53,87.69999694824219,13.364567,52.5325973
|
||||
1758611311621278500,27.659278564453125,28.493446350097656,1.1112605333328247,3.929804801940918,13.727999687194824,0.30000001192092896,53,87.69999694824219,13.3645672,52.5325976
|
||||
1758611311720979000,27.75897900390625,29.318504333496094,1.1531262397766113,3.9308018684387207,13.871000289916992,0.30000001192092896,53,87.69999694824219,13.3645674,52.5325978
|
||||
1758611311821662500,27.859662353515624,30.28107261657715,1.2024142742156982,3.9318087100982666,14.015000343322754,0.30000001192092896,53,87.69999694824219,13.3645676,52.5325981
|
||||
1758611311921368800,27.959368896484374,31.10613250732422,1.2448292970657349,3.9328057765960693,14.157999992370605,0.30000001192092896,53,87.69999694824219,13.3645678,52.5325983
|
||||
1758611312021006600,28.059006591796877,24.918188095092773,1.0610371828079224,3.9338021278381348,14.211000442504883,0.3100000023841858,53,87.69999694824219,13.3644532,52.532653
|
||||
1758611312121665800,28.159665771484374,0,0.3471311032772064,3.9348087310791016,14.251999855041504,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312220788700,28.258788818359374,0,0.3471311032772064,3.9357998371124268,14.291999816894531,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312320982800,28.358982666015624,0,0.3471311032772064,3.9368019104003906,14.329000473022461,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312421212400,28.45921240234375,0,0.3471311032772064,3.9378042221069336,14.352999687194824,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312521444000,28.559444091796873,0,0.3471311032772064,3.9388065338134766,14.375,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312621666300,28.659666259765626,0,0.3471311032772064,3.9398086071014404,14.394000053405762,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312720958200,28.758958251953125,0,0.3471311032772064,3.9408016204833984,14.409000396728516,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312821213000,28.859212890625,0,0.3471311032772064,3.9418041706085205,14.42199993133545,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611312921472300,28.95947216796875,0,0.3471311032772064,3.9428067207336426,14.430999755859375,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611313020774100,29.058774169921875,0,0.3471311032772064,3.9437997341156006,14.437000274658203,0,0,87.69999694824219,13.3643356,52.5325925
|
||||
1758611313121207600,29.15920751953125,0,0.3538361191749573,3.9448041915893555,14.4399995803833,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313221438500,29.2594384765625,0,0.3538361191749573,3.9458065032958984,14.439000129699707,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313321605400,29.35960546875,0,0.3538361191749573,3.946808099746704,14.434000015258789,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313421117700,29.45911767578125,0,0.3538361191749573,3.947803258895874,14.437999725341797,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313521714000,29.5597138671875,0,0.3538361191749573,3.9488091468811035,14.4399995803833,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313620935000,29.658934814453126,0,0.3538361191749573,3.949801445007324,14.440999984741211,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313720788000,29.7587880859375,0,0.3538361191749573,3.9507999420166016,14.440999984741211,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313821133800,29.8591337890625,0,0.3538361191749573,3.95180344581604,14.439000129699707,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611313921463800,29.9594638671875,0,0.3538361191749573,3.9528067111968994,14.4350004196167,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611314021200600,30.05920068359375,0,0.3538361191749573,3.9538040161132812,14.428999900817871,0,0,87.69999694824219,13.3643322,52.5326281
|
||||
1758611314121440000,30.15943994140625,0,0.4360045790672302,20.474790573120117,14.420999526977539,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314221642500,30.259642578125,0,0.4360045790672302,20.474790573120117,14.411999702453613,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314320820000,30.358820068359375,0,0.4360045790672302,20.474790573120117,14.399999618530273,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314421109800,30.45910986328125,0,0.4360045790672302,20.474790573120117,14.348999977111816,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314521393200,30.55939306640625,0,0.4360045790672302,20.474790573120117,14.295999526977539,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314621557800,30.659557861328125,0,0.4360045790672302,20.474790573120117,14.241000175476074,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314721312500,30.7593125,0,0.4360045790672302,20.474790573120117,14.184000015258789,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314821538800,30.859538818359376,0,0.4360045790672302,20.474790573120117,14.12600040435791,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611314920755700,30.958755615234374,0,0.4360045790672302,20.474790573120117,14.065999984741211,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611315021022000,31.05902197265625,0,0.4360045790672302,20.474790573120117,14.003000259399414,0,0,100.76953125,13.364331,52.5326336
|
||||
1758611315121248300,31.159248291015626,0,0.7201388478279114,19.45343017578125,13.939000129699707,0,0,101.8375244140625,13.3643289,52.5326355
|
||||
1758611315221404200,31.259404052734375,0,0.7201388478279114,19.45343017578125,13.871999740600586,0,0,101.8375244140625,13.3643289,52.5326355
|
||||
1758611315320842500,31.358842529296876,0,0.7201388478279114,19.45343017578125,13.803000450134277,0,0,101.8375244140625,13.3643289,52.5326355
|
||||
1758611315421091600,31.459091552734375,0,0.7201388478279114,19.45343017578125,13.755000114440918,0,0,101.8375244140625,13.3643289,52.5326355
|
||||
1758611315521448000,31.559447998046874,0,0.7201388478279114,19.45343017578125,13.706000328063965,0,0,101.8375244140625,13.3643289,52.5326355
|
||||
1758611315621665500,31.65966552734375,0,0.7201388478279114,77.53600311279297,13.654999732971191,0,0,87.80000305175781,13.3643289,52.5326355
|
||||
1758611315721014000,31.759013916015626,0,0.7201388478279114,77.53699493408203,13.602999687194824,0,0,87.80000305175781,13.3643289,52.5326355
|
||||
1758611315821728000,31.85972802734375,0,0.7201388478279114,77.53800201416016,13.548999786376953,0,0,87.80000305175781,13.3643289,52.5326355
|
||||
1758611315920901600,31.958901611328123,0,0.7201388478279114,77.53899383544922,13.493000030517578,0,0,87.80000305175781,13.3643289,52.5326355
|
||||
1758611316021352700,32.059352783203124,0,0.7201388478279114,77.54000091552734,13.434000015258789,0,0,87.80000305175781,13.3643289,52.5326355
|
||||
1758611316121085200,32.15908520507813,0,0.8381527066230774,77.5409927368164,13.378999710083008,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316221284900,32.25928491210937,0,0.8381527066230774,77.54199981689453,13.321000099182129,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316321534000,32.35953393554688,0,0.8381527066230774,77.54299926757812,13.168000221252441,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316420829200,32.4588291015625,0,0.8381527066230774,77.54399108886719,13.16100025177002,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316521109800,32.55910986328125,0,0.8381527066230774,77.54499816894531,13.079000473022461,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316621276400,32.6592763671875,0,0.8381527066230774,77.5459976196289,12.994999885559082,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316721141000,32.75914111328125,0,0.8381527066230774,77.5469970703125,12.821000099182129,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316821008400,32.85900830078125,0,0.8381527066230774,77.5479965209961,12.821000099182129,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611316920890400,32.95889038085937,0,0.8381527066230774,77.54899597167969,12.730999946594238,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611317020795600,33.05879565429687,0,0.8381527066230774,77.54999542236328,12.637999534606934,0,0,87.80000305175781,13.364328,52.5326355
|
||||
1758611317121742300,33.15974243164062,0,0.7818567752838135,77.5510025024414,12.654000282287598,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317221033700,33.25903369140625,0,0.7818567752838135,77.55199432373047,12.677000045776367,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317321416200,33.359416259765624,0,0.7818567752838135,77.5530014038086,12.699000358581543,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317420727000,33.45872705078125,0,0.7818567752838135,77.55399322509766,12.718999862670898,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317521025000,33.55902490234375,0,0.7818567752838135,77.55499267578125,12.741999626159668,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317621144000,33.65914404296875,0,0.7818567752838135,77.55599212646484,12.763999938964844,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317721330000,33.759329833984374,0,0.7818567752838135,77.55699920654297,12.791000366210938,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317821508900,33.8595087890625,0,0.7818567752838135,77.55799865722656,12.814000129699707,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611317921652200,33.95965234375,0,0.7818567752838135,77.55899810791016,12.836000442504883,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611318020853000,34.05885302734375,0,0.7818567752838135,77.55998992919922,12.859000205993652,0,0,87.80000305175781,13.3643275,52.5326353
|
||||
1758611318121332500,34.15933251953125,0,1.0594810247421265,77.56099700927734,12.913000106811523,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318220771800,34.258771728515626,0,1.0594810247421265,77.5619888305664,12.958999633789062,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318320931800,34.358931884765624,0,1.0594810247421265,77.56299591064453,13.01099967956543,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318421198300,34.4591982421875,0,1.0594810247421265,77.56399536132812,13.074000358581543,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318521000700,34.55900073242187,0,1.0594810247421265,77.56499481201172,13.116999626159668,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318621115600,34.65911572265625,0,1.0594810247421265,77.56599426269531,13.180999755859375,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318721130500,34.759130615234376,0,1.0594810247421265,77.5669937133789,13.234999656677246,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318821354000,34.85935400390625,0,1.0594810247421265,77.56800079345703,13.288000106811523,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611318921415400,34.95941552734375,0,1.0594810247421265,77.56900024414062,13.32699966430664,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611319021465000,35.05946508789062,0,1.0594810247421265,77.56999969482422,13.395000457763672,0,0,87.80000305175781,13.3643266,52.532635
|
||||
1758611319120865500,35.15886547851562,0,1.261269211769104,18.79852294921875,13.47700023651123,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319220975400,35.25897534179688,0,1.261269211769104,18.79852294921875,13.574999809265137,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319321060600,35.359060546875,0,1.261269211769104,18.79852294921875,13.694000244140625,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319421101800,35.459101806640625,0,1.261269211769104,18.79852294921875,13.770000457763672,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319521239600,35.55923950195312,0,1.261269211769104,18.79852294921875,13.866999626159668,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319621349000,35.65934912109375,0,1.261269211769104,18.79852294921875,13.96500015258789,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319721366800,35.75936669921875,0,1.261269211769104,18.79852294921875,14.092000007629395,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319821246200,35.85924609375,0,1.261269211769104,18.79852294921875,14.15999984741211,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611319921249000,35.9592490234375,0,1.261269211769104,18.79852294921875,14.291000366210938,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320020761000,36.058760986328124,0,1.261269211769104,18.79852294921875,14.354999542236328,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320121130800,36.159130859375,0,1.4263590574264526,18.590946197509766,14.510000228881836,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320221186600,36.2591865234375,0,1.4263590574264526,18.590946197509766,14.664999961853027,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320321211100,36.359211181640624,0,1.4263590574264526,18.590946197509766,14.864999771118164,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320421260800,36.4592607421875,0,1.4263590574264526,18.590946197509766,15.02299976348877,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320521388300,36.55938818359375,0,1.4263590574264526,18.590946197509766,15.130999565124512,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320621409800,36.659409912109375,0,1.4263590574264526,18.590946197509766,15.28600025177002,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320721445400,36.7594453125,0,1.4263590574264526,18.590946197509766,15.498000144958496,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320821565200,36.85956518554688,0,1.4263590574264526,18.590946197509766,15.595999717712402,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611320921678600,36.9596787109375,0,1.4263590574264526,18.590946197509766,15.814000129699707,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321020756500,37.05875659179687,0,1.4263590574264526,18.590946197509766,15.906000137329102,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321121143600,37.1591435546875,0,1.5826876163482666,19.292627334594727,16.222000122070312,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321221326300,37.259326416015625,0,1.5826876163482666,19.292627334594727,16.472000122070312,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321321459200,37.359459228515625,0,1.5826876163482666,19.292627334594727,16.645000457763672,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321421213700,37.45921362304688,0,1.5826876163482666,19.292627334594727,16.97100067138672,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321521342700,37.5593427734375,0,1.5826876163482666,19.292627334594727,17.22100067138672,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321621300500,37.659300537109374,0,1.5826876163482666,19.292627334594727,17.469999313354492,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321720845300,37.75884521484375,0,1.5826876163482666,19.292627334594727,17.624000549316406,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321820916200,37.85891625976563,0,1.5826876163482666,19.292627334594727,17.868999481201172,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611321921005000,37.95900512695312,0,1.5826876163482666,19.292627334594727,18.2189998626709,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322020750000,38.05875,0,1.5826876163482666,19.292627334594727,18.358999252319336,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322121084700,38.159084716796876,0,1.7200291156768799,20.751747131347656,18.740999221801758,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322221174800,38.2591748046875,0,1.7200291156768799,20.751747131347656,19.21299934387207,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322321221000,38.35922119140625,0,1.7200291156768799,20.751747131347656,19.469999313354492,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322421327600,38.45932763671875,0,1.7200291156768799,20.751747131347656,19.95800018310547,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322521399800,38.55939990234375,0,1.7200291156768799,20.751747131347656,20.329999923706055,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322621310500,38.659310546875,0,1.7200291156768799,20.751747131347656,20.70199966430664,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322721608200,38.75960815429688,0,1.7200291156768799,20.751747131347656,21.073999404907227,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322821563000,38.85956298828125,0,1.7200291156768799,20.751747131347656,21.445999145507812,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611322921061600,38.9590615234375,0,1.7200291156768799,20.751747131347656,21.659000396728516,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323021437000,39.05943701171875,0,1.7200291156768799,20.751747131347656,22.190000534057617,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323121146000,39.15914599609375,0,2.171750545501709,22.386638641357422,22.559999465942383,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323221189400,39.259189453125,0,2.171750545501709,22.386638641357422,23.22100067138672,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323320861400,39.358861328125,0,2.171750545501709,22.386638641357422,23.56999969482422,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323420878800,39.45887890625,0,2.171750545501709,22.386638641357422,24.076000213623047,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323520895700,39.55889575195312,0,2.171750545501709,22.386638641357422,24.58099937438965,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323621439000,39.65943896484375,0,2.171750545501709,22.386638641357422,25.283000946044922,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323721331700,39.759331787109375,0,2.171750545501709,22.386638641357422,25.798999786376953,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323821237200,39.8592373046875,0,2.171750545501709,22.386638641357422,26.097999572753906,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611323921223000,39.95922290039063,0,2.171750545501709,22.386638641357422,26.60300064086914,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611324021182500,40.05918237304687,0,2.171750545501709,22.386638641357422,27.107999801635742,0,0,102.84710693359375,13.3643259,52.5326347
|
||||
1758611324121473500,40.1594736328125,0,2.2407588958740234,24.203948974609375,28.003000259399414,0,0,102.8095703125,13.364326,52.5326346
|
||||
1758611324221509400,40.25950927734375,0,2.2407588958740234,24.203948974609375,28.660999298095703,0,0,102.8095703125,13.364326,52.5326346
|
||||
1758611324320870400,40.35887036132812,0,2.2407588958740234,24.203948974609375,29.089000701904297,0,0,102.8095703125,13.364326,52.5326346
|
||||
1758611324420888300,40.45888842773437,0,2.2407588958740234,24.203948974609375,29.733999252319336,0,0,102.8095703125,13.364326,52.5326346
|
||||
1758611326121687300,42.159687255859374,0,1.9847922325134277,39.61509704589844,35.70100021362305,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326220808000,42.25880786132812,0,1.9847922325134277,39.6160888671875,36.12900161743164,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326320876500,42.35887646484375,0,1.9847922325134277,39.617088317871094,36.854000091552734,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326420969000,42.458968994140626,0,1.9847922325134277,39.61809158325195,37.57899856567383,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326521724700,42.559724609375,0,1.9847922325134277,39.61909866333008,38.68600082397461,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326620774000,42.65877392578125,0,1.9847922325134277,39.620086669921875,39.02899932861328,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326720847400,42.758847412109375,0,1.9847922325134277,39.621089935302734,40.17900085449219,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326821476000,42.85947607421875,0,1.9847922325134277,39.622093200683594,40.92499923706055,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611326921587700,42.95958764648437,0,1.9847922325134277,39.62309646606445,41.672000885009766,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611327021593000,43.05959301757812,0,1.9847922325134277,39.62409591674805,42.417999267578125,0,0,87.80000305175781,13.3643258,52.5326348
|
||||
1758611332021117000,48.05911694335938,59.16693115234375,3.9996249675750732,11.339604377746582,46.74599838256836,3.5,94,87.80000305175781,13.3648951,52.5325644
|
||||
1758611332120726000,48.15872607421875,59.84537124633789,4.045553207397461,11.34060001373291,43.005001068115234,3.5,94,87.80000305175781,13.3649,52.5325642
|
||||
1758611332221246200,48.25924609375,60.52415084838867,4.081874370574951,11.341605186462402,43.21099853515625,3.5,94,87.80000305175781,13.364905,52.5325639
|
||||
1758611332320777700,48.35877783203125,61.31617736816406,4.137692451477051,11.34260082244873,43.4370002746582,3.5,94,87.80000305175781,13.3649108,52.5325637
|
||||
1758611332421047300,48.45904736328125,61.99492263793945,4.1717143058776855,11.34360408782959,43.65700149536133,3.5,94,87.80000305175781,13.3649157,52.5325635
|
||||
1758611332521322500,48.55932250976562,62.67333221435547,4.217973232269287,11.344606399536133,43.875999450683594,3.5,94,87.80000305175781,13.3649206,52.5325632
|
||||
1758611332621538600,48.65953857421875,63.464111328125,4.264317035675049,11.345608711242676,44.104000091552734,3.5,94,87.80000305175781,13.3649264,52.532563
|
||||
1758611332721239600,48.759239501953125,64.14112091064453,4.308131694793701,11.34660530090332,44.33000183105469,3.5,94,87.80000305175781,13.3649314,52.5325628
|
||||
1758611332821491500,48.85949145507813,64.81717681884766,4.354595184326172,11.347607612609863,44.555999755859375,3.5,94,87.80000305175781,13.3649363,52.5325625
|
||||
1758611332921725400,48.959725341796876,65.49211120605469,4.39150333404541,11.348610877990723,44.78099822998047,3.5,94,87.80000305175781,13.3649412,52.5325623
|
||||
1758611335987000000,52.025,0,0,11.348610877990723,46.637001037597656,0,0,87.80000305175781,13.3649412,52.5325623
|
||||
1758611341042000000,57.079999755859376,0,0,11.348610877990723,95.52799987792969,0,0,87.80000305175781,13.3649412,52.5325623
|
||||
1758611351098000000,67.13599975585937,0,0,64.52108001708984,155.86399841308594,0,0,119.4000015258789,13.3649412,52.5325623
|
||||
1758611358542000000,74.58000024414062,0,0,1,20,0,0,75.80000305175781,13.3646897,52.5325409
|
||||
1758611363561000000,79.599,0,0,1,50.11399841308594,0,0,75.80000305175781,13.3646897,52.5325409
|
||||
1758611366906000000,82.94399975585938,0,0,1.10775887966156,35.05699920654297,0,0,75.80000305175781,13.3646803,52.5325661
|
||||
1758611374767000000,90.805,0,0,1,28.11400032043457,0,0,75.30000305175781,13.3646551,52.5325255
|
||||
|
10000
test-data/gyro.csv
Normal file
10000
test-data/gyro.csv
Normal file
File diff suppressed because it is too large
Load Diff
Reference in New Issue
Block a user